mirror of https://github.com/ArduPilot/ardupilot
ArduSub: support preflight calibration via command_int
This commit is contained in:
parent
c1b5e9a446
commit
2d5452d540
|
@ -431,9 +431,9 @@ MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration_baro(const mav
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
}
|
}
|
||||||
|
|
||||||
MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
|
MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
if (is_equal(packet.param6,1.0f)) {
|
if (packet.y == 1) {
|
||||||
// compassmot calibration
|
// compassmot calibration
|
||||||
//result = sub.mavlink_compassmot(chan);
|
//result = sub.mavlink_compassmot(chan);
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "#CompassMot calibration not supported");
|
gcs().send_text(MAV_SEVERITY_INFO, "#CompassMot calibration not supported");
|
||||||
|
|
|
@ -19,7 +19,7 @@ protected:
|
||||||
|
|
||||||
MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override;
|
MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override;
|
||||||
MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg) override;
|
MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg) override;
|
||||||
MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override;
|
MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
|
||||||
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override;
|
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override;
|
||||||
|
|
||||||
// override sending of scaled_pressure3 to send on-board temperature:
|
// override sending of scaled_pressure3 to send on-board temperature:
|
||||||
|
|
Loading…
Reference in New Issue