Commit 8cf835c3 authored by Bryant Mairs's avatar Bryant Mairs

Exposed HEARTBEAT.system_status and HEARTBEAT.base_mode to the realtime...

Exposed HEARTBEAT.system_status and HEARTBEAT.base_mode to the realtime plotter widget via the valueChanged signal.
parent 1529ae86
......@@ -282,6 +282,14 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit heartbeat(this);
mavlink_heartbeat_t state;
mavlink_msg_heartbeat_decode(&message, &state);
// Send the base_mode and system_status values to the plotter. This uses the ground time
// so the Ground Time checkbox must be ticked for these values to display
quint64 time = getUnixTime();
QString name = QString("M%1:HEARTBEAT.%2").arg(message.sysid);
emit valueChanged(uasId, name.arg("base_mode"), "none", state.base_mode, time);
emit valueChanged(uasId, name.arg("system_status"), "none", state.system_status, time);
// Set new type if it has changed
if (this->type != state.type)
{
......@@ -384,20 +392,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
GAudioOutput::instance()->stopEmergency();
GAudioOutput::instance()->say(audiostring.toLower());
}
// if (state.system_status == MAV_STATE_POWEROFF)
// {
// emit systemRemoved(this);
// emit systemRemoved();
// }
}
break;
// case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
// case MAVLINK_MSG_ID_NAMED_VALUE_INT:
// // Receive named value message
// receiveMessageNamedValue(message);
// break;
case MAVLINK_MSG_ID_SYS_STATUS:
{
if (multiComponentSourceDetected && wrongComponent)
......
......@@ -408,24 +408,22 @@ signals:
void deactivated();
/** @brief The robot is manually controlled **/
void manualControl();
/** @brief A value of the robot has changed.
*
* Typically this is used to send lowlevel information like the battery voltage to the plotting facilities of
* the groundstation
* the groundstation. The data here should be converted to human-readable values before being passed, so ideally
* SI units.
*
* @param uasId ID of this system
* @param name name of the value, e.g. "battery voltage"
* @param unit The units this variable is in as an abbreviation. For system-dependent (such as raw ADC values) use "raw", for unitless values use "none".
* @param value the value that changed
* @param msec the timestamp of the message, in milliseconds
*/
//void valueChanged(const int uasId, const QString& name, const double value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const int value, const quint64 msec);
// void valueChanged(const int uasId, const QString& name, const double value, const quint64 msec);
// //void valueChanged(UASInterface* uas, QString name, double value, quint64 msec);
void voltageChanged(int uasId, double voltage);
void waypointUpdated(int uasId, int id, double x, double y, double z, double yaw, bool autocontinue, bool active);
void waypointSelected(int uasId, int id);
......
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