Browse Source

Merge branch 'master' of git@pixhawk.ethz.ch:qgroundcontrol

QGC4.4
lm 15 years ago
parent
commit
6ba7f6cbf3
  1. 9
      qgroundcontrol.pri
  2. 19
      src/uas/UAS.cc
  3. 268
      src/uas/UASWaypointManager.cc
  4. 58
      src/uas/UASWaypointManager.h
  5. 35
      src/ui/WaypointList.cc
  6. 4
      src/ui/WaypointList.h
  7. 2
      src/ui/WaypointView.cc
  8. 1
      src/ui/WaypointView.h
  9. 1
      src/ui/linechart/LinechartWidget.cc

9
qgroundcontrol.pri

@ -37,16 +37,17 @@ message(Qt version $$[QT_VERSION])
macx { macx {
HARDWARE_PLATFORM = $$system(uname -a) HARDWARE_PLATFORM = $$system(uname -a)
contains( HARDWARE_PLATFORM, 9.8.0 ) { contains( HARDWARE_PLATFORM, 9.6.0 ) || contains( HARDWARE_PLATFORM, 9.7.0 ) || contains( HARDWARE_PLATFORM, 9.8.0 ) || || contains( HARDWARE_PLATFORM, 9.9.0 )
{
# x86 Mac OS X Leopard 10.5 and earlier # x86 Mac OS X Leopard 10.5 and earlier
CONFIG += x86 cocoa phonon CONFIG += x86 cocoa phonon
message(Building for Mac OS X 32bit/Leopard 10.5 and earlier) message(Building for Mac OS X 32bit/Leopard 10.5 and earlier)
# Enable function-profiling with the OS X saturn tool # Enable function-profiling with the OS X saturn tool
debug { debug {
#QMAKE_CXXFLAGS += -finstrument-functions #QMAKE_CXXFLAGS += -finstrument-functions
#LIBS += -lSaturn #LIBS += -lSaturn
} }
} else { } else {
# x64 Mac OS X Snow Leopard 10.6 and later # x64 Mac OS X Snow Leopard 10.6 and later
CONFIG += x86_64 cocoa CONFIG += x86_64 cocoa

19
src/uas/UAS.cc

@ -437,6 +437,17 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
} }
break; break;
case MAVLINK_MSG_ID_WAYPOINT_ACK:
{
mavlink_waypoint_ack_t wpa;
mavlink_msg_waypoint_ack_decode(&message, &wpa);
if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
{
waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
}
}
break;
case MAVLINK_MSG_ID_WAYPOINT_REQUEST: case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
{ {
mavlink_waypoint_request_t wpr; mavlink_waypoint_request_t wpr;
@ -456,11 +467,11 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
} }
break; break;
case MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT: case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
{ {
mavlink_waypoint_set_current_t wpsc; mavlink_waypoint_current_t wpc;
mavlink_msg_waypoint_set_current_decode(&message, &wpsc); mavlink_msg_waypoint_current_decode(&message, &wpc);
waypointManager.handleWaypointSetCurrent(message.sysid, message.compid, &wpsc); waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
} }
break; break;

268
src/uas/UASWaypointManager.cc

@ -32,10 +32,13 @@ This file is part of the PIXHAWK project
#include "UASWaypointManager.h" #include "UASWaypointManager.h"
#include "UAS.h" #include "UAS.h"
#define PROTOCOL_TIMEOUT_MS 2000 #define PROTOCOL_TIMEOUT_MS 2000 ///< maximum time to wait for pending messages until timeout
#define PROTOCOL_DELAY_MS 40 ///< minimum delay between sent messages
#define PROTOCOL_MAX_RETRIES 3 ///< maximum number of send retries (after timeout)
UASWaypointManager::UASWaypointManager(UAS &_uas) UASWaypointManager::UASWaypointManager(UAS &_uas)
: uas(_uas), : uas(_uas),
current_retries(0),
current_wp_id(0), current_wp_id(0),
current_count(0), current_count(0),
current_state(WP_IDLE), current_state(WP_IDLE),
@ -48,25 +51,59 @@ UASWaypointManager::UASWaypointManager(UAS &_uas)
void UASWaypointManager::timeout() void UASWaypointManager::timeout()
{ {
protocol_timer.stop(); if (current_retries > 0)
{
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries--;
qDebug() << "Timeout, retrying (retries left:" << current_retries << ")";
if (current_state == WP_GETLIST)
{
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);
}
}
else
{
protocol_timer.stop();
qDebug() << "Waypoint transaction (state=" << current_state << ") timed out going to state WP_IDLE"; qDebug() << "Waypoint transaction (state=" << current_state << ") timed out going to state WP_IDLE";
emit updateStatusString("Operation timed out."); emit updateStatusString("Operation timed out.");
current_state = WP_IDLE; current_state = WP_IDLE;
current_count = 0; current_count = 0;
current_wp_id = 0; current_wp_id = 0;
current_partner_systemid = 0; current_partner_systemid = 0;
current_partner_compid = 0; current_partner_compid = 0;
}
} }
void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, quint16 count) void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, quint16 count)
{ {
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
if (current_state == WP_GETLIST && systemId == current_partner_systemid && compId == current_partner_compid) if (current_state == WP_GETLIST && systemId == current_partner_systemid && compId == current_partner_compid)
{ {
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries = PROTOCOL_MAX_RETRIES;
qDebug() << "got waypoint count (" << count << ") from ID " << systemId; qDebug() << "got waypoint count (" << count << ") from ID " << systemId;
if (count > 0) if (count > 0)
@ -87,10 +124,11 @@ void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, qui
void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_waypoint_t *wp) void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_waypoint_t *wp)
{ {
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
if (systemId == current_partner_systemid && compId == current_partner_compid && current_state == WP_GETLIST_GETWPS && wp->seq == current_wp_id) if (systemId == current_partner_systemid && compId == current_partner_compid && current_state == WP_GETLIST_GETWPS && wp->seq == current_wp_id)
{ {
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries = PROTOCOL_MAX_RETRIES;
if(wp->seq == current_wp_id) if(wp->seq == current_wp_id)
{ {
//update the UI FIXME //update the UI FIXME
@ -105,6 +143,8 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
} }
else else
{ {
sendWaypointAck(0);
// all waypoints retrieved, change state to idle // all waypoints retrieved, change state to idle
current_state = WP_IDLE; current_state = WP_IDLE;
current_count = 0; current_count = 0;
@ -125,30 +165,40 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
} }
} }
void UASWaypointManager::handleWaypointRequest(quint8 systemId, quint8 compId, mavlink_waypoint_request_t *wpr) void UASWaypointManager::handleWaypointAck(quint8 systemId, quint8 compId, mavlink_waypoint_ack_t *wpa)
{ {
protocol_timer.start(PROTOCOL_TIMEOUT_MS); if (systemId == current_partner_systemid && compId == current_partner_compid)
{
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;
emit updateStatusString("done.");
qDebug() << "sent all waypoints to ID " << systemId;
}
else if(current_state == WP_CLEARLIST)
{
protocol_timer.stop();
current_state = WP_IDLE;
emit updateStatusString("done.");
qDebug() << "cleared waypoint list of ID " << systemId;
}
}
}
if (systemId == current_partner_systemid && compId == current_partner_compid && ((current_state == WP_SENDLIST && wpr->seq == 0) || (current_state == WP_SENDLIST_SENDWPS && (wpr->seq == current_wp_id || wpr->seq == current_wp_id + 1)) || (current_state == WP_IDLE && wpr->seq == current_count-1))) void UASWaypointManager::handleWaypointRequest(quint8 systemId, quint8 compId, mavlink_waypoint_request_t *wpr)
{
if (systemId == current_partner_systemid && compId == current_partner_compid && ((current_state == WP_SENDLIST && wpr->seq == 0) || (current_state == WP_SENDLIST_SENDWPS && (wpr->seq == current_wp_id || wpr->seq == current_wp_id + 1))))
{ {
qDebug() << "handleWaypointRequest"; protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries = PROTOCOL_MAX_RETRIES;
if (wpr->seq < waypoint_buffer.count()) if (wpr->seq < waypoint_buffer.count())
{ {
current_state = WP_SENDLIST_SENDWPS; current_state = WP_SENDLIST_SENDWPS;
current_wp_id = wpr->seq; current_wp_id = wpr->seq;
sendWaypoint(current_wp_id); sendWaypoint(current_wp_id);
if(current_wp_id == waypoint_buffer.count()-1)
{
//all waypoints sent, but we still have to wait for a possible rerequest of the last waypoint
current_state = WP_IDLE;
protocol_timer.stop();
emit updateStatusString("done.");
qDebug() << "send all waypoints to ID " << systemId;
}
} }
else else
{ {
@ -165,54 +215,77 @@ void UASWaypointManager::handleWaypointReached(quint8 systemId, quint8 compId, m
} }
} }
void UASWaypointManager::handleWaypointSetCurrent(quint8 systemId, quint8 compId, mavlink_waypoint_set_current_t *wpr) void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, mavlink_waypoint_current_t *wpc)
{ {
if (systemId == uas.getUASID() && compId == MAV_COMP_ID_WAYPOINTPLANNER) if (systemId == uas.getUASID() && compId == MAV_COMP_ID_WAYPOINTPLANNER)
{ {
qDebug() << "new current waypoint" << wpr->seq; if (current_state == WP_SETCURRENT)
emit currentWaypointChanged(wpr->seq); {
protocol_timer.stop();
current_state = WP_IDLE;
emit updateStatusString(QString("New current waypoint %1").arg(wpc->seq));
}
qDebug() << "new current waypoint" << wpc->seq;
emit currentWaypointChanged(wpc->seq);
} }
} }
void UASWaypointManager::clearWaypointList() void UASWaypointManager::clearWaypointList()
{ {
if(current_state == WP_IDLE)
{
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries = PROTOCOL_MAX_RETRIES;
current_state = WP_CLEARLIST;
current_wp_id = 0;
current_partner_systemid = uas.getUASID();
current_partner_compid = MAV_COMP_ID_WAYPOINTPLANNER;
sendWaypointClearAll();
}
} }
void UASWaypointManager::requestWaypoints() void UASWaypointManager::setCurrent(quint16 seq)
{ {
if(current_state == WP_IDLE) if(current_state == WP_IDLE)
{ {
protocol_timer.start(PROTOCOL_TIMEOUT_MS); protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries = PROTOCOL_MAX_RETRIES;
current_state = WP_SETCURRENT;
current_wp_id = seq;
current_partner_systemid = uas.getUASID();
current_partner_compid = MAV_COMP_ID_WAYPOINTPLANNER;
mavlink_message_t message; sendWaypointSetCurrent(current_wp_id);
mavlink_waypoint_request_list_t wprl; }
}
wprl.target_system = uas.getUASID(); void UASWaypointManager::readWaypoints()
wprl.target_component = MAV_COMP_ID_WAYPOINTPLANNER; {
if(current_state == WP_IDLE)
{
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries = PROTOCOL_MAX_RETRIES;
current_state = WP_GETLIST; current_state = WP_GETLIST;
current_wp_id = 0; current_wp_id = 0;
current_partner_systemid = uas.getUASID(); current_partner_systemid = uas.getUASID();
current_partner_compid = MAV_COMP_ID_WAYPOINTPLANNER; current_partner_compid = MAV_COMP_ID_WAYPOINTPLANNER;
const QString str = QString("requesting waypoint list..."); sendWaypointRequestList();
emit updateStatusString(str);
mavlink_msg_waypoint_request_list_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wprl);
uas.sendMessage(message);
qDebug() << "sent waypoint list request to ID " << wprl.target_system;
} }
} }
void UASWaypointManager::sendWaypoints() void UASWaypointManager::writeWaypoints()
{ {
if (current_state == WP_IDLE) if (current_state == WP_IDLE)
{ {
if (waypoints.count() > 0) if (waypoints.count() > 0)
{ {
protocol_timer.start(PROTOCOL_TIMEOUT_MS); protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries = PROTOCOL_MAX_RETRIES;
current_count = waypoints.count(); current_count = waypoints.count();
current_state = WP_SENDLIST; current_state = WP_SENDLIST;
@ -250,20 +323,7 @@ void UASWaypointManager::sendWaypoints()
} }
//send the waypoint count to UAS (this starts the send transaction) //send the waypoint count to UAS (this starts the send transaction)
mavlink_message_t message; sendWaypointCount();
mavlink_waypoint_count_t wpc;
wpc.target_system = uas.getUASID();
wpc.target_component = MAV_COMP_ID_WAYPOINTPLANNER;
wpc.count = current_count;
const QString str = QString("start transmitting waypoints...");
emit updateStatusString(str);
mavlink_msg_waypoint_count_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wpc);
uas.sendMessage(message);
qDebug() << "sent waypoint count (" << wpc.count << ") to ID " << wpc.target_system;
} }
} }
else else
@ -273,6 +333,80 @@ void UASWaypointManager::sendWaypoints()
} }
} }
void UASWaypointManager::sendWaypointClearAll()
{
mavlink_message_t message;
mavlink_waypoint_clear_all_t wpca;
wpca.target_system = uas.getUASID();
wpca.target_component = MAV_COMP_ID_WAYPOINTPLANNER;
const QString str = QString("clearing waypoint list...");
emit updateStatusString(str);
mavlink_msg_waypoint_clear_all_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wpca);
uas.sendMessage(message);
usleep(PROTOCOL_DELAY_MS * 1000);
qDebug() << "sent waypoint clear all to ID " << wpca.target_system;
}
void UASWaypointManager::sendWaypointSetCurrent(quint16 seq)
{
mavlink_message_t message;
mavlink_waypoint_set_current_t wpsc;
wpsc.target_system = uas.getUASID();
wpsc.target_component = MAV_COMP_ID_WAYPOINTPLANNER;
wpsc.seq = seq;
const QString str = QString("Updating target waypoint...");
emit updateStatusString(str);
mavlink_msg_waypoint_set_current_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wpsc);
uas.sendMessage(message);
usleep(PROTOCOL_DELAY_MS * 1000);
qDebug() << "sent waypoint set current (" << wpsc.seq << ") to ID " << wpsc.target_system;
}
void UASWaypointManager::sendWaypointCount()
{
mavlink_message_t message;
mavlink_waypoint_count_t wpc;
wpc.target_system = uas.getUASID();
wpc.target_component = MAV_COMP_ID_WAYPOINTPLANNER;
wpc.count = current_count;
const QString str = QString("start transmitting waypoints...");
emit updateStatusString(str);
mavlink_msg_waypoint_count_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wpc);
uas.sendMessage(message);
usleep(PROTOCOL_DELAY_MS * 1000);
qDebug() << "sent waypoint count (" << wpc.count << ") to ID " << wpc.target_system;
}
void UASWaypointManager::sendWaypointRequestList()
{
mavlink_message_t message;
mavlink_waypoint_request_list_t wprl;
wprl.target_system = uas.getUASID();
wprl.target_component = MAV_COMP_ID_WAYPOINTPLANNER;
const QString str = QString("requesting waypoint list...");
emit updateStatusString(str);
mavlink_msg_waypoint_request_list_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wprl);
uas.sendMessage(message);
usleep(PROTOCOL_DELAY_MS * 1000);
qDebug() << "sent waypoint list request to ID " << wprl.target_system;
}
void UASWaypointManager::sendWaypointRequest(quint16 seq) void UASWaypointManager::sendWaypointRequest(quint16 seq)
{ {
mavlink_message_t message; mavlink_message_t message;
@ -287,6 +421,7 @@ void UASWaypointManager::sendWaypointRequest(quint16 seq)
mavlink_msg_waypoint_request_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wpr); mavlink_msg_waypoint_request_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wpr);
uas.sendMessage(message); uas.sendMessage(message);
usleep(PROTOCOL_DELAY_MS * 1000);
qDebug() << "sent waypoint request (" << wpr.seq << ") to ID " << wpr.target_system; qDebug() << "sent waypoint request (" << wpr.seq << ") to ID " << wpr.target_system;
} }
@ -308,7 +443,24 @@ void UASWaypointManager::sendWaypoint(quint16 seq)
mavlink_msg_waypoint_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, wp); mavlink_msg_waypoint_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, wp);
uas.sendMessage(message); uas.sendMessage(message);
usleep(PROTOCOL_DELAY_MS * 1000);
qDebug() << "sent waypoint (" << wp->seq << ") to ID " << wp->target_system; qDebug() << "sent waypoint (" << wp->seq << ") to ID " << wp->target_system;
} }
} }
void UASWaypointManager::sendWaypointAck(quint8 type)
{
mavlink_message_t message;
mavlink_waypoint_ack_t wpa;
wpa.target_system = uas.getUASID();
wpa.target_component = MAV_COMP_ID_WAYPOINTPLANNER;
wpa.type = type;
mavlink_msg_waypoint_ack_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wpa);
uas.sendMessage(message);
usleep(PROTOCOL_DELAY_MS * 1000);
qDebug() << "sent waypoint ack (" << wpa.type << ") to ID " << wpa.target_system;
}

