source: flair-src/trunk/tools/Controller/Mavlink/src/GuiGcs.cpp@ 318

Last change on this file since 318 was 300, checked in by Sanahuja Guillaume, 6 years ago

m

File size: 6.8 KB
Line 
1// %flair:license{
2// This file is part of the Flair framework distributed under the
3// CECILL-C License, Version 1.0.
4// %flair:license}
5// created: 2016/09/02
6// filename: GuiGcs.h
7//
8// authors: Thomas Fuhrmann
9// Milan Erdelj
10// Copyright Heudiasyc UMR UTC/CNRS 7253
11//
12// version: $Id: $
13//
14// purpose: Implementation of GuiInterface, using sockets
15//
16//
17/*********************************************************************/
18
19#include "GuiGcs.h"
20#include "GuiInterface.h"
21
22#include "MavlinkUDP.h"
23
24#include <ListWidget.h>
25
26#include <iostream>
27#include <array>
28
29using namespace std;
30using namespace flair::core;
31using namespace flair::gui;
32
33const std::string delimiter = "|";
34
35GuiGcs::GuiGcs(string name,
36 std::string &outputAddress, int outputPort):
37 GuiInterface(name) {
38 cout << "MavPlanner GuiGcs constructor" << endl;
39 //outputSocket = new Socket((Thread *)this, "output socket", outputAddress + ":" + to_string(outputPort));
40
41 missionPauseEnabled = false;
42
43 mavCom = new MavlinkUDP(outputAddress, outputPort);
44}
45
46GuiGcs::~GuiGcs() {
47 if (mavCom) {
48 mavCom->stopThreads();
49 delete mavCom;
50 }
51}
52
53void GuiGcs::MissionStart() {
54 cout << "MavPlanner GuiGcs MissionStart" << endl;
55
56 Initialize();
57
58 cout << "--------------------\n";
59 cout << " MISSION START\n";
60 cout << "--------------------\n";
61
62 // set auto armed mode
63 mavCom->cmdDoSetMode(mavCom->target.getSysID(), mavCom->target.getCompID(), MAV_MODE_AUTO_ARMED);
64 mavCom->waitCommandAck(ACK_TIMEOUT);
65
66 usleep(INTER_COMMAND_PAUSE);
67
68 // mission start message
69 mavCom->cmdMissionStart(mavCom->target.getSysID(), mavCom->target.getCompID(), mavCom->missionFirst, mavCom->missionLast);
70 mavCom->waitCommandAck(ACK_TIMEOUT);
71
72 mavCom->missionStarted();
73}
74
75void GuiGcs::MissionStop() {
76 cout << "MavPlanner GuiGcs MissionStop" << endl;
77}
78
79void GuiGcs::MissionPause() {
80 cout << "MavPlanner GuiGcs MissionPause" << endl;
81 // send pause/continue depending on the state of the button
82 if(missionPauseEnabled) {
83 missionPauseEnabled = false;
84 cout << "Sent pause command.\n";
85 mavCom->cmdDoPauseContinue(mavCom->target.getSysID(), mavCom->target.getCompID(), 0);
86 } else {
87 missionPauseEnabled = true;
88 cout << "Sent continue command.\n";
89 mavCom->cmdDoPauseContinue(mavCom->target.getSysID(), mavCom->target.getCompID(), 1);
90 }
91 mavCom->waitCommandAck(ACK_TIMEOUT);
92}
93
94void GuiGcs::MissionSend() {
95 cout << "MavPlanner GuiGcs MissionSend" << endl;
96
97 // upload a flight plan
98 cout << "---------------\n";
99 cout << "Flight planning \n";
100 cout << "---------------\n";
101
102 // get the list of commands to send
103 std::vector<std::string> missionCommandList = listMissionItems->GetItemList();
104
105 // reset all the previous waypoints
106 mavCom->sendMissionClearAll(mavCom->target.getSysID(), mavCom->target.getCompID());
107
108 cout << "[INFO] Mission write partial list.\n";
109 // write partial list, takeoff + 4 waypoints + land
110 mavCom->sendMissionWritePartialList(mavCom->target.getSysID(),mavCom->target.getCompID(), 0, missionCommandList.size());
111 mavCom->waitMissionAck(ACK_TIMEOUT);
112
113 // sending mission items
114 cout << "[INFO] Mission items.\n";
115 for (auto &missionCommand : missionCommandList) {
116 cout << "[INFO] Mission item : " << missionCommand << "\n";
117 // Parse command
118 std::string command = missionCommand.substr(0, missionCommand.find(delimiter));
119 missionCommand.erase(0, missionCommand.find(delimiter) + delimiter.length());
120 std::array<float, 6> missionParameters;
121 ParametersParse(missionCommand, missionParameters);
122
123 mavCom->sendMissionItem(mavCom->target.getSysID(), mavCom->target.getCompID(), 0, MAV_FRAME_GLOBAL_RELATIVE_ALT, MavCommandGet(command), 0, 1,
124 missionParameters[0], missionParameters[1], missionParameters[2], 0, missionParameters[3], missionParameters[4], missionParameters[5]);
125 mavCom->waitMissionAck(ACK_TIMEOUT);
126 }
127
128 cout << "[INFO] Check mission item list.\n";
129 // mission request list (to check)
130 mavCom->sendMissionRequestList(mavCom->target.getSysID(), mavCom->target.getCompID());
131 //mavCom.waitMissionCount(ACK_TIMEOUT);
132
133 cout << "----------------\n";
134 cout << "Flight plan sent \n";
135 cout << "----------------\n";
136}
137
138void GuiGcs::ParametersParse(const std::string& parametersString, std::array<float, 6>& parametersFloat) {
139 std::string parametersBuffer = parametersString;
140 for (int count = 0; count < parametersFloat.size(); count++) {
141 parametersFloat[count] = std::stof(parametersBuffer.substr(0, parametersBuffer.find(delimiter)));
142 parametersBuffer.erase(0, parametersBuffer.find(delimiter) + delimiter.length());
143 }
144}
145
146uint16_t GuiGcs::MavCommandGet(const std::string& command) const {
147 uint16_t returnValue = -1;
148 if (command == "WAYPOINT") {
149 returnValue = MAV_CMD_NAV_WAYPOINT;
150 }
151 if (command == "TAKEOFF") {
152 returnValue = MAV_CMD_NAV_TAKEOFF;
153 }
154 if (command == "LAND") {
155 returnValue = MAV_CMD_NAV_LAND;
156 }
157 if (command == "RETURN") {
158 returnValue = MAV_CMD_NAV_RETURN_TO_LAUNCH;
159 }
160 if (command == "JUMP") {
161 returnValue = MAV_CMD_DO_JUMP;
162 }
163 return returnValue;
164}
165
166void GuiGcs::Initialize() {
167 cout << "--------------------\n";
168 cout << "Initialization START\n";
169 cout << "--------------------\n";
170
171 // UAV start heartbeat, message ID=0, interval 1000 ms
172 mavCom->cmdSetMessageInterval(mavCom->target.getSysID(), mavCom->target.getCompID(), MAVLINK_MSG_ID_HEARTBEAT, PERIOD_SECOND);
173 mavCom->waitCommandAck(ACK_TIMEOUT);
174
175 usleep(INTER_COMMAND_PAUSE);
176
177 // ask for the autopilot capabilities
178 mavCom->cmdRequestAutopilotCapabilities(mavCom->target.getSysID(), mavCom->target.getCompID());
179 // TODO wait for autopilot version
180 //
181
182 usleep(INTER_COMMAND_PAUSE);
183
184 // initiate system status callback on the UAV, message ID=1, interval 1000 ms
185 mavCom->cmdSetMessageInterval(mavCom->target.getSysID(), mavCom->target.getCompID(), MAVLINK_MSG_ID_SYS_STATUS, PERIOD_SECOND);
186
187 usleep(INTER_COMMAND_PAUSE);
188
189 // initiate system time callback on the UAV
190 mavCom->cmdSetMessageInterval(mavCom->target.getSysID(), mavCom->target.getCompID(), MAVLINK_MSG_ID_SYSTEM_TIME, PERIOD_SECOND);
191
192 usleep(INTER_COMMAND_PAUSE);
193
194 // set preflight mode
195 mavCom->cmdDoSetMode(mavCom->target.getSysID(), mavCom->target.getCompID(), MAV_MODE_PREFLIGHT);
196 mavCom->waitCommandAck(ACK_TIMEOUT);
197
198 usleep(INTER_COMMAND_PAUSE);
199
200 // set home position
201 mavCom->cmdDoSetHome(mavCom->target.getSysID(), mavCom->target.getCompID(), 0);
202 mavCom->waitCommandAck(ACK_TIMEOUT);
203
204 usleep(INTER_COMMAND_PAUSE);
205
206 // clear all mission waypoints
207 mavCom->sendMissionClearAll(mavCom->target.getSysID(), mavCom->target.getCompID());
208 usleep(INTER_COMMAND_PAUSE);
209 mavCom->waitMissionAck(ACK_TIMEOUT);
210 cout << "--------------------\n";
211 cout << "Initialization END\n";
212 cout << "--------------------\n";
213}
Note: See TracBrowser for help on using the repository browser.