Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
nav2_rotation_shim_controller.hpp
1 // Copyright (c) 2021 Samsung Research America
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_ROTATION_SHIM_CONTROLLER__NAV2_ROTATION_SHIM_CONTROLLER_HPP_
16 #define NAV2_ROTATION_SHIM_CONTROLLER__NAV2_ROTATION_SHIM_CONTROLLER_HPP_
17 
18 #include <string>
19 #include <vector>
20 #include <memory>
21 #include <algorithm>
22 #include <mutex>
23 #include <limits>
24 
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/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"
36 
37 namespace nav2_rotation_shim_controller
38 {
39 
45 {
46 public:
51 
55  ~RotationShimController() override = default;
56 
64  void configure(
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;
68 
72  void cleanup() override;
73 
77  void activate() override;
78 
82  void deactivate() override;
83 
91  geometry_msgs::msg::TwistStamped computeVelocityCommands(
92  const geometry_msgs::msg::PoseStamped & pose,
93  const geometry_msgs::msg::Twist & velocity,
94  nav2_core::GoalChecker * /*goal_checker*/) override;
95 
100  void setPlan(const nav_msgs::msg::Path & path) override;
101 
109  void setSpeedLimit(const double & speed_limit, const bool & percentage) override;
110 
111 protected:
118  geometry_msgs::msg::PoseStamped getSampledPathPt();
119 
125  geometry_msgs::msg::PoseStamped getSampledPathGoal();
126 
132  geometry_msgs::msg::Pose transformPoseToBaseFrame(const geometry_msgs::msg::PoseStamped & pt);
133 
141  geometry_msgs::msg::TwistStamped computeRotateToHeadingCommand(
142  const double & angular_distance,
143  const geometry_msgs::msg::PoseStamped & pose,
144  const geometry_msgs::msg::Twist & velocity);
145 
152  void isCollisionFree(
153  const geometry_msgs::msg::TwistStamped & cmd_vel,
154  const double & angular_distance_to_heading,
155  const geometry_msgs::msg::PoseStamped & pose);
156 
161  rcl_interfaces::msg::SetParametersResult
162  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
163 
164  rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
165  std::shared_ptr<tf2_ros::Buffer> tf_;
166  std::string plugin_name_;
167  rclcpp::Logger logger_ {rclcpp::get_logger("RotationShimController")};
168  rclcpp::Clock::SharedPtr clock_;
169  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
170  std::unique_ptr<nav2_costmap_2d::FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>
171  collision_checker_;
172 
173  pluginlib::ClassLoader<nav2_core::Controller> lp_loader_;
174  nav2_core::Controller::Ptr primary_controller_;
175  bool path_updated_;
176  nav_msgs::msg::Path current_path_;
177  double forward_sampling_distance_, angular_dist_threshold_, angular_disengage_threshold_;
178  double rotate_to_heading_angular_vel_, max_angular_accel_;
179  double control_duration_, simulate_ahead_time_;
180  bool rotate_to_goal_heading_, in_rotation_;
181  bool closed_loop_;
182  double last_angular_vel_ = std::numeric_limits<double>::max();
183 
184  // Dynamic parameters handler
185  std::mutex mutex_;
186  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
187  std::unique_ptr<nav2_controller::PositionGoalChecker> position_goal_checker_;
188 };
189 
190 } // namespace nav2_rotation_shim_controller
191 
192 #endif // NAV2_ROTATION_SHIM_CONTROLLER__NAV2_ROTATION_SHIM_CONTROLLER_HPP_
controller interface that acts as a virtual base class for all controller plugins
Definition: controller.hpp:61
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.
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.