Skip to content

Commit d1ad640

Browse files
authored
Fix backward motion for graceful controller (#4527)
* Fix backward motion for graceful controller Signed-off-by: Alberto Tudela <ajtudela@gmail.com> * Update smooth_control_law.cpp Signed-off-by: Alberto Tudela <ajtudela@gmail.com> --------- Signed-off-by: Alberto Tudela <ajtudela@gmail.com>
1 parent ba247b4 commit d1ad640

File tree

4 files changed

+20
-25
lines changed

4 files changed

+20
-25
lines changed

nav2_graceful_controller/include/nav2_graceful_controller/ego_polar_coords.hpp

Lines changed: 0 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,6 @@ namespace nav2_graceful_controller
3333
struct EgocentricPolarCoordinates
3434
{
3535
float r; // Radial distance between the robot pose and the target pose.
36-
// Negative value if the robot is moving backwards.
3736
float phi; // Orientation of target with respect to the line of sight
3837
// from the robot to the target.
3938
float delta; // Steering angle of the robot with respect to the line of sight.
@@ -68,21 +67,6 @@ struct EgocentricPolarCoordinates
6867
r = sqrt(dX * dX + dY * dY);
6968
phi = angles::normalize_angle(tf2::getYaw(target.orientation) + line_of_sight);
7069
delta = angles::normalize_angle(tf2::getYaw(current.orientation) + line_of_sight);
71-
// If the robot is moving backwards, flip the sign of the radial distance
72-
r *= backward ? -1.0 : 1.0;
73-
}
74-
75-
/**
76-
* @brief Construct a new egocentric polar coordinates for the target pose.
77-
*
78-
* @param target Target pose.
79-
* @param backward If true, the robot is moving backwards. Defaults to false.
80-
*/
81-
explicit EgocentricPolarCoordinates(
82-
const geometry_msgs::msg::Pose & target,
83-
bool backward = false)
84-
{
85-
EgocentricPolarCoordinates(target, geometry_msgs::msg::Pose(), backward);
8670
}
8771
};
8872

nav2_graceful_controller/include/nav2_graceful_controller/smooth_control_law.hpp

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -79,8 +79,7 @@ class SmoothControlLaw
7979
* @param v_angular_max The maximum absolute velocity in the angular direction.
8080
*/
8181
void setSpeedLimit(
82-
const double v_linear_min, const double v_linear_max,
83-
const double v_angular_max);
82+
const double v_linear_min, const double v_linear_max, const double v_angular_max);
8483

8584
/**
8685
* @brief Compute linear and angular velocities command using the curvature.
@@ -103,8 +102,7 @@ class SmoothControlLaw
103102
* @return Velocity command.
104103
*/
105104
geometry_msgs::msg::Twist calculateRegularVelocity(
106-
const geometry_msgs::msg::Pose & target,
107-
const bool & backward = false);
105+
const geometry_msgs::msg::Pose & target, const bool & backward = false);
108106

109107
/**
110108
* @brief Calculate the next pose of the robot by generating a velocity command using the

nav2_graceful_controller/src/smooth_control_law.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -43,8 +43,7 @@ void SmoothControlLaw::setSlowdownRadius(double slowdown_radius)
4343
}
4444

4545
void SmoothControlLaw::setSpeedLimit(
46-
const double v_linear_min, const double v_linear_max,
47-
const double v_angular_max)
46+
const double v_linear_min, const double v_linear_max, const double v_angular_max)
4847
{
4948
v_linear_min_ = v_linear_min;
5049
v_linear_max_ = v_linear_max;
@@ -59,6 +58,8 @@ geometry_msgs::msg::Twist SmoothControlLaw::calculateRegularVelocity(
5958
auto ego_coords = EgocentricPolarCoordinates(target, current, backward);
6059
// Calculate the curvature
6160
double curvature = calculateCurvature(ego_coords.r, ego_coords.phi, ego_coords.delta);
61+
// Invert the curvature if the robot is moving backwards
62+
curvature = backward ? -curvature : curvature;
6263

6364
// Adjust the linear velocity as a function of the path curvature to
6465
// slowdown the controller as it approaches its target

nav2_graceful_controller/test/test_egopolar.cpp

Lines changed: 15 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -31,8 +31,7 @@ TEST(EgocentricPolarCoordinatesTest, constructorWithValues) {
3131
float phi_value = 1.2;
3232
float delta_value = -0.5;
3333

34-
nav2_graceful_controller::EgocentricPolarCoordinates coords(r_value, phi_value,
35-
delta_value);
34+
nav2_graceful_controller::EgocentricPolarCoordinates coords(r_value, phi_value, delta_value);
3635

3736
EXPECT_FLOAT_EQ(r_value, coords.r);
3837
EXPECT_FLOAT_EQ(phi_value, coords.phi);
@@ -57,6 +56,19 @@ TEST(EgocentricPolarCoordinatesTest, constructorFromPoses) {
5756
EXPECT_FLOAT_EQ(-1.1827937483787536, coords.delta);
5857
}
5958

59+
TEST(EgocentricPolarCoordinatesTest, constructorFromPose) {
60+
geometry_msgs::msg::Pose target;
61+
target.position.x = 3.0;
62+
target.position.y = 3.0;
63+
target.orientation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0, 0, 1), M_PI));
64+
65+
nav2_graceful_controller::EgocentricPolarCoordinates coords(target);
66+
67+
EXPECT_FLOAT_EQ(4.2426405, coords.r);
68+
EXPECT_FLOAT_EQ(2.3561945, coords.phi);
69+
EXPECT_FLOAT_EQ(-M_PI / 4, coords.delta);
70+
}
71+
6072
TEST(EgocentricPolarCoordinatesTest, constructorFromPosesBackward) {
6173
geometry_msgs::msg::Pose target;
6274
target.position.x = -3.0;
@@ -70,7 +82,7 @@ TEST(EgocentricPolarCoordinatesTest, constructorFromPosesBackward) {
7082

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

73-
EXPECT_FLOAT_EQ(-6.4031243, coords.r);
85+
EXPECT_FLOAT_EQ(6.4031243, coords.r);
7486
EXPECT_FLOAT_EQ(-0.096055523, coords.phi);
7587
EXPECT_FLOAT_EQ(-1.0960555, coords.delta);
7688
}

0 commit comments

Comments
 (0)