Rover: Sailboat: revert friends and private Sailboat functions. See https://github.com/ArduPilot/ardupilot/pull/26152#discussion_r1495156661

This commit is contained in:
Andy Little 2024-02-20 11:36:32 +00:00 committed by Randy Mackay
parent 057d7dca96
commit d867364088
1 changed files with 35 additions and 39 deletions

View File

@ -18,15 +18,6 @@
*/ */
class Sailboat 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: public:
// constructor // constructor
@ -38,15 +29,39 @@ public:
// true if sailboat navigation (aka tacking) is enabled // true if sailboat navigation (aka tacking) is enabled
bool tack_enabled() const; 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 // Velocity Made Good, this is the speed we are traveling towards the desired destination
float get_VMG() const; 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 // returns true if boat is currently tacking
bool tacking() const; bool tacking() const;
// returns true if sailboat should take a indirect navigation route to go upwind // returns true if sailboat should take a indirect navigation route to go upwind
bool use_indirect_route(float desired_heading_cd) const; 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 // states of USE_MOTOR parameter and motor_state variable
enum class UseMotor { enum class UseMotor {
USE_MOTOR_NEVER = 0, USE_MOTOR_NEVER = 0,
@ -54,46 +69,27 @@ public:
USE_MOTOR_ALWAYS = 2 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 // set state of motor
// if report_failure is true a message will be sent to all GCSs // if report_failure is true a message will be sent to all GCSs
void set_motor_state(UseMotor state, bool report_failure = true); void set_motor_state(UseMotor state, bool report_failure = true);
// calculate the heading to sail on if we cant go upwind // var_info for holding Parameter information
float calc_heading(float desired_heading_cd); 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(); void set_pilot_desired_mainsail();
// set mainsail in auto modes
void set_auto_mainsail(float desired_speed); 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(); void relax_sails();
// calculate throttle and set sail private:
void get_throttle_and_set_mainsail(float desired_speed, float &throttle_out);
// true if motor is on to assist with slow tack // true if motor is on to assist with slow tack
bool motor_assist_tack() const; bool motor_assist_tack() const;