mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: move handling of DO_SET_HOME up to GCS_MAVLink base class
This commit is contained in:
parent
d78e96cc6b
commit
420f80db75
|
@ -526,8 +526,8 @@ protected:
|
|||
virtual MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg);
|
||||
MAV_RESULT handle_command_int_external_position_estimate(const mavlink_command_int_t &packet);
|
||||
|
||||
virtual bool set_home_to_current_location(bool lock) = 0;
|
||||
virtual bool set_home(const Location& loc, bool lock) = 0;
|
||||
bool set_home_to_current_location(bool lock);
|
||||
bool set_home(const Location& loc, bool lock);
|
||||
|
||||
#if AP_ARMING_ENABLED
|
||||
virtual MAV_RESULT handle_command_component_arm_disarm(const mavlink_command_int_t &packet);
|
||||
|
|
|
@ -5057,6 +5057,23 @@ void GCS_MAVLINK::handle_landing_target(const mavlink_message_t &msg)
|
|||
}
|
||||
|
||||
|
||||
bool GCS_MAVLINK::set_home_to_current_location(bool _lock)
|
||||
{
|
||||
#if AP_VEHICLE_ENABLED
|
||||
return AP::vehicle()->set_home_to_current_location(_lock);
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
|
||||
bool GCS_MAVLINK::set_home(const Location& loc, bool _lock) {
|
||||
#if AP_VEHICLE_ENABLED
|
||||
return AP::vehicle()->set_home(loc, _lock);
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_do_set_home(const mavlink_command_int_t &packet)
|
||||
{
|
||||
if (is_equal(packet.param1, 1.0f) || (packet.x == 0 && packet.y == 0)) {
|
||||
|
|
|
@ -33,9 +33,6 @@ protected:
|
|||
MAV_MODE base_mode() const override { return (MAV_MODE)MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; }
|
||||
MAV_STATE vehicle_system_status() const override { return MAV_STATE_CALIBRATING; }
|
||||
|
||||
bool set_home_to_current_location(bool _lock) override { return false; }
|
||||
bool set_home(const Location& loc, bool _lock) override { return false; }
|
||||
|
||||
void send_nav_controller_output() const override {};
|
||||
void send_pid_tuning() override {};
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue