Rover: AP_MotorsUGV make has sail protected

This commit is contained in:
Peter Hall 2019-05-14 17:36:10 +01:00 committed by Randy Mackay
parent 960c30c909
commit e2ed76886c

View File

@ -79,9 +79,6 @@ public:
// true if vehicle has vectored thrust (i.e. boat with motor on steering servo) // true if vehicle has vectored thrust (i.e. boat with motor on steering servo)
bool have_vectored_thrust() const { return is_positive(_vector_throttle_base); } bool have_vectored_thrust() const { return is_positive(_vector_throttle_base); }
// true if the vehicle has a mainsail
bool has_sail() const;
// output to motors and steering servos // output to motors and steering servos
// ground_speed should be the vehicle's speed over the surface in m/s // ground_speed should be the vehicle's speed over the surface in m/s
// dt should be expected time between calls to this function // dt should be expected time between calls to this function
@ -144,6 +141,9 @@ protected:
// output for sailboat's mainsail in the range of 0 to 100 // output for sailboat's mainsail in the range of 0 to 100
void output_mainsail(); void output_mainsail();
// true if the vehicle has a mainsail
bool has_sail() const;
// slew limit throttle for one iteration // slew limit throttle for one iteration
void slew_limit_throttle(float dt); void slew_limit_throttle(float dt);