Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
range_sensor_layer.hpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018 David V. Lu!!
5  * Copyright (c) 2020, Bytes Robotics
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the copyright holder nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
36 #ifndef NAV2_COSTMAP_2D__RANGE_SENSOR_LAYER_HPP_
37 #define NAV2_COSTMAP_2D__RANGE_SENSOR_LAYER_HPP_
38 
39 #include <list>
40 #include <string>
41 #include <vector>
42 #include <mutex>
43 
44 #include "map_msgs/msg/occupancy_grid_update.hpp"
45 #include "message_filters/subscriber.h"
46 #include "nav2_costmap_2d/costmap_layer.hpp"
47 #include "nav2_costmap_2d/layered_costmap.hpp"
48 #include "nav_msgs/msg/occupancy_grid.hpp"
49 #include "rclcpp/rclcpp.hpp"
50 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
51 #include "sensor_msgs/msg/range.hpp"
52 
53 namespace nav2_costmap_2d
54 {
55 
61 {
62 public:
63  enum class InputSensorType
64  {
65  VARIABLE,
66  FIXED,
67  ALL
68  };
69 
74 
78  virtual void onInitialize();
79 
90  virtual void updateBounds(
91  double robot_x, double robot_y, double robot_yaw,
92  double * min_x, double * min_y, double * max_x, double * max_y);
93 
102  virtual void updateCosts(
103  nav2_costmap_2d::Costmap2D & master_grid, int min_i,
104  int min_j, int max_i, int max_j);
105 
109  virtual void reset();
110 
114  virtual void deactivate();
115 
119  virtual void activate();
120 
124  virtual bool isClearable() {return true;}
125 
129  void bufferIncomingRangeMsg(const sensor_msgs::msg::Range::SharedPtr range_message);
130 
131 protected:
135  void updateCostmap();
139  void updateCostmap(sensor_msgs::msg::Range & range_message, bool clear_sensor_cone);
140 
145  void processRangeMsg(sensor_msgs::msg::Range & range_message);
149  void processFixedRangeMsg(sensor_msgs::msg::Range & range_message);
153  void processVariableRangeMsg(sensor_msgs::msg::Range & range_message);
154 
158  void resetRange();
159 
163  inline double gamma(double theta);
167  inline double delta(double phi);
171  inline double sensor_model(double r, double phi, double theta);
172 
176  inline void get_deltas(double angle, double * dx, double * dy);
177 
181  inline void update_cell(
182  double ox, double oy, double ot,
183  double r, double nx, double ny, bool clear);
184 
188  inline double to_prob(unsigned char c)
189  {
190  return static_cast<double>(c) / nav2_costmap_2d::LETHAL_OBSTACLE;
191  }
192 
196  inline unsigned char to_cost(double p)
197  {
198  return static_cast<unsigned char>(p * nav2_costmap_2d::LETHAL_OBSTACLE);
199  }
200 
201  std::function<void(sensor_msgs::msg::Range & range_message)> processRangeMessageFunc_;
202  std::mutex range_message_mutex_;
203  std::list<sensor_msgs::msg::Range> range_msgs_buffer_;
204 
205  double max_angle_, phi_v_;
206  double inflate_cone_;
207  std::string global_frame_;
208 
209  double clear_threshold_, mark_threshold_;
210  bool clear_on_max_reading_;
211  bool was_reset_;
212 
213  tf2::Duration transform_tolerance_;
214  double no_readings_timeout_;
215  rclcpp::Time last_reading_time_;
216  unsigned int buffered_readings_;
217  std::vector<rclcpp::Subscription<sensor_msgs::msg::Range>::SharedPtr> range_subs_;
218  double min_x_, min_y_, max_x_, max_y_;
219 
223  float area(int x1, int y1, int x2, int y2, int x3, int y3)
224  {
225  return fabs((x1 * (y2 - y3) + x2 * (y3 - y1) + x3 * (y1 - y2)) / 2.0);
226  }
227 
231  int orient2d(int Ax, int Ay, int Bx, int By, int Cx, int Cy)
232  {
233  return (Bx - Ax) * (Cy - Ay) - (By - Ay) * (Cx - Ax);
234  }
235 };
236 } // namespace nav2_costmap_2d
237 #endif // NAV2_COSTMAP_2D__RANGE_SENSOR_LAYER_HPP_
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
A costmap layer base class for costmap plugin layers. Rather than just a layer, this object also cont...
Takes in IR/Sonar/similar point measurement sensors and populates in costmap.
void processVariableRangeMsg(sensor_msgs::msg::Range &range_message)
Process variable range incoming range sensor data.
void processFixedRangeMsg(sensor_msgs::msg::Range &range_message)
Process fixed range incoming range sensor data.
void processRangeMsg(sensor_msgs::msg::Range &range_message)
Process general incoming range sensor data. If min=max ranges, fixed processor callback is used,...
double delta(double phi)
Get the delta value for an angle, phi.
virtual void activate()
Activate the layer.
virtual void onInitialize()
Initialization process of layer on startup.
double gamma(double theta)
Get the gamma value for an angle, theta.
void updateCostmap()
Processes all sensors into the costmap buffered from callbacks.
virtual bool isClearable()
If clearing operations should be processed on this layer or not.
unsigned char to_cost(double p)
Find cost value of a probability.
double to_prob(unsigned char c)
Find probability value of a cost.
float area(int x1, int y1, int x2, int y2, int x3, int y3)
Find the area of 3 points of a triangle.
virtual void reset()
Reset this costmap.
void bufferIncomingRangeMsg(const sensor_msgs::msg::Range::SharedPtr range_message)
Handle an incoming Range message to populate into costmap.
virtual void updateCosts(nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Update the costs in the master costmap in the window.
void update_cell(double ox, double oy, double ot, double r, double nx, double ny, bool clear)
Update the cost in a cell with information.
virtual void deactivate()
Deactivate the layer.
void resetRange()
Reset the angle min/max x, and min/max y values.
double sensor_model(double r, double phi, double theta)
Apply the sensor model of the layer for range sensors.
int orient2d(int Ax, int Ay, int Bx, int By, int Cx, int Cy)
Find the cross product of 3 vectors, A,B,C.
void get_deltas(double angle, double *dx, double *dy)
Get angles.
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
Update the bounds of the master costmap by this layer's update dimensions.