Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
dwb_local_planner.hpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #ifndef DWB_CORE__DWB_LOCAL_PLANNER_HPP_
36 #define DWB_CORE__DWB_LOCAL_PLANNER_HPP_
37 
38 #include <memory>
39 #include <string>
40 #include <vector>
41 
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"
53 
54 namespace dwb_core
55 {
56 
62 {
63 public:
68 
69  void configure(
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;
73 
74  virtual ~DWBLocalPlanner() {}
75 
79  void activate() override;
80 
84  void deactivate() override;
85 
89  void cleanup() override;
90 
95  void setPlan(const nav_msgs::msg::Path & path) override;
96 
110  geometry_msgs::msg::TwistStamped computeVelocityCommands(
111  const geometry_msgs::msg::PoseStamped & pose,
112  const geometry_msgs::msg::Twist & velocity,
113  nav2_core::GoalChecker * /*goal_checker*/) override;
114 
126  virtual dwb_msgs::msg::TrajectoryScore scoreTrajectory(
127  const dwb_msgs::msg::Trajectory2D & traj,
128  double best_score = -1);
129 
142  virtual nav_2d_msgs::msg::Twist2DStamped computeVelocityCommands(
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);
146 
154  void setSpeedLimit(const double & speed_limit, const bool & percentage) override
155  {
156  if (traj_generator_) {
157  traj_generator_->setSpeedLimit(speed_limit, percentage);
158  }
159  }
160 
161 protected:
169  void prepareGlobalPlan(
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);
172 
176  virtual dwb_msgs::msg::TrajectoryScore coreScoringAlgorithm(
177  const geometry_msgs::msg::Pose2D & pose,
178  const nav_2d_msgs::msg::Twist2D velocity,
179  std::shared_ptr<dwb_msgs::msg::LocalPlanEvaluation> & results);
180 
196  virtual nav_2d_msgs::msg::Path2D transformGlobalPlan(
197  const nav_2d_msgs::msg::Pose2DStamped & pose);
198  nav_2d_msgs::msg::Path2D global_plan_;
199  bool prune_plan_;
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_;
205 
212  std::string resolveCriticClassName(std::string base_name);
213 
218  virtual void loadCritics();
219 
220  rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
221  rclcpp::Clock::SharedPtr clock_;
222  rclcpp::Logger logger_{rclcpp::get_logger("DWBLocalPlanner")};
223 
224  std::shared_ptr<tf2_ros::Buffer> tf_;
225  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
226 
227  std::unique_ptr<DWBPublisher> pub_;
228  std::vector<std::string> default_critic_namespaces_;
229 
230  // Plugin handling
231  pluginlib::ClassLoader<TrajectoryGenerator> traj_gen_loader_;
232  TrajectoryGenerator::Ptr traj_generator_;
233 
234  pluginlib::ClassLoader<TrajectoryCritic> critic_loader_;
235  std::vector<TrajectoryCritic::Ptr> critics_;
236 
237  std::string dwb_plugin_name_;
238 
239  bool short_circuit_trajectory_evaluation_;
240 };
241 
242 } // namespace dwb_core
243 
244 #endif // DWB_CORE__DWB_LOCAL_PLANNER_HPP_
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
Definition: controller.hpp:61
Function-object for checking whether a goal has been reached.