Commit 5b6f3fad authored by pixhawk's avatar pixhawk

Added setpoint to UAS

parent 88cf8600
...@@ -104,13 +104,6 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -104,13 +104,6 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "vis. vy", pos.vy, time); emit valueChanged(uasId, "vis. vy", pos.vy, time);
emit valueChanged(uasId, "vis. vz", pos.vz, time); emit valueChanged(uasId, "vis. vz", pos.vz, time);
emit valueChanged(uasId, "vis. vyaw", pos.vyaw, time); emit valueChanged(uasId, "vis. vyaw", pos.vyaw, time);
// Set internal state
if (!positionLock)
{
// If position was not locked before, notify positive
GAudioOutput::instance()->notifyPositive();
}
positionLock = true;
} }
break; break;
case MAVLINK_MSG_ID_AUX_STATUS: case MAVLINK_MSG_ID_AUX_STATUS:
......
...@@ -100,7 +100,7 @@ void UAS::updateState() ...@@ -100,7 +100,7 @@ void UAS::updateState()
} }
else else
{ {
if (mode > MAV_MODE_LOCKED && positionLock) if (mode > (uint8_t)MAV_MODE_LOCKED && positionLock)
{ {
GAudioOutput::instance()->notifyNegative(); GAudioOutput::instance()->notifyNegative();
} }
...@@ -301,6 +301,14 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -301,6 +301,14 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "vy", pos.vy, time); emit valueChanged(uasId, "vy", pos.vy, time);
emit valueChanged(uasId, "vz", pos.vz, time); emit valueChanged(uasId, "vz", pos.vz, time);
emit localPositionChanged(this, pos.x, pos.y, pos.z, time); emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
// Set internal state
if (!positionLock)
{
// If position was not locked before, notify positive
GAudioOutput::instance()->notifyPositive();
}
positionLock = true;
} }
break; break;
case MAVLINK_MSG_ID_GLOBAL_POSITION: case MAVLINK_MSG_ID_GLOBAL_POSITION:
...@@ -317,6 +325,14 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -317,6 +325,14 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "g-vy", pos.vy, time); emit valueChanged(uasId, "g-vy", pos.vy, time);
emit valueChanged(uasId, "g-vz", pos.vz, time); emit valueChanged(uasId, "g-vz", pos.vz, time);
emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time); emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
// Set internal state
if (!positionLock)
{
// If position was not locked before, notify positive
GAudioOutput::instance()->notifyPositive();
}
positionLock = true;
} }
break; break;
case MAVLINK_MSG_ID_GPS_RAW: case MAVLINK_MSG_ID_GPS_RAW:
...@@ -464,6 +480,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -464,6 +480,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
} }
} }
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
mavlink_message_t msg;
}
quint64 UAS::getUnixTime(quint64 time) quint64 UAS::getUnixTime(quint64 time)
{ {
if (time == 0) if (time == 0)
......
...@@ -216,6 +216,9 @@ public slots: ...@@ -216,6 +216,9 @@ public slots:
/** @brief Update the system state */ /** @brief Update the system state */
void updateState(); void updateState();
/** @brief Set local position setpoint */
void setLocalPositionSetpoint(float x, float y, float z, float yaw);
signals: signals:
/** @brief The main/battery voltage has changed/was updated */ /** @brief The main/battery voltage has changed/was updated */
......
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