Plane: move handling of PREFLIGHT_SET_SENSOR_OFFSETS up
This commit is contained in:
parent
ad1c379445
commit
7f0cb82797
@ -1256,23 +1256,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
||||
plane.in_calibration = false;
|
||||
break;
|
||||
|
||||
case MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS:
|
||||
{
|
||||
uint8_t compassNumber = -1;
|
||||
if (is_equal(packet.param1, 2.0f)) {
|
||||
compassNumber = 0;
|
||||
} else if (is_equal(packet.param1, 5.0f)) {
|
||||
compassNumber = 1;
|
||||
} else if (is_equal(packet.param1, 6.0f)) {
|
||||
compassNumber = 2;
|
||||
}
|
||||
if (compassNumber != (uint8_t) -1) {
|
||||
plane.compass.set_and_save_offsets(compassNumber, packet.param2, packet.param3, packet.param4);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case MAV_CMD_COMPONENT_ARM_DISARM:
|
||||
if (is_equal(packet.param1,1.0f)) {
|
||||
// run pre_arm_checks and arm_checks and display failures
|
||||
|
Loading…
Reference in New Issue
Block a user