Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added collision detection for docking #4752

Merged
merged 7 commits into from
Nov 21, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 7 additions & 0 deletions nav2_bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -421,6 +421,13 @@ docking_server:
k_delta: 2.0
v_linear_min: 0.15
v_linear_max: 0.15
use_collision_detection: true
costmap_topic: "/local_costmap/costmap_raw"
footprint_topic: "/local_costmap/published_footprint"
transform_tolerance: 0.1
projection_time: 5.0
simulation_step: 0.1
dock_collision_threshold: 0.3

loopback_simulator:
ros__parameters:
Expand Down
23 changes: 15 additions & 8 deletions nav2_docking/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -208,14 +208,21 @@ For debugging purposes, there are several publishers which can be used with RVIZ
| dock_database | The filepath to the dock database to use for this environment | string | N/A |
| docks | Instead of `dock_database`, the set of docks specified in the params file itself | vector<string> | N/A |
| navigator_bt_xml | BT XML to use for Navigator, if non-default | string | "" |
| controller.k_phi | TODO | double | 3.0 |
| controller.k_delta | TODO | double | 2.0 |
| controller.beta | TODO | double | 0.4 |
| controller.lambda | TODO | double | 2.0 |
| controller.v_linear_min | TODO | double | 0.1 |
| controller.v_linear_max | TODO | double | 0.25 |
| controller.v_angular_max | TODO | double | 0.75 |
| controller.slowdown_radius | TODO | double | 0.25 |
| 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 |
| controller.k_delta | Constant factor applied to the heading error feedback. Controls the convergence of the fast subsystem | double | 2.0 |
| 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 |
| 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 |
| controller.v_linear_min | Minimum linear velocity (m/s) | double | 0.1 |
| controller.v_linear_max | Maximum linear velocity (m/s) | double | 0.25 |
| controller.v_angular_max | Maximum angular velocity (rad/s) produced by the control law | double | 0.75 |
| controller.slowdown_radius | Radius (m) around the goal pose in which the robot will start to slow down | double | 0.25 |
| controller.use_collision_detection | Whether to use collision detection to avoid obstacles | bool | true |
| controller.costmap_topic | The topic to use for the costmap | string | "local_costmap/costmap_raw" |
| controller.footprint_topic | The topic to use for the robot's footprint | string | "local_costmap/published_footprint" |
| 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 |
| controller.projection_time | Time to look ahead for collisions (s). | double | 5.0 |
| controller.simulation_time_step | Time step for projections (s). | double | 0.1 |
| controller.dock_collision_threshold | Distance (m) from the dock pose to ignore collisions. | double | 0.3 |

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

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
// Copyright (c) 2024 Open Navigation LLC
// Copyright (c) 2024 Alberto J. Tudela Roldán
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -16,11 +17,16 @@
#define OPENNAV_DOCKING__CONTROLLER_HPP_

#include <memory>
#include <string>
#include <vector>

#include "geometry_msgs/msg/pose.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include "nav2_costmap_2d/costmap_subscriber.hpp"
#include "nav2_costmap_2d/footprint_subscriber.hpp"
#include "nav2_costmap_2d/costmap_topic_collision_checker.hpp"
#include "nav2_graceful_controller/smooth_control_law.hpp"
#include "nav_msgs/msg/path.hpp"
#include "nav2_util/lifecycle_node.hpp"

namespace opennav_docking
Expand All @@ -34,36 +40,91 @@ class Controller
public:
/**
* @brief Create a controller instance. Configure ROS 2 parameters.
*
* @param node Lifecycle node
* @param tf tf2_ros TF buffer
* @param fixed_frame Fixed frame
* @param base_frame Robot base frame
*/
explicit Controller(const rclcpp_lifecycle::LifecycleNode::SharedPtr & node);
Controller(
const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, std::shared_ptr<tf2_ros::Buffer> tf,
std::string fixed_frame, std::string base_frame);

/**
* @brief A destructor for opennav_docking::Controller
*/
~Controller();