58
src/uas/UASWaypointManager.h

@ -39,38 +39,59 @@ This file is part of the PIXHAWK project
#include <mavlink.h> #include <mavlink.h>
class UAS; class UAS;
/**
* @brief Implementation of the MAVLINK waypoint protocol
*
* This class handles the communication with a waypoint manager on the MAV.
* All waypoints are stored in the QVector waypoints, modifications can be done with the WaypointList widget.
* Notice that currently the access to the internal waypoint storage is not guarded nor thread-safe. This works as long as no other widget alters the data.
*
* See http://qgroundcontrol.org/waypoint_protocol for more information about the protocol and the states.
*/
class UASWaypointManager : public QObject class UASWaypointManager : public QObject
{ {
Q_OBJECT Q_OBJECT
private: private:
enum WaypointState { enum WaypointState {
WP_IDLE = 0, WP_IDLE = 0, ///< Waiting for commands
WP_SENDLIST, WP_SENDLIST, ///< Initial state for sending waypoints to the MAV
WP_SENDLIST_SENDWPS, WP_SENDLIST_SENDWPS,///< Sending waypoints
WP_GETLIST, WP_GETLIST, ///< Initial state for retrieving wayppoints from the MAV
WP_GETLIST_GETWPS WP_GETLIST_GETWPS, ///< Receiving waypoints
WP_CLEARLIST, ///< Clearing waypoint list on the MAV
WP_SETCURRENT ///< Setting new current waypoint on the MAV
}; ///< The possible states for the waypoint protocol }; ///< The possible states for the waypoint protocol
public: public:
UASWaypointManager(UAS&); UASWaypointManager(UAS&); ///< Standard constructor.
void handleWaypointCount(quint8 systemId, quint8 compId, quint16 count); /** @name Protocol handlers */
void handleWaypoint(quint8 systemId, quint8 compId, mavlink_waypoint_t *wp); /*@{*/
void handleWaypointRequest(quint8 systemId, quint8 compId, mavlink_waypoint_request_t *wpr); void handleWaypointCount(quint8 systemId, quint8 compId, quint16 count); ///< Handles received waypoint count messages
void handleWaypointReached(quint8 systemId, quint8 compId, mavlink_waypoint_reached_t *wpr); void handleWaypoint(quint8 systemId, quint8 compId, mavlink_waypoint_t *wp); ///< Handles received waypoint messages
void handleWaypointSetCurrent(quint8 systemId, quint8 compId, mavlink_waypoint_set_current_t *wpr); void handleWaypointAck(quint8 systemId, quint8 compId, mavlink_waypoint_ack_t *wpa); ///< Handles received waypoint ack messages
void handleWaypointRequest(quint8 systemId, quint8 compId, mavlink_waypoint_request_t *wpr); ///< Handles received waypoint request messages
void handleWaypointReached(quint8 systemId, quint8 compId, mavlink_waypoint_reached_t *wpr); ///< Handles received waypoint reached messages
void handleWaypointCurrent(quint8 systemId, quint8 compId, mavlink_waypoint_current_t *wpc); ///< Handles received set current waypoint messages
/*@}*/
QVector<Waypoint *> &getWaypointList(void) { return waypoints; } QVector<Waypoint *> &getWaypointList(void) { return waypoints; } ///< Returns a reference to the local waypoint list. Gives full access to the internal data structure - Subject to change: Public const access and friend access for the waypoint list widget.
private: private:
void sendWaypointRequest(quint16 seq); void sendWaypointClearAll();
void sendWaypoint(quint16 seq); void sendWaypointSetCurrent(quint16 seq);
void sendWaypointCount();
void sendWaypointRequestList();
void sendWaypointRequest(quint16 seq); ///< Requests a waypoint with sequence number seq
void sendWaypoint(quint16 seq); ///< Sends a waypoint with sequence number seq
void sendWaypointAck(quint8 type); ///< Sends a waypoint ack
public slots: public slots:
void timeout(); void timeout(); ///< Called by the timer if a response times out. Handles send retries.
void clearWaypointList(); void setCurrent(quint16 seq); ///< Sends the sequence number of the waypoint that should get the new target waypoint
void requestWaypoints(); void clearWaypointList(); ///< Sends the waypoint clear all message to the MAV
void sendWaypoints(); void readWaypoints(); ///< Requests the MAV's current waypoint list
void writeWaypoints(); ///< Sends the local waypoint list to the MAV
signals: signals:
void waypointUpdated(quint16,double,double,double,double,bool,bool,double,int); ///< Adds a waypoint to the waypoint list widget void waypointUpdated(quint16,double,double,double,double,bool,bool,double,int); ///< Adds a waypoint to the waypoint list widget
@ -79,6 +100,7 @@ signals:
private: private:
UAS &uas; ///< Reference to the corresponding UAS UAS &uas; ///< Reference to the corresponding UAS
quint32 current_retries; ///< The current number of retries left
quint16 current_wp_id; ///< The last used waypoint ID in the current protocol transaction quint16 current_wp_id; ///< The last used waypoint ID in the current protocol transaction
quint16 current_count; ///< The number of waypoints in the current protocol transaction quint16 current_count; ///< The number of waypoints in the current protocol transaction
WaypointState current_state; ///< The current protocol state WaypointState current_state; ///< The current protocol state

35
src/ui/WaypointList.cc

@ -126,9 +126,10 @@ void WaypointList::setUAS(UASInterface* uas)
connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64))); connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64))); connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
connect(this, SIGNAL(sendWaypoints()), &uas->getWaypointManager(), SLOT(sendWaypoints())); connect(this, SIGNAL(sendWaypoints()), &uas->getWaypointManager(), SLOT(writeWaypoints()));
connect(this, SIGNAL(requestWaypoints()), &uas->getWaypointManager(), SLOT(requestWaypoints())); connect(this, SIGNAL(requestWaypoints()), &uas->getWaypointManager(), SLOT(readWaypoints()));
connect(this, SIGNAL(clearWaypointList()), &uas->getWaypointManager(), SLOT(clearWaypointList())); connect(this, SIGNAL(clearWaypointList()), &uas->getWaypointManager(), SLOT(clearWaypointList()));
connect(this, SIGNAL(setCurrent(quint16)), &uas->getWaypointManager(), SLOT(setCurrent(quint16)));
} }
} }
@ -149,6 +150,35 @@ void WaypointList::waypointReached(quint16 waypointId)
} }
} }
void WaypointList::changeCurrentWaypoint(quint16 seq)
{
if (this->uas)
{
QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
if (seq < waypoints.size())
{
for(int i = 0; i < waypoints.size(); i++)
{
WaypointView* widget = wpViews.find(waypoints[i]).value();
if (waypoints[i]->getId() == seq)
{
waypoints[i]->setCurrent(true);
widget->setCurrent(true);
emit setCurrent(seq);
}
else
{
waypoints[i]->setCurrent(false);
widget->setCurrent(false);
}
}
redrawList();
}
}
}
void WaypointList::currentWaypointChanged(quint16 seq) void WaypointList::currentWaypointChanged(quint16 seq)
{ {
if (this->uas) if (this->uas)
@ -250,6 +280,7 @@ void WaypointList::addWaypoint(Waypoint* wp)
connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*))); connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*)));
connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*))); connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*)));
connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16))); connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16)));
} }
} }
} }

