AP_AccelCal: pass mavlink_command_ack_t to accelcal library

The library needs to look at the content of the packet.  Given that GCS_MAVLink is already within handle_command_ack, decoding it there makes sense.
This commit is contained in:
Peter Barker 2022-05-25 08:57:36 +10:00 committed by Andrew Tridgell
parent 069fdfae60
commit dcc1818ee2
2 changed files with 3 additions and 5 deletions

View File

@ -362,16 +362,14 @@ bool AP_AccelCal::client_active(uint8_t client_num)
} }
#if HAL_GCS_ENABLED #if HAL_GCS_ENABLED
void AP_AccelCal::handleMessage(const mavlink_message_t &msg) void AP_AccelCal::handle_command_ack(const mavlink_command_ack_t &packet)
{ {
if (!_waiting_for_mavlink_ack) { if (!_waiting_for_mavlink_ack) {
return; return;
} }
_waiting_for_mavlink_ack = false; _waiting_for_mavlink_ack = false;
if (msg.msgid == MAVLINK_MSG_ID_COMMAND_ACK) {
_start_collect_sample = true; _start_collect_sample = true;
} }
}
bool AP_AccelCal::gcs_vehicle_position(float position) bool AP_AccelCal::gcs_vehicle_position(float position)
{ {

View File

@ -43,7 +43,7 @@ public:
static void register_client(AP_AccelCal_Client* client); static void register_client(AP_AccelCal_Client* client);
#if HAL_GCS_ENABLED #if HAL_GCS_ENABLED
void handleMessage(const mavlink_message_t &msg); void handle_command_ack(const mavlink_command_ack_t &packet);
#endif #endif
// true if we are in a calibration process // true if we are in a calibration process