mirror of https://github.com/ArduPilot/ardupilot
Rover: acro and steering steer even with target speed of zero
This commit is contained in:
parent
36fab0209e
commit
4e8399ca3f
|
@ -172,7 +172,15 @@ void Mode::calc_throttle(float target_speed, bool nudge_allowed)
|
|||
}
|
||||
|
||||
// call throttle controller and convert output to -100 to +100 range
|
||||
float throttle_out = 100.0f * attitude_control.get_throttle_out_speed(target_speed, g2.motors.limit.throttle_lower, g2.motors.limit.throttle_upper, g.speed_cruise, g.throttle_cruise * 0.01f);
|
||||
float throttle_out;
|
||||
|
||||
// call speed or stop controller
|
||||
if (is_zero(target_speed)) {
|
||||
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, stopped);
|
||||
} else {
|
||||
throttle_out = 100.0f * attitude_control.get_throttle_out_speed(target_speed, g2.motors.limit.throttle_lower, g2.motors.limit.throttle_upper, g.speed_cruise, g.throttle_cruise * 0.01f);
|
||||
}
|
||||
|
||||
// send to motor
|
||||
g2.motors.set_throttle(throttle_out);
|
||||
|
|
|
@ -22,15 +22,6 @@ void ModeAcro::update()
|
|||
// convert pilot steering input to desired turn rate in radians/sec
|
||||
const float target_turn_rate = (desired_steering / 4500.0f) * radians(g2.acro_turn_rate);
|
||||
|
||||
// determine if pilot is requesting pivot turn
|
||||
const bool is_pivot_turning = g2.motors.have_skid_steering() && is_zero(target_speed) && (!is_zero(desired_steering));
|
||||
|
||||
// stop vehicle if target speed is zero and not pivot turning
|
||||
if (is_zero(target_speed) && !is_pivot_turning) {
|
||||
stop_vehicle();
|
||||
return;
|
||||
}
|
||||
|
||||
// set reverse flag backing up
|
||||
const bool reversed = is_negative(target_speed);
|
||||
rover.set_reverse(reversed);
|
||||
|
|
|
@ -50,14 +50,9 @@ void ModeSteering::update()
|
|||
// apply object avoidance to desired speed using half vehicle's maximum acceleration/deceleration
|
||||
rover.g2.avoid.adjust_speed(0.0f, 0.5f * attitude_control.get_accel_max(), ahrs.yaw, target_speed, rover.G_Dt);
|
||||
|
||||
// run speed to throttle output controller
|
||||
if (is_zero(target_speed) && !is_pivot_turning) {
|
||||
stop_vehicle();
|
||||
} else {
|
||||
// run lateral acceleration to steering controller
|
||||
calc_steering_from_lateral_acceleration(desired_lat_accel, reversed);
|
||||
// run lateral acceleration to steering controller
|
||||
calc_steering_from_lateral_acceleration(desired_lat_accel, reversed);
|
||||
|
||||
// run speed to throttle controller
|
||||
calc_throttle(target_speed, false);
|
||||
}
|
||||
// run speed to throttle controller
|
||||
calc_throttle(target_speed, false);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue