mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Rover: sailboat class formatting fixes
move constructor to top of sailboat.h move var_info to be the last public declaration remove some spaces
This commit is contained in:
parent
4ae62a2983
commit
79feb4edb8
@ -20,8 +20,8 @@ class Sailboat
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
|
||||||
// var_info for holding Parameter information
|
// constructor
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
Sailboat();
|
||||||
|
|
||||||
// enabled
|
// enabled
|
||||||
bool sail_enabled() const { return enable > 0;}
|
bool sail_enabled() const { return enable > 0;}
|
||||||
@ -29,9 +29,6 @@ public:
|
|||||||
// true if sailboat navigation (aka tacking) is enabled
|
// true if sailboat navigation (aka tacking) is enabled
|
||||||
bool nav_enabled() const;
|
bool nav_enabled() const;
|
||||||
|
|
||||||
// constructor
|
|
||||||
Sailboat();
|
|
||||||
|
|
||||||
// setup
|
// setup
|
||||||
void init();
|
void init();
|
||||||
|
|
||||||
@ -49,22 +46,22 @@ public:
|
|||||||
float get_VMG() const;
|
float get_VMG() const;
|
||||||
|
|
||||||
// handle user initiated tack while in acro mode
|
// handle user initiated tack while in acro mode
|
||||||
void handle_tack_request_acro();
|
void handle_tack_request_acro();
|
||||||
|
|
||||||
// return target heading in radians when tacking (only used in acro)
|
// return target heading in radians when tacking (only used in acro)
|
||||||
float get_tack_heading_rad() const;
|
float get_tack_heading_rad() const;
|
||||||
|
|
||||||
// handle user initiated tack while in autonomous modes (Auto, Guided, RTL, SmartRTL, etc)
|
// handle user initiated tack while in autonomous modes (Auto, Guided, RTL, SmartRTL, etc)
|
||||||
void handle_tack_request_auto();
|
void handle_tack_request_auto();
|
||||||
|
|
||||||
// clear tacking state variables
|
// clear tacking state variables
|
||||||
void clear_tack();
|
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
|
// calculate the heading to sail on if we cant go upwind
|
||||||
float calc_heading(float desired_heading_cd);
|
float calc_heading(float desired_heading_cd);
|
||||||
@ -76,6 +73,9 @@ public:
|
|||||||
FORCE_MOTOR = 2
|
FORCE_MOTOR = 2
|
||||||
} throttle_state;
|
} throttle_state;
|
||||||
|
|
||||||
|
// var_info for holding Parameter information
|
||||||
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
// Check if we should assist with throttle
|
// Check if we should assist with throttle
|
||||||
|
Loading…
Reference in New Issue
Block a user