Newer
Older
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009-2012 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Implementation of the waypoint protocol handler
*
* @author Petri Tanskanen <mavteam@student.ethz.ch>
*
*/
#include "UASWaypointManager.h"
#include "UAS.h"
#include "mavlink_types.h"
#include "UASManager.h"
#include "MainWindow.h"
#define PROTOCOL_TIMEOUT_MS 2000 ///< maximum time to wait for pending messages until timeout
#define PROTOCOL_DELAY_MS 20 ///< minimum delay between sent messages
#define PROTOCOL_MAX_RETRIES 5 ///< maximum number of send retries (after timeout)
Michael Carpenter
committed
const float UASWaypointManager::defaultAltitudeHomeOffset = 30.0f;
UASWaypointManager::UASWaypointManager(UAS* _uas)
: uas(_uas),
current_retries(0),
current_wp_id(0),
current_count(0),
current_state(WP_IDLE),
current_partner_systemid(0),
current_partner_compid(0),
Lorenz Meier
committed
currentWaypointEditable(NULL),
protocol_timer(this)
uasid = uas->getUASID();
connect(&protocol_timer, SIGNAL(timeout()), this, SLOT(timeout()));
connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(handleLocalPositionChanged(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(handleGlobalPositionChanged(UASInterface*,double,double,double,quint64)));
}
else
{
uasid = 0;
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries--;
emit updateStatusString(tr("Timeout, retrying (retries left: %1)").arg(current_retries));
sendWaypointRequestList();
} else if (current_state == WP_GETLIST_GETWPS) {
sendWaypointRequest(current_wp_id);
} else if (current_state == WP_SENDLIST) {
sendWaypointCount();
} else if (current_state == WP_SENDLIST_SENDWPS) {
sendWaypoint(current_wp_id);
} else if (current_state == WP_CLEARLIST) {
sendWaypointClearAll();
} else if (current_state == WP_SETCURRENT) {
sendWaypointSetCurrent(current_wp_id);
}
protocol_timer.stop();
emit updateStatusString("Operation timed out.");
current_state = WP_IDLE;
current_count = 0;
current_wp_id = 0;
current_partner_systemid = 0;
current_partner_compid = 0;
}
void UASWaypointManager::handleLocalPositionChanged(UASInterface* mav, double x, double y, double z, quint64 time)
{
Q_UNUSED(mav);
Q_UNUSED(time);
if (waypointsEditable.count() > 0 && currentWaypointEditable && (currentWaypointEditable->getFrame() == MAV_FRAME_LOCAL_NED || currentWaypointEditable->getFrame() == MAV_FRAME_LOCAL_ENU))
double xdiff = x-currentWaypointEditable->getX();
double ydiff = y-currentWaypointEditable->getY();
double zdiff = z-currentWaypointEditable->getZ();
double dist = sqrt(xdiff*xdiff + ydiff*ydiff + zdiff*zdiff);
emit waypointDistanceChanged(dist);
}
}
void UASWaypointManager::handleGlobalPositionChanged(UASInterface* mav, double lat, double lon, double alt, quint64 time)
{
Lorenz Meier
committed
Q_UNUSED(mav);
Q_UNUSED(time);
Q_UNUSED(alt);
Q_UNUSED(lon);
Q_UNUSED(lat);
Lorenz Meier
committed
if (waypointsEditable.count() > 0 && currentWaypointEditable && (currentWaypointEditable->getFrame() == MAV_FRAME_GLOBAL || currentWaypointEditable->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT))
{
// TODO FIXME Calculate distance
double dist = 0;
emit waypointDistanceChanged(dist);
}
void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, quint16 count)
{
if (current_state == WP_GETLIST && systemId == current_partner_systemid) {
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries = PROTOCOL_MAX_RETRIES;
//Clear the old edit-list before receiving the new one
if (read_to_edit == true){
while(waypointsEditable.count()>0) {
Waypoint *t = waypointsEditable[0];
delete t;
}
emit waypointEditableListChanged();
}
current_count = count;
current_wp_id = 0;
current_state = WP_GETLIST_GETWPS;
sendWaypointRequest(current_wp_id);
current_state = WP_IDLE;
current_count = 0;
current_wp_id = 0;
current_partner_systemid = 0;
current_partner_compid = 0;
} else {
qDebug("Rejecting message, check mismatch: current_state: %d == %d, system id %d == %d, comp id %d == %d", current_state, WP_GETLIST, current_partner_systemid, systemId, current_partner_compid, compId);
void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_mission_item_t *wp)
if (systemId == current_partner_systemid && current_state == WP_GETLIST_GETWPS && wp->seq == current_wp_id) {
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries = PROTOCOL_MAX_RETRIES;
Waypoint *lwp_vo = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->param1, wp->param2, wp->param3, wp->param4, wp->autocontinue, wp->current, (MAV_FRAME) wp->frame, (MAV_CMD) wp->command);
addWaypointViewOnly(lwp_vo);
if (read_to_edit == true) {
Waypoint *lwp_ed = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->param1, wp->param2, wp->param3, wp->param4, wp->autocontinue, wp->current, (MAV_FRAME) wp->frame, (MAV_CMD) wp->command);
addWaypointEditable(lwp_ed, false);
if (wp->current == 1) currentWaypointEditable = lwp_ed;
}
if(current_wp_id < current_count) {
sendWaypointRequest(current_wp_id);
sendWaypointAck(0);
current_state = WP_IDLE;
current_count = 0;
current_wp_id = 0;
current_partner_systemid = 0;
current_partner_compid = 0;
QTime time = QTime::currentTime();
QString timeString = time.toString();
emit updateStatusString(tr("done. (updated at %1)").arg(timeString));
emit updateStatusString(tr("Waypoint ID mismatch, rejecting waypoint"));
} else {
qDebug("Rejecting message, check mismatch: current_state: %d == %d, system id %d == %d, comp id %d == %d", current_state, WP_GETLIST, current_partner_systemid, systemId, current_partner_compid, compId);
void UASWaypointManager::handleWaypointAck(quint8 systemId, quint8 compId, mavlink_mission_ack_t *wpa)
Bryant Mairs
committed
if (systemId == current_partner_systemid && (compId == current_partner_compid || compId == MAV_COMP_ID_ALL)) {
if((current_state == WP_SENDLIST || current_state == WP_SENDLIST_SENDWPS) && (current_wp_id == waypoint_buffer.count()-1 && wpa->type == 0)) {
//all waypoints sent and ack received
protocol_timer.stop();
current_state = WP_IDLE;
readWaypoints(false); //Update "Onboard Waypoints"-tab immidiately after the waypoint list has been sent.
emit updateStatusString("done.");
} else if((current_state == WP_SENDLIST || current_state == WP_SENDLIST_SENDWPS) && wpa->type != 0) {
//give up transmitting if a WP is rejected
if (wpa->type == 1) {
emit updateStatusString("upload failed: general error");
} else if (wpa->type == 2) {
emit updateStatusString("upload failed: coordinate frame unsupported.");
} else {
emit updateStatusString("upload failed: other error.");
}
protocol_timer.stop();
current_state = WP_IDLE;
} else if(current_state == WP_CLEARLIST) {
protocol_timer.stop();
current_state = WP_IDLE;
emit updateStatusString("done.");
}
void UASWaypointManager::handleWaypointRequest(quint8 systemId, quint8 compId, mavlink_mission_request_t *wpr)
if (systemId == current_partner_systemid && ((current_state == WP_SENDLIST && wpr->seq == 0) || (current_state == WP_SENDLIST_SENDWPS && (wpr->seq == current_wp_id || wpr->seq == current_wp_id + 1)))) {
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries = PROTOCOL_MAX_RETRIES;
if (wpr->seq < waypoint_buffer.count()) {
current_state = WP_SENDLIST_SENDWPS;
current_wp_id = wpr->seq;
sendWaypoint(current_wp_id);
} else {
qDebug("Rejecting message, check mismatch: current_state: %d == %d, system id %d == %d, comp id %d == %d", current_state, WP_GETLIST, current_partner_systemid, systemId, current_partner_compid, compId);
void UASWaypointManager::handleWaypointReached(quint8 systemId, quint8 compId, mavlink_mission_item_reached_t *wpr)
if (systemId == uasid) {
emit updateStatusString(QString("Reached waypoint %1").arg(wpr->seq));
}
void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, mavlink_mission_current_t *wpc)
Lorenz Meier
committed
Q_UNUSED(compId);
if (systemId == uasid) {
if (current_state == WP_SETCURRENT) {
protocol_timer.stop();
current_state = WP_IDLE;
// update the local main storage
if (wpc->seq < waypointsViewOnly.size()) {
for(int i = 0; i < waypointsViewOnly.size(); i++) {
if (waypointsViewOnly[i]->getId() == wpc->seq) {
waypointsViewOnly[i]->setCurrent(true);
}
}
}
emit updateStatusString(QString("New current waypoint %1").arg(wpc->seq));
//emit update to UI widgets
emit currentWaypointChanged(wpc->seq);
pixhawk
committed
void UASWaypointManager::notifyOfChangeEditable(Waypoint* wp)
pixhawk
committed
{
// If only one waypoint was changed, emit only WP signal
emit waypointEditableChanged(uasid, wp);
pixhawk
committed
emit waypointEditableListChanged();
emit waypointEditableListChanged(uasid);
pixhawk
committed
}
void UASWaypointManager::notifyOfChangeViewOnly(Waypoint* wp)
{
if (wp != NULL) {
emit waypointViewOnlyChanged(uasid, wp);
} else {
emit waypointViewOnlyListChanged();
emit waypointViewOnlyListChanged(uasid);
}
}
pixhawk
committed
int UASWaypointManager::setCurrentWaypoint(quint16 seq)
//send change to UAS - important to note: if the transmission fails, we have inconsistencies
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries = PROTOCOL_MAX_RETRIES;
current_state = WP_SETCURRENT;
current_wp_id = seq;
current_partner_systemid = uasid;
current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
sendWaypointSetCurrent(current_wp_id);
return 0;
}
}
return -1;
}
int UASWaypointManager::setCurrentEditable(quint16 seq)
{
if (seq < waypointsEditable.count()) {
if(current_state == WP_IDLE) {
//update local main storage
for(int i = 0; i < waypointsEditable.count(); i++) {
if (waypointsEditable[i]->getId() == seq) {
waypointsEditable[i]->setCurrent(true);
} else {
waypointsEditable[i]->setCurrent(false);
}
}
return 0;
}
}
return -1;
}
void UASWaypointManager::addWaypointViewOnly(Waypoint *wp)
{
if (wp)
{
waypointsViewOnly.insert(waypointsViewOnly.size(), wp);
connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeViewOnly(Waypoint*)));
emit waypointViewOnlyListChanged();
emit waypointViewOnlyListChanged(uasid);
* @warning Make sure the waypoint stays valid for the whole application lifecycle!
* @param enforceFirstActive Enforces that the first waypoint is set as active
* @see createWaypoint() is more suitable for most use cases
pixhawk
committed
void UASWaypointManager::addWaypointEditable(Waypoint *wp, bool enforceFirstActive)
// Check if this is the first waypoint in an offline list
if (waypointsEditable.count() == 0 && uas == NULL)
MainWindow::instance()->showCriticalMessage(tr("OFFLINE Waypoint Editing Mode"), tr("You are in offline editing mode. Make sure to safe your mission to a file before connecting to a system - you will need to load the file into the system, the offline list will be cleared on connect."));
wp->setId(waypointsEditable.count());
if (enforceFirstActive && waypointsEditable.count() == 0)
{
wp->setCurrent(true);
waypointsEditable.insert(waypointsEditable.count(), wp);
pixhawk
committed
connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*)));
pixhawk
committed
emit waypointEditableListChanged();
emit waypointEditableListChanged(uasid);
/**
* @param enforceFirstActive Enforces that the first waypoint is set as active
*/
Waypoint* UASWaypointManager::createWaypoint(bool enforceFirstActive)
{
// Check if this is the first waypoint in an offline list
if (waypointsEditable.count() == 0 && uas == NULL)
MainWindow::instance()->showCriticalMessage(tr("OFFLINE Waypoint Editing Mode"), tr("You are in offline editing mode. Make sure to safe your mission to a file before connecting to a system - you will need to load the file into the system, the offline list will be cleared on connect."));
wp->setId(waypointsEditable.count());
wp->setFrame((MAV_FRAME)getFrameRecommendation());
wp->setAltitude(getAltitudeRecommendation());
wp->setAcceptanceRadius(getAcceptanceRadiusRecommendation());
if (enforceFirstActive && waypointsEditable.count() == 0)
{
wp->setCurrent(true);
waypointsEditable.append(wp);
pixhawk
committed
connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*)));
pixhawk
committed
emit waypointEditableListChanged();
emit waypointEditableListChanged(uasid);
int UASWaypointManager::removeWaypoint(quint16 seq)
if (seq < waypointsEditable.count())
pixhawk
committed
if (t->getCurrent() == true) //trying to remove the current waypoint
{
if (seq+1 < waypointsEditable.count()) // setting the next waypoint as current
pixhawk
committed
{
waypointsEditable[seq+1]->setCurrent(true);
}
else if (seq-1 >= 0) // if deleting the last on the list, then setting the previous waypoint as current
pixhawk
committed
{
waypointsEditable[seq-1]->setCurrent(true);
}
}
t = NULL;
for(int i = seq; i < waypointsEditable.count(); i++)
pixhawk
committed
emit waypointEditableListChanged();
emit waypointEditableListChanged(uasid);
return 0;
}
return -1;
}
void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq)
if (cur_seq != new_seq && cur_seq < waypointsEditable.count() && new_seq < waypointsEditable.count())
for (int i = cur_seq; i < new_seq; i++)
{
waypointsEditable[i]->setId(i);
}
else
{
for (int i = cur_seq; i > new_seq; i--)
{
waypointsEditable[i]->setId(i);
waypointsEditable[new_seq]->setId(new_seq);
pixhawk
committed
emit waypointEditableListChanged();
emit waypointEditableListChanged(uasid);
}
}
void UASWaypointManager::saveWaypoints(const QString &saveFile)
{
QFile file(saveFile);
if (!file.open(QIODevice::WriteOnly | QIODevice::Text))
return;
QTextStream out(&file);
//write the waypoint list version to the first line for compatibility check
out << "QGC WPL 120\r\n";
for (int i = 0; i < waypointsEditable.count(); i++)
waypointsEditable[i]->setId(i);
waypointsEditable[i]->save(out);
}
file.close();
}
void UASWaypointManager::loadWaypoints(const QString &loadFile)
{
QFile file(loadFile);
if (!file.open(QIODevice::ReadOnly | QIODevice::Text))
return;
while(waypointsEditable.count()>0) {
delete t;
}
QTextStream in(&file);
const QStringList &version = in.readLine().split(" ");
if (!(version.size() == 3 && version[0] == "QGC" && version[1] == "WPL" && version[2] == "120"))
emit updateStatusString(tr("The waypoint file is not compatible with the current version of QGroundControl."));
}
else
{
while (!in.atEnd())
{
Waypoint *t = new Waypoint();
if(t->load(in))
{
t->setId(waypointsEditable.count());
waypointsEditable.insert(waypointsEditable.count(), t);
emit updateStatusString(tr("The waypoint file is corrupted. Load operation only partly succesful."));
break;
}
file.close();
pixhawk
committed
emit waypointEditableListChanged();
emit waypointEditableListChanged(uasid);
}
void UASWaypointManager::clearWaypointList()
if (current_state == WP_IDLE)
current_retries = PROTOCOL_MAX_RETRIES;
current_state = WP_CLEARLIST;
current_wp_id = 0;
current_partner_systemid = uasid;
current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
sendWaypointClearAll();
const QList<Waypoint *> UASWaypointManager::getGlobalFrameWaypointList()
{
// TODO Keep this global frame list up to date
// with complete waypoint list
// instead of filtering on each request
{
if (wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
{
wps.append(wp);
}
}
return wps;
}
const QList<Waypoint *> UASWaypointManager::getGlobalFrameAndNavTypeWaypointList()
{
// TODO Keep this global frame list up to date
// with complete waypoint list
// instead of filtering on each request
{
if ((wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && wp->isNavigationType())
{
const QList<Waypoint *> UASWaypointManager::getNavTypeWaypointList()
{
// TODO Keep this global frame list up to date
// with complete waypoint list
// instead of filtering on each request
{
if (wp->isNavigationType())
{
int UASWaypointManager::getIndexOf(Waypoint* wp)
{
int UASWaypointManager::getGlobalFrameIndexOf(Waypoint* wp)
{
// counting only those in global frame
int i = 0;
if (p->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
{
if (p == wp)
{
return i;
}
i++;
}
}
return -1;
}
int UASWaypointManager::getGlobalFrameAndNavTypeIndexOf(Waypoint* wp)
{
if ((p->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && p->isNavigationType())
{
if (p->isNavigationType())
{
if (p == wp)
{
int UASWaypointManager::getGlobalFrameCount()
{
// counting only those in global frame
int i = 0;
if (p->getFrame() == MAV_FRAME_GLOBAL || p->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
{
i++;
}
}
return i;
}
if ((p->getFrame() == MAV_FRAME_GLOBAL || p->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && p->isNavigationType())
if (p->isNavigationType()) {
i++;
}
}
return i;
}
int UASWaypointManager::getLocalFrameCount()
{
// counting only those in global frame
int i = 0;
if (p->getFrame() == MAV_FRAME_LOCAL_NED || p->getFrame() == MAV_FRAME_LOCAL_ENU)
i++;
}
}
return i;
}
int UASWaypointManager::getLocalFrameIndexOf(Waypoint* wp)
{
// counting only those in local frame
int i = 0;
{
if (p->getFrame() == MAV_FRAME_LOCAL_NED || p->getFrame() == MAV_FRAME_LOCAL_ENU)
{
if (p == wp)
{
return i;
}
i++;
}
}
return -1;
}
int UASWaypointManager::getMissionFrameIndexOf(Waypoint* wp)
{
// counting only those in mission frame
int i = 0;
if (p->getFrame() == MAV_FRAME_MISSION)
{
if (p == wp)
{
return i;
}
i++;
}
}
return -1;
}
/**
* @param readToEdit If true, incoming waypoints will be copied both to "edit"-tab and "view"-tab. Otherwise, only to "view"-tab.
*/
void UASWaypointManager::readWaypoints(bool readToEdit)
//Clear the old view-list before receiving the new one
while(waypointsViewOnly.size()>0) {
Waypoint *t = waypointsViewOnly[0];
delete t;
}
emit waypointViewOnlyListChanged();
/* THIS PART WAS MOVED TO handleWaypointCount. THE EDIT-LIST SHOULD NOT BE CLEARED UNLESS THERE IS A RESPONSE FROM UAV.
//Clear the old edit-list before receiving the new one
if (read_to_edit == true){
while(waypointsEditable.count()>0) {
Waypoint *t = waypointsEditable[0];
waypointsEditable.remove(0);
delete t;
}
emit waypointEditableListChanged();
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries = PROTOCOL_MAX_RETRIES;
current_partner_systemid = uasid;
current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
sendWaypointRequestList();
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
bool UASWaypointManager::guidedModeSupported()
{
return (uas->getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA);
}
void UASWaypointManager::goToWaypoint(Waypoint *wp)
{
//Don't try to send a guided mode message to an AP that does not support it.
if (uas->getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA)
{
mavlink_mission_item_t mission;
memset(&mission, 0, sizeof(mavlink_mission_item_t)); //initialize with zeros
//const Waypoint *cur_s = waypointsEditable.at(i);
mission.autocontinue = 0;
mission.current = 2; //2 for guided mode
mission.param1 = wp->getParam1();
mission.param2 = wp->getParam2();
mission.param3 = wp->getParam3();
mission.param4 = wp->getParam4();
mission.frame = wp->getFrame();
mission.command = wp->getAction();
mission.seq = 0; // don't read out the sequence number of the waypoint class
mission.x = wp->getX();
mission.y = wp->getY();
mission.z = wp->getZ();
mavlink_message_t message;
mission.target_system = uasid;
mission.target_component = MAV_COMP_ID_MISSIONPLANNER;
mavlink_msg_mission_item_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &mission);
uas->sendMessage(message);
QGC::SLEEP::msleep(PROTOCOL_DELAY_MS);
}
}
void UASWaypointManager::writeWaypoints()
current_retries = PROTOCOL_MAX_RETRIES;
current_state = WP_SENDLIST;
current_wp_id = 0;
current_partner_systemid = uasid;
current_partner_compid = MAV_COMP_ID_MISSIONPLANNER;
// Why not replace with waypoint_buffer.clear() ?
// because this will lead to memory leaks, the waypoint-structs
// have to be deleted, clear() would only delete the pointers.
delete waypoint_buffer.back();
waypoint_buffer.pop_back();
}
bool noCurrent = true;
for (int i=0; i < current_count; i++) {
waypoint_buffer.push_back(new mavlink_mission_item_t);
mavlink_mission_item_t *cur_d = waypoint_buffer.back();
memset(cur_d, 0, sizeof(mavlink_mission_item_t)); //initialize with zeros
cur_d->autocontinue = cur_s->getAutoContinue();
cur_d->current = cur_s->getCurrent() & noCurrent; //make sure only one current waypoint is selected, the first selected will be chosen
cur_d->param1 = cur_s->getParam1();
cur_d->param2 = cur_s->getParam2();
cur_d->param3 = cur_s->getParam3();
cur_d->param4 = cur_s->getParam4();
cur_d->frame = cur_s->getFrame();
cur_d->seq = i; // don't read out the sequence number of the waypoint class
cur_d->x = cur_s->getX();
cur_d->y = cur_s->getY();
cur_d->z = cur_s->getZ();
if (cur_s->getCurrent() && noCurrent)
noCurrent = false;
if (i == (current_count - 1) && noCurrent == true) //not a single waypoint was set as "current"
cur_d->current = true; // set the last waypoint as current. Or should it better be the first waypoint ?
//send the waypoint count to UAS (this starts the send transaction)
sendWaypointCount();
{
}
//we're in another transaction, ignore command
qDebug() << "UASWaypointManager::sendWaypoints() doing something else ignoring command";
void UASWaypointManager::sendWaypointClearAll()
{
mavlink_message_t message;
wpca.target_system = uasid;
wpca.target_component = MAV_COMP_ID_MISSIONPLANNER;
emit updateStatusString(QString("Clearing waypoint list..."));
mavlink_msg_mission_clear_all_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpca);
uas->sendMessage(message);
}
void UASWaypointManager::sendWaypointSetCurrent(quint16 seq)
{
mavlink_message_t message;
wpsc.target_system = uasid;
wpsc.target_component = MAV_COMP_ID_MISSIONPLANNER;
wpsc.seq = seq;
emit updateStatusString(QString("Updating target waypoint..."));
mavlink_msg_mission_set_current_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpsc);
uas->sendMessage(message);
}
void UASWaypointManager::sendWaypointCount()
{
mavlink_message_t message;
wpc.target_system = uasid;
wpc.target_component = MAV_COMP_ID_MISSIONPLANNER;
wpc.count = current_count;
emit updateStatusString(QString("Starting to transmit waypoints..."));
mavlink_msg_mission_count_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wpc);
uas->sendMessage(message);
}
void UASWaypointManager::sendWaypointRequestList()
{
mavlink_message_t message;
wprl.target_system = uasid;
wprl.target_component = MAV_COMP_ID_MISSIONPLANNER;
QString statusMsg(tr("Requesting waypoint list..."));
qDebug() << __FILE__ << __LINE__ << statusMsg;
emit updateStatusString(statusMsg);
mavlink_msg_mission_request_list_encode(uas->mavlink->getSystemId(), uas->mavlink->getComponentId(), &message, &wprl);
uas->sendMessage(message);
void UASWaypointManager::sendWaypointRequest(quint16 seq)