Skip to content

Commit

Permalink
Fix backward motion
Browse files Browse the repository at this point in the history
Signed-off-by: Alberto Tudela <[email protected]>
  • Loading branch information
ajtudela committed Feb 6, 2024
1 parent 05e0edc commit a217e4e
Showing 1 changed file with 3 additions and 0 deletions.
3 changes: 3 additions & 0 deletions nav2_graceful_motion_controller/src/smooth_control_law.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,9 @@ geometry_msgs::msg::Twist SmoothControlLaw::calculateRegularVelocity(
// turning motion when the curvature is very high
v = std::clamp(v, v_linear_min_, v_linear_max_);

// Set the velocity to negative if the robot is moving backwards
v = backward ? -v : v;

// Compute the angular velocity
double w = curvature * v;
// Bound angular velocity between [-max_angular_vel, max_angular_vel]
Expand Down

0 comments on commit a217e4e

Please sign in to comment.