mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Rover: balance bots continue balancing when stopped
This commit is contained in:
parent
e806d0c385
commit
85c3286c6e
@ -309,7 +309,7 @@ void Mode::calc_throttle(float target_speed, bool nudge_allowed, bool avoidance_
|
|||||||
float throttle_out;
|
float throttle_out;
|
||||||
|
|
||||||
// call speed or stop controller
|
// call speed or stop controller
|
||||||
if (is_zero(target_speed)) {
|
if (is_zero(target_speed) && !rover.is_balancebot()) {
|
||||||
bool stopped;
|
bool stopped;
|
||||||
throttle_out = 100.0f * attitude_control.get_throttle_out_stop(g2.motors.limit.throttle_lower, g2.motors.limit.throttle_upper, g.speed_cruise, g.throttle_cruise * 0.01f, rover.G_Dt, stopped);
|
throttle_out = 100.0f * attitude_control.get_throttle_out_stop(g2.motors.limit.throttle_lower, g2.motors.limit.throttle_upper, g.speed_cruise, g.throttle_cruise * 0.01f, rover.G_Dt, stopped);
|
||||||
} else {
|
} else {
|
||||||
@ -333,11 +333,14 @@ bool Mode::stop_vehicle()
|
|||||||
{
|
{
|
||||||
// call throttle controller and convert output to -100 to +100 range
|
// call throttle controller and convert output to -100 to +100 range
|
||||||
bool stopped = false;
|
bool stopped = false;
|
||||||
float throttle_out = 100.0f * attitude_control.get_throttle_out_stop(g2.motors.limit.throttle_lower, g2.motors.limit.throttle_upper, g.speed_cruise, g.throttle_cruise * 0.01f, rover.G_Dt, stopped);
|
float throttle_out;
|
||||||
|
|
||||||
// if vehicle is balance bot, calculate actual throttle required for balancing
|
// if vehicle is balance bot, calculate throttle required for balancing
|
||||||
if (rover.is_balancebot()) {
|
if (rover.is_balancebot()) {
|
||||||
|
throttle_out = 100.0f * attitude_control.get_throttle_out_speed(0, g2.motors.limit.throttle_lower, g2.motors.limit.throttle_upper, g.speed_cruise, g.throttle_cruise * 0.01f, rover.G_Dt);
|
||||||
rover.balancebot_pitch_control(throttle_out);
|
rover.balancebot_pitch_control(throttle_out);
|
||||||
|
} else {
|
||||||
|
throttle_out = 100.0f * attitude_control.get_throttle_out_stop(g2.motors.limit.throttle_lower, g2.motors.limit.throttle_upper, g.speed_cruise, g.throttle_cruise * 0.01f, rover.G_Dt, stopped);
|
||||||
}
|
}
|
||||||
|
|
||||||
// relax mainsail if present
|
// relax mainsail if present
|
||||||
|
Loading…
Reference in New Issue
Block a user