mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Vehicle: move handling of DO_SET_HOME up to GCS_MAVLink base class
This commit is contained in:
parent
ecf93f6d86
commit
d78e96cc6b
@ -289,6 +289,11 @@ public:
|
||||
*/
|
||||
virtual bool get_rate_ef_targets(Vector3f& rate_ef_targets) const { return false; }
|
||||
|
||||
#if AP_AHRS_ENABLED
|
||||
virtual bool set_home_to_current_location(bool lock) WARN_IF_UNUSED = 0;
|
||||
virtual bool set_home(const Location& loc, bool lock) WARN_IF_UNUSED = 0;
|
||||
#endif
|
||||
|
||||
protected:
|
||||
|
||||
virtual void init_ardupilot() = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user