/**
* @brief Compute a velocity command using control law.
* @param pose Target pose, in robot centric coordinates.
* @param cmd Command velocity.
* @param is_docking If true, robot is docking. If false, robot is undocking.
* @param backward If true, robot will drive backwards to goal.
* @returns True if command is valid, false otherwise.
*/
bool computeVelocityCommand(
const geometry_msgs::msg::Pose & pose, geometry_msgs::msg::Twist & cmd,
const geometry_msgs::msg::Pose & pose, geometry_msgs::msg::Twist & cmd, bool is_docking,
bool backward = false);

protected:
/**
* @brief Check if a trajectory is collision free.
*
* @param target_pose Target pose, in robot centric coordinates.
* @param is_docking If true, robot is docking. If false, robot is undocking.
* @param backward If true, robot will drive backwards to goal.
* @return True if trajectory is collision free.
*/
bool isTrajectoryCollisionFree(
const geometry_msgs::msg::Pose & target_pose, bool is_docking, bool backward = false);

/**
* @brief Callback executed when a parameter change is detected
* @brief Callback executed when a parameter change is detected.
*
* @param event ParameterEvent message
*/
rcl_interfaces::msg::SetParametersResult
dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);

/**
* @brief Configure the collision checker.
*
* @param node Lifecycle node
* @param costmap_topic Costmap topic
* @param footprint_topic Footprint topic
* @param transform_tolerance Transform tolerance
*/
void configureCollisionChecker(
const rclcpp_lifecycle::LifecycleNode::SharedPtr & node,
std::string costmap_topic, std::string footprint_topic, double transform_tolerance);

// Dynamic parameters handler
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
std::mutex dynamic_params_lock_;

protected:
std::unique_ptr<nav2_graceful_controller::SmoothControlLaw> control_law_;
rclcpp::Logger logger_{rclcpp::get_logger("Controller")};
rclcpp::Clock::SharedPtr clock_;

// Smooth control law
std::unique_ptr<nav2_graceful_controller::SmoothControlLaw> control_law_;
double k_phi_, k_delta_, beta_, lambda_;
double slowdown_radius_, v_linear_min_, v_linear_max_, v_angular_max_;

// The trajectory of the robot while dock / undock for visualization / debug purposes
rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr trajectory_pub_;

// Used for collision checking
bool use_collision_detection_;
double projection_time_;
double simulation_time_step_;
double dock_collision_threshold_;
double transform_tolerance_;
std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
std::unique_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
std::unique_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_;
std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> collision_checker_;
std::string fixed_frame_, base_frame_;
};

} // namespace opennav_docking
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -112,12 +112,13 @@ class DockingServer : public nav2_util::LifecycleNode
* @param pose The pose to command towards.
* @param linear_tolerance Pose is reached when linear distance is within this tolerance.
* @param angular_tolerance Pose is reached when angular distance is within this tolerance.
* @param is_docking If true, the robot is docking. If false, the robot is undocking.
* @param backward If true, the robot will drive backwards.
* @returns True if pose is reached.
*/
bool getCommandToPose(
geometry_msgs::msg::Twist & cmd, const geometry_msgs::msg::PoseStamped & pose,
double linear_tolerance, double angular_tolerance, bool backward);
double linear_tolerance, double angular_tolerance, bool is_docking, bool backward);

