Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
cost_critic.hpp
1 // Copyright (c) 2023 Robocc Brice Renaudeau
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_MPPI_CONTROLLER__CRITICS__COST_CRITIC_HPP_
16 #define NAV2_MPPI_CONTROLLER__CRITICS__COST_CRITIC_HPP_
17 
18 #include <memory>
19 #include <string>
20 
21 #include "nav2_costmap_2d/footprint_collision_checker.hpp"
22 #include "nav2_costmap_2d/inflation_layer.hpp"
23 
24 #include "nav2_mppi_controller/critic_function.hpp"
25 #include "nav2_mppi_controller/models/state.hpp"
26 #include "nav2_mppi_controller/tools/utils.hpp"
27 
28 namespace mppi::critics
29 {
30 
35 class CostCritic : public CriticFunction
36 {
37 public:
41  void initialize() override;
42 
48  void score(CriticData & data) override;
49 
50 protected:
59  inline bool inCollision(float cost, float x, float y, float theta)
60  {
61  // If consider_footprint_ check footprint scort for collision
62  float score_cost = cost;
63  if (consider_footprint_ &&
64  (cost >= possible_collision_cost_ || possible_collision_cost_ < 1.0f))
65  {
66  score_cost = static_cast<float>(collision_checker_.footprintCostAtPose(
67  static_cast<double>(x), static_cast<double>(y), static_cast<double>(theta),
68  costmap_ros_->getRobotFootprint()));
69  }
70 
71  switch (static_cast<unsigned char>(score_cost)) {
72  case (nav2_costmap_2d::LETHAL_OBSTACLE):
73  return true;
74  case (nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE):
75  return consider_footprint_ ? false : true;
76  case (nav2_costmap_2d::NO_INFORMATION):
77  return is_tracking_unknown_ ? false : true;
78  }
79 
80  return false;
81  }
82 
90  inline float findCircumscribedCost(std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap);
91 
100  inline bool worldToMapFloat(float wx, float wy, unsigned int & mx, unsigned int & my) const
101  {
102  if (wx < origin_x_ || wy < origin_y_) {
103  return false;
104  }
105 
106  mx = static_cast<unsigned int>((wx - origin_x_) / resolution_);
107  my = static_cast<unsigned int>((wy - origin_y_) / resolution_);
108 
109  if (mx < size_x_ && my < size_y_) {
110  return true;
111  }
112  return false;
113  }
114 
121  inline unsigned int getIndex(unsigned int mx, unsigned int my) const
122  {
123  return my * size_x_ + mx;
124  }
125 
127  collision_checker_{nullptr};
128  float possible_collision_cost_;
129 
130  bool consider_footprint_{true};
131  bool is_tracking_unknown_{true};
132  float circumscribed_radius_{0.0f};
133  float circumscribed_cost_{0.0f};
134  float collision_cost_{0.0f};
135  float critical_cost_{0.0f};
136  unsigned int near_collision_cost_{253};
137  float weight_{0};
138  unsigned int trajectory_point_step_;
139 
140  float origin_x_, origin_y_, resolution_;
141  unsigned int size_x_, size_y_;
142 
143  float near_goal_distance_;
144  std::string inflation_layer_name_;
145 
146  unsigned int power_{0};
147 };
148 
149 } // namespace mppi::critics
150 
151 #endif // NAV2_MPPI_CONTROLLER__CRITICS__COST_CRITIC_HPP_
Critic objective function for avoiding obstacles using costmap's inflated cost.
Definition: cost_critic.hpp:36
bool worldToMapFloat(float wx, float wy, unsigned int &mx, unsigned int &my) const
An implementation of worldToMap fully using floats.
unsigned int getIndex(unsigned int mx, unsigned int my) const
A local implementation of getIndex.
bool inCollision(float cost, float x, float y, float theta)
Checks if cost represents a collision.
Definition: cost_critic.hpp:59
float findCircumscribedCost(std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap)
Find the min cost of the inflation decay function for which the robot MAY be in collision in any orie...
Definition: cost_critic.cpp:82
void initialize() override
Initialize critic.
Definition: cost_critic.cpp:23
void score(CriticData &data) override
Evaluate cost related to obstacle avoidance.
Abstract critic objective function to score trajectories.
double footprintCostAtPose(double x, double y, double theta, const Footprint &footprint)
Find the footprint cost a a post with an unoriented footprint.
Data to pass to critics for scoring, including state, trajectories, pruned path, global goal,...
Definition: critic_data.hpp:45