15 #ifndef NAV2_GRACEFUL_CONTROLLER__GRACEFUL_CONTROLLER_HPP_
16 #define NAV2_GRACEFUL_CONTROLLER__GRACEFUL_CONTROLLER_HPP_
25 #include "nav2_core/controller.hpp"
26 #include "nav2_costmap_2d/footprint_collision_checker.hpp"
27 #include "rclcpp/rclcpp.hpp"
28 #include "pluginlib/class_loader.hpp"
29 #include "pluginlib/class_list_macros.hpp"
30 #include "nav2_graceful_controller/path_handler.hpp"
31 #include "nav2_graceful_controller/parameter_handler.hpp"
32 #include "nav2_graceful_controller/smooth_control_law.hpp"
33 #include "nav2_graceful_controller/utils.hpp"
35 namespace nav2_graceful_controller
63 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
64 std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
65 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
override;
90 const geometry_msgs::msg::PoseStamped & pose,
91 const geometry_msgs::msg::Twist & velocity,
98 void setPlan(
const nav_msgs::msg::Path & path)
override;
107 void setSpeedLimit(
const double & speed_limit,
const bool & percentage)
override;
122 const geometry_msgs::msg::PoseStamped & motion_target,
123 const geometry_msgs::msg::TransformStamped & costmap_transform,
124 nav_msgs::msg::Path & trajectory,
125 geometry_msgs::msg::TwistStamped & cmd_vel,
143 bool inCollision(
const double & x,
const double & y,
const double & theta);
151 const std::vector<geometry_msgs::msg::PoseStamped> & poses,
152 std::vector<double> & distances);
160 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
161 std::string plugin_name_;
162 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
163 std::unique_ptr<nav2_costmap_2d::FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>
165 rclcpp::Logger logger_{rclcpp::get_logger(
"GracefulController")};
168 double goal_dist_tolerance_;
172 bool do_initial_rotation_;
174 std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> transformed_plan_pub_;
175 std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> local_plan_pub_;
176 std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PoseStamped>>
178 std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::Marker>>
180 std::unique_ptr<nav2_graceful_controller::PathHandler> path_handler_;
181 std::unique_ptr<nav2_graceful_controller::ParameterHandler> param_handler_;
182 std::unique_ptr<nav2_graceful_controller::SmoothControlLaw> control_law_;
controller interface that acts as a virtual base class for all controller plugins
Function-object for checking whether a goal has been reached.
Graceful controller plugin.
void activate() override
Activate controller state machine.
~GracefulController() override=default
Destructor for nav2_graceful_controller::GracefulController.
void setPlan(const nav_msgs::msg::Path &path) override
nav2_core setPlan - Sets the global plan.
void computeDistanceAlongPath(const std::vector< geometry_msgs::msg::PoseStamped > &poses, std::vector< double > &distances)
Compute the distance to each pose in a path.
void deactivate() override
Deactivate controller state machine.
bool simulateTrajectory(const geometry_msgs::msg::PoseStamped &motion_target, const geometry_msgs::msg::TransformStamped &costmap_transform, nav_msgs::msg::Path &trajectory, geometry_msgs::msg::TwistStamped &cmd_vel, bool backward)
Simulate trajectory calculating in every step the new velocity command based on a new curvature value...
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.
GracefulController()=default
Constructor for nav2_graceful_controller::GracefulController.
void cleanup() override
Cleanup controller state machine.
geometry_msgs::msg::Twist rotateToTarget(double angle_to_target)
Rotate the robot to face the motion target with maximum angular velocity.
void setSpeedLimit(const double &speed_limit, const bool &percentage) override
Limits the maximum linear speed of the robot.
geometry_msgs::msg::TwistStamped computeVelocityCommands(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::Twist &velocity, nav2_core::GoalChecker *goal_checker) override
Compute the best command given the current pose and velocity.
bool inCollision(const double &x, const double &y, const double &theta)
Checks if the robot is in collision.
void validateOrientations(std::vector< geometry_msgs::msg::PoseStamped > &path)
Control law requires proper orientations, not all planners provide them.