Skip to content

Commit cb921b6

Browse files
author
Kemal Bektas
committed
feat(nav2_rotation_shim_controller): add use_path_orientations
Signed-off-by: Kemal Bektas <[email protected]>
1 parent 4936318 commit cb921b6

File tree

4 files changed

+22
-5
lines changed

4 files changed

+22
-5
lines changed

nav2_rotation_shim_controller/README.md

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,7 @@ See its [Configuration Guide Page](https://docs.nav2.org/configuration/packages/
3838
| `max_angular_accel` | Maximum angular acceleration for rotation to heading |
3939
| `simulate_ahead_time` | Time in seconds to forward simulate a rotation command to check for collisions. If a collision is found, forwards control back to the primary controller plugin. |
4040
| `rotate_to_goal_heading` | If true, the rotationShimController will take back control of the robot when in XY tolerance of the goal and start rotating to the goal heading |
41+
| `use_path_orientations` | If true, the controller will use the orientations of the path points to compute the heading of the path instead of computing the heading from the path points. If true, the controller will use the orientations of the path points to compute the heading of the path instead of computing the heading from the path points. Use for for feasible planners like the Smac Planner which generate feasible paths with orientations for forward and reverse motion. |
4142

4243
Example fully-described XML with default parameter values:
4344

@@ -70,6 +71,7 @@ controller_server:
7071
max_angular_accel: 3.2
7172
simulate_ahead_time: 1.0
7273
rotate_to_goal_heading: false
74+
use_path_orientations: false
7375
7476
# DWB parameters
7577
...

nav2_rotation_shim_controller/include/nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -186,6 +186,7 @@ class RotationShimController : public nav2_core::Controller
186186
double control_duration_, simulate_ahead_time_;
187187
bool rotate_to_goal_heading_, in_rotation_, rotate_to_heading_once_;
188188
bool closed_loop_;
189+
bool use_path_orientations_;
189190
double last_angular_vel_ = std::numeric_limits<double>::max();
190191

191192
// Dynamic parameters handler

nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp

Lines changed: 16 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -75,6 +75,8 @@ void RotationShimController::configure(
7575
node, plugin_name_ + ".rotate_to_heading_once", rclcpp::ParameterValue(false));
7676
nav2_util::declare_parameter_if_not_declared(
7777
node, plugin_name_ + ".closed_loop", rclcpp::ParameterValue(true));
78+
nav2_util::declare_parameter_if_not_declared(
79+
node, plugin_name_ + ".use_path_orientations", rclcpp::ParameterValue(false));
7880

7981
node->get_parameter(plugin_name_ + ".angular_dist_threshold", angular_dist_threshold_);
8082
node->get_parameter(plugin_name_ + ".angular_disengage_threshold", angular_disengage_threshold_);
@@ -92,6 +94,7 @@ void RotationShimController::configure(
9294
node->get_parameter(plugin_name_ + ".rotate_to_goal_heading", rotate_to_goal_heading_);
9395
node->get_parameter(plugin_name_ + ".rotate_to_heading_once", rotate_to_heading_once_);
9496
node->get_parameter(plugin_name_ + ".closed_loop", closed_loop_);
97+
node->get_parameter(plugin_name_ + ".use_path_orientations", use_path_orientations_);
9598

9699
try {
97100
primary_controller_ = lp_loader_.createUniqueInstance(primary_controller);
@@ -207,10 +210,17 @@ geometry_msgs::msg::TwistStamped RotationShimController::computeVelocityCommands
207210

208211
std::lock_guard<std::mutex> lock_reinit(mutex_);
209212
try {
210-
geometry_msgs::msg::Pose sampled_pt_base = transformPoseToBaseFrame(getSampledPathPt());
211-
212-
double angular_distance_to_heading =
213-
std::atan2(sampled_pt_base.position.y, sampled_pt_base.position.x);
213+
auto sampled_pt = getSampledPathPt();
214+
double angular_distance_to_heading;
215+
if (use_path_orientations_) {
216+
angular_distance_to_heading = angles::shortest_angular_distance(
217+
tf2::getYaw(pose.pose.orientation),
218+
tf2::getYaw(sampled_pt.pose.orientation));
219+
} else {
220+
geometry_msgs::msg::Pose sampled_pt_base = transformPoseToBaseFrame(sampled_pt);
221+
angular_distance_to_heading = std::atan2(sampled_pt_base.position.y,
222+
sampled_pt_base.position.x);
223+
}
214224

215225
double angular_thresh =
216226
in_rotation_ ? angular_disengage_threshold_ : angular_dist_threshold_;
@@ -423,6 +433,8 @@ RotationShimController::dynamicParametersCallback(std::vector<rclcpp::Parameter>
423433
rotate_to_heading_once_ = parameter.as_bool();
424434
} else if (name == plugin_name_ + ".closed_loop") {
425435
closed_loop_ = parameter.as_bool();
436+
} else if (name == plugin_name_ + ".use_path_orientations") {
437+
use_path_orientations_ = parameter.as_bool();
426438
}
427439
}
428440
}

nav2_rotation_shim_controller/test/test_shim_controller.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -621,7 +621,8 @@ TEST(RotationShimControllerTest, testDynamicParameter)
621621
rclcpp::Parameter("test.primary_controller", std::string("HI")),
622622
rclcpp::Parameter("test.rotate_to_goal_heading", true),
623623
rclcpp::Parameter("test.rotate_to_heading_once", true),
624-
rclcpp::Parameter("test.closed_loop", false)});
624+
rclcpp::Parameter("test.closed_loop", false),
625+
rclcpp::Parameter("test.use_path_orientations", true)});
625626

626627
rclcpp::spin_until_future_complete(
627628
node->get_node_base_interface(),
@@ -635,6 +636,7 @@ TEST(RotationShimControllerTest, testDynamicParameter)
635636
EXPECT_EQ(node->get_parameter("test.rotate_to_goal_heading").as_bool(), true);
636637
EXPECT_EQ(node->get_parameter("test.rotate_to_heading_once").as_bool(), true);
637638
EXPECT_EQ(node->get_parameter("test.closed_loop").as_bool(), false);
639+
EXPECT_EQ(node->get_parameter("test.use_path_orientations").as_bool(), true);
638640
}
639641

640642
int main(int argc, char **argv)

0 commit comments

Comments
 (0)