Skip to content

Commit

Permalink
AP_Vehicle: Set position target depends on ext control
Browse files Browse the repository at this point in the history
* Used to depend on scripting but now it's used in AP_ExternalControl

Signed-off-by: Ryan Friedman <[email protected]>
  • Loading branch information
Ryanf55 committed Dec 19, 2023
1 parent 090453d commit b6e5a20
Showing 1 changed file with 5 additions and 1 deletion.
6 changes: 5 additions & 1 deletion libraries/AP_Vehicle/AP_Vehicle.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#include <AP_Button/AP_Button.h>
#include <AP_Compass/AP_Compass.h>
#include <AP_EFI/AP_EFI.h>
#include <AP_ExternalControl/AP_ExternalControl_config.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Generator/AP_Generator.h>
#include <AP_Notify/AP_Notify.h> // Notify library
Expand Down Expand Up @@ -151,12 +152,15 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks {
// returns true if the vehicle has crashed
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
/*
methods to control vehicle for use by scripting
*/
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_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; }
Expand Down

0 comments on commit b6e5a20

Please sign in to comment.