16 #ifndef OPENNAV_DOCKING__CONTROLLER_HPP_
17 #define OPENNAV_DOCKING__CONTROLLER_HPP_
23 #include "geometry_msgs/msg/pose.hpp"
24 #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"
28 #include "nav2_graceful_controller/smooth_control_law.hpp"
29 #include "nav_msgs/msg/path.hpp"
30 #include "nav2_util/lifecycle_node.hpp"
32 namespace opennav_docking
50 const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, std::shared_ptr<tf2_ros::Buffer> tf,
51 std::string fixed_frame, std::string base_frame);
67 const geometry_msgs::msg::Pose & pose, geometry_msgs::msg::Twist & cmd,
bool is_docking,
68 bool backward =
false);
80 const geometry_msgs::msg::Pose & target_pose,
bool is_docking,
bool backward =
false);
87 rcl_interfaces::msg::SetParametersResult
99 const rclcpp_lifecycle::LifecycleNode::SharedPtr & node,
100 std::string costmap_topic, std::string footprint_topic,
double transform_tolerance);
103 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
104 std::mutex dynamic_params_lock_;
106 rclcpp::Logger logger_{rclcpp::get_logger(
"Controller")};
107 rclcpp::Clock::SharedPtr clock_;
110 std::unique_ptr<nav2_graceful_controller::SmoothControlLaw> control_law_;
111 double k_phi_, k_delta_, beta_, lambda_;
112 double slowdown_radius_, v_linear_min_, v_linear_max_, v_angular_max_;
115 rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr trajectory_pub_;
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_;
Default control law for approaching a dock target.
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.
void configureCollisionChecker(const rclcpp_lifecycle::LifecycleNode::SharedPtr &node, std::string costmap_topic, std::string footprint_topic, double transform_tolerance)
Configure the collision checker.
Controller(const rclcpp_lifecycle::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.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.