Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion diff_drive_controller/src/speed_limiter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,7 @@ namespace diff_drive_controller
const double dv = v - v0;
const double dv0 = v0 - v1;

const double dt2 = 2. * dt * dt;
const double dt2 = dt * dt;

const double da_min = min_jerk * dt2;
const double da_max = max_jerk * dt2;
Expand Down
4 changes: 2 additions & 2 deletions diff_drive_controller/test/diffbot_limits.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,12 +8,12 @@ diffbot_controller:
min_acceleration: -0.5
max_acceleration: 1.0
has_jerk_limits: true
max_jerk: 5.0
max_jerk: 10.0
angular:
z:
has_velocity_limits: true
max_velocity: 2.0
has_acceleration_limits: true
max_acceleration: 2.0
has_jerk_limits: true
max_jerk: 10.0
max_jerk: 20.0
2 changes: 1 addition & 1 deletion four_wheel_steering_controller/src/speed_limiter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ namespace four_wheel_steering_controller
const double dv = v - v0;
const double dv0 = v0 - v1;

const double dt2 = 2. * dt * dt;
const double dt2 = dt * dt;

const double da_min = min_jerk * dt2;
const double da_max = max_jerk * dt2;
Expand Down