mirror of https://github.com/ArduPilot/ardupilot
AP_Vehicle: add set_target_posvel_NED method
This commit is contained in:
parent
0fe65fd6d3
commit
858d69ca0e
|
@ -183,6 +183,7 @@ public:
|
|||
*/
|
||||
virtual bool start_takeoff(float alt) { return false; }
|
||||
virtual bool set_target_location(const Location& target_loc) { return false; }
|
||||
virtual bool set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel) { return false; }
|
||||
virtual bool set_target_velocity_NED(const Vector3f& vel_ned) { 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; }
|
||||
|
||||
|
|
Loading…
Reference in New Issue