GCS_MAVLink: Update the accelcal signature to accept uint32_t

This commit is contained in:
Michael du Breuil 2017-05-29 14:03:10 -07:00 committed by Francisco Ferreira
parent bc8df31fc3
commit c62e79b5c0
2 changed files with 2 additions and 2 deletions

View File

@ -162,7 +162,7 @@ public:
void send_heartbeat(uint8_t type, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status);
void send_servo_output_raw(bool hil);
static void send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour);
void send_accelcal_vehicle_position(uint8_t position);
void send_accelcal_vehicle_position(uint32_t position);
// return a bitmap of active channels. Used by libraries to loop
// over active channels to send to all active channels

View File

@ -1509,7 +1509,7 @@ void GCS_MAVLINK::send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_C
}
}
void GCS_MAVLINK::send_accelcal_vehicle_position(uint8_t position)
void GCS_MAVLINK::send_accelcal_vehicle_position(uint32_t position)
{
if (HAVE_PAYLOAD_SPACE(chan, COMMAND_LONG)) {
mavlink_msg_command_long_send(