GCS_MAVLink: Update the accelcal signature to accept uint32_t
This commit is contained in:
parent
bc8df31fc3
commit
c62e79b5c0
@ -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
|
||||
|
@ -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(
|
||||
|
Loading…
Reference in New Issue
Block a user