source: flair-src/branches/mavlink/tools/Controller/Mavlink/src/GuiGcs.cpp @ 79

Last change on this file since 79 was 79, checked in by Thomas Fuhrmann, 5 years ago

MissionSend? is working

File size: 4.4 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//              Copyright Heudiasyc UMR UTC/CNRS 7253
10//
11//  version:    $Id: $
12//
13//  purpose:    Implementation of GuiInterface, using sockets
14//
15//
16/*********************************************************************/
17
18#include "GuiGcs.h"
19#include "GuiInterface.h"
20
21#include <Socket.h>
22#include <FrameworkManager.h>
23
24#include "MavlinkUDP.h"
25
26#include <ListWidget.h>
27
28//todo remove for tests
29#include <iostream>
30
31using namespace std;
32using namespace flair::core;
33using namespace flair::gui;
34
35GuiGcs::GuiGcs(const FrameworkManager *parent, string name,
36                           std::string &outputAddress, int outputPort):
37                           GuiInterface(parent, name) {
38  cout << "MavPlanner GuiGcs constructor" << endl;
39  //outputSocket = new Socket((Thread *)this, "output socket", outputAddress + ":" + to_string(outputPort));
40
41  mavCom = new MavlinkUDP(outputAddress, outputPort);
42  if (mavCom) {
43    // mavCom->startThreads();   
44  } else {
45    //TODO handle the error
46  }
47 
48}
49
50GuiGcs::~GuiGcs() {
51  if (mavCom) {
52    mavCom->stopThreads();
53    delete mavCom;
54  }
55}
56
57void GuiGcs::MissionStart() {
58  cout << "MavPlanner GuiGcs MissionStart" << endl;
59  outputSocket->SendMessage("MavPlanner GuiGcs MissionStart");
60}
61
62void GuiGcs::MissionStop() {
63  cout << "MavPlanner GuiGcs MissionStop" << endl;
64  outputSocket->SendMessage("MavPlanner GuiGcs MissionStop");
65}
66
67void GuiGcs::MissionResume() {
68  cout << "MavPlanner GuiGcs MissionResume" << endl;
69  outputSocket->SendMessage("MavPlanner GuiGcs MissionResume");
70}
71
72void GuiGcs::MissionSend() {
73  cout << "MavPlanner GuiGcs MissionSend" << endl;
74
75
76  // upload a flight plan
77  cout << "---------------\n";
78  cout << "Flight planning \n";
79  cout << "---------------\n";
80
81  // get the list of commands to send
82  std::vector<std::string> missionCommandList = listMissionItems->GetItemList();
83
84  // reset all the previous waypoints
85  mavCom->sendMissionClearAll(mavCom->target.getSysID(), mavCom->target.getCompID());
86
87  cout << "[INFO] Mission write partial list.\n";
88  // write partial list, takeoff + 4 waypoints + land
89  mavCom->sendMissionWritePartialList(mavCom->target.getSysID(),mavCom->target.getCompID(), 0, missionCommandList.size());
90  mavCom->waitMissionAck(ACK_TIMEOUT);
91
92  // sending mission items
93  cout << "[INFO] Mission items.\n";
94  std::string delimiter = "|";
95  for (auto &missionCommand : missionCommandList) {
96    cout << "[INFO] Mission item : " << missionCommand << "\n";
97    // Parse command
98    std::string command = missionCommand.substr(0, missionCommand.find(delimiter));
99    missionCommand.erase(0, missionCommand.find(delimiter) + delimiter.length());
100    // Parse param1
101    float param1 = std::stof(missionCommand.substr(0, missionCommand.find(delimiter)));
102    missionCommand.erase(0, missionCommand.find(delimiter) + delimiter.length());
103    // Parse param2
104    float param2 = std::stof(missionCommand.substr(0, missionCommand.find(delimiter)));
105    missionCommand.erase(0, missionCommand.find(delimiter) + delimiter.length());
106    // Parse param3
107    float param3 = std::stof(missionCommand.substr(0, missionCommand.find(delimiter)));
108    // cout << "[INFO] Mission item commands : " << command << ", " << param1 << ", " << param2 << ", " << param3 << std::endl;
109    mavCom->sendMissionItem(mavCom->target.getSysID(), mavCom->target.getCompID(), 0, MAV_FRAME_GLOBAL_RELATIVE_ALT, MavCommandGet(command), 0, 1, 0, 0, 0, 0, param1, param2, param3);
110    mavCom->waitMissionAck(ACK_TIMEOUT);
111  }
112
113  cout << "[INFO] Check mission item list.\n";
114  // mission request list (to check)
115  mavCom->sendMissionRequestList(mavCom->target.getSysID(), mavCom->target.getCompID());
116  //mavCom.waitMissionCount(ACK_TIMEOUT);
117
118  cout << "----------------\n";
119  cout << "Flight plan sent \n";
120  cout << "----------------\n";
121}
122
123uint16_t GuiGcs::MavCommandGet(const std::string& command) const {
124  uint16_t returnValue = -1;
125  if (command == "WAYPOINT") {
126    returnValue = MAV_CMD_NAV_WAYPOINT;
127  }
128  if (command == "TAKEOFF") {
129    returnValue = MAV_CMD_NAV_TAKEOFF;
130  }
131  if (command == "LAND") {
132    returnValue = MAV_CMD_NAV_LAND;
133  }
134  if (command == "RETURN") {
135    returnValue = MAV_CMD_NAV_RETURN_TO_LAUNCH;
136  }
137  if (command == "JUMP") {
138    returnValue = MAV_CMD_DO_JUMP;
139  }
140  return returnValue;
141}
Note: See TracBrowser for help on using the repository browser.