15 #ifndef NAV2_ROTATION_SHIM_CONTROLLER__NAV2_ROTATION_SHIM_CONTROLLER_HPP_
16 #define NAV2_ROTATION_SHIM_CONTROLLER__NAV2_ROTATION_SHIM_CONTROLLER_HPP_
25 #include "rclcpp/rclcpp.hpp"
26 #include "pluginlib/class_loader.hpp"
27 #include "pluginlib/class_list_macros.hpp"
28 #include "nav2_util/geometry_utils.hpp"
29 #include "nav2_util/robot_utils.hpp"
30 #include "nav2_core/controller.hpp"
31 #include "nav2_core/controller_exceptions.hpp"
32 #include "nav2_util/node_utils.hpp"
33 #include "nav2_costmap_2d/footprint_collision_checker.hpp"
34 #include "nav2_controller/plugins/position_goal_checker.hpp"
35 #include "angles/angles.h"
37 namespace nav2_rotation_shim_controller
65 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
66 std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
67 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
override;
92 const geometry_msgs::msg::PoseStamped & pose,
93 const geometry_msgs::msg::Twist & velocity,
100 void setPlan(
const nav_msgs::msg::Path & path)
override;
109 void setSpeedLimit(
const double & speed_limit,
const bool & percentage)
override;
114 void reset()
override;
147 const double & angular_distance,
148 const geometry_msgs::msg::PoseStamped & pose,
149 const geometry_msgs::msg::Twist & velocity);
158 const geometry_msgs::msg::TwistStamped & cmd_vel,
159 const double & angular_distance_to_heading,
160 const geometry_msgs::msg::PoseStamped & pose);
173 rcl_interfaces::msg::SetParametersResult
176 rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
177 std::shared_ptr<tf2_ros::Buffer> tf_;
178 std::string plugin_name_;
179 rclcpp::Logger logger_ {rclcpp::get_logger(
"RotationShimController")};
180 rclcpp::Clock::SharedPtr clock_;
181 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
182 std::unique_ptr<nav2_costmap_2d::FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>
185 pluginlib::ClassLoader<nav2_core::Controller> lp_loader_;
186 nav2_core::Controller::Ptr primary_controller_;
188 nav_msgs::msg::Path current_path_;
189 double forward_sampling_distance_, angular_dist_threshold_, angular_disengage_threshold_;
190 double rotate_to_heading_angular_vel_, max_angular_accel_;
191 double control_duration_, simulate_ahead_time_;
192 bool rotate_to_goal_heading_, in_rotation_, rotate_to_heading_once_;
194 bool use_path_orientations_;
195 double last_angular_vel_ = std::numeric_limits<double>::max();
199 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
200 std::unique_ptr<nav2_controller::PositionGoalChecker> position_goal_checker_;
controller interface that acts as a virtual base class for all controller plugins
Function-object for checking whether a goal has been reached.
Rotate to rough path heading controller shim plugin.
void deactivate() override
Deactivate controller state machine.
void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
Configure controller state machine.
geometry_msgs::msg::PoseStamped getSampledPathPt()
Finds the point on the path that is roughly the sampling point distance away from the robot for use....
geometry_msgs::msg::TwistStamped computeVelocityCommands(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::Twist &velocity, nav2_core::GoalChecker *) override
Compute the best command given the current pose and velocity.
geometry_msgs::msg::Pose transformPoseToBaseFrame(const geometry_msgs::msg::PoseStamped &pt)
Uses TF to find the location of the sampled path point in base frame.
void cleanup() override
Cleanup controller state machine.
geometry_msgs::msg::PoseStamped getSampledPathGoal()
Find the goal point in path May throw exception if the path is empty.
bool isGoalChanged(const nav_msgs::msg::Path &path)
Checks if the goal has changed based on the given path.
geometry_msgs::msg::TwistStamped computeRotateToHeadingCommand(const double &angular_distance, const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::Twist &velocity)
Rotates the robot to the rough heading.
void activate() override
Activate controller state machine.
void setPlan(const nav_msgs::msg::Path &path) override
nav2_core setPlan - Sets the global plan
void setSpeedLimit(const double &speed_limit, const bool &percentage) override
Limits the maximum linear speed of the robot.
~RotationShimController() override=default
Destrructor for nav2_rotation_shim_controller::RotationShimController.
RotationShimController()
Constructor for nav2_rotation_shim_controller::RotationShimController.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
void isCollisionFree(const geometry_msgs::msg::TwistStamped &cmd_vel, const double &angular_distance_to_heading, const geometry_msgs::msg::PoseStamped &pose)
Checks if rotation is safe.
void reset() override
Reset the state of the controller.