Skip to content

Commit 2da6aa8

Browse files
Added collision detection for docking (#4752) (#4758)
* Added collision detection for docking Signed-off-by: Alberto Tudela <ajtudela@gmail.com> * Minor fixes Signed-off-by: Alberto Tudela <ajtudela@gmail.com> * Improve collision while undocking and test Signed-off-by: Alberto Tudela <ajtudela@gmail.com> * Fix smoke testing Signed-off-by: Alberto Tudela <ajtudela@gmail.com> * Rename dock_collision_threshold Signed-off-by: Alberto Tudela <ajtudela@gmail.com> * Added docs and params Signed-off-by: Alberto Tudela <ajtudela@gmail.com> * Minor changes in README Signed-off-by: Alberto Tudela <ajtudela@gmail.com> --------- Signed-off-by: Alberto Tudela <ajtudela@gmail.com> (cherry picked from commit 90a6c8d) Co-authored-by: Alberto Tudela <ajtudela@gmail.com>
1 parent 3140a6a commit 2da6aa8

File tree

8 files changed

+717
-33
lines changed

8 files changed

+717
-33
lines changed

nav2_bringup/params/nav2_params.yaml

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -421,6 +421,13 @@ docking_server:
421421
k_delta: 2.0
422422
v_linear_min: 0.15
423423
v_linear_max: 0.15
424+
use_collision_detection: true
425+
costmap_topic: "/local_costmap/costmap_raw"
426+
footprint_topic: "/local_costmap/published_footprint"
427+
transform_tolerance: 0.1
428+
projection_time: 5.0
429+
simulation_step: 0.1
430+
dock_collision_threshold: 0.3
424431

425432
loopback_simulator:
426433
ros__parameters:

nav2_docking/README.md

Lines changed: 15 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -208,14 +208,21 @@ For debugging purposes, there are several publishers which can be used with RVIZ
208208
| dock_database | The filepath to the dock database to use for this environment | string | N/A |
209209
| docks | Instead of `dock_database`, the set of docks specified in the params file itself | vector<string> | N/A |
210210
| navigator_bt_xml | BT XML to use for Navigator, if non-default | string | "" |
211-
| controller.k_phi | TODO | double | 3.0 |
212-
| controller.k_delta | TODO | double | 2.0 |
213-
| controller.beta | TODO | double | 0.4 |
214-
| controller.lambda | TODO | double | 2.0 |
215-
| controller.v_linear_min | TODO | double | 0.1 |
216-
| controller.v_linear_max | TODO | double | 0.25 |
217-
| controller.v_angular_max | TODO | double | 0.75 |
218-
| controller.slowdown_radius | TODO | double | 0.25 |
211+
| controller.k_phi | Ratio of the rate of change in phi to the rate of change in r. Controls the convergence of the slow subsystem | double | 3.0 |
212+
| controller.k_delta | Constant factor applied to the heading error feedback. Controls the convergence of the fast subsystem | double | 2.0 |
213+
| controller.beta | Constant factor applied to the path curvature. This value must be positive. Determines how fast the velocity drops when the curvature increases | double | 0.4 |
214+
| controller.lambda | Constant factor applied to the path curvature. This value must be greater or equal to 1. Determines the sharpness of the curve: higher lambda implies sharper curves | double | 2.0 |
215+
| controller.v_linear_min | Minimum linear velocity (m/s) | double | 0.1 |
216+
| controller.v_linear_max | Maximum linear velocity (m/s) | double | 0.25 |
217+
| controller.v_angular_max | Maximum angular velocity (rad/s) produced by the control law | double | 0.75 |
218+
| controller.slowdown_radius | Radius (m) around the goal pose in which the robot will start to slow down | double | 0.25 |
219+
| controller.use_collision_detection | Whether to use collision detection to avoid obstacles | bool | true |
220+
| controller.costmap_topic | The topic to use for the costmap | string | "local_costmap/costmap_raw" |
221+
| controller.footprint_topic | The topic to use for the robot's footprint | string | "local_costmap/published_footprint" |
222+
| controller.transform_tolerance | Time with which to post-date the transform that is published, to indicate that this transform is valid into the future. | double | 0.1 |
223+
| controller.projection_time | Time to look ahead for collisions (s). | double | 5.0 |
224+
| controller.simulation_time_step | Time step for projections (s). | double | 0.1 |
225+
| controller.dock_collision_threshold | Distance (m) from the dock pose to ignore collisions. | double | 0.3 |
219226

220227
Note: `dock_plugins` and either `docks` or `dock_database` are required.
221228

nav2_docking/opennav_docking/include/opennav_docking/controller.hpp

Lines changed: 66 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
11
// Copyright (c) 2024 Open Navigation LLC
2+
// Copyright (c) 2024 Alberto J. Tudela Roldán
23
//
34
// Licensed under the Apache License, Version 2.0 (the "License");
45
// you may not use this file except in compliance with the License.
@@ -16,11 +17,16 @@
1617
#define OPENNAV_DOCKING__CONTROLLER_HPP_
1718

1819
#include <memory>
20+
#include <string>
1921
#include <vector>
2022

2123
#include "geometry_msgs/msg/pose.hpp"
2224
#include "geometry_msgs/msg/twist.hpp"
25+
#include "nav2_costmap_2d/costmap_subscriber.hpp"
26+
#include "nav2_costmap_2d/footprint_subscriber.hpp"
27+
#include "nav2_costmap_2d/costmap_topic_collision_checker.hpp"
2328
#include "nav2_graceful_controller/smooth_control_law.hpp"
29+
#include "nav_msgs/msg/path.hpp"
2430
#include "nav2_util/lifecycle_node.hpp"
2531

2632
namespace opennav_docking
@@ -34,36 +40,91 @@ class Controller
3440
public:
3541
/**
3642
* @brief Create a controller instance. Configure ROS 2 parameters.
43+
*
44+
* @param node Lifecycle node
45+
* @param tf tf2_ros TF buffer
46+
* @param fixed_frame Fixed frame
47+
* @param base_frame Robot base frame
3748
*/
38-
explicit Controller(const rclcpp_lifecycle::LifecycleNode::SharedPtr & node);
49+
Controller(
50+
const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, std::shared_ptr<tf2_ros::Buffer> tf,
51+
std::string fixed_frame, std::string base_frame);
52+
53+
/**
54+
* @brief A destructor for opennav_docking::Controller
55+
*/
56+
~Controller();
3957

4058
/**
4159
* @brief Compute a velocity command using control law.
4260
* @param pose Target pose, in robot centric coordinates.
4361
* @param cmd Command velocity.
62+
* @param is_docking If true, robot is docking. If false, robot is undocking.
4463
* @param backward If true, robot will drive backwards to goal.
4564
* @returns True if command is valid, false otherwise.
4665
*/
4766
bool computeVelocityCommand(
48-
const geometry_msgs::msg::Pose & pose, geometry_msgs::msg::Twist & cmd,
67+
const geometry_msgs::msg::Pose & pose, geometry_msgs::msg::Twist & cmd, bool is_docking,
4968
bool backward = false);
5069

70+
protected:
71+
/**
72+
* @brief Check if a trajectory is collision free.
73+
*
74+
* @param target_pose Target pose, in robot centric coordinates.
75+
* @param is_docking If true, robot is docking. If false, robot is undocking.
76+
* @param backward If true, robot will drive backwards to goal.
77+
* @return True if trajectory is collision free.
78+
*/
79+
bool isTrajectoryCollisionFree(
80+
const geometry_msgs::msg::Pose & target_pose, bool is_docking, bool backward = false);
81+
5182
/**
52-
* @brief Callback executed when a parameter change is detected
83+
* @brief Callback executed when a parameter change is detected.
84+
*
5385
* @param event ParameterEvent message
5486
*/
5587
rcl_interfaces::msg::SetParametersResult
5688
dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
5789

90+
/**
91+
* @brief Configure the collision checker.
92+
*
93+
* @param node Lifecycle node
94+
* @param costmap_topic Costmap topic
95+
* @param footprint_topic Footprint topic
96+
* @param transform_tolerance Transform tolerance
97+
*/
98+
void configureCollisionChecker(
99+
const rclcpp_lifecycle::LifecycleNode::SharedPtr & node,
100+
std::string costmap_topic, std::string footprint_topic, double transform_tolerance);
101+
58102
// Dynamic parameters handler
59103
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
60104
std::mutex dynamic_params_lock_;
61105

62-
protected:
63-
std::unique_ptr<nav2_graceful_controller::SmoothControlLaw> control_law_;
106+
rclcpp::Logger logger_{rclcpp::get_logger("Controller")};
107+
rclcpp::Clock::SharedPtr clock_;
64108

109+
// Smooth control law
110+
std::unique_ptr<nav2_graceful_controller::SmoothControlLaw> control_law_;
65111
double k_phi_, k_delta_, beta_, lambda_;
66112
double slowdown_radius_, v_linear_min_, v_linear_max_, v_angular_max_;
113+
114+
// The trajectory of the robot while dock / undock for visualization / debug purposes
115+
rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr trajectory_pub_;
116+
117+
// Used for collision checking
118+
bool use_collision_detection_;
119+
double projection_time_;
120+
double simulation_time_step_;
121+
double dock_collision_threshold_;
122+
double transform_tolerance_;
123+
std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
124+
std::unique_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
125+
std::unique_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_;
126+
std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> collision_checker_;
127+
std::string fixed_frame_, base_frame_;
67128
};
68129

