Commit 0d1656d8 authored by Michael Carpenter's avatar Michael Carpenter

Added support for MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT for Distance to waypoint property

parent fefba511
...@@ -1344,6 +1344,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -1344,6 +1344,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
case MAVLINK_MSG_ID_RAW_IMU: case MAVLINK_MSG_ID_RAW_IMU:
case MAVLINK_MSG_ID_SCALED_IMU: case MAVLINK_MSG_ID_SCALED_IMU:
case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT: case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
{
//mavlink_set_local_position_setpoint_t p;
//mavlink_msg_set_local_position_setpoint_decode(&message, &p);
//emit userPositionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw);
mavlink_nav_controller_output_t p;
mavlink_msg_nav_controller_output_decode(&message,&p);
setDistToWaypoint(p.wp_dist);
}
break;
case MAVLINK_MSG_ID_RAW_PRESSURE: case MAVLINK_MSG_ID_RAW_PRESSURE:
case MAVLINK_MSG_ID_SCALED_PRESSURE: case MAVLINK_MSG_ID_SCALED_PRESSURE:
case MAVLINK_MSG_ID_OPTICAL_FLOW: case MAVLINK_MSG_ID_OPTICAL_FLOW:
......
...@@ -112,6 +112,7 @@ public: ...@@ -112,6 +112,7 @@ public:
Q_PROPERTY(double roll READ getRoll WRITE setRoll NOTIFY rollChanged) Q_PROPERTY(double roll READ getRoll WRITE setRoll NOTIFY rollChanged)
Q_PROPERTY(double pitch READ getPitch WRITE setPitch NOTIFY pitchChanged) Q_PROPERTY(double pitch READ getPitch WRITE setPitch NOTIFY pitchChanged)
Q_PROPERTY(double yaw READ getYaw WRITE setYaw NOTIFY yawChanged) Q_PROPERTY(double yaw READ getYaw WRITE setYaw NOTIFY yawChanged)
Q_PROPERTY(double distToWaypoint READ getDistToWaypoint WRITE setDistToWaypoint NOTIFY distToWaypointChanged)
void setLocalX(double val) void setLocalX(double val)
{ {
...@@ -194,6 +195,17 @@ public: ...@@ -194,6 +195,17 @@ public:
return isGlobalPositionKnown; return isGlobalPositionKnown;
} }
void setDistToWaypoint(double val)
{
distToWaypoint = val;
emit distToWaypointChanged(val,"distToWaypoint");
}
double getDistToWaypoint() const
{
return distToWaypoint;
}
void setRoll(double val) void setRoll(double val)
{ {
roll = val; roll = val;
...@@ -370,6 +382,7 @@ protected: //COMMENTS FOR TEST UNIT ...@@ -370,6 +382,7 @@ protected: //COMMENTS FOR TEST UNIT
double speedX; ///< True speed in X axis double speedX; ///< True speed in X axis
double speedY; ///< True speed in Y axis double speedY; ///< True speed in Y axis
double speedZ; ///< True speed in Z axis double speedZ; ///< True speed in Z axis
double distToWaypoint; ///< Distance to next waypoint
double roll; double roll;
double pitch; double pitch;
double yaw; double yaw;
...@@ -792,6 +805,7 @@ signals: ...@@ -792,6 +805,7 @@ signals:
void pitchChanged(double val,QString name); void pitchChanged(double val,QString name);
void yawChanged(double val,QString name); void yawChanged(double val,QString name);
void satelliteCountChanged(double val,QString name); void satelliteCountChanged(double val,QString name);
void distToWaypointChanged(double val,QString name);
protected: protected:
/** @brief Get the UNIX timestamp in milliseconds, enter microseconds */ /** @brief Get the UNIX timestamp in milliseconds, enter microseconds */
......
...@@ -61,6 +61,18 @@ UASQuickView::UASQuickView(QWidget *parent) : QWidget(parent) ...@@ -61,6 +61,18 @@ UASQuickView::UASQuickView(QWidget *parent) : QWidget(parent)
uasPropertyToLabelMap["satelliteCount"] = item; uasPropertyToLabelMap["satelliteCount"] = item;
} }
{
QAction *action = new QAction("distToWaypoint",this);
action->setCheckable(true);
action->setChecked(true);
connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool)));
this->addAction(action);
UASQuickViewItem *item = new UASQuickViewItem(this);
item->setTitle("distToWaypoint");
ui.verticalLayout->addWidget(item);
uasPropertyToLabelMap["distToWaypoint"] = item;
}
updateTimer = new QTimer(this); updateTimer = new QTimer(this);
connect(updateTimer,SIGNAL(timeout()),this,SLOT(updateTimerTick())); connect(updateTimer,SIGNAL(timeout()),this,SLOT(updateTimerTick()));
updateTimer->start(1000); updateTimer->start(1000);
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment