18 #include "rclcpp/rclcpp.hpp"
19 #include "opennav_docking/controller.hpp"
20 #include "nav2_util/geometry_utils.hpp"
21 #include "nav2_ros_common/node_utils.hpp"
22 #include "tf2/utils.hpp"
24 namespace opennav_docking
28 const nav2::LifecycleNode::SharedPtr & node, std::shared_ptr<tf2_ros::Buffer> tf,
29 std::string fixed_frame, std::string base_frame)
30 : tf2_buffer_(tf), fixed_frame_(fixed_frame), base_frame_(base_frame)
32 logger_ = node->get_logger();
33 clock_ = node->get_clock();
35 nav2::declare_parameter_if_not_declared(
36 node,
"controller.k_phi", rclcpp::ParameterValue(3.0));
37 nav2::declare_parameter_if_not_declared(
38 node,
"controller.k_delta", rclcpp::ParameterValue(2.0));
39 nav2::declare_parameter_if_not_declared(
40 node,
"controller.beta", rclcpp::ParameterValue(0.4));
41 nav2::declare_parameter_if_not_declared(
42 node,
"controller.lambda", rclcpp::ParameterValue(2.0));
43 nav2::declare_parameter_if_not_declared(
44 node,
"controller.v_linear_min", rclcpp::ParameterValue(0.1));
45 nav2::declare_parameter_if_not_declared(
46 node,
"controller.v_linear_max", rclcpp::ParameterValue(0.25));
47 nav2::declare_parameter_if_not_declared(
48 node,
"controller.v_angular_max", rclcpp::ParameterValue(0.75));
49 nav2::declare_parameter_if_not_declared(
50 node,
"controller.slowdown_radius", rclcpp::ParameterValue(0.25));
51 nav2::declare_parameter_if_not_declared(
52 node,
"controller.rotate_to_heading_angular_vel", rclcpp::ParameterValue(1.0));
53 nav2::declare_parameter_if_not_declared(
54 node,
"controller.rotate_to_heading_max_angular_accel", rclcpp::ParameterValue(3.2));
55 nav2::declare_parameter_if_not_declared(
56 node,
"controller.use_collision_detection", rclcpp::ParameterValue(
true));
57 nav2::declare_parameter_if_not_declared(
58 node,
"controller.costmap_topic",
59 rclcpp::ParameterValue(std::string(
"local_costmap/costmap_raw")));
60 nav2::declare_parameter_if_not_declared(
61 node,
"controller.footprint_topic", rclcpp::ParameterValue(
62 std::string(
"local_costmap/published_footprint")));
63 nav2::declare_parameter_if_not_declared(
64 node,
"controller.transform_tolerance", rclcpp::ParameterValue(0.1));
65 nav2::declare_parameter_if_not_declared(
66 node,
"controller.projection_time", rclcpp::ParameterValue(5.0));
67 nav2::declare_parameter_if_not_declared(
68 node,
"controller.simulation_time_step", rclcpp::ParameterValue(0.1));
69 nav2::declare_parameter_if_not_declared(
70 node,
"controller.dock_collision_threshold", rclcpp::ParameterValue(0.3));
72 node->get_parameter(
"controller.k_phi", k_phi_);
73 node->get_parameter(
"controller.k_delta", k_delta_);
74 node->get_parameter(
"controller.beta", beta_);
75 node->get_parameter(
"controller.lambda", lambda_);
76 node->get_parameter(
"controller.v_linear_min", v_linear_min_);
77 node->get_parameter(
"controller.v_linear_max", v_linear_max_);
78 node->get_parameter(
"controller.v_angular_max", v_angular_max_);
79 node->get_parameter(
"controller.slowdown_radius", slowdown_radius_);
80 control_law_ = std::make_unique<nav2_graceful_controller::SmoothControlLaw>(
81 k_phi_, k_delta_, beta_, lambda_, slowdown_radius_, v_linear_min_, v_linear_max_,
85 dyn_params_handler_ = node->add_on_set_parameters_callback(
88 node->get_parameter(
"controller.use_collision_detection", use_collision_detection_);
89 node->get_parameter(
"controller.projection_time", projection_time_);
90 node->get_parameter(
"controller.simulation_time_step", simulation_time_step_);
91 node->get_parameter(
"controller.transform_tolerance", transform_tolerance_);
93 if (use_collision_detection_) {
94 std::string costmap_topic, footprint_topic;
95 node->get_parameter(
"controller.costmap_topic", costmap_topic);
96 node->get_parameter(
"controller.footprint_topic", footprint_topic);
97 node->get_parameter(
"controller.dock_collision_threshold", dock_collision_threshold_);
101 node->get_parameter(
"controller.rotate_to_heading_angular_vel", rotate_to_heading_angular_vel_);
102 node->get_parameter(
"controller.rotate_to_heading_max_angular_accel",
103 rotate_to_heading_max_angular_accel_);
106 node->create_publisher<nav_msgs::msg::Path>(
"docking_trajectory");
111 control_law_.reset();
112 trajectory_pub_.reset();
113 collision_checker_.reset();
114 costmap_sub_.reset();
115 footprint_sub_.reset();
119 const geometry_msgs::msg::Pose & pose, geometry_msgs::msg::Twist & cmd,
bool is_docking,
122 std::lock_guard<std::mutex> lock(dynamic_params_lock_);
123 cmd = control_law_->calculateRegularVelocity(pose, backward);
128 const double & angular_distance_to_heading,
129 const geometry_msgs::msg::Twist & current_velocity,
132 geometry_msgs::msg::Twist cmd_vel;
133 const double sign = angular_distance_to_heading > 0.0 ? 1.0 : -1.0;
134 const double angular_vel = sign * rotate_to_heading_angular_vel_;
135 const double min_feasible_angular_speed =
136 current_velocity.angular.z - rotate_to_heading_max_angular_accel_ * dt;
137 const double max_feasible_angular_speed =
138 current_velocity.angular.z + rotate_to_heading_max_angular_accel_ * dt;
140 std::clamp(angular_vel, min_feasible_angular_speed, max_feasible_angular_speed);
143 double max_vel_to_stop =
144 std::sqrt(2 * rotate_to_heading_max_angular_accel_ * fabs(angular_distance_to_heading));
145 if (fabs(cmd_vel.angular.z) > max_vel_to_stop) {
146 cmd_vel.angular.z = sign * max_vel_to_stop;
153 const geometry_msgs::msg::Pose & target_pose,
bool is_docking,
bool backward)
156 nav_msgs::msg::Path trajectory;
157 trajectory.header.frame_id = base_frame_;
158 trajectory.header.stamp = clock_->now();
161 geometry_msgs::msg::PoseStamped next_pose;
162 next_pose.header.frame_id = base_frame_;
163 trajectory.poses.push_back(next_pose);
166 geometry_msgs::msg::TransformStamped base_to_fixed_transform;
168 base_to_fixed_transform = tf2_buffer_->lookupTransform(
169 fixed_frame_, base_frame_, trajectory.header.stamp,
170 tf2::durationFromSec(transform_tolerance_));
171 }
catch (tf2::TransformException & ex) {
173 logger_,
"Could not get transform from %s to %s: %s",
174 base_frame_.c_str(), fixed_frame_.c_str(), ex.what());
179 double distance = std::numeric_limits<double>::max();
180 unsigned int max_iter =
static_cast<unsigned int>(ceil(projection_time_ / simulation_time_step_));
184 next_pose.pose = control_law_->calculateNextPose(
185 simulation_time_step_, target_pose, next_pose.pose, backward);
188 trajectory.poses.push_back(next_pose);
191 geometry_msgs::msg::PoseStamped local_pose = next_pose;
192 local_pose.header.stamp = trajectory.header.stamp;
193 tf2::doTransform(local_pose, local_pose, base_to_fixed_transform);
199 double dock_collision_distance = is_docking ?
200 nav2_util::geometry_utils::euclidean_distance(target_pose, next_pose.pose) :
201 std::hypot(next_pose.pose.position.x, next_pose.pose.position.y);
204 if (use_collision_detection_ &&
205 dock_collision_distance > dock_collision_threshold_ &&
206 !collision_checker_->isCollisionFree(local_pose.pose))
209 logger_,
"Collision detected at pose: (%.2f, %.2f, %.2f) in frame %s",
210 local_pose.pose.position.x, local_pose.pose.position.y, local_pose.pose.position.z,
211 local_pose.header.frame_id.c_str());
212 trajectory_pub_->publish(trajectory);
217 distance = nav2_util::geometry_utils::euclidean_distance(target_pose, next_pose.pose);
218 }
while(distance > 1e-2 && trajectory.poses.size() < max_iter);
220 trajectory_pub_->publish(trajectory);
226 const nav2::LifecycleNode::SharedPtr & node,
227 std::string costmap_topic, std::string footprint_topic,
double transform_tolerance)
229 costmap_sub_ = std::make_unique<nav2_costmap_2d::CostmapSubscriber>(node, costmap_topic);
230 footprint_sub_ = std::make_unique<nav2_costmap_2d::FootprintSubscriber>(
231 node, footprint_topic, *tf2_buffer_, base_frame_, transform_tolerance);
232 collision_checker_ = std::make_shared<nav2_costmap_2d::CostmapTopicCollisionChecker>(
233 *costmap_sub_, *footprint_sub_, node->get_name());
236 rcl_interfaces::msg::SetParametersResult
239 std::lock_guard<std::mutex> lock(dynamic_params_lock_);
241 rcl_interfaces::msg::SetParametersResult result;
242 for (
auto parameter : parameters) {
243 const auto & param_type = parameter.get_type();
244 const auto & param_name = parameter.get_name();
245 if (param_name.find(
"controller.") != 0) {
248 if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE) {
249 if (param_name ==
"controller.k_phi") {
250 k_phi_ = parameter.as_double();
251 }
else if (param_name ==
"controller.k_delta") {
252 k_delta_ = parameter.as_double();
253 }
else if (param_name ==
"controller.beta") {
254 beta_ = parameter.as_double();
255 }
else if (param_name ==
"controller.lambda") {
256 lambda_ = parameter.as_double();
257 }
else if (param_name ==
"controller.v_linear_min") {
258 v_linear_min_ = parameter.as_double();
259 }
else if (param_name ==
"controller.v_linear_max") {
260 v_linear_max_ = parameter.as_double();
261 }
else if (param_name ==
"controller.v_angular_max") {
262 v_angular_max_ = parameter.as_double();
263 }
else if (param_name ==
"controller.slowdown_radius") {
264 slowdown_radius_ = parameter.as_double();
265 }
else if (param_name ==
"controller.rotate_to_heading_angular_vel") {
266 rotate_to_heading_angular_vel_ = parameter.as_double();
267 }
else if (param_name ==
"controller.rotate_to_heading_max_angular_accel") {
268 rotate_to_heading_max_angular_accel_ = parameter.as_double();
269 }
else if (param_name ==
"controller.projection_time") {
270 projection_time_ = parameter.as_double();
271 }
else if (param_name ==
"controller.simulation_time_step") {
272 simulation_time_step_ = parameter.as_double();
273 }
else if (param_name ==
"controller.dock_collision_threshold") {
274 dock_collision_threshold_ = parameter.as_double();
278 control_law_->setCurvatureConstants(k_phi_, k_delta_, beta_, lambda_);
279 control_law_->setSlowdownRadius(slowdown_radius_);
280 control_law_->setSpeedLimit(v_linear_min_, v_linear_max_, v_angular_max_);
284 result.successful =
true;
Controller(const nav2::LifecycleNode::SharedPtr &node, std::shared_ptr< tf2_ros::Buffer > tf, std::string fixed_frame, std::string base_frame)
Create a controller instance. Configure ROS 2 parameters.
bool isTrajectoryCollisionFree(const geometry_msgs::msg::Pose &target_pose, bool is_docking, bool backward=false)
Check if a trajectory is collision free.
bool computeVelocityCommand(const geometry_msgs::msg::Pose &pose, geometry_msgs::msg::Twist &cmd, bool is_docking, bool backward=false)
Compute a velocity command using control law.
~Controller()
A destructor for opennav_docking::Controller.
geometry_msgs::msg::Twist computeRotateToHeadingCommand(const double &angular_distance_to_heading, const geometry_msgs::msg::Twist ¤t_velocity, const double &dt)
Perform a command for in-place rotation.
void configureCollisionChecker(const nav2::LifecycleNode::SharedPtr &node, std::string costmap_topic, std::string footprint_topic, double transform_tolerance)
Configure the collision checker.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.