AP_Vehicle: added nav_script_time methods

for supporting aerobatics in scripts
This commit is contained in:
Andrew Tridgell 2021-10-25 15:34:59 +11:00
parent 0c1e576544
commit 527d9b38e6

View File

@ -201,6 +201,10 @@ public:
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; }
// command throttle percentage and roll, pitch, yaw target
// rates. For use with scripting controllers
virtual bool set_target_throttle_rate_rpy(float throttle_pct, float roll_rate_dps, float pitch_rate_dps, float yaw_rate_dps) { return false; }
// get target location (for use by scripting)
virtual bool get_target_location(Location& target_loc) { return false; }
@ -210,6 +214,11 @@ public:
// set steering and throttle (-1 to +1) (for use by scripting with Rover)
virtual bool set_steering_and_throttle(float steering, float throttle) { return false; }
// support for NAV_SCRIPT_TIME mission command
virtual bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2) { return false; }
virtual void nav_script_time_done(uint16_t id) {}
#endif // ENABLE_SCRIPTING