diff --git a/Rover/sailboat.h b/Rover/sailboat.h index b6d529c44a577..e0f9d06f30403 100644 --- a/Rover/sailboat.h +++ b/Rover/sailboat.h @@ -18,15 +18,6 @@ */ class Sailboat { - - friend class Rover; - friend class Mode; - friend class ModeManual; - friend class ModeHold; - friend class ModeLoiter; - friend class ModeAcro; - friend class RC_Channel_Rover; - public: // constructor @@ -38,15 +29,39 @@ class Sailboat // true if sailboat navigation (aka tacking) is enabled bool tack_enabled() const; + // setup + void init(); + + // initialise rc input (channel_mainsail) + void init_rc_in(); + + // calculate throttle and set sail + void get_throttle_and_set_mainsail(float desired_speed, float &throttle_out); + // Velocity Made Good, this is the speed we are traveling towards the desired destination float get_VMG() const; + // handle user initiated tack while in acro mode + void handle_tack_request_acro(); + + // return target heading in radians when tacking (only used in acro) + float get_tack_heading_rad(); + + // handle user initiated tack while in autonomous modes (Auto, Guided, RTL, SmartRTL, etc) + void handle_tack_request_auto(); + + // clear tacking state variables + void clear_tack(); + // returns true if boat is currently tacking bool tacking() const; // returns true if sailboat should take a indirect navigation route to go upwind bool use_indirect_route(float desired_heading_cd) const; + // calculate the heading to sail on if we cant go upwind + float calc_heading(float desired_heading_cd); + // states of USE_MOTOR parameter and motor_state variable enum class UseMotor { USE_MOTOR_NEVER = 0, @@ -54,46 +69,27 @@ class Sailboat USE_MOTOR_ALWAYS = 2 }; - // return sailboat loiter radius - float get_loiter_radius() const {return loit_radius;} - - // var_info for holding Parameter information - static const struct AP_Param::GroupInfo var_info[]; - -private: - - // handle user initiated tack while in acro mode - void handle_tack_request_acro(); - - // setup - void init(); - - // initialise rc input (channel_mainsail) - void init_rc_in(); - - // return target heading in radians when tacking (only used in acro) - float get_tack_heading_rad(); - - // clear tacking state variables - void clear_tack(); - - // handle user initiated tack while in autonomous modes (Auto, Guided, RTL, SmartRTL, etc) - void handle_tack_request_auto(); - // set state of motor // if report_failure is true a message will be sent to all GCSs void set_motor_state(UseMotor state, bool report_failure = true); - // calculate the heading to sail on if we cant go upwind - float calc_heading(float desired_heading_cd); + // var_info for holding Parameter information + static const struct AP_Param::GroupInfo var_info[]; + // return sailboat loiter radius + float get_loiter_radius() const {return loit_radius;} + + // set mainsail according to pilot input void set_pilot_desired_mainsail(); + // set mainsail in auto modes void set_auto_mainsail(float desired_speed); + + // as far as possible stop sails driving the boat + // by feathering or sheeting right out void relax_sails(); - // calculate throttle and set sail - void get_throttle_and_set_mainsail(float desired_speed, float &throttle_out); +private: // true if motor is on to assist with slow tack bool motor_assist_tack() const;