Rover: support preflight calibration via command_int

This commit is contained in:
Peter Barker 2023-09-07 20:13:30 +10:00 committed by Peter Barker
parent 0f48bf7552
commit 0894cfc0c8
2 changed files with 4 additions and 4 deletions

View File

@ -610,15 +610,15 @@ bool GCS_MAVLINK_Rover::handle_guided_request(AP_Mission::Mission_Command &cmd)
return rover.mode_guided.set_desired_location(cmd.content.location);
}
MAV_RESULT GCS_MAVLINK_Rover::_handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
MAV_RESULT GCS_MAVLINK_Rover::_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) {
if (rover.g2.windvane.start_direction_calibration()) {
return MAV_RESULT_ACCEPTED;
} else {
return MAV_RESULT_FAILED;
}
} else if (is_equal(packet.param6, 2.0f)) {
} else if (packet.y == 2) {
if (rover.g2.windvane.start_speed_calibration()) {
return MAV_RESULT_ACCEPTED;
} else {

View File

@ -20,7 +20,7 @@ protected:
uint8_t sysid_my_gcs() const override;
bool sysid_enforce() const 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_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);
MAV_RESULT handle_command_nav_set_yaw_speed(const mavlink_command_int_t &packet, const mavlink_message_t &msg);