Browse Source

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
master
Randy Mackay 6 years ago
parent
commit
c3f3ee03d0
  1. 6
      APMrover2/GCS_Mavlink.cpp

6
APMrover2/GCS_Mavlink.cpp

@ -584,6 +584,12 @@ MAV_RESULT GCS_MAVLINK_Rover::_handle_command_preflight_calibration(const mavlin @@ -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…
Cancel
Save