mirror of https://github.com/ArduPilot/ardupilot
AP_AccelCal: pass mavlink_message_t by const reference
This commit is contained in:
parent
a9814d34c7
commit
a44ed03a91
|
@ -353,13 +353,13 @@ bool AP_AccelCal::client_active(uint8_t client_num)
|
|||
return (bool)_clients[client_num]->_acal_get_calibrator(0);
|
||||
}
|
||||
|
||||
void AP_AccelCal::handleMessage(const mavlink_message_t* msg)
|
||||
void AP_AccelCal::handleMessage(const mavlink_message_t &msg)
|
||||
{
|
||||
if (!_waiting_for_mavlink_ack) {
|
||||
return;
|
||||
}
|
||||
_waiting_for_mavlink_ack = false;
|
||||
if (msg->msgid == MAVLINK_MSG_ID_COMMAND_ACK) {
|
||||
if (msg.msgid == MAVLINK_MSG_ID_COMMAND_ACK) {
|
||||
_start_collect_sample = true;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -33,7 +33,7 @@ public:
|
|||
// interface to the clients for registration
|
||||
static void register_client(AP_AccelCal_Client* client);
|
||||
|
||||
void handleMessage(const mavlink_message_t * msg);
|
||||
void handleMessage(const mavlink_message_t &msg);
|
||||
|
||||
private:
|
||||
GCS_MAVLINK *_gcs;
|
||||
|
|
Loading…
Reference in New Issue