mirror of https://github.com/ArduPilot/ardupilot
AP_ExternalControl: add REP-147 Global Position Control
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
This commit is contained in:
parent
da976300d1
commit
c22a3439d4
|
@ -0,0 +1,22 @@
|
|||
/*
|
||||
external control library for plane
|
||||
*/
|
||||
|
||||
|
||||
#include "AP_ExternalControl_Plane.h"
|
||||
#if AP_EXTERNAL_CONTROL_ENABLED
|
||||
|
||||
#include "Plane.h"
|
||||
|
||||
/*
|
||||
Sets the target global position for a loiter point.
|
||||
*/
|
||||
bool AP_ExternalControl_Plane::set_global_position(const Location& loc)
|
||||
{
|
||||
|
||||
// set_target_location already checks if plane is ready for external control.
|
||||
// It doesn't check if flying or armed, just that it's in guided mode.
|
||||
return plane.set_target_location(loc);
|
||||
}
|
||||
|
||||
#endif // AP_EXTERNAL_CONTROL_ENABLED
|
|
@ -8,6 +8,7 @@
|
|||
|
||||
#if AP_EXTERNAL_CONTROL_ENABLED
|
||||
|
||||
#include <AP_Common/Location.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
class AP_ExternalControl
|
||||
|
@ -24,9 +25,18 @@ public:
|
|||
return false;
|
||||
}
|
||||
|
||||
/*
|
||||
Sets the target global position with standard guided mode behavior.
|
||||
*/
|
||||
virtual bool set_global_position(const Location& loc) WARN_IF_UNUSED {
|
||||
return false;
|
||||
}
|
||||
|
||||
static AP_ExternalControl *get_singleton(void) WARN_IF_UNUSED {
|
||||
return singleton;
|
||||
}
|
||||
protected:
|
||||
~AP_ExternalControl() {}
|
||||
|
||||
private:
|
||||
static AP_ExternalControl *singleton;
|
||||
|
|
Loading…
Reference in New Issue