dwb_local_planner.h
Go to the documentation of this file.
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_LOCAL_PLANNER_DWB_LOCAL_PLANNER_H
36 #define DWB_LOCAL_PLANNER_DWB_LOCAL_PLANNER_H
37 
43 #include <pluginlib/class_loader.h>
44 #include <string>
45 #include <vector>
46 
47 namespace dwb_local_planner
48 {
49 
55 {
56 public:
61 
62  virtual ~DWBLocalPlanner() {}
63 
70  void initialize(const ros::NodeHandle& parent, const std::string& name,
71  TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override;
72 
77  void setGoalPose(const nav_2d_msgs::Pose2DStamped& goal_pose) override;
78 
83  void setPlan(const nav_2d_msgs::Path2D& path) override;
84 
97  nav_2d_msgs::Twist2DStamped computeVelocityCommands(const nav_2d_msgs::Pose2DStamped& pose,
98  const nav_2d_msgs::Twist2D& velocity) override;
99 
110  bool isGoalReached(const nav_2d_msgs::Pose2DStamped& pose, const nav_2d_msgs::Twist2D& velocity) override;
111 
123  virtual dwb_msgs::TrajectoryScore scoreTrajectory(const dwb_msgs::Trajectory2D& traj, double best_score = -1);
124 
137  virtual nav_2d_msgs::Twist2DStamped computeVelocityCommands(const nav_2d_msgs::Pose2DStamped& pose,
138  const nav_2d_msgs::Twist2D& velocity,
139  std::shared_ptr<dwb_msgs::LocalPlanEvaluation>& results);
140 
141 
142 protected:
148  virtual void prepare(const nav_2d_msgs::Pose2DStamped& pose, const nav_2d_msgs::Twist2D& velocity);
149 
153  virtual dwb_msgs::TrajectoryScore coreScoringAlgorithm(const geometry_msgs::Pose2D& pose,
154  const nav_2d_msgs::Twist2D velocity,
155  std::shared_ptr<dwb_msgs::LocalPlanEvaluation>& results);
156 
167  virtual nav_2d_msgs::Path2D transformGlobalPlan(const nav_2d_msgs::Pose2DStamped& pose);
168 
172  geometry_msgs::Pose2D transformPoseToLocal(const nav_2d_msgs::Pose2DStamped& pose);
173 
174  nav_2d_msgs::Path2D global_plan_;
175  nav_2d_msgs::Pose2DStamped goal_pose_;
180 
181  // Plugin handling
187  std::vector<TrajectoryCritic::Ptr> critics_;
188 
195  std::string resolveCriticClassName(std::string base_name);
196 
201  virtual void loadCritics(const std::string name);
202 
203  std::vector<std::string> default_critic_namespaces_;
204 
209 
211 };
212 
213 } // namespace dwb_local_planner
214 
215 #endif // DWB_LOCAL_PLANNER_DWB_LOCAL_PLANNER_H
pluginlib::ClassLoader< TrajectoryCritic > critic_loader_
TrajectoryGenerator::Ptr traj_generator_
virtual void prepare(const nav_2d_msgs::Pose2DStamped &pose, const nav_2d_msgs::Twist2D &velocity)
Helper method for preparing for the core scoring algorithm.
Consolidation of all the publishing logic for the DWB Local Planner.
Definition: publisher.h:59
void initialize(const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override
nav_core2 initialization
nav_2d_msgs::Pose2DStamped goal_pose_
Saved Goal Pose.
Plugin-based flexible local_planner.
nav_2d_msgs::Twist2DStamped computeVelocityCommands(const nav_2d_msgs::Pose2DStamped &pose, const nav_2d_msgs::Twist2D &velocity) override
nav_core2 computeVelocityCommands - calculates the best command given the current pose and velocity ...
std::shared_ptr< dwb_local_planner::TrajectoryGenerator > Ptr
pluginlib::ClassLoader< GoalChecker > goal_checker_loader_
std::shared_ptr< dwb_local_planner::GoalChecker > Ptr
Definition: goal_checker.h:57
pluginlib::ClassLoader< TrajectoryGenerator > traj_gen_loader_
void setPlan(const nav_2d_msgs::Path2D &path) override
nav_core2 setPlan - Sets the global plan
bool isGoalReached(const nav_2d_msgs::Pose2DStamped &pose, const nav_2d_msgs::Twist2D &velocity) override
nav_core2 isGoalReached - Check whether the robot has reached its goal, given the current pose & velo...
nav_2d_msgs::Path2D global_plan_
Saved Global Plan.
virtual void loadCritics(const std::string name)
Load the critic parameters from the namespace.
std::vector< std::string > default_critic_namespaces_
std::string resolveCriticClassName(std::string base_name)
try to resolve a possibly shortened critic name with the default namespaces and the suffix "Critic" ...
virtual nav_2d_msgs::Path2D transformGlobalPlan(const nav_2d_msgs::Pose2DStamped &pose)
Transforms global plan into same frame as pose, clips far away poses and possibly prunes passed poses...
std::vector< TrajectoryCritic::Ptr > critics_
std::shared_ptr< Costmap > Ptr
std::shared_ptr< tf::TransformListener > TFListenerPtr
virtual dwb_msgs::TrajectoryScore coreScoringAlgorithm(const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D velocity, std::shared_ptr< dwb_msgs::LocalPlanEvaluation > &results)
Iterate through all the twists and find the best one.
geometry_msgs::Pose2D transformPoseToLocal(const nav_2d_msgs::Pose2DStamped &pose)
Helper method to transform a given pose to the local costmap frame.
virtual dwb_msgs::TrajectoryScore scoreTrajectory(const dwb_msgs::Trajectory2D &traj, double best_score=-1)
Score a given command. Can be used for testing.
void setGoalPose(const nav_2d_msgs::Pose2DStamped &goal_pose) override
nav_core2 setGoalPose - Sets the global goal pose
DWBLocalPlanner()
Constructor that brings up pluginlib loaders.


dwb_local_planner
Author(s): David V. Lu!!
autogenerated on Wed Jun 26 2019 20:06:13