mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Rover: circle mode loses input shaping
This commit is contained in:
parent
dc9e1a2bc3
commit
12268609b1
@ -177,7 +177,7 @@ void ModeCircle::update()
|
|||||||
target.accel = Vector2f(sq(target.speed) / config.radius, 0);
|
target.accel = Vector2f(sq(target.speed) / config.radius, 0);
|
||||||
target.accel.rotate(target.yaw_rad + radians(180));
|
target.accel.rotate(target.yaw_rad + radians(180));
|
||||||
|
|
||||||
g2.pos_control.input_pos_vel_accel_target(target.pos, target.vel, target.accel, rover.G_Dt);
|
g2.pos_control.set_pos_vel_accel_target(target.pos, target.vel, target.accel);
|
||||||
g2.pos_control.update(rover.G_Dt);
|
g2.pos_control.update(rover.G_Dt);
|
||||||
|
|
||||||
// get desired speed and turn rate from pos_control
|
// get desired speed and turn rate from pos_control
|
||||||
|
Loading…
Reference in New Issue
Block a user