|
|
|
@ -580,9 +580,11 @@ void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
@@ -580,9 +580,11 @@ void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
tracker.init_barometer(false); |
|
|
|
|
// zero the altitude difference on next baro update
|
|
|
|
|
tracker.nav_status.need_altitude_calibration = true; |
|
|
|
|
result = MAV_RESULT_ACCEPTED; |
|
|
|
|
} |
|
|
|
|
if (is_equal(packet.param4,1.0f)) { |
|
|
|
|
// Can't trim radio
|
|
|
|
|
result = MAV_RESULT_UNSUPPORTED; |
|
|
|
|
} else if (is_equal(packet.param5,1.0f)) { |
|
|
|
|
result = MAV_RESULT_ACCEPTED; |
|
|
|
|
// start with gyro calibration
|
|
|
|
@ -609,7 +611,6 @@ void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
@@ -609,7 +611,6 @@ void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
result = MAV_RESULT_FAILED; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
result = MAV_RESULT_ACCEPTED; |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|