Skip to content

Commit 2429d1c

Browse files
committed
Added collision detection for docking (ros-navigation#4752)
* Added collision detection for docking Signed-off-by: Alberto Tudela <[email protected]> * Minor fixes Signed-off-by: Alberto Tudela <[email protected]> * Improve collision while undocking and test Signed-off-by: Alberto Tudela <[email protected]> * Fix smoke testing Signed-off-by: Alberto Tudela <[email protected]> * Rename dock_collision_threshold Signed-off-by: Alberto Tudela <[email protected]> * Added docs and params Signed-off-by: Alberto Tudela <[email protected]> * Minor changes in README Signed-off-by: Alberto Tudela <[email protected]> --------- Signed-off-by: Alberto Tudela <[email protected]> Signed-off-by: Jakubach <[email protected]>
1 parent 24792d9 commit 2429d1c

File tree

8 files changed

+721
-30
lines changed

8 files changed

+721
-30
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: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -209,6 +209,7 @@ For debugging purposes, there are several publishers which can be used with RVIZ
209209
| dock_database | The filepath to the dock database to use for this environment | string | N/A |
210210
| docks | Instead of `dock_database`, the set of docks specified in the params file itself | vector<string> | N/A |
211211
| navigator_bt_xml | BT XML to use for Navigator, if non-default | string | "" |
212+
<<<<<<< HEAD
212213
| controller.k_phi | Ratio of the rate of change of angle relative to distance from the target. Much be > 0. | double | 3.0 |
213214
| controller.k_delta | Higher values result in converging to the target more quickly. | double | 2.0 |
214215
| controller.beta | Parameter to reduce linear velocity proportional to path curvature. Increasing this linearly reduces the velocity (v(t) = v_max / (1 + beta * |curv|^lambda)). | double | 0.4 |
@@ -218,6 +219,23 @@ For debugging purposes, there are several publishers which can be used with RVIZ
218219
| controller.v_angular_min | Minimum angular velocity for approaching dock. | double | 0.15 |
219220
| controller.v_angular_max | Maximum angular velocity for approaching dock. | double | 0.75 |
220221
| controller.slowdown_radius | Radius to end goal to commense slow down. | double | 0.25 |
222+
=======
223+
| 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 |
224+
| controller.k_delta | Constant factor applied to the heading error feedback. Controls the convergence of the fast subsystem | double | 2.0 |
225+
| 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 |
226+
| 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 |
227+
| controller.v_linear_min | Minimum linear velocity (m/s) | double | 0.1 |
228+
| controller.v_linear_max | Maximum linear velocity (m/s) | double | 0.25 |
229+
| controller.v_angular_max | Maximum angular velocity (rad/s) produced by the control law | double | 0.75 |
230+
| controller.slowdown_radius | Radius (m) around the goal pose in which the robot will start to slow down | double | 0.25 |
231+
| controller.use_collision_detection | Whether to use collision detection to avoid obstacles | bool | true |
232+
| controller.costmap_topic | The topic to use for the costmap | string | "local_costmap/costmap_raw" |
233+
| controller.footprint_topic | The topic to use for the robot's footprint | string | "local_costmap/published_footprint" |
234+
| 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 |
235+
| controller.projection_time | Time to look ahead for collisions (s). | double | 5.0 |
236+
| controller.simulation_time_step | Time step for projections (s). | double | 0.1 |
237+
| controller.dock_collision_threshold | Distance (m) from the dock pose to ignore collisions. | double | 0.3 |
238+
>>>>>>> 90a6c8d8 (Added collision detection for docking (#4752))
221239
222240
Note: `dock_plugins` and either `docks` or `dock_database` are required.
223241

nav2_docking/opennav_docking/include/opennav_docking/controller.hpp

Lines changed: 67 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,27 +40,65 @@ 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,
49-
geometry_msgs::msg::Twist & cmd, bool backward = false);
67+
const geometry_msgs::msg::Pose & pose, geometry_msgs::msg::Twist & cmd, bool is_docking,
68+
bool backward = false);
69+
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);
5081

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_;
@@ -72,11 +116,29 @@ class Controller
72116
const double & dt);
73117

