mirror of https://github.com/ArduPilot/ardupilot
AP_Navigation: Adding set_reverse to virtual parent class
This commit is contained in:
parent
acaf0c6a5d
commit
647602ed4d
|
@ -113,6 +113,8 @@ public:
|
||||||
// every update_XXXXXX() call.
|
// every update_XXXXXX() call.
|
||||||
virtual bool data_is_stale(void) const = 0;
|
virtual bool data_is_stale(void) const = 0;
|
||||||
|
|
||||||
|
virtual void set_reverse(bool reverse) = 0;
|
||||||
|
|
||||||
// add new navigation controllers to this enum. Users can then
|
// add new navigation controllers to this enum. Users can then
|
||||||
// select which navigation controller to use by setting the
|
// select which navigation controller to use by setting the
|
||||||
// NAV_CONTROLLER parameter
|
// NAV_CONTROLLER parameter
|
||||||
|
|
Loading…
Reference in New Issue