mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
GCS_MAVLink: move handling of get_home_position up
This commit is contained in:
parent
3af4806d38
commit
bed3f0c344
@ -301,6 +301,7 @@ protected:
|
|||||||
MAV_RESULT handle_command_camera(const mavlink_command_long_t &packet);
|
MAV_RESULT handle_command_camera(const mavlink_command_long_t &packet);
|
||||||
MAV_RESULT handle_command_do_send_banner(const mavlink_command_long_t &packet);
|
MAV_RESULT handle_command_do_send_banner(const mavlink_command_long_t &packet);
|
||||||
MAV_RESULT handle_command_do_set_mode(const mavlink_command_long_t &packet);
|
MAV_RESULT handle_command_do_set_mode(const mavlink_command_long_t &packet);
|
||||||
|
MAV_RESULT handle_command_get_home_position(const mavlink_command_long_t &packet);
|
||||||
|
|
||||||
// vehicle-overridable message send function
|
// vehicle-overridable message send function
|
||||||
virtual bool try_send_message(enum ap_message id);
|
virtual bool try_send_message(enum ap_message id);
|
||||||
|
@ -2124,6 +2124,20 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_set_mode(const mavlink_command_long_t
|
|||||||
return _set_mode_common(base_mode, custom_mode);
|
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().home_is_set()) {
|
||||||
|
return MAV_RESULT_FAILED;
|
||||||
|
}
|
||||||
|
send_home(AP::ahrs().get_home());
|
||||||
|
|
||||||
|
Location ekf_origin;
|
||||||
|
if (AP::ahrs().get_origin(ekf_origin)) {
|
||||||
|
send_ekf_origin(ekf_origin);
|
||||||
|
}
|
||||||
|
return MAV_RESULT_ACCEPTED;
|
||||||
|
}
|
||||||
|
|
||||||
MAV_RESULT GCS_MAVLINK::handle_command_long_message(mavlink_command_long_t &packet)
|
MAV_RESULT GCS_MAVLINK::handle_command_long_message(mavlink_command_long_t &packet)
|
||||||
{
|
{
|
||||||
MAV_RESULT result = MAV_RESULT_FAILED;
|
MAV_RESULT result = MAV_RESULT_FAILED;
|
||||||
@ -2167,6 +2181,10 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_message(mavlink_command_long_t &pack
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
case MAV_CMD_GET_HOME_POSITION:
|
||||||
|
result = handle_command_get_home_position(packet);
|
||||||
|
break;
|
||||||
|
|
||||||
case MAV_CMD_PREFLIGHT_STORAGE:
|
case MAV_CMD_PREFLIGHT_STORAGE:
|
||||||
if (is_equal(packet.param1, 2.0f)) {
|
if (is_equal(packet.param1, 2.0f)) {
|
||||||
AP_Param::erase_all();
|
AP_Param::erase_all();
|
||||||
|
Loading…
Reference in New Issue
Block a user