Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
trajectory_critic.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__TRAJECTORY_CRITIC_HPP_
36 #define DWB_CORE__TRAJECTORY_CRITIC_HPP_
37 
38 #include <string>
39 #include <vector>
40 #include <memory>
41 #include <utility>
42 
43 #include "rclcpp/rclcpp.hpp"
44 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
45 #include "geometry_msgs/msg/pose2_d.hpp"
46 #include "nav_2d_msgs/msg/twist2_d.hpp"
47 #include "nav_2d_msgs/msg/path2_d.hpp"
48 #include "dwb_msgs/msg/trajectory2_d.hpp"
49 #include "sensor_msgs/msg/point_cloud.hpp"
50 #include "nav2_util/lifecycle_node.hpp"
51 
52 namespace dwb_core
53 {
79 {
80 public:
81  using Ptr = std::shared_ptr<dwb_core::TrajectoryCritic>;
82 
83  virtual ~TrajectoryCritic() {}
84 
95  void initialize(
96  const nav2_util::LifecycleNode::SharedPtr & nh,
97  const std::string & name,
98  const std::string & ns,
99  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
100  {
101  node_ = nh;
102  name_ = name;
103  costmap_ros_ = costmap_ros;
104  dwb_plugin_name_ = ns;
105  if (!nh->has_parameter(dwb_plugin_name_ + "." + name_ + ".scale")) {
106  nh->declare_parameter(
107  dwb_plugin_name_ + "." + name_ + ".scale",
108  rclcpp::ParameterValue(1.0));
109  }
110  nh->get_parameter(dwb_plugin_name_ + "." + name_ + ".scale", scale_);
111  onInit();
112  }
113  virtual void onInit() {}
114 
121  virtual void reset() {}
122 
133  virtual bool prepare(
134  const geometry_msgs::msg::Pose2D &, const nav_2d_msgs::msg::Twist2D &,
135  const geometry_msgs::msg::Pose2D &,
136  const nav_2d_msgs::msg::Path2D &)
137  {
138  return true;
139  }
140 
147  virtual double scoreTrajectory(const dwb_msgs::msg::Trajectory2D & traj) = 0;
148 
152  virtual void debrief(const nav_2d_msgs::msg::Twist2D &) {}
153 
170  virtual void addCriticVisualization(std::vector<std::pair<std::string, std::vector<float>>> &) {}
171 
172  std::string getName()
173  {
174  return name_;
175  }
176 
177  virtual double getScale() const {return scale_;}
178  void setScale(const double scale) {scale_ = scale;}
179 
180 protected:
181  std::string name_;
182  std::string dwb_plugin_name_;
183  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
184  double scale_;
185  rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
186 };
187 
188 } // namespace dwb_core
189 
190 #endif // DWB_CORE__TRAJECTORY_CRITIC_HPP_
Evaluates a Trajectory2D to produce a score.
virtual bool prepare(const geometry_msgs::msg::Pose2D &, const nav_2d_msgs::msg::Twist2D &, const geometry_msgs::msg::Pose2D &, const nav_2d_msgs::msg::Path2D &)
Prior to evaluating any trajectories, look at contextual information constant across all trajectories...
virtual double scoreTrajectory(const dwb_msgs::msg::Trajectory2D &traj)=0
Return a raw score for the given trajectory.
virtual void reset()
Reset the state of the critic.
virtual void debrief(const nav_2d_msgs::msg::Twist2D &)
debrief informs the critic what the chosen cmd_vel was (if it cares)
virtual void addCriticVisualization(std::vector< std::pair< std::string, std::vector< float >>> &)
Add information to the given pointcloud for debugging costmap-grid based scores.
void initialize(const nav2_util::LifecycleNode::SharedPtr &nh, const std::string &name, const std::string &ns, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros)
Initialize the critic with appropriate pointers and parameters.