mirror of https://github.com/ArduPilot/ardupilot
Rover: windvane calibration can be started with preflight-calibration msg
send COMMAND_LONG with MAV_CMD_PREFLIGHT_CALIBRATION command and set param6 field to 3
This commit is contained in:
parent
30f20827ec
commit
c3f3ee03d0
|
@ -584,6 +584,12 @@ MAV_RESULT GCS_MAVLINK_Rover::_handle_command_preflight_calibration(const mavlin
|
|||
} else {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
} else if (is_equal(packet.param6, 1.0f)) {
|
||||
if (rover.g2.windvane.start_calibration()) {
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
} else {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
}
|
||||
|
||||
return GCS_MAVLINK::_handle_command_preflight_calibration(packet);
|
||||
|
|
Loading…
Reference in New Issue