mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-06 16:08:28 -04:00
Rover: remove redundant avoidance call from steering
This commit is contained in:
parent
a7d66fdad6
commit
dcce9dffba
@ -47,9 +47,6 @@ void ModeSteering::update()
|
|||||||
// mark us as in_reverse when using a negative throttle
|
// mark us as in_reverse when using a negative throttle
|
||||||
rover.set_reverse(reversed);
|
rover.set_reverse(reversed);
|
||||||
|
|
||||||
// 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 lateral acceleration to steering controller
|
// run lateral acceleration to steering controller
|
||||||
calc_steering_from_lateral_acceleration(desired_lat_accel, reversed);
|
calc_steering_from_lateral_acceleration(desired_lat_accel, reversed);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user