Browse Source

Rover: split SYS_STATUS and POWER_STATUS onto separate ap_messages

mission-4.1.18
Peter Barker 6 years ago committed by Peter Barker
parent
commit
90d13548a1
  1. 21
      APMrover2/GCS_Mavlink.cpp
  2. 2
      APMrover2/GCS_Mavlink.h

21
APMrover2/GCS_Mavlink.cpp

@ -301,6 +301,11 @@ uint32_t GCS_MAVLINK_Rover::telem_delay() const
return static_cast<uint32_t>(rover.g.telem_delay); return static_cast<uint32_t>(rover.g.telem_delay);
} }
bool GCS_MAVLINK_Rover::vehicle_initialised() const
{
return rover.control_mode != &rover.mode_initializing;
}
// try to send a message, return false if it won't fit in the serial tx buffer // try to send a message, return false if it won't fit in the serial tx buffer
bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id) bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
{ {
@ -319,17 +324,14 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
switch (id) { switch (id) {
case MSG_EXTENDED_STATUS1: case MSG_SYS_STATUS:
// send extended status only once vehicle has been initialised // send extended status only once vehicle has been initialised
// to avoid unnecessary errors being reported to user // to avoid unnecessary errors being reported to user
if (initialised) { if (!vehicle_initialised()) {
if (PAYLOAD_SIZE(chan, SYS_STATUS) + return true;
PAYLOAD_SIZE(chan, POWER_STATUS) > comm_get_txspace(chan)) {
return false;
} }
CHECK_PAYLOAD_SIZE(SYS_STATUS);
rover.send_sys_status(chan); rover.send_sys_status(chan);
send_power_status();
}
break; break;
case MSG_NAV_CONTROLLER_OUTPUT: case MSG_NAV_CONTROLLER_OUTPUT:
@ -479,7 +481,8 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = {
MSG_SENSOR_OFFSETS MSG_SENSOR_OFFSETS
}; };
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
MSG_EXTENDED_STATUS1, // SYS_STATUS, POWER_STATUS MSG_SYS_STATUS,
MSG_POWER_STATUS,
MSG_MEMINFO, MSG_MEMINFO,
MSG_CURRENT_WAYPOINT, MSG_CURRENT_WAYPOINT,
MSG_GPS_RAW, MSG_GPS_RAW,
@ -1178,7 +1181,7 @@ void Rover::mavlink_delay_cb()
if (tnow - last_1hz > 1000) { if (tnow - last_1hz > 1000) {
last_1hz = tnow; last_1hz = tnow;
gcs().send_message(MSG_HEARTBEAT); gcs().send_message(MSG_HEARTBEAT);
gcs().send_message(MSG_EXTENDED_STATUS1); gcs().send_message(MSG_SYS_STATUS);
} }
if (tnow - last_50hz > 20) { if (tnow - last_50hz > 20) {
last_50hz = tnow; last_50hz = tnow;

2
APMrover2/GCS_Mavlink.h

@ -30,6 +30,8 @@ protected:
bool persist_streamrates() const override { return true; } bool persist_streamrates() const override { return true; }
bool vehicle_initialised() const override;
private: private:
void handleMessage(mavlink_message_t * msg) override; void handleMessage(mavlink_message_t * msg) override;

Loading…
Cancel
Save