mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
GCS_MAVLink: pass mavlink acks into accelcal library if it exists
This commit is contained in:
parent
9ad058783a
commit
484d97597b
@ -252,6 +252,7 @@ protected:
|
||||
|
||||
void handle_request_data_stream(mavlink_message_t *msg, bool save);
|
||||
|
||||
virtual void handle_command_ack(const mavlink_message_t* msg);
|
||||
void handle_set_mode(mavlink_message_t* msg);
|
||||
void handle_mission_request_list(AP_Mission &mission, mavlink_message_t *msg);
|
||||
void handle_mission_request(AP_Mission &mission, mavlink_message_t *msg);
|
||||
|
@ -1869,7 +1869,6 @@ void GCS_MAVLINK::handle_vision_position_delta(mavlink_message_t *msg)
|
||||
if (visual_odom == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
visual_odom->handle_msg(msg);
|
||||
}
|
||||
|
||||
@ -1959,12 +1958,25 @@ void GCS_MAVLINK::handle_att_pos_mocap(mavlink_message_t *msg)
|
||||
reset_timestamp_ms);
|
||||
}
|
||||
|
||||
void GCS_MAVLINK::handle_command_ack(const mavlink_message_t* msg)
|
||||
{
|
||||
AP_AccelCal *accelcal = AP::ins().get_acal();
|
||||
if (accelcal != nullptr) {
|
||||
accelcal->handleMessage(msg);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
handle messages which don't require vehicle specific data
|
||||
*/
|
||||
void GCS_MAVLINK::handle_common_message(mavlink_message_t *msg)
|
||||
{
|
||||
switch (msg->msgid) {
|
||||
case MAVLINK_MSG_ID_COMMAND_ACK: {
|
||||
handle_command_ack(msg);
|
||||
break;
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_SETUP_SIGNING:
|
||||
handle_setup_signing(msg);
|
||||
break;
|
||||
|
Loading…
Reference in New Issue
Block a user