mirror of https://github.com/ArduPilot/ardupilot
AP_Vehicle: Set position target depends on ext control
* Used to depend on scripting but now it's used in AP_ExternalControl Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
This commit is contained in:
parent
76861eaa9b
commit
faa8ac0085
|
@ -34,6 +34,7 @@
|
||||||
#include <AP_Button/AP_Button.h>
|
#include <AP_Button/AP_Button.h>
|
||||||
#include <AP_Compass/AP_Compass.h>
|
#include <AP_Compass/AP_Compass.h>
|
||||||
#include <AP_EFI/AP_EFI.h>
|
#include <AP_EFI/AP_EFI.h>
|
||||||
|
#include <AP_ExternalControl/AP_ExternalControl_config.h>
|
||||||
#include <AP_GPS/AP_GPS.h>
|
#include <AP_GPS/AP_GPS.h>
|
||||||
#include <AP_Generator/AP_Generator.h>
|
#include <AP_Generator/AP_Generator.h>
|
||||||
#include <AP_Notify/AP_Notify.h> // Notify library
|
#include <AP_Notify/AP_Notify.h> // Notify library
|
||||||
|
@ -155,12 +156,15 @@ public:
|
||||||
// returns true if the vehicle has crashed
|
// returns true if the vehicle has crashed
|
||||||
virtual bool is_crashed() const;
|
virtual bool is_crashed() const;
|
||||||
|
|
||||||
|
#if AP_EXTERNAL_CONTROL_ENABLED
|
||||||
|
// Method to control vehicle position for use by external control
|
||||||
|
virtual bool set_target_location(const Location& target_loc) { return false; }
|
||||||
|
#endif // AP_EXTERNAL_CONTROL_ENABLED
|
||||||
#if AP_SCRIPTING_ENABLED
|
#if AP_SCRIPTING_ENABLED
|
||||||
/*
|
/*
|
||||||
methods to control vehicle for use by scripting
|
methods to control vehicle for use by scripting
|
||||||
*/
|
*/
|
||||||
virtual bool start_takeoff(float alt) { return false; }
|
virtual bool start_takeoff(float alt) { return false; }
|
||||||
virtual bool set_target_location(const Location& target_loc) { return false; }
|
|
||||||
virtual bool set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt) { return false; }
|
virtual bool set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt) { return false; }
|
||||||
virtual bool set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel) { return false; }
|
virtual bool set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel) { return false; }
|
||||||
virtual bool set_target_posvelaccel_NED(const Vector3f& target_pos, const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative) { return false; }
|
virtual bool set_target_posvelaccel_NED(const Vector3f& target_pos, const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative) { return false; }
|
||||||
|
|
Loading…
Reference in New Issue