|
|
|
@ -25,7 +25,7 @@ const AP_Param::GroupInfo Sailboat::var_info[] = {
@@ -25,7 +25,7 @@ const AP_Param::GroupInfo Sailboat::var_info[] = {
|
|
|
|
|
// @Param: ENABLE
|
|
|
|
|
// @DisplayName: Enable Sailboat
|
|
|
|
|
// @Description: This enables Sailboat functionality
|
|
|
|
|
// @Values: 0:Disable,1:Enable
|
|
|
|
|
// @Values: 0:Disable,1:Enable sail assist only,2:Enable
|
|
|
|
|
// @User: Standard
|
|
|
|
|
// @RebootRequired: True
|
|
|
|
|
AP_GROUPINFO_FLAGS("ENABLE", 1, Sailboat, enable, 0, AP_PARAM_FLAG_ENABLE), |
|
|
|
@ -75,6 +75,15 @@ const AP_Param::GroupInfo Sailboat::var_info[] = {
@@ -75,6 +75,15 @@ const AP_Param::GroupInfo Sailboat::var_info[] = {
|
|
|
|
|
// @User: Standard
|
|
|
|
|
AP_GROUPINFO("NO_GO_ANGLE", 6, Sailboat, sail_no_go, 45), |
|
|
|
|
|
|
|
|
|
// @Param: WNDSPD_MIN
|
|
|
|
|
// @DisplayName: Sailboat minimum wind speed to sail in
|
|
|
|
|
// @Description: Sailboat minimum wind speed to continue sail in, at lower wind speeds the sailboat will motor if one is fitted
|
|
|
|
|
// @Units: m/s
|
|
|
|
|
// @Range: 0 5
|
|
|
|
|
// @Increment: 0.1
|
|
|
|
|
// @User: Standard
|
|
|
|
|
AP_GROUPINFO("WNDSPD_MIN", 7, Sailboat, sail_assist_windspeed, 0), |
|
|
|
|
|
|
|
|
|
AP_GROUPEND |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
@ -87,30 +96,93 @@ Sailboat::Sailboat()
@@ -87,30 +96,93 @@ Sailboat::Sailboat()
|
|
|
|
|
AP_Param::setup_object_defaults(this, var_info); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// Should we use sailboat navigation?
|
|
|
|
|
bool Sailboat::nav_enabled() const |
|
|
|
|
{ |
|
|
|
|
return (enable == 2) && |
|
|
|
|
(throttle_state != Sailboat_Throttle::FORCE_MOTOR) && |
|
|
|
|
(!throttle_assist() || tack_assist); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void Sailboat::init() |
|
|
|
|
{ |
|
|
|
|
// sailboat defaults
|
|
|
|
|
if (enabled()) { |
|
|
|
|
if (sail_enabled()) { |
|
|
|
|
rover.g2.crash_angle.set_default(0); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (nav_enabled()) { |
|
|
|
|
rover.g2.loit_type.set_default(1); |
|
|
|
|
rover.g2.loit_radius.set_default(5); |
|
|
|
|
rover.g2.wp_nav.set_default_overshoot(10); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// if we have a throttle of some sort allow to use it
|
|
|
|
|
if (rover.g2.motors.have_skid_steering() || |
|
|
|
|
SRV_Channels::function_assigned(SRV_Channel::k_throttle) || |
|
|
|
|
rover.get_frame_type() != rover.g2.motors.frame_type::FRAME_TYPE_UNDEFINED) { |
|
|
|
|
throttle_state = Sailboat_Throttle::ASSIST; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// update mainsail's desired angle based on wind speed and direction and desired speed (in m/s)
|
|
|
|
|
void Sailboat::update_mainsail(float desired_speed) |
|
|
|
|
// initialise rc input (channel_mainsail), may be called intermittently
|
|
|
|
|
void Sailboat::init_rc_in() |
|
|
|
|
{ |
|
|
|
|
if (!enabled()) { |
|
|
|
|
// get auxiliary throttle value
|
|
|
|
|
RC_Channel *rc_ptr = rc().find_channel_for_option(RC_Channel::AUX_FUNC::MAINSAIL); |
|
|
|
|
if (rc_ptr != nullptr) { |
|
|
|
|
// use aux as sail input if defined
|
|
|
|
|
channel_mainsail = rc_ptr; |
|
|
|
|
channel_mainsail->set_angle(100); |
|
|
|
|
channel_mainsail->set_default_dead_zone(30); |
|
|
|
|
} else { |
|
|
|
|
// use throttle channel
|
|
|
|
|
channel_mainsail = rover.channel_throttle; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// decode pilot mainsail input and return in steer_out and throttle_out arguments
|
|
|
|
|
// mainsail_out is in the range 0 to 100, defaults to 100 (fully relaxed) if no input configured
|
|
|
|
|
void Sailboat::get_pilot_desired_mainsail(float &mainsail_out) |
|
|
|
|
{ |
|
|
|
|
// no RC input means mainsail is moved to trim
|
|
|
|
|
if ((rover.failsafe.bits & FAILSAFE_EVENT_THROTTLE) || (channel_mainsail == nullptr)) { |
|
|
|
|
mainsail_out = 100.0f; |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
mainsail_out = constrain_float(channel_mainsail->get_control_in(), 0.0f, 100.0f); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// relax sail if desired speed is zero
|
|
|
|
|
if (!is_positive(desired_speed)) { |
|
|
|
|
rover.g2.motors.set_mainsail(100.0f); |
|
|
|
|
// calculate throttle and mainsail angle required to attain desired speed (in m/s)
|
|
|
|
|
// returns true if successful, false if sailboats not enabled
|
|
|
|
|
void Sailboat::get_throttle_and_mainsail_out(float desired_speed, float &throttle_out, float &mainsail_out) |
|
|
|
|
{ |
|
|
|
|
if (!sail_enabled()) { |
|
|
|
|
throttle_out = 0.0f; |
|
|
|
|
mainsail_out = 0.0f; |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// run speed controller if motor is forced on or if assistance is enabled for low speeds or tacking
|
|
|
|
|
if ((throttle_state == Sailboat_Throttle::FORCE_MOTOR) || throttle_assist()) { |
|
|
|
|
// run speed controller - duplicate of calls found in mode::calc_throttle();
|
|
|
|
|
throttle_out = 100.0f * rover.g2.attitude_control.get_throttle_out_speed(desired_speed, |
|
|
|
|
rover.g2.motors.limit.throttle_lower, |
|
|
|
|
rover.g2.motors.limit.throttle_upper, |
|
|
|
|
rover.g.speed_cruise, |
|
|
|
|
rover.g.throttle_cruise * 0.01f, |
|
|
|
|
rover.G_Dt); |
|
|
|
|
} else { |
|
|
|
|
throttle_out = 0.0f; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
//
|
|
|
|
|
// mainsail control
|
|
|
|
|
//
|
|
|
|
|
// if we are motoring or attempting to reverse relax the sail
|
|
|
|
|
if (throttle_state == Sailboat_Throttle::FORCE_MOTOR || !is_positive(desired_speed)) { |
|
|
|
|
mainsail_out = 100.0f; |
|
|
|
|
} else { |
|
|
|
|
// + is wind over starboard side, - is wind over port side, but as the sails are sheeted the same on each side it makes no difference so take abs
|
|
|
|
|
float wind_dir_apparent = fabsf(rover.g2.windvane.get_apparent_wind_direction_rad()); |
|
|
|
|
wind_dir_apparent = degrees(wind_dir_apparent); |
|
|
|
@ -122,13 +194,13 @@ void Sailboat::update_mainsail(float desired_speed)
@@ -122,13 +194,13 @@ void Sailboat::update_mainsail(float desired_speed)
|
|
|
|
|
mainsail_angle = constrain_float(mainsail_angle,sail_angle_min, sail_angle_max); |
|
|
|
|
|
|
|
|
|
// linear interpolate mainsail value (0 to 100) from wind angle mainsail_angle
|
|
|
|
|
float mainsail = linear_interpolate(0.0f, 100.0f, mainsail_angle,sail_angle_min,sail_angle_max); |
|
|
|
|
float mainsail_base = linear_interpolate(0.0f, 100.0f, mainsail_angle,sail_angle_min,sail_angle_max); |
|
|
|
|
|
|
|
|
|
// use PID controller to sheet out
|
|
|
|
|
const float pid_offset = rover.g2.attitude_control.get_sail_out_from_heel(radians(sail_heel_angle_max), rover.G_Dt) * 100.0f; |
|
|
|
|
|
|
|
|
|
mainsail = constrain_float((mainsail+pid_offset), 0.0f ,100.0f); |
|
|
|
|
rover.g2.motors.set_mainsail(mainsail); |
|
|
|
|
mainsail_out = constrain_float((mainsail_base + pid_offset), 0.0f ,100.0f); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// Velocity Made Good, this is the speed we are traveling towards the desired destination
|
|
|
|
@ -152,9 +224,14 @@ float Sailboat::get_VMG() const
@@ -152,9 +224,14 @@ float Sailboat::get_VMG() const
|
|
|
|
|
// handle user initiated tack while in acro mode
|
|
|
|
|
void Sailboat::handle_tack_request_acro() |
|
|
|
|
{ |
|
|
|
|
if (!nav_enabled() || currently_tacking) { |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
// set tacking heading target to the current angle relative to the true wind but on the new tack
|
|
|
|
|
currently_tacking = true; |
|
|
|
|
tack_heading_rad = wrap_2PI(rover.ahrs.yaw + 2.0f * wrap_PI((rover.g2.windvane.get_absolute_wind_direction_rad() - rover.ahrs.yaw))); |
|
|
|
|
|
|
|
|
|
auto_tack_request_ms = AP_HAL::millis(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// return target heading in radians when tacking (only used in acro)
|
|
|
|
@ -166,6 +243,10 @@ float Sailboat::get_tack_heading_rad() const
@@ -166,6 +243,10 @@ float Sailboat::get_tack_heading_rad() const
|
|
|
|
|
// handle user initiated tack while in autonomous modes (Auto, Guided, RTL, SmartRTL, etc)
|
|
|
|
|
void Sailboat::handle_tack_request_auto() |
|
|
|
|
{ |
|
|
|
|
if (!nav_enabled() || currently_tacking) { |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// record time of request for tack. This will be processed asynchronously by sailboat_calc_heading
|
|
|
|
|
auto_tack_request_ms = AP_HAL::millis(); |
|
|
|
|
} |
|
|
|
@ -174,20 +255,21 @@ void Sailboat::handle_tack_request_auto()
@@ -174,20 +255,21 @@ void Sailboat::handle_tack_request_auto()
|
|
|
|
|
void Sailboat::clear_tack() |
|
|
|
|
{ |
|
|
|
|
currently_tacking = false; |
|
|
|
|
tack_assist = false; |
|
|
|
|
auto_tack_request_ms = 0; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// returns true if boat is currently tacking
|
|
|
|
|
bool Sailboat::tacking() const |
|
|
|
|
{ |
|
|
|
|
return enabled() && currently_tacking; |
|
|
|
|
return nav_enabled() && currently_tacking; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// returns true if sailboat should take a indirect navigation route to go upwind
|
|
|
|
|
// desired_heading should be in centi-degrees
|
|
|
|
|
bool Sailboat::use_indirect_route(float desired_heading_cd) const |
|
|
|
|
{ |
|
|
|
|
if (!enabled()) { |
|
|
|
|
if (!nav_enabled()) { |
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -202,7 +284,7 @@ bool Sailboat::use_indirect_route(float desired_heading_cd) const
@@ -202,7 +284,7 @@ bool Sailboat::use_indirect_route(float desired_heading_cd) const
|
|
|
|
|
// this function assumes the caller has already checked sailboat_use_indirect_route(desired_heading_cd) returned true
|
|
|
|
|
float Sailboat::calc_heading(float desired_heading_cd) |
|
|
|
|
{ |
|
|
|
|
if (!enabled()) { |
|
|
|
|
if (!nav_enabled()) { |
|
|
|
|
return desired_heading_cd; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -266,9 +348,14 @@ float Sailboat::calc_heading(float desired_heading_cd)
@@ -266,9 +348,14 @@ float Sailboat::calc_heading(float desired_heading_cd)
|
|
|
|
|
clear_tack(); |
|
|
|
|
} else if ((now - auto_tack_start_ms) > SAILBOAT_AUTO_TACKING_TIMEOUT_MS) { |
|
|
|
|
// tack has taken too long
|
|
|
|
|
if ((throttle_state == Sailboat_Throttle::ASSIST) && (now - auto_tack_start_ms) < (3.0f * SAILBOAT_AUTO_TACKING_TIMEOUT_MS)) { |
|
|
|
|
// if we have throttle available use it for another two time periods to get the tack done
|
|
|
|
|
tack_assist = true; |
|
|
|
|
} else { |
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Sailboat: Tacking timed out"); |
|
|
|
|
clear_tack(); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
// return tack target heading
|
|
|
|
|
return degrees(tack_heading_rad) * 100.0f; |
|
|
|
|
} |
|
|
|
@ -280,3 +367,26 @@ float Sailboat::calc_heading(float desired_heading_cd)
@@ -280,3 +367,26 @@ float Sailboat::calc_heading(float desired_heading_cd)
|
|
|
|
|
return degrees(right_no_go_heading_rad) * 100.0f; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// should we use the throttle?
|
|
|
|
|
bool Sailboat::throttle_assist() const |
|
|
|
|
{ |
|
|
|
|
// throttle is assist is disabled
|
|
|
|
|
if (throttle_state != Sailboat_Throttle::ASSIST) { |
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// assist with a tack
|
|
|
|
|
if (tack_assist) { |
|
|
|
|
return true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// wind speed is less than sailing cut-off
|
|
|
|
|
if (!is_zero(sail_assist_windspeed) && |
|
|
|
|
rover.g2.windvane.wind_speed_enabled() && |
|
|
|
|
rover.g2.windvane.get_true_wind_speed() < sail_assist_windspeed) { |
|
|
|
|
return true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|