Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
base_obstacle.cpp
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 #include <vector>
35 #include <string>
36 #include <utility>
37 
38 #include "dwb_critics/base_obstacle.hpp"
39 #include "dwb_core/exceptions.hpp"
40 #include "pluginlib/class_list_macros.hpp"
41 #include "nav2_costmap_2d/cost_values.hpp"
42 #include "nav2_ros_common/node_utils.hpp"
43 
45 
46 namespace dwb_critics
47 {
48 
49 void BaseObstacleCritic::onInit()
50 {
51  costmap_ = costmap_ros_->getCostmap();
52 
53  auto node = node_.lock();
54  if (!node) {
55  throw std::runtime_error{"Failed to lock node"};
56  }
57 
58  nav2::declare_parameter_if_not_declared(
59  node,
60  dwb_plugin_name_ + "." + name_ + ".sum_scores", rclcpp::ParameterValue(false));
61  node->get_parameter(dwb_plugin_name_ + "." + name_ + ".sum_scores", sum_scores_);
62 }
63 
64 double BaseObstacleCritic::scoreTrajectory(const dwb_msgs::msg::Trajectory2D & traj)
65 {
66  double score = 0.0;
67  for (unsigned int i = 0; i < traj.poses.size(); ++i) {
68  double pose_score = scorePose(traj.poses[i]);
69  // Optimized/branchless version of if (sum_scores_) score += pose_score,
70  // else score = pose_score;
71  score = static_cast<double>(sum_scores_) * score + pose_score;
72  }
73  return score;
74 }
75 
76 double BaseObstacleCritic::scorePose(const geometry_msgs::msg::Pose & pose)
77 {
78  unsigned int cell_x, cell_y;
79  if (!costmap_->worldToMap(pose.position.x, pose.position.y, cell_x, cell_y)) {
80  throw dwb_core::
81  IllegalTrajectoryException(name_, "Trajectory Goes Off Grid.");
82  }
83  unsigned char cost = costmap_->getCost(cell_x, cell_y);
84  if (!isValidCost(cost)) {
85  throw dwb_core::
86  IllegalTrajectoryException(name_, "Trajectory Hits Obstacle.");
87  }
88  return cost;
89 }
90 
91 bool BaseObstacleCritic::isValidCost(const unsigned char cost)
92 {
93  return cost != nav2_costmap_2d::LETHAL_OBSTACLE &&
94  cost != nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE &&
95  cost != nav2_costmap_2d::NO_INFORMATION;
96 }
97 
99  std::vector<std::pair<std::string, std::vector<float>>> & cost_channels)
100 {
101  std::pair<std::string, std::vector<float>> grid_scores;
102  grid_scores.first = name_;
103 
104  unsigned int size_x = costmap_->getSizeInCellsX();
105  unsigned int size_y = costmap_->getSizeInCellsY();
106  grid_scores.second.resize(size_x * size_y);
107  unsigned int i = 0;
108  for (unsigned int cy = 0; cy < size_y; cy++) {
109  for (unsigned int cx = 0; cx < size_x; cx++) {
110  grid_scores.second[i] = costmap_->getCost(cx, cy);
111  i++;
112  }
113  }
114  cost_channels.push_back(grid_scores);
115 }
116 
117 } // namespace dwb_critics
Evaluates a Trajectory2D to produce a score.
Uses costmap 2d to assign negative costs if a circular robot would collide at any point of the trajec...
virtual double scorePose(const geometry_msgs::msg::Pose &pose)
Return the obstacle score for a particular pose.
double scoreTrajectory(const dwb_msgs::msg::Trajectory2D &traj) override
Return a raw score for the given trajectory.
void addCriticVisualization(std::vector< std::pair< std::string, std::vector< float >>> &cost_channels) override
Add information to the given pointcloud for debugging costmap-grid based scores.
virtual bool isValidCost(const unsigned char cost)
Check to see whether a given cell cost is valid for driving through.
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
Definition: costmap_2d.cpp:264
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:291
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:546
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:551