Skip to content

Commit

Permalink
AP_Vehicle: add bindings to support Plane scripted follow
Browse files Browse the repository at this point in the history
  • Loading branch information
timtuxworth committed Jun 24, 2024
1 parent 92f96a2 commit 9e18667
Showing 1 changed file with 4 additions and 0 deletions.
4 changes: 4 additions & 0 deletions libraries/AP_Vehicle/AP_Vehicle.h
Original file line number Diff line number Diff line change
Expand Up @@ -184,6 +184,7 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks {
virtual bool set_target_velocity_NED(const Vector3f& vel_ned) { return false; }
virtual bool set_target_velaccel_NED(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_angle_and_climbrate(float roll_deg, float pitch_deg, float yaw_deg, float climb_rate_ms, bool use_yaw_rate, float yaw_rate_degs) { return false; }
virtual bool set_guided_radius_and_direction(float radius, bool direction_is_ccw) { return false; }

// command throttle percentage and roll, pitch, yaw target
// rates. For use with scripting controllers
Expand All @@ -209,6 +210,9 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks {
// set auto mode speed in meters/sec (for use by scripting with Copter/Rover)
virtual bool set_desired_speed(float speed) { return false; }

// set auto mode airspeed in meters/sec (for use by scripting with Plane)
virtual bool set_desired_airspeed(float airspeed_new) { return false; }

// support for NAV_SCRIPT_TIME mission command
virtual bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4) { return false; }
virtual void nav_script_time_done(uint16_t id) {}
Expand Down

0 comments on commit 9e18667

Please sign in to comment.