Skip to content

Commit

Permalink
Fix backward motion for graceful controller (ros-navigation#4527)
Browse files Browse the repository at this point in the history
* Fix backward motion for graceful controller

Signed-off-by: Alberto Tudela <[email protected]>

* Update smooth_control_law.cpp

Signed-off-by: Alberto Tudela <[email protected]>

---------

Signed-off-by: Alberto Tudela <[email protected]>
  • Loading branch information
ajtudela committed Jul 23, 2024
1 parent ba247b4 commit d1ad640
Show file tree
Hide file tree
Showing 4 changed files with 20 additions and 25 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,6 @@ namespace nav2_graceful_controller
struct EgocentricPolarCoordinates
{
float r; // Radial distance between the robot pose and the target pose.
// Negative value if the robot is moving backwards.
float phi; // Orientation of target with respect to the line of sight
// from the robot to the target.
float delta; // Steering angle of the robot with respect to the line of sight.
Expand Down Expand Up @@ -68,21 +67,6 @@ struct EgocentricPolarCoordinates
r = sqrt(dX * dX + dY * dY);
phi = angles::normalize_angle(tf2::getYaw(target.orientation) + line_of_sight);
delta = angles::normalize_angle(tf2::getYaw(current.orientation) + line_of_sight);
// If the robot is moving backwards, flip the sign of the radial distance
r *= backward ? -1.0 : 1.0;
}

/**
* @brief Construct a new egocentric polar coordinates for the target pose.
*
* @param target Target pose.
* @param backward If true, the robot is moving backwards. Defaults to false.
*/
explicit EgocentricPolarCoordinates(
const geometry_msgs::msg::Pose & target,
bool backward = false)
{
EgocentricPolarCoordinates(target, geometry_msgs::msg::Pose(), backward);
}
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -79,8 +79,7 @@ class SmoothControlLaw
* @param v_angular_max The maximum absolute velocity in the angular direction.
*/
void setSpeedLimit(
const double v_linear_min, const double v_linear_max,
const double v_angular_max);
const double v_linear_min, const double v_linear_max, const double v_angular_max);

/**
* @brief Compute linear and angular velocities command using the curvature.
Expand All @@ -103,8 +102,7 @@ class SmoothControlLaw
* @return Velocity command.
*/
geometry_msgs::msg::Twist calculateRegularVelocity(
const geometry_msgs::msg::Pose & target,
const bool & backward = false);
const geometry_msgs::msg::Pose & target, const bool & backward = false);

/**
* @brief Calculate the next pose of the robot by generating a velocity command using the
Expand Down
5 changes: 3 additions & 2 deletions nav2_graceful_controller/src/smooth_control_law.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,7 @@ void SmoothControlLaw::setSlowdownRadius(double slowdown_radius)
}

void SmoothControlLaw::setSpeedLimit(
const double v_linear_min, const double v_linear_max,
const double v_angular_max)
const double v_linear_min, const double v_linear_max, const double v_angular_max)
{
v_linear_min_ = v_linear_min;
v_linear_max_ = v_linear_max;
Expand All @@ -59,6 +58,8 @@ geometry_msgs::msg::Twist SmoothControlLaw::calculateRegularVelocity(
auto ego_coords = EgocentricPolarCoordinates(target, current, backward);
// Calculate the curvature
double curvature = calculateCurvature(ego_coords.r, ego_coords.phi, ego_coords.delta);
// Invert the curvature if the robot is moving backwards
curvature = backward ? -curvature : curvature;

// Adjust the linear velocity as a function of the path curvature to
// slowdown the controller as it approaches its target
Expand Down
18 changes: 15 additions & 3 deletions nav2_graceful_controller/test/test_egopolar.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,7 @@ TEST(EgocentricPolarCoordinatesTest, constructorWithValues) {
float phi_value = 1.2;
float delta_value = -0.5;

nav2_graceful_controller::EgocentricPolarCoordinates coords(r_value, phi_value,
delta_value);
nav2_graceful_controller::EgocentricPolarCoordinates coords(r_value, phi_value, delta_value);

EXPECT_FLOAT_EQ(r_value, coords.r);
EXPECT_FLOAT_EQ(phi_value, coords.phi);
Expand All @@ -57,6 +56,19 @@ TEST(EgocentricPolarCoordinatesTest, constructorFromPoses) {
EXPECT_FLOAT_EQ(-1.1827937483787536, coords.delta);
}

TEST(EgocentricPolarCoordinatesTest, constructorFromPose) {
geometry_msgs::msg::Pose target;
target.position.x = 3.0;
target.position.y = 3.0;
target.orientation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0, 0, 1), M_PI));

nav2_graceful_controller::EgocentricPolarCoordinates coords(target);

EXPECT_FLOAT_EQ(4.2426405, coords.r);
EXPECT_FLOAT_EQ(2.3561945, coords.phi);
EXPECT_FLOAT_EQ(-M_PI / 4, coords.delta);
}

TEST(EgocentricPolarCoordinatesTest, constructorFromPosesBackward) {
geometry_msgs::msg::Pose target;
target.position.x = -3.0;
Expand All @@ -70,7 +82,7 @@ TEST(EgocentricPolarCoordinatesTest, constructorFromPosesBackward) {

nav2_graceful_controller::EgocentricPolarCoordinates coords(target, current, true);

EXPECT_FLOAT_EQ(-6.4031243, coords.r);
EXPECT_FLOAT_EQ(6.4031243, coords.r);
EXPECT_FLOAT_EQ(-0.096055523, coords.phi);
EXPECT_FLOAT_EQ(-1.0960555, coords.delta);
}
Expand Down

0 comments on commit d1ad640

Please sign in to comment.