4
src/ui/WaypointList.h

@ -72,7 +72,8 @@ public slots:
/** @brief sets statusLabel string */ /** @brief sets statusLabel string */
void updateStatusLabel(const QString &string); void updateStatusLabel(const QString &string);
void currentWaypointChanged(quint16 seq); void changeCurrentWaypoint(quint16 seq); ///< The user wants to change the current waypoint
void currentWaypointChanged(quint16 seq); ///< The waypointplanner changed the current waypoint
void setWaypoint(quint16 id, double x, double y, double z, double yaw, bool autocontinue, bool current, double orbit, int holdTime); void setWaypoint(quint16 id, double x, double y, double z, double yaw, bool autocontinue, bool current, double orbit, int holdTime);
void addWaypoint(Waypoint* wp); void addWaypoint(Waypoint* wp);
void removeWaypoint(Waypoint* wp); void removeWaypoint(Waypoint* wp);
@ -84,6 +85,7 @@ signals:
void sendWaypoints(); void sendWaypoints();
void requestWaypoints(); void requestWaypoints();
void clearWaypointList(); void clearWaypointList();
void setCurrent(quint16);
protected: protected:
virtual void changeEvent(QEvent *e); virtual void changeEvent(QEvent *e);

2
src/ui/WaypointView.cc

