mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: move to use new sailboat class
This commit is contained in:
parent
5519527874
commit
f22d7c906a
@ -46,7 +46,7 @@ void Rover::Log_Write_Attitude()
|
||||
}
|
||||
|
||||
// log heel to sail control for sailboats
|
||||
if (g2.motors.has_sail()) {
|
||||
if (rover.g2.sailboat.enabled()) {
|
||||
logger.Write_PID(LOG_PIDR_MSG, g2.attitude_control.get_sailboat_heel_pid().get_pid_info());
|
||||
}
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
@ -141,7 +141,7 @@ void Rover::Log_Write_Nav_Tuning()
|
||||
void Rover::Log_Write_Sail()
|
||||
{
|
||||
// only log sail if present
|
||||
if (!g2.motors.has_sail()) {
|
||||
if (!rover.g2.sailboat.enabled()) {
|
||||
return;
|
||||
}
|
||||
|
||||
@ -164,7 +164,7 @@ void Rover::Log_Write_Sail()
|
||||
(double)wind_speed_true,
|
||||
(double)wind_speed_apparent,
|
||||
(double)g2.motors.get_mainsail(),
|
||||
(double)sailboat_get_VMG());
|
||||
(double)g2.sailboat.get_VMG());
|
||||
}
|
||||
|
||||
struct PACKED log_Steering {
|
||||
|
@ -45,7 +45,7 @@ bool Mode::enter()
|
||||
set_reversed(false);
|
||||
|
||||
// clear sailboat tacking flags
|
||||
rover.sailboat_clear_tack();
|
||||
rover.g2.sailboat.clear_tack();
|
||||
}
|
||||
|
||||
return ret;
|
||||
@ -257,7 +257,7 @@ void Mode::handle_tack_request()
|
||||
{
|
||||
// autopilot modes handle tacking
|
||||
if (is_autopilot_mode()) {
|
||||
rover.sailboat_handle_tack_request_auto();
|
||||
rover.g2.sailboat.handle_tack_request_auto();
|
||||
}
|
||||
}
|
||||
|
||||
@ -288,7 +288,7 @@ void Mode::calc_throttle(float target_speed, bool avoidance_enabled)
|
||||
}
|
||||
|
||||
// update mainsail position if present
|
||||
rover.sailboat_update_mainsail(target_speed);
|
||||
rover.g2.sailboat.update_mainsail(target_speed);
|
||||
|
||||
// send to motor
|
||||
g2.motors.set_throttle(throttle_out);
|
||||
@ -395,9 +395,9 @@ void Mode::navigate_to_waypoint()
|
||||
calc_throttle(desired_speed, true);
|
||||
|
||||
float desired_heading_cd = g2.wp_nav.wp_bearing_cd();
|
||||
if (rover.sailboat_use_indirect_route(desired_heading_cd)) {
|
||||
if (g2.sailboat.use_indirect_route(desired_heading_cd)) {
|
||||
// sailboats use heading controller when tacking upwind
|
||||
desired_heading_cd = rover.sailboat_calc_heading(desired_heading_cd);
|
||||
desired_heading_cd = g2.sailboat.calc_heading(desired_heading_cd);
|
||||
calc_steering_to_heading(desired_heading_cd, g2.wp_nav.get_pivot_rate());
|
||||
} else {
|
||||
// call turn rate steering controller
|
||||
|
@ -23,11 +23,12 @@ void ModeAcro::update()
|
||||
// handle sailboats
|
||||
if (!is_zero(desired_steering)) {
|
||||
// steering input return control to user
|
||||
rover.sailboat_clear_tack();
|
||||
rover.g2.sailboat.clear_tack();
|
||||
}
|
||||
if (g2.motors.has_sail() && rover.sailboat_tacking()) {
|
||||
if (rover.g2.sailboat.tacking()) {
|
||||
// call heading controller during tacking
|
||||
steering_out = attitude_control.get_steering_out_heading(rover.sailboat_get_tack_heading_rad(),
|
||||
|
||||
steering_out = attitude_control.get_steering_out_heading(rover.g2.sailboat.get_tack_heading_rad(),
|
||||
g2.wp_nav.get_pivot_rate(),
|
||||
g2.motors.limit.steer_left,
|
||||
g2.motors.limit.steer_right,
|
||||
@ -54,5 +55,5 @@ bool ModeAcro::requires_velocity() const
|
||||
// sailboats in acro mode support user manually initiating tacking from transmitter
|
||||
void ModeAcro::handle_tack_request()
|
||||
{
|
||||
rover.sailboat_handle_tack_request_acro();
|
||||
rover.g2.sailboat.handle_tack_request_acro();
|
||||
}
|
||||
|
@ -25,7 +25,7 @@ void ModeLoiter::update()
|
||||
// if within loiter radius slew desired speed towards zero and use existing desired heading
|
||||
if (_distance_to_destination <= g2.loit_radius) {
|
||||
// sailboats do not stop
|
||||
const float desired_speed_within_radius = g2.motors.has_sail() ? 0.1f : 0.0f;
|
||||
const float desired_speed_within_radius = rover.g2.sailboat.enabled() ? 0.1f : 0.0f;
|
||||
_desired_speed = attitude_control.get_desired_speed_accel_limited(desired_speed_within_radius, rover.G_Dt);
|
||||
} else {
|
||||
// P controller with hard-coded gain to convert distance to desired speed
|
||||
|
Loading…
Reference in New Issue
Block a user