35 #ifndef DWB_CORE__DWB_LOCAL_PLANNER_HPP_
36 #define DWB_CORE__DWB_LOCAL_PLANNER_HPP_
42 #include "nav2_core/controller.hpp"
43 #include "nav2_core/goal_checker.hpp"
44 #include "dwb_core/publisher.hpp"
45 #include "dwb_core/trajectory_critic.hpp"
46 #include "dwb_core/trajectory_generator.hpp"
47 #include "nav_2d_msgs/msg/pose2_d_stamped.hpp"
48 #include "nav_2d_msgs/msg/twist2_d_stamped.hpp"
49 #include "rclcpp/rclcpp.hpp"
50 #include "rclcpp_lifecycle/lifecycle_node.hpp"
51 #include "pluginlib/class_loader.hpp"
52 #include "pluginlib/class_list_macros.hpp"
70 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
71 std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
72 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
override;
95 void setPlan(
const nav_msgs::msg::Path & path)
override;
111 const geometry_msgs::msg::PoseStamped & pose,
112 const geometry_msgs::msg::Twist & velocity,
127 const dwb_msgs::msg::Trajectory2D & traj,
128 double best_score = -1);
143 const nav_2d_msgs::msg::Pose2DStamped & pose,
144 const nav_2d_msgs::msg::Twist2D & velocity,
145 std::shared_ptr<dwb_msgs::msg::LocalPlanEvaluation> & results);
154 void setSpeedLimit(
const double & speed_limit,
const bool & percentage)
override
156 if (traj_generator_) {
157 traj_generator_->setSpeedLimit(speed_limit, percentage);
170 const nav_2d_msgs::msg::Pose2DStamped & pose, nav_2d_msgs::msg::Path2D & transformed_plan,
171 nav_2d_msgs::msg::Pose2DStamped & goal_pose,
bool publish_plan =
true);
177 const geometry_msgs::msg::Pose2D & pose,
178 const nav_2d_msgs::msg::Twist2D velocity,
179 std::shared_ptr<dwb_msgs::msg::LocalPlanEvaluation> & results);
197 const nav_2d_msgs::msg::Pose2DStamped & pose);
200 double prune_distance_;
201 bool debug_trajectory_details_;
202 rclcpp::Duration transform_tolerance_{0, 0};
203 bool shorten_transformed_plan_;
204 double forward_prune_distance_;
220 rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
221 rclcpp::Clock::SharedPtr clock_;
222 rclcpp::Logger logger_{rclcpp::get_logger(
"DWBLocalPlanner")};
224 std::shared_ptr<tf2_ros::Buffer> tf_;
225 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
227 std::unique_ptr<DWBPublisher> pub_;
228 std::vector<std::string> default_critic_namespaces_;
231 pluginlib::ClassLoader<TrajectoryGenerator> traj_gen_loader_;
232 TrajectoryGenerator::Ptr traj_generator_;
234 pluginlib::ClassLoader<TrajectoryCritic> critic_loader_;
235 std::vector<TrajectoryCritic::Ptr> critics_;
237 std::string dwb_plugin_name_;
239 bool short_circuit_trajectory_evaluation_;
Plugin-based flexible controller.
void cleanup() override
Cleanup lifecycle node.
void setPlan(const nav_msgs::msg::Path &path) override
nav2_core setPlan - Sets the global plan
std::string resolveCriticClassName(std::string base_name)
try to resolve a possibly shortened critic name with the default namespaces and the suffix "Critic"
void deactivate() override
Deactivate lifecycle node.
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
DWBLocalPlanner()
Constructor that brings up pluginlib loaders.
virtual dwb_msgs::msg::TrajectoryScore coreScoringAlgorithm(const geometry_msgs::msg::Pose2D &pose, const nav_2d_msgs::msg::Twist2D velocity, std::shared_ptr< dwb_msgs::msg::LocalPlanEvaluation > &results)
Iterate through all the twists and find the best one.
void setSpeedLimit(const double &speed_limit, const bool &percentage) override
Limits the maximum linear speed of the robot.
virtual dwb_msgs::msg::TrajectoryScore scoreTrajectory(const dwb_msgs::msg::Trajectory2D &traj, double best_score=-1)
Score a given command. Can be used for testing.
void prepareGlobalPlan(const nav_2d_msgs::msg::Pose2DStamped &pose, nav_2d_msgs::msg::Path2D &transformed_plan, nav_2d_msgs::msg::Pose2DStamped &goal_pose, bool publish_plan=true)
Helper method for two common operations for the operating on the global_plan.
geometry_msgs::msg::TwistStamped computeVelocityCommands(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::Twist &velocity, nav2_core::GoalChecker *) override
nav2_core computeVelocityCommands - calculates the best command given the current pose and velocity
virtual void loadCritics()
Load the critic parameters from the namespace.
void activate() override
Activate lifecycle node.
nav_2d_msgs::msg::Path2D global_plan_
Saved Global Plan.
virtual nav_2d_msgs::msg::Path2D transformGlobalPlan(const nav_2d_msgs::msg::Pose2DStamped &pose)
Transforms global plan into same frame as pose, clips far away poses and possibly prunes passed poses...
controller interface that acts as a virtual base class for all controller plugins
Function-object for checking whether a goal has been reached.