mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-08 22:53:57 -04:00
GCS_MAVLink: move try_send_message compass message handling up
This commit is contained in:
parent
4b63443633
commit
b8cb758fac
@ -284,6 +284,12 @@ protected:
|
||||
MAV_RESULT handle_command_long_message(mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_camera(const mavlink_command_long_t &packet);
|
||||
|
||||
// vehicle-overridable message send function
|
||||
virtual bool try_send_message(enum ap_message id);
|
||||
|
||||
// message sending functions:
|
||||
bool try_send_compass_message(enum ap_message id);
|
||||
|
||||
private:
|
||||
|
||||
float adjust_rate_for_stream_trigger(enum streams stream_num);
|
||||
@ -399,9 +405,6 @@ private:
|
||||
// a vehicle can optionally snoop on messages for other systems
|
||||
static void (*msg_snoop)(const mavlink_message_t* msg);
|
||||
|
||||
// vehicle specific message send function
|
||||
virtual bool try_send_message(enum ap_message id) = 0;
|
||||
|
||||
virtual bool handle_guided_request(AP_Mission::Mission_Command &cmd) = 0;
|
||||
virtual void handle_change_alt_request(AP_Mission::Mission_Command &cmd) = 0;
|
||||
void handle_common_mission_message(mavlink_message_t *msg);
|
||||
|
@ -2031,6 +2031,59 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_message(mavlink_command_long_t &pack
|
||||
return result;
|
||||
}
|
||||
|
||||
bool GCS_MAVLINK::try_send_compass_message(const enum ap_message id)
|
||||
{
|
||||
Compass *compass = get_compass();
|
||||
if (compass == nullptr) {
|
||||
return true;
|
||||
}
|
||||
bool ret = true;
|
||||
switch (id) {
|
||||
case MSG_MAG_CAL_PROGRESS:
|
||||
compass->send_mag_cal_progress(chan);
|
||||
ret = true;;
|
||||
break;
|
||||
case MSG_MAG_CAL_REPORT:
|
||||
compass->send_mag_cal_report(chan);
|
||||
ret = true;
|
||||
break;
|
||||
default:
|
||||
ret = true;
|
||||
break;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||
{
|
||||
if (telemetry_delayed()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
bool ret = true;
|
||||
|
||||
switch(id) {
|
||||
|
||||
case MSG_MAG_CAL_PROGRESS:
|
||||
/* fall through */
|
||||
case MSG_MAG_CAL_REPORT:
|
||||
ret = try_send_compass_message(id);
|
||||
break;
|
||||
|
||||
default:
|
||||
// try_send_message must always at some stage return true for
|
||||
// a message, or we will attempt to infinitely retry the
|
||||
// message as part of send_message.
|
||||
// This message will be sent out at the same rate as the
|
||||
// unknown message, so should be safe.
|
||||
gcs().send_text(MAV_SEVERITY_DEBUG, "Sending unknown message (%u)", id);
|
||||
ret = true;
|
||||
break;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
GCS &gcs()
|
||||
{
|
||||
return *GCS::instance();
|
||||
|
Loading…
Reference in New Issue
Block a user