@ -115,7 +115,7 @@ void WaypointView::changedCurrent(int state)
else else
{ {
wp->setCurrent(true); wp->setCurrent(true);
emit currentWaypointChanged(wp->getId()); //the slot currentWayppointChanged() in WaypointList sets all other current flags to false emit changeCurrentWaypoint(wp->getId()); //the slot changeCurrentWaypoint() in WaypointList sets all other current flags to false
} }
} }

1
src/ui/WaypointView.h

@ -72,6 +72,7 @@ signals:
void moveDownWaypoint(Waypoint*); void moveDownWaypoint(Waypoint*);
void removeWaypoint(Waypoint*); void removeWaypoint(Waypoint*);
void currentWaypointChanged(quint16); void currentWaypointChanged(quint16);
void changeCurrentWaypoint(quint16);
void setYaw(double); void setYaw(double);
}; };

1
src/ui/linechart/LinechartWidget.cc

@ -415,6 +415,7 @@ QWidget* LinechartWidget::createCurveItem(QString curve)
**/ **/
void LinechartWidget::removeCurve(QString curve) void LinechartWidget::removeCurve(QString curve)
{ {
Q_UNUSED(curve)
//TODO @todo Ensure that the button for a curve gets deleted when the original curve is deleted //TODO @todo Ensure that the button for a curve gets deleted when the original curve is deleted
// Remove name // Remove name
} }

Loading…
Cancel
Save