/**
* @brief Get the robot pose (aka base_frame pose) in another frame.
Expand Down
140 changes: 138 additions & 2 deletions nav2_docking/opennav_docking/src/controller.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
// Copyright (c) 2024 Open Navigation LLC
// Copyright (c) 2024 Alberto J. Tudela Roldán
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -16,13 +17,22 @@

#include "rclcpp/rclcpp.hpp"
#include "opennav_docking/controller.hpp"
#include "nav2_util/geometry_utils.hpp"
#include "nav2_util/node_utils.hpp"
#include "nav_2d_utils/conversions.hpp"
#include "tf2/utils.h"

namespace opennav_docking
{

Controller::Controller(const rclcpp_lifecycle::LifecycleNode::SharedPtr & node)
Controller::Controller(
const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, std::shared_ptr<tf2_ros::Buffer> tf,
std::string fixed_frame, std::string base_frame)
: tf2_buffer_(tf), fixed_frame_(fixed_frame), base_frame_(base_frame)
{
logger_ = node->get_logger();
clock_ = node->get_clock();

nav2_util::declare_parameter_if_not_declared(
node, "controller.k_phi", rclcpp::ParameterValue(3.0));
nav2_util::declare_parameter_if_not_declared(
Expand All @@ -39,6 +49,22 @@ Controller::Controller(const rclcpp_lifecycle::LifecycleNode::SharedPtr & node)
node, "controller.v_angular_max", rclcpp::ParameterValue(0.75));
nav2_util::declare_parameter_if_not_declared(
node, "controller.slowdown_radius", rclcpp::ParameterValue(0.25));
nav2_util::declare_parameter_if_not_declared(
node, "controller.use_collision_detection", rclcpp::ParameterValue(true));
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
nav2_util::declare_parameter_if_not_declared(
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
node, "controller.costmap_topic",
rclcpp::ParameterValue(std::string("local_costmap/costmap_raw")));
nav2_util::declare_parameter_if_not_declared(
node, "controller.footprint_topic", rclcpp::ParameterValue(
std::string("local_costmap/published_footprint")));
nav2_util::declare_parameter_if_not_declared(
node, "controller.transform_tolerance", rclcpp::ParameterValue(0.1));
nav2_util::declare_parameter_if_not_declared(
node, "controller.projection_time", rclcpp::ParameterValue(5.0));
nav2_util::declare_parameter_if_not_declared(
node, "controller.simulation_time_step", rclcpp::ParameterValue(0.1));
nav2_util::declare_parameter_if_not_declared(
node, "controller.dock_collision_threshold", rclcpp::ParameterValue(0.3));

node->get_parameter("controller.k_phi", k_phi_);
node->get_parameter("controller.k_delta", k_delta_);
Expand All @@ -55,16 +81,120 @@ Controller::Controller(const rclcpp_lifecycle::LifecycleNode::SharedPtr & node)
// Add callback for dynamic parameters
dyn_params_handler_ = node->add_on_set_parameters_callback(
std::bind(&Controller::dynamicParametersCallback, this, std::placeholders::_1));

node->get_parameter("controller.use_collision_detection", use_collision_detection_);
node->get_parameter("controller.projection_time", projection_time_);
node->get_parameter("controller.simulation_time_step", simulation_time_step_);
node->get_parameter("controller.transform_tolerance", transform_tolerance_);

if (use_collision_detection_) {
std::string costmap_topic, footprint_topic;
node->get_parameter("controller.costmap_topic", costmap_topic);
node->get_parameter("controller.footprint_topic", footprint_topic);
node->get_parameter("controller.dock_collision_threshold", dock_collision_threshold_);
configureCollisionChecker(node, costmap_topic, footprint_topic, transform_tolerance_);
}

trajectory_pub_ =
node->create_publisher<nav_msgs::msg::Path>("docking_trajectory", 1);
}

Controller::~Controller()
{
control_law_.reset();
trajectory_pub_.reset();
collision_checker_.reset();
costmap_sub_.reset();
footprint_sub_.reset();
}

bool Controller::computeVelocityCommand(
const geometry_msgs::msg::Pose & pose, geometry_msgs::msg::Twist & cmd, bool backward)
const geometry_msgs::msg::Pose & pose, geometry_msgs::msg::Twist & cmd, bool is_docking,
bool backward)
{
std::lock_guard<std::mutex> lock(dynamic_params_lock_);
cmd = control_law_->calculateRegularVelocity(pose, backward);
return isTrajectoryCollisionFree(pose, is_docking, backward);
}

bool Controller::isTrajectoryCollisionFree(
const geometry_msgs::msg::Pose & target_pose, bool is_docking, bool backward)
{
// Visualization of the trajectory
nav_msgs::msg::Path trajectory;
trajectory.header.frame_id = base_frame_;
trajectory.header.stamp = clock_->now();

// First pose
geometry_msgs::msg::PoseStamped next_pose;
next_pose.header.frame_id = base_frame_;
trajectory.poses.push_back(next_pose);

// Get the transform from base_frame to fixed_frame
geometry_msgs::msg::TransformStamped base_to_fixed_transform;
try {
base_to_fixed_transform = tf2_buffer_->lookupTransform(
fixed_frame_, base_frame_, trajectory.header.stamp,
tf2::durationFromSec(transform_tolerance_));
} catch (tf2::TransformException & ex) {
RCLCPP_ERROR(
logger_, "Could not get transform from %s to %s: %s",
base_frame_.c_str(), fixed_frame_.c_str(), ex.what());
return false;
}

// Generate path
for (double t = 0; t < projection_time_; t += simulation_time_step_) {
// Apply velocities to calculate next pose
next_pose.pose = control_law_->calculateNextPose(
simulation_time_step_, target_pose, next_pose.pose, backward);

// Add the pose to the trajectory for visualization
trajectory.poses.push_back(next_pose);

// Transform pose from base_frame into fixed_frame
geometry_msgs::msg::PoseStamped local_pose = next_pose;
local_pose.header.stamp = trajectory.header.stamp;
tf2::doTransform(local_pose, local_pose, base_to_fixed_transform);

// Determine the distance at which to check for collisions
// Skip the final segment of the trajectory for docking
// and the initial segment for undocking
// This avoids false positives when the robot is at the dock
double dock_collision_distance = is_docking ?
nav2_util::geometry_utils::euclidean_distance(target_pose, next_pose.pose) :
std::hypot(next_pose.pose.position.x, next_pose.pose.position.y);

// If this distance is greater than the dock_collision_threshold, check for collisions
if (use_collision_detection_ &&
dock_collision_distance > dock_collision_threshold_ &&
!collision_checker_->isCollisionFree(nav_2d_utils::poseToPose2D(local_pose.pose)))
{
RCLCPP_WARN(
logger_, "Collision detected at pose: (%.2f, %.2f, %.2f) in frame %s",
local_pose.pose.position.x, local_pose.pose.position.y, local_pose.pose.position.z,
local_pose.header.frame_id.c_str());
trajectory_pub_->publish(trajectory);
return false;
}
}

trajectory_pub_->publish(trajectory);
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved

return true;
}

void Controller::configureCollisionChecker(
const rclcpp_lifecycle::LifecycleNode::SharedPtr & node,
std::string costmap_topic, std::string footprint_topic, double transform_tolerance)
{
costmap_sub_ = std::make_unique<nav2_costmap_2d::CostmapSubscriber>(node, costmap_topic);
footprint_sub_ = std::make_unique<nav2_costmap_2d::FootprintSubscriber>(
node, footprint_topic, *tf2_buffer_, base_frame_, transform_tolerance);
collision_checker_ = std::make_shared<nav2_costmap_2d::CostmapTopicCollisionChecker>(
*costmap_sub_, *footprint_sub_, node->get_name());
}

rcl_interfaces::msg::SetParametersResult
Controller::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
{
Expand Down Expand Up @@ -92,6 +222,12 @@ Controller::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
v_angular_max_ = parameter.as_double();
} else if (name == "controller.slowdown_radius") {
slowdown_radius_ = parameter.as_double();
} else if (name == "controller.projection_time") {
projection_time_ = parameter.as_double();
} else if (name == "controller.simulation_time_step") {
simulation_time_step_ = parameter.as_double();
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
} else if (name == "controller.dock_collision_threshold") {
dock_collision_threshold_ = parameter.as_double();
}

// Update the smooth control law with the new params
Expand Down
Loading
Loading