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

Last change on this file since 289 was 137, checked in by Sanahuja Guillaume, 8 years ago

singleton manager

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