69130
} // namespace opennav_docking

nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -112,12 +112,13 @@ class DockingServer : public nav2_util::LifecycleNode
112112
* @param pose The pose to command towards.
113113
* @param linear_tolerance Pose is reached when linear distance is within this tolerance.
114114
* @param angular_tolerance Pose is reached when angular distance is within this tolerance.
115+
* @param is_docking If true, the robot is docking. If false, the robot is undocking.
115116
* @param backward If true, the robot will drive backwards.
116117
* @returns True if pose is reached.
117118
*/
118119
bool getCommandToPose(
119120
geometry_msgs::msg::Twist & cmd, const geometry_msgs::msg::PoseStamped & pose,
120-
double linear_tolerance, double angular_tolerance, bool backward);
121+
double linear_tolerance, double angular_tolerance, bool is_docking, bool backward);
121122

122123
/**
123124
* @brief Get the robot pose (aka base_frame pose) in another frame.

nav2_docking/opennav_docking/src/controller.cpp

Lines changed: 138 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
11
// Copyright (c) 2024 Open Navigation LLC
2+
// Copyright (c) 2024 Alberto J. Tudela Roldán
23
//
34
// Licensed under the Apache License, Version 2.0 (the "License");
45
// you may not use this file except in compliance with the License.
@@ -16,13 +17,22 @@
1617

1718
#include "rclcpp/rclcpp.hpp"
1819
#include "opennav_docking/controller.hpp"
20+
#include "nav2_util/geometry_utils.hpp"
1921
#include "nav2_util/node_utils.hpp"
22+
#include "nav_2d_utils/conversions.hpp"
23+
#include "tf2/utils.h"
2024

2125
namespace opennav_docking
2226
{
2327

24-
Controller::Controller(const rclcpp_lifecycle::LifecycleNode::SharedPtr & node)
28+
Controller::Controller(
29+
const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, std::shared_ptr<tf2_ros::Buffer> tf,
30+
std::string fixed_frame, std::string base_frame)
31+
: tf2_buffer_(tf), fixed_frame_(fixed_frame), base_frame_(base_frame)
2532
{
33+
logger_ = node->get_logger();
34+
clock_ = node->get_clock();
35+
2636
nav2_util::declare_parameter_if_not_declared(
2737
node, "controller.k_phi", rclcpp::ParameterValue(3.0));
2838
nav2_util::declare_parameter_if_not_declared(
@@ -39,6 +49,22 @@ Controller::Controller(const rclcpp_lifecycle::LifecycleNode::SharedPtr & node)
3949
node, "controller.v_angular_max", rclcpp::ParameterValue(0.75));
4050
nav2_util::declare_parameter_if_not_declared(
4151
node, "controller.slowdown_radius", rclcpp::ParameterValue(0.25));
52+
nav2_util::declare_parameter_if_not_declared(
53+
node, "controller.use_collision_detection", rclcpp::ParameterValue(true));
54+
nav2_util::declare_parameter_if_not_declared(
55+
node, "controller.costmap_topic",
56+
rclcpp::ParameterValue(std::string("local_costmap/costmap_raw")));
57+
nav2_util::declare_parameter_if_not_declared(
58+
node, "controller.footprint_topic", rclcpp::ParameterValue(
59+
std::string("local_costmap/published_footprint")));
60+
nav2_util::declare_parameter_if_not_declared(
61+
node, "controller.transform_tolerance", rclcpp::ParameterValue(0.1));
62+
nav2_util::declare_parameter_if_not_declared(
63+
node, "controller.projection_time", rclcpp::ParameterValue(5.0));
64+
nav2_util::declare_parameter_if_not_declared(
65+
node, "controller.simulation_time_step", rclcpp::ParameterValue(0.1));
66+
nav2_util::declare_parameter_if_not_declared(
67+
node, "controller.dock_collision_threshold", rclcpp::ParameterValue(0.3));
4268

4369
node->get_parameter("controller.k_phi", k_phi_);
4470
node->get_parameter("controller.k_delta", k_delta_);
@@ -55,16 +81,120 @@ Controller::Controller(const rclcpp_lifecycle::LifecycleNode::SharedPtr & node)
5581
// Add callback for dynamic parameters
5682
dyn_params_handler_ = node->add_on_set_parameters_callback(
5783
std::bind(&Controller::dynamicParametersCallback, this, std::placeholders::_1));
84+
85+
node->get_parameter("controller.use_collision_detection", use_collision_detection_);
86+
node->get_parameter("controller.projection_time", projection_time_);
87+
node->get_parameter("controller.simulation_time_step", simulation_time_step_);
88+
node->get_parameter("controller.transform_tolerance", transform_tolerance_);
89+
90+
if (use_collision_detection_) {
91+
std::string costmap_topic, footprint_topic;
92+
node->get_parameter("controller.costmap_topic", costmap_topic);
93+
node->get_parameter("controller.footprint_topic", footprint_topic);
94+
node->get_parameter("controller.dock_collision_threshold", dock_collision_threshold_);
95+
configureCollisionChecker(node, costmap_topic, footprint_topic, transform_tolerance_);
96+
}
97+
98+
trajectory_pub_ =
99+
node->create_publisher<nav_msgs::msg::Path>("docking_trajectory", 1);
100+
}
101+
102+
Controller::~Controller()
103+
{
104+
control_law_.reset();
105+
trajectory_pub_.reset();
106+
collision_checker_.reset();
107+
costmap_sub_.reset();
108+
footprint_sub_.reset();
58109
}
59110

60111
bool Controller::computeVelocityCommand(
61-
const geometry_msgs::msg::Pose & pose, geometry_msgs::msg::Twist & cmd, bool backward)
112+
const geometry_msgs::msg::Pose & pose, geometry_msgs::msg::Twist & cmd, bool is_docking,
113+
bool backward)
62114
{
63115
std::lock_guard<std::mutex> lock(dynamic_params_lock_);
64116
cmd = control_law_->calculateRegularVelocity(pose, backward);
117+
return isTrajectoryCollisionFree(pose, is_docking, backward);
118+
}
119+
120+
bool Controller::isTrajectoryCollisionFree(
121+
const geometry_msgs::msg::Pose & target_pose, bool is_docking, bool backward)
122+
{
123+
// Visualization of the trajectory
124+
nav_msgs::msg::Path trajectory;
125+
trajectory.header.frame_id = base_frame_;
126+
trajectory.header.stamp = clock_->now();
127+
128+
// First pose
129+
geometry_msgs::msg::PoseStamped next_pose;
130+
next_pose.header.frame_id = base_frame_;
131+
trajectory.poses.push_back(next_pose);
132+
133+
// Get the transform from base_frame to fixed_frame
134+
geometry_msgs::msg::TransformStamped base_to_fixed_transform;
135+
try {
136+
base_to_fixed_transform = tf2_buffer_->lookupTransform(
137+
fixed_frame_, base_frame_, trajectory.header.stamp,
138+
tf2::durationFromSec(transform_tolerance_));
139+
} catch (tf2::TransformException & ex) {
140+
RCLCPP_ERROR(
141+
logger_, "Could not get transform from %s to %s: %s",
142+
base_frame_.c_str(), fixed_frame_.c_str(), ex.what());
143+
return false;
144+
}
145+
146+
// Generate path
147+
for (double t = 0; t < projection_time_; t += simulation_time_step_) {
148+
// Apply velocities to calculate next pose
149+
next_pose.pose = control_law_->calculateNextPose(
150+
simulation_time_step_, target_pose, next_pose.pose, backward);
151+
152+
// Add the pose to the trajectory for visualization
153+
trajectory.poses.push_back(next_pose);
154+
155+
// Transform pose from base_frame into fixed_frame
156+
geometry_msgs::msg::PoseStamped local_pose = next_pose;
157+
local_pose.header.stamp = trajectory.header.stamp;
158+
tf2::doTransform(local_pose, local_pose, base_to_fixed_transform);
159+
160+
// Determine the distance at which to check for collisions
161+
// Skip the final segment of the trajectory for docking
162+
// and the initial segment for undocking
163+
// This avoids false positives when the robot is at the dock
164+
double dock_collision_distance = is_docking ?
165+
nav2_util::geometry_utils::euclidean_distance(target_pose, next_pose.pose) :
166+
std::hypot(next_pose.pose.position.x, next_pose.pose.position.y);
167+
168+
// If this distance is greater than the dock_collision_threshold, check for collisions
169+
if (use_collision_detection_ &&
170+
dock_collision_distance > dock_collision_threshold_ &&
171+
!collision_checker_->isCollisionFree(nav_2d_utils::poseToPose2D(local_pose.pose)))
172+
{
173+
RCLCPP_WARN(
174+
logger_, "Collision detected at pose: (%.2f, %.2f, %.2f) in frame %s",
175+
local_pose.pose.position.x, local_pose.pose.position.y, local_pose.pose.position.z,
176+
local_pose.header.frame_id.c_str());
177+
trajectory_pub_->publish(trajectory);
178+
return false;
179+
}
180+
}
181+
182+
trajectory_pub_->publish(trajectory);
183+
65184
return true;
66185
}
67186

187+
void Controller::configureCollisionChecker(
188+
const rclcpp_lifecycle::LifecycleNode::SharedPtr & node,
189+
std::string costmap_topic, std::string footprint_topic, double transform_tolerance)
190+
{
191+
costmap_sub_ = std::make_unique<nav2_costmap_2d::CostmapSubscriber>(node, costmap_topic);
192+
footprint_sub_ = std::make_unique<nav2_costmap_2d::FootprintSubscriber>(
193+
node, footprint_topic, *tf2_buffer_, base_frame_, transform_tolerance);
194+
collision_checker_ = std::make_shared<nav2_costmap_2d::CostmapTopicCollisionChecker>(
195+
*costmap_sub_, *footprint_sub_, node->get_name());
196+
}
197+
68198
rcl_interfaces::msg::SetParametersResult
69199
Controller::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
70200
{
@@ -92,6 +222,12 @@ Controller::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
92222
v_angular_max_ = parameter.as_double();
93223
} else if (name == "controller.slowdown_radius") {
94224
slowdown_radius_ = parameter.as_double();
225+
} else if (name == "controller.projection_time") {
226+
projection_time_ = parameter.as_double();
227+
} else if (name == "controller.simulation_time_step") {
228+
simulation_time_step_ = parameter.as_double();
229+
} else if (name == "controller.dock_collision_threshold") {
230+
dock_collision_threshold_ = parameter.as_double();
95231
}
96232

97233
// Update the smooth control law with the new params

0 commit comments

Comments
 (0)