74118
protected:
75-
std::unique_ptr<nav2_graceful_controller::SmoothControlLaw> control_law_;
119+
rclcpp::Logger logger_{rclcpp::get_logger("Controller")};
120+
rclcpp::Clock::SharedPtr clock_;
76121

122+
// Smooth control law
123+
std::unique_ptr<nav2_graceful_controller::SmoothControlLaw> control_law_;
77124
double k_phi_, k_delta_, beta_, lambda_;
78125
double slowdown_radius_, v_linear_min_, v_linear_max_, v_angular_max_;
79126
double rotate_to_heading_angular_vel_, rotate_to_heading_max_angular_accel_;
127+
128+
// The trajectory of the robot while dock / undock for visualization / debug purposes
129+
rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr trajectory_pub_;
130+
131+
// Used for collision checking
132+
bool use_collision_detection_;
133+
double projection_time_;
134+
double simulation_time_step_;
135+
double dock_collision_threshold_;
136+
double transform_tolerance_;
137+
std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
138+
std::unique_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
139+
std::unique_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_;
140+
std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> collision_checker_;
141+
std::string fixed_frame_, base_frame_;
80142
};
81143

82144
} // 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
@@ -118,12 +118,13 @@ class DockingServer : public nav2_util::LifecycleNode
118118
* @param pose The pose to command towards.
119119
* @param linear_tolerance Pose is reached when linear distance is within this tolerance.
120120
* @param angular_tolerance Pose is reached when angular distance is within this tolerance.
121+
* @param is_docking If true, the robot is docking. If false, the robot is undocking.
121122
* @param backward If true, the robot will drive backwards.
122123
* @returns True if pose is reached.
123124
*/
124125
bool getCommandToPose(
125126
geometry_msgs::msg::Twist & cmd, const geometry_msgs::msg::PoseStamped & pose,
126-
double linear_tolerance, double angular_tolerance, bool backward);
127+
double linear_tolerance, double angular_tolerance, bool is_docking, bool backward);
127128

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

nav2_docking/opennav_docking/src/controller.cpp

Lines changed: 139 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,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(
@@ -35,8 +45,6 @@ Controller::Controller(const rclcpp_lifecycle::LifecycleNode::SharedPtr & node)
3545
node, "controller.v_linear_min", rclcpp::ParameterValue(0.1));
3646
nav2_util::declare_parameter_if_not_declared(
3747
node, "controller.v_linear_max", rclcpp::ParameterValue(0.25));
38-
nav2_util::declare_parameter_if_not_declared(
39-
node, "controller.v_angular_min", rclcpp::ParameterValue(0.15));
4048
nav2_util::declare_parameter_if_not_declared(
4149
node, "controller.v_angular_max", rclcpp::ParameterValue(0.75));
4250
nav2_util::declare_parameter_if_not_declared(
@@ -45,6 +53,22 @@ Controller::Controller(const rclcpp_lifecycle::LifecycleNode::SharedPtr & node)
4553
node, "controller.rotate_to_heading_angular_vel", rclcpp::ParameterValue(1.0));
4654
nav2_util::declare_parameter_if_not_declared(
4755
node, "controller.rotate_to_heading_max_angular_accel", rclcpp::ParameterValue(3.2));
56+
nav2_util::declare_parameter_if_not_declared(
57+
node, "controller.use_collision_detection", rclcpp::ParameterValue(true));
58+
nav2_util::declare_parameter_if_not_declared(
59+
node, "controller.costmap_topic",
60+
rclcpp::ParameterValue(std::string("local_costmap/costmap_raw")));
61+
nav2_util::declare_parameter_if_not_declared(
62+
node, "controller.footprint_topic", rclcpp::ParameterValue(
63+
std::string("local_costmap/published_footprint")));
64+
nav2_util::declare_parameter_if_not_declared(
65+
node, "controller.transform_tolerance", rclcpp::ParameterValue(0.1));
66+
nav2_util::declare_parameter_if_not_declared(
67+
node, "controller.projection_time", rclcpp::ParameterValue(5.0));
68+
nav2_util::declare_parameter_if_not_declared(
69+
node, "controller.simulation_time_step", rclcpp::ParameterValue(0.1));
70+
nav2_util::declare_parameter_if_not_declared(
71+
node, "controller.dock_collision_threshold", rclcpp::ParameterValue(0.3));
4872

