mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: support balance bot in AUTO mdoe
This commit is contained in:
parent
87f8e523de
commit
6dcab4e87b
@ -554,7 +554,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||||||
// @Range: 0 5
|
// @Range: 0 5
|
||||||
// @Increment: 0.1
|
// @Increment: 0.1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("BAL_PITCH_MAX", 21, ParametersG2, bal_pitch_max, 5),
|
AP_GROUPINFO("BAL_PITCH_MAX", 21, ParametersG2, bal_pitch_max, 2),
|
||||||
|
|
||||||
// @Param: CRASH_ANGLE
|
// @Param: CRASH_ANGLE
|
||||||
// @DisplayName: Crash Angle
|
// @DisplayName: Crash Angle
|
||||||
|
@ -268,6 +268,11 @@ bool Mode::stop_vehicle()
|
|||||||
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 = 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);
|
||||||
|
|
||||||
|
// if vehicle is balance bot, calculate actual throttle required for balancing
|
||||||
|
if (rover.is_balancebot()) {
|
||||||
|
rover.balancebot_pitch_control(throttle_out, rover.arming.is_armed());
|
||||||
|
}
|
||||||
|
|
||||||
// send to motor
|
// send to motor
|
||||||
g2.motors.set_throttle(throttle_out);
|
g2.motors.set_throttle(throttle_out);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user