mirror of https://github.com/ArduPilot/ardupilot
Rover: support preflight calibration via command_int
This commit is contained in:
parent
0f48bf7552
commit
0894cfc0c8
|
@ -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);
|
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()) {
|
if (rover.g2.windvane.start_direction_calibration()) {
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
} else {
|
} else {
|
||||||
return MAV_RESULT_FAILED;
|
return MAV_RESULT_FAILED;
|
||||||
}
|
}
|
||||||
} else if (is_equal(packet.param6, 2.0f)) {
|
} else if (packet.y == 2) {
|
||||||
if (rover.g2.windvane.start_speed_calibration()) {
|
if (rover.g2.windvane.start_speed_calibration()) {
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
} else {
|
} else {
|
||||||
|
|
|
@ -20,7 +20,7 @@ protected:
|
||||||
uint8_t sysid_my_gcs() const override;
|
uint8_t sysid_my_gcs() const override;
|
||||||
bool sysid_enforce() 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_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_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);
|
MAV_RESULT handle_command_nav_set_yaw_speed(const mavlink_command_int_t &packet, const mavlink_message_t &msg);
|
||||||
|
|
Loading…
Reference in New Issue