trajectory_critic.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_TRAJECTORY_CRITIC_H
36 #define DWB_LOCAL_PLANNER_TRAJECTORY_CRITIC_H
37 
38 #include <ros/ros.h>
39 #include <nav_core2/common.h>
40 #include <nav_core2/costmap.h>
41 #include <geometry_msgs/Pose2D.h>
42 #include <nav_2d_msgs/Twist2D.h>
43 #include <nav_2d_msgs/Path2D.h>
44 #include <dwb_msgs/Trajectory2D.h>
45 #include <sensor_msgs/PointCloud.h>
46 #include <memory>
47 #include <string>
48 #include <vector>
49 
50 namespace dwb_local_planner
51 {
77 {
78 public:
79  using Ptr = std::shared_ptr<dwb_local_planner::TrajectoryCritic>;
80 
81  virtual ~TrajectoryCritic() {}
82 
93  void initialize(const ros::NodeHandle& planner_nh, std::string name, nav_core2::Costmap::Ptr costmap)
94  {
95  name_ = name;
96  costmap_ = costmap;
97  planner_nh_ = planner_nh;
99  critic_nh_.param("scale", scale_, 1.0);
100  onInit();
101  }
102 
103  virtual void onInit() {}
104 
111  virtual void reset() {}
112 
123  virtual bool prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel,
124  const geometry_msgs::Pose2D& goal,
125  const nav_2d_msgs::Path2D& global_plan)
126  {
127  return true;
128  }
129 
136  virtual double scoreTrajectory(const dwb_msgs::Trajectory2D& traj) = 0;
137 
141  virtual void debrief(const nav_2d_msgs::Twist2D& cmd_vel) {}
142 
159  virtual void addCriticVisualization(sensor_msgs::PointCloud& pc) {}
160 
161  std::string getName()
162  {
163  return name_;
164  }
165 
166  virtual double getScale() const { return scale_; }
167  void setScale(const double scale) { scale_ = scale; }
168 protected:
169  std::string name_;
171  double scale_;
173 };
174 
175 } // namespace dwb_local_planner
176 
177 #endif // DWB_LOCAL_PLANNER_TRAJECTORY_CRITIC_H
dwb_local_planner::TrajectoryCritic::initialize
void initialize(const ros::NodeHandle &planner_nh, std::string name, nav_core2::Costmap::Ptr costmap)
Initialize the critic with appropriate pointers and parameters.
Definition: trajectory_critic.h:93
dwb_local_planner::TrajectoryCritic::Ptr
std::shared_ptr< dwb_local_planner::TrajectoryCritic > Ptr
Definition: trajectory_critic.h:79
ros.h
dwb_local_planner::TrajectoryCritic::name_
std::string name_
Definition: trajectory_critic.h:169
common.h
dwb_local_planner
Definition: backwards_compatibility.h:40
dwb_local_planner::TrajectoryCritic::reset
virtual void reset()
Reset the state of the critic.
Definition: trajectory_critic.h:111
costmap.h
dwb_local_planner::TrajectoryCritic::getScale
virtual double getScale() const
Definition: trajectory_critic.h:166
dwb_local_planner::TrajectoryCritic::scoreTrajectory
virtual double scoreTrajectory(const dwb_msgs::Trajectory2D &traj)=0
Return a raw score for the given trajectory.
dwb_local_planner::TrajectoryCritic::debrief
virtual void debrief(const nav_2d_msgs::Twist2D &cmd_vel)
debrief informs the critic what the chosen cmd_vel was (if it cares)
Definition: trajectory_critic.h:141
dwb_local_planner::TrajectoryCritic::setScale
void setScale(const double scale)
Definition: trajectory_critic.h:167
dwb_local_planner::TrajectoryCritic::~TrajectoryCritic
virtual ~TrajectoryCritic()
Definition: trajectory_critic.h:81
nav_core2::Costmap::Ptr
std::shared_ptr< Costmap > Ptr
dwb_local_planner::TrajectoryCritic::critic_nh_
ros::NodeHandle critic_nh_
Definition: trajectory_critic.h:172
dwb_local_planner::TrajectoryCritic::prepare
virtual bool prepare(const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D &vel, const geometry_msgs::Pose2D &goal, const nav_2d_msgs::Path2D &global_plan)
Prior to evaluating any trajectories, look at contextual information constant across all trajectories...
Definition: trajectory_critic.h:123
dwb_local_planner::TrajectoryCritic::planner_nh_
ros::NodeHandle planner_nh_
Definition: trajectory_critic.h:172
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
dwb_local_planner::TrajectoryCritic::scale_
double scale_
Definition: trajectory_critic.h:171
dwb_local_planner::TrajectoryCritic
Evaluates a Trajectory2D to produce a score.
Definition: trajectory_critic.h:76
dwb_local_planner::TrajectoryCritic::costmap_
nav_core2::Costmap::Ptr costmap_
Definition: trajectory_critic.h:170
ros::NodeHandle
dwb_local_planner::TrajectoryCritic::getName
std::string getName()
Definition: trajectory_critic.h:161
dwb_local_planner::TrajectoryCritic::addCriticVisualization
virtual void addCriticVisualization(sensor_msgs::PointCloud &pc)
Add information to the given pointcloud for debugging costmap-grid based scores.
Definition: trajectory_critic.h:159
dwb_local_planner::TrajectoryCritic::onInit
virtual void onInit()
Definition: trajectory_critic.h:103


dwb_local_planner
Author(s): David V. Lu!!
autogenerated on Sun May 18 2025 02:47:25