mirror of https://github.com/ArduPilot/ardupilot
AP_Vehicle: add support for `set_target_rate_and_throttle`
This commit is contained in:
parent
94944427da
commit
fc327fa370
|
@ -186,6 +186,7 @@ public:
|
||||||
virtual bool set_target_velocity_NED(const Vector3f& vel_ned) { return false; }
|
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_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_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_target_rate_and_throttle(float roll_rate_dps, float pitch_rate_dps, float yaw_rate_dps, float throttle) { return false; }
|
||||||
|
|
||||||
// command throttle percentage and roll, pitch, yaw target
|
// command throttle percentage and roll, pitch, yaw target
|
||||||
// rates. For use with scripting controllers
|
// rates. For use with scripting controllers
|
||||||
|
|
Loading…
Reference in New Issue