GCS_MAVLink: add function to send command requesting vehicle position during accel cal

This commit is contained in:
Francisco Ferreira 2016-11-12 09:45:36 +00:00 committed by Tom Pittenger
parent bc661f013e
commit 7463d4c8f7
2 changed files with 15 additions and 0 deletions

View File

@ -171,6 +171,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);
// return a bitmap of active channels. Used by libraries to loop
// over active channels to send to all active channels

View File

@ -1747,6 +1747,20 @@ void GCS_MAVLINK::send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_C
}
}
void GCS_MAVLINK::send_accelcal_vehicle_position(uint8_t position)
{
if (HAVE_PAYLOAD_SPACE(chan, COMMAND_LONG)) {
mavlink_msg_command_long_send(
chan,
0,
0,
MAV_CMD_ACCELCAL_VEHICLE_POS,
0,
(float) position,
0, 0, 0, 0, 0, 0);
}
}
/*
handle a MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN command