mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-09 08:04:14 -03:00
GCS_MAVLink: added MCU_STATUS message
This commit is contained in:
parent
a95906ea93
commit
5c3056e50d
@ -225,6 +225,9 @@ public:
|
||||
void send_meminfo(void);
|
||||
void send_fence_status() const;
|
||||
void send_power_status(void);
|
||||
#if HAL_WITH_MCU_MONITORING
|
||||
void send_mcu_status(void);
|
||||
#endif
|
||||
void send_battery_status(const uint8_t instance) const;
|
||||
bool send_battery_status();
|
||||
void send_distance_sensor();
|
||||
|
@ -194,6 +194,23 @@ void GCS_MAVLINK::send_power_status(void)
|
||||
hal.analogin->power_status_flags());
|
||||
}
|
||||
|
||||
#if HAL_WITH_MCU_MONITORING
|
||||
// report MCU voltage/temperature status
|
||||
void GCS_MAVLINK::send_mcu_status(void)
|
||||
{
|
||||
if (!gcs().vehicle_initialised()) {
|
||||
// avoid unnecessary errors being reported to user
|
||||
return;
|
||||
}
|
||||
mavlink_msg_mcu_status_send(chan,
|
||||
0, // only one MCU
|
||||
hal.analogin->mcu_temperature() * 100,
|
||||
hal.analogin->mcu_voltage() * 1000,
|
||||
hal.analogin->mcu_voltage_min() * 1000,
|
||||
hal.analogin->mcu_voltage_max() * 1000);
|
||||
}
|
||||
#endif
|
||||
|
||||
void GCS_MAVLINK::send_battery_status(const uint8_t instance) const
|
||||
{
|
||||
// catch the battery backend not supporting the required number of cells
|
||||
@ -796,6 +813,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
|
||||
{ MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, MSG_ORIGIN},
|
||||
{ MAVLINK_MSG_ID_SYS_STATUS, MSG_SYS_STATUS},
|
||||
{ MAVLINK_MSG_ID_POWER_STATUS, MSG_POWER_STATUS},
|
||||
{ MAVLINK_MSG_ID_MCU_STATUS, MSG_MCU_STATUS},
|
||||
{ MAVLINK_MSG_ID_MEMINFO, MSG_MEMINFO},
|
||||
{ MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, MSG_NAV_CONTROLLER_OUTPUT},
|
||||
{ MAVLINK_MSG_ID_MISSION_CURRENT, MSG_CURRENT_WAYPOINT},
|
||||
@ -4984,6 +5002,13 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||
send_power_status();
|
||||
break;
|
||||
|
||||
case MSG_MCU_STATUS:
|
||||
#if HAL_WITH_MCU_MONITORING
|
||||
CHECK_PAYLOAD_SIZE(MCU_STATUS);
|
||||
send_mcu_status();
|
||||
#endif
|
||||
break;
|
||||
|
||||
case MSG_RC_CHANNELS:
|
||||
CHECK_PAYLOAD_SIZE(RC_CHANNELS);
|
||||
send_rc_channels();
|
||||
|
@ -79,5 +79,6 @@ enum ap_message : uint8_t {
|
||||
MSG_WATER_DEPTH,
|
||||
MSG_HIGH_LATENCY2,
|
||||
MSG_AIS_VESSEL,
|
||||
MSG_MCU_STATUS,
|
||||
MSG_LAST // MSG_LAST must be the last entry in this enum
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user