Skip to content

Commit 6b56b43

Browse files
authored
Add option to use open-loop control with Rotation Shim (backport #4880) (#4896)
* Add option to use open-loop control with Rotation Shim (#4880) * Initial implementation Signed-off-by: RBT22 <[email protected]> * replace feedback param with closed_loop Signed-off-by: RBT22 <[email protected]> * Reset last_angular_vel_ in activate method Signed-off-by: RBT22 <[email protected]> * Add closed_loop parameter to dynamicParametersCallback Signed-off-by: RBT22 <[email protected]> * Add tests Signed-off-by: RBT22 <[email protected]> * Override reset function Signed-off-by: RBT22 <[email protected]> --------- Signed-off-by: RBT22 <[email protected]> * Remove reset Signed-off-by: RBT22 <[email protected]> --------- Signed-off-by: RBT22 <[email protected]>
1 parent aabad9a commit 6b56b43

File tree

3 files changed

+106
-6
lines changed

3 files changed

+106
-6
lines changed

nav2_rotation_shim_controller/include/nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include <memory>
2121
#include <algorithm>
2222
#include <mutex>
23+
#include <limits>
2324

2425
#include "rclcpp/rclcpp.hpp"
2526
#include "pluginlib/class_loader.hpp"
@@ -176,6 +177,8 @@ class RotationShimController : public nav2_core::Controller
176177
double rotate_to_heading_angular_vel_, max_angular_accel_;
177178
double control_duration_, simulate_ahead_time_;
178179
bool rotate_to_goal_heading_, in_rotation_;
180+
bool closed_loop_;
181+
double last_angular_vel_ = std::numeric_limits<double>::max();
179182

180183
// Dynamic parameters handler
181184
std::mutex mutex_;

nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp

Lines changed: 22 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -67,6 +67,8 @@ void RotationShimController::configure(
6767
node, plugin_name_ + ".primary_controller", rclcpp::PARAMETER_STRING);
6868
nav2_util::declare_parameter_if_not_declared(
6969
node, plugin_name_ + ".rotate_to_goal_heading", rclcpp::ParameterValue(false));
70+
nav2_util::declare_parameter_if_not_declared(
71+
node, plugin_name_ + ".closed_loop", rclcpp::ParameterValue(true));
7072

7173
node->get_parameter(plugin_name_ + ".angular_dist_threshold", angular_dist_threshold_);
7274
node->get_parameter(plugin_name_ + ".angular_disengage_threshold", angular_disengage_threshold_);
@@ -82,6 +84,7 @@ void RotationShimController::configure(
8284
control_duration_ = 1.0 / control_frequency;
8385

8486
node->get_parameter(plugin_name_ + ".rotate_to_goal_heading", rotate_to_goal_heading_);
87+
node->get_parameter(plugin_name_ + ".closed_loop", closed_loop_);
8588

8689
try {
8790
primary_controller_ = lp_loader_.createUniqueInstance(primary_controller);
@@ -112,6 +115,7 @@ void RotationShimController::activate()
112115

113116
primary_controller_->activate();
114117
in_rotation_ = false;
118+
last_angular_vel_ = std::numeric_limits<double>::max();
115119

116120
auto node = node_.lock();
117121
dyn_params_handler_ = node->add_on_set_parameters_callback(
@@ -174,7 +178,9 @@ geometry_msgs::msg::TwistStamped RotationShimController::computeVelocityCommands
174178

175179
double angular_distance_to_heading = angles::shortest_angular_distance(pose_yaw, goal_yaw);
176180

177-
return computeRotateToHeadingCommand(angular_distance_to_heading, pose, velocity);
181+
auto cmd_vel = computeRotateToHeadingCommand(angular_distance_to_heading, pose, velocity);
182+
last_angular_vel_ = cmd_vel.twist.angular.z;
183+
return cmd_vel;
178184
}
179185
} catch (const std::runtime_error & e) {
180186
RCLCPP_INFO(
@@ -203,7 +209,9 @@ geometry_msgs::msg::TwistStamped RotationShimController::computeVelocityCommands
203209
logger_,
204210
"Robot is not within the new path's rough heading, rotating to heading...");
205211
in_rotation_ = true;
206-
return computeRotateToHeadingCommand(angular_distance_to_heading, pose, velocity);
212+
auto cmd_vel = computeRotateToHeadingCommand(angular_distance_to_heading, pose, velocity);
213+
last_angular_vel_ = cmd_vel.twist.angular.z;
214+
return cmd_vel;
207215
} else {
208216
RCLCPP_DEBUG(
209217
logger_,
@@ -222,7 +230,9 @@ geometry_msgs::msg::TwistStamped RotationShimController::computeVelocityCommands
222230

223231
// If at this point, use the primary controller to path track
224232
in_rotation_ = false;
225-
return primary_controller_->computeVelocityCommands(pose, velocity, goal_checker);
233+
auto cmd_vel = primary_controller_->computeVelocityCommands(pose, velocity, goal_checker);
234+
last_angular_vel_ = cmd_vel.twist.angular.z;
235+
return cmd_vel;
226236
}
227237

228238
geometry_msgs::msg::PoseStamped RotationShimController::getSampledPathPt()
@@ -280,13 +290,18 @@ RotationShimController::computeRotateToHeadingCommand(
280290
const geometry_msgs::msg::PoseStamped & pose,
281291
const geometry_msgs::msg::Twist & velocity)
282292
{
293+
auto current = closed_loop_ ? velocity.angular.z : last_angular_vel_;
294+
if (current == std::numeric_limits<double>::max()) {
295+
current = 0.0;
296+
}
297+
283298
geometry_msgs::msg::TwistStamped cmd_vel;
284299
cmd_vel.header = pose.header;
285300
const double sign = angular_distance_to_heading > 0.0 ? 1.0 : -1.0;
286301
const double angular_vel = sign * rotate_to_heading_angular_vel_;
287302
const double & dt = control_duration_;
288-
const double min_feasible_angular_speed = velocity.angular.z - max_angular_accel_ * dt;
289-
const double max_feasible_angular_speed = velocity.angular.z + max_angular_accel_ * dt;
303+
const double min_feasible_angular_speed = current - max_angular_accel_ * dt;
304+
const double max_feasible_angular_speed = current + max_angular_accel_ * dt;
290305
cmd_vel.twist.angular.z =
291306
std::clamp(angular_vel, min_feasible_angular_speed, max_feasible_angular_speed);
292307

@@ -370,6 +385,8 @@ RotationShimController::dynamicParametersCallback(std::vector<rclcpp::Parameter>
370385
} else if (type == ParameterType::PARAMETER_BOOL) {
371386
if (name == plugin_name_ + ".rotate_to_goal_heading") {
372387
rotate_to_goal_heading_ = parameter.as_bool();
388+
} else if (name == plugin_name_ + ".closed_loop") {
389+
closed_loop_ = parameter.as_bool();
373390
}
374391
}
375392
}

nav2_rotation_shim_controller/test/test_shim_controller.cpp

Lines changed: 81 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -309,6 +309,84 @@ TEST(RotationShimControllerTest, computeVelocityTests)
309309
EXPECT_THROW(controller->computeVelocityCommands(pose, velocity, &checker), std::runtime_error);
310310
}
311311

312+
TEST(RotationShimControllerTest, openLoopRotationTests) {
313+
auto ctrl = std::make_shared<RotationShimShim>();
314+
auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("ShimControllerTest");
315+
std::string name = "PathFollower";
316+
auto tf = std::make_shared<tf2_ros::Buffer>(node->get_clock());
317+
auto listener = std::make_shared<tf2_ros::TransformListener>(*tf, node, true);
318+
auto costmap = std::make_shared<nav2_costmap_2d::Costmap2DROS>("fake_costmap");
319+
rclcpp_lifecycle::State state;
320+
costmap->on_configure(state);
321+
auto tf_broadcaster = std::make_shared<tf2_ros::TransformBroadcaster>(node);
322+
323+
geometry_msgs::msg::TransformStamped transform;
324+
transform.header.frame_id = "base_link";
325+
transform.child_frame_id = "odom";
326+
transform.transform.rotation.x = 0.0;
327+
transform.transform.rotation.y = 0.0;
328+
transform.transform.rotation.z = 0.0;
329+
transform.transform.rotation.w = 1.0;
330+
tf_broadcaster->sendTransform(transform);
331+
332+
// set a valid primary controller so we can do lifecycle
333+
node->declare_parameter(
334+
"PathFollower.primary_controller",
335+
std::string("nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController"));
336+
node->declare_parameter(
337+
"controller_frequency",
338+
20.0);
339+
node->declare_parameter(
340+
"PathFollower.rotate_to_goal_heading",
341+
true);
342+
node->declare_parameter(
343+
"PathFollower.closed_loop",
344+
false);
345+
346+
auto controller = std::make_shared<RotationShimShim>();
347+
controller->configure(node, name, tf, costmap);
348+
controller->activate();
349+
350+
// Test state update and path setting
351+
nav_msgs::msg::Path path;
352+
path.header.frame_id = "base_link";
353+
path.poses.resize(4);
354+
355+
geometry_msgs::msg::PoseStamped pose;
356+
pose.header.frame_id = "base_link";
357+
geometry_msgs::msg::Twist velocity;
358+
nav2_controller::SimpleGoalChecker checker;
359+
node->declare_parameter(
360+
"checker.xy_goal_tolerance",
361+
1.0);
362+
checker.initialize(node, "checker", costmap);
363+
364+
path.header.frame_id = "base_link";
365+
path.poses[0].pose.position.x = 0.0;
366+
path.poses[0].pose.position.y = 0.0;
367+
path.poses[1].pose.position.x = 0.05;
368+
path.poses[1].pose.position.y = 0.05;
369+
path.poses[2].pose.position.x = 0.10;
370+
path.poses[2].pose.position.y = 0.10;
371+
// goal position within checker xy_goal_tolerance
372+
path.poses[3].pose.position.x = 0.20;
373+
path.poses[3].pose.position.y = 0.20;
374+
// goal heading 45 degrees to the left
375+
path.poses[3].pose.orientation.z = -0.3826834;
376+
path.poses[3].pose.orientation.w = 0.9238795;
377+
path.poses[3].header.frame_id = "base_link";
378+
379+
// Calculate first velocity command
380+
controller->setPlan(path);
381+
auto cmd_vel = controller->computeVelocityCommands(pose, velocity, &checker);
382+
EXPECT_NEAR(cmd_vel.twist.angular.z, -0.16, 1e-4);
383+
384+
// Test second velocity command with wrong odometry
385+
velocity.angular.z = 1.8;
386+
cmd_vel = controller->computeVelocityCommands(pose, velocity, &checker);
387+
EXPECT_NEAR(cmd_vel.twist.angular.z, -0.32, 1e-4);
388+
}
389+
312390
TEST(RotationShimControllerTest, computeVelocityGoalRotationTests) {
313391
auto ctrl = std::make_shared<RotationShimShim>();
314392
auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("ShimControllerTest");
@@ -412,7 +490,8 @@ TEST(RotationShimControllerTest, testDynamicParameter)
412490
rclcpp::Parameter("test.max_angular_accel", 7.0),
413491
rclcpp::Parameter("test.simulate_ahead_time", 7.0),
414492
rclcpp::Parameter("test.primary_controller", std::string("HI")),
415-
rclcpp::Parameter("test.rotate_to_goal_heading", true)});
493+
rclcpp::Parameter("test.rotate_to_goal_heading", true),
494+
rclcpp::Parameter("test.closed_loop", false)});
416495

417496
rclcpp::spin_until_future_complete(
418497
node->get_node_base_interface(),
@@ -424,4 +503,5 @@ TEST(RotationShimControllerTest, testDynamicParameter)
424503
EXPECT_EQ(node->get_parameter("test.max_angular_accel").as_double(), 7.0);
425504
EXPECT_EQ(node->get_parameter("test.simulate_ahead_time").as_double(), 7.0);
426505
EXPECT_EQ(node->get_parameter("test.rotate_to_goal_heading").as_bool(), true);
506+
EXPECT_EQ(node->get_parameter("test.closed_loop").as_bool(), false);
427507
}

0 commit comments

Comments
 (0)