4973
node->get_parameter("controller.k_phi", k_phi_);
5074
node->get_parameter("controller.k_delta", k_delta_);
@@ -63,17 +87,120 @@ Controller::Controller(const rclcpp_lifecycle::LifecycleNode::SharedPtr & node)
6387
// Add callback for dynamic parameters
6488
dyn_params_handler_ = node->add_on_set_parameters_callback(
6589
std::bind(&Controller::dynamicParametersCallback, this, std::placeholders::_1));
90+
91+
node->get_parameter("controller.use_collision_detection", use_collision_detection_);
92+
node->get_parameter("controller.projection_time", projection_time_);
93+
node->get_parameter("controller.simulation_time_step", simulation_time_step_);
94+
node->get_parameter("controller.transform_tolerance", transform_tolerance_);
95+
96+
if (use_collision_detection_) {
97+
std::string costmap_topic, footprint_topic;
98+
node->get_parameter("controller.costmap_topic", costmap_topic);
99+
node->get_parameter("controller.footprint_topic", footprint_topic);
100+
node->get_parameter("controller.dock_collision_threshold", dock_collision_threshold_);
101+
configureCollisionChecker(node, costmap_topic, footprint_topic, transform_tolerance_);
102+
}
103+
104+
trajectory_pub_ =
105+
node->create_publisher<nav_msgs::msg::Path>("docking_trajectory", 1);
106+
}
107+
108+
Controller::~Controller()
109+
{
110+
control_law_.reset();
111+
trajectory_pub_.reset();
112+
collision_checker_.reset();
113+
costmap_sub_.reset();
114+
footprint_sub_.reset();
66115
}
67116

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

193+
void Controller::configureCollisionChecker(
194+
const rclcpp_lifecycle::LifecycleNode::SharedPtr & node,
195+
std::string costmap_topic, std::string footprint_topic, double transform_tolerance)
196+
{
197+
costmap_sub_ = std::make_unique<nav2_costmap_2d::CostmapSubscriber>(node, costmap_topic);
198+
footprint_sub_ = std::make_unique<nav2_costmap_2d::FootprintSubscriber>(
199+
node, footprint_topic, *tf2_buffer_, base_frame_, transform_tolerance);
200+
collision_checker_ = std::make_shared<nav2_costmap_2d::CostmapTopicCollisionChecker>(
201+
*costmap_sub_, *footprint_sub_, node->get_name());
202+
}
203+
77204
rcl_interfaces::msg::SetParametersResult
78205
Controller::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
79206
{
@@ -105,6 +232,13 @@ Controller::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
105232
rotate_to_heading_angular_vel_ = parameter.as_double();
106233
} else if (name == "controller.rotate_to_heading_max_angular_accel") {
107234
rotate_to_heading_max_angular_accel_ = parameter.as_double();
235+
} else if (name == "controller.projection_time") {
236+
projection_time_ = parameter.as_double();
237+
} else if (name == "controller.simulation_time_step") {
238+
simulation_time_step_ = parameter.as_double();
239+
} else if (name == "controller.dock_collision_threshold") {
240+
dock_collision_threshold_ = parameter.as_double();
241+
}
108242

109243
// Update the smooth control law with the new params
110244
control_law_->setCurvatureConstants(k_phi_, k_delta_, beta_, lambda_);

0 commit comments

Comments
 (0)