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

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

m

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