mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
GCS_MAVLink: handle MAV_CMD_GET_HOME_POSITION as both long and int
This commit is contained in:
parent
e8be3a4e21
commit
e71227fe3a
@ -658,7 +658,7 @@ protected:
|
||||
MAV_RESULT handle_command_do_gripper(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_do_sprayer(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_do_set_mode(const mavlink_command_int_t &packet);
|
||||
MAV_RESULT handle_command_get_home_position(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_get_home_position(const mavlink_command_int_t &packet);
|
||||
MAV_RESULT handle_command_do_fence_enable(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_debug_trap(const mavlink_command_int_t &packet);
|
||||
MAV_RESULT handle_command_set_ekf_source_set(const mavlink_command_int_t &packet);
|
||||
|
@ -4523,7 +4523,8 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_set_mode(const mavlink_command_int_t &
|
||||
return _set_mode_common(_base_mode, _custom_mode);
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_get_home_position(const mavlink_command_long_t &packet)
|
||||
#if AP_AHRS_ENABLED
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_get_home_position(const mavlink_command_int_t &packet)
|
||||
{
|
||||
if (!AP::ahrs().home_is_set()) {
|
||||
return MAV_RESULT_FAILED;
|
||||
@ -4539,6 +4540,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_get_home_position(const mavlink_command_l
|
||||
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
#endif // AP_AHRS_ENABLED
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_debug_trap(const mavlink_command_int_t &packet)
|
||||
{
|
||||
@ -4819,10 +4821,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
|
||||
break;
|
||||
}
|
||||
|
||||
case MAV_CMD_GET_HOME_POSITION:
|
||||
result = handle_command_get_home_position(packet);
|
||||
break;
|
||||
|
||||
default:
|
||||
result = try_command_long_as_command_int(packet, msg);
|
||||
break;
|
||||
@ -5134,6 +5132,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
|
||||
return handle_command_mag_cal(packet);
|
||||
#endif
|
||||
|
||||
#if AP_AHRS_ENABLED
|
||||
case MAV_CMD_GET_HOME_POSITION:
|
||||
return handle_command_get_home_position(packet);
|
||||
#endif
|
||||
|
||||
case MAV_CMD_PREFLIGHT_CALIBRATION:
|
||||
return handle_command_preflight_calibration(packet, msg);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user