Skip to content

Commit 6c5ca28

Browse files
Michael-EquiSteveMacenski
authored andcommitted
Add in range sensor costmap layer (#1888)
* range costmap building * range sensor layer working * nav2 costmap pass linter and uncrustify tests * Added back semicolon to range class * Added docs * Added angles dependency * Added BSD license * Added BSD license * Made functions inline * revmoed get_clock * added input_sensor_type to docs * Made defualt topic name empty to cause error * using chorno literal to denote time units * Added small initial test * Fixed linter error, line breaks, enum, logger level, and transform_tolerance issue * fixed segmentation fault in test and added transfrom tolerances to tf_->transform * Got test to pass * Added more tests * removed incorrect parameter declaration * Improved marking while moving tests and added clearing tests * removed general clearing test * changed testing helper import in test
1 parent 7b58975 commit 6c5ca28

File tree

10 files changed

+1021
-6
lines changed

10 files changed

+1021
-6
lines changed

doc/parameters/param_list.md

Lines changed: 20 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -51,11 +51,13 @@ For example:
5151
```yaml
5252
local_costmap:
5353
ros__parameters:
54-
plugins: ["obstacle_layer", "voxel_layer", "inflation_layer"]
54+
plugins: ["obstacle_layer", "voxel_layer", "sonar_layer", "inflation_layer"]
5555
obstacle_layer:
5656
plugin: "nav2_costmap_2d::ObstacleLayer"
5757
voxel_layer:
5858
plugin: "nav2_costmap_2d::VoxelLayer"
59+
sonar_layer:
60+
plugin: "nav2_costmap_2d::RangeSensorLayer"
5961
inflation_layer:
6062
plugin: "nav2_costmap_2d::InflationLayer"
6163
```
@@ -115,7 +117,23 @@ When `plugins` parameter is not overridden, the following default plugins are lo
115117
| `<data source>`.marking | true | Whether source should mark in costmap |
116118
| `<data source>`.clearing | false | Whether source should raytrace clear in costmap |
117119
| `<data source>`.obstacle_range | 2.5 | Maximum range to mark obstacles in costmap |
118-
| `<data source>`.raytrace_range | 3.0 | Maximum range to raytrace clear obstacles from costmap |
120+
| `<data source>`.raytrace_range | 3.0 | Maximum range to raytrace clear obstacles from costmap |
121+
122+
## range_sensor_layer plugin
123+
124+
* `<range layer>`: Name corresponding to the `nav2_costmap_2d::RangeSensorLayer` plugin. This name gets defined in `plugin_names`.
125+
126+
| Parameter | Default | Description |
127+
| ----------| --------| ------------|
128+
| `<range layer>`.enabled | true | Whether it is enabled |
129+
| `<range layer>`.topics | [""] | Range topics to subscribe to |
130+
| `<range layer>`.phi | 1.2 | Phi value |
131+
| `<range layer>`.inflate_cone | 1.0 | Inflate the triangular area covered by the sensor (percentage) |
132+
| `<range layer>`.no_readings_timeout | 0.0 | No Readings Timeout |
133+
| `<range layer>`.clear_threshold | 0.2 | Probability below which cells are marked as free |
134+
| `<range layer>`.mark_threshold | 0.8 | Probability above which cells are marked as occupied |
135+
| `<range layer>`.clear_on_max_reading | false | Clear on max reading |
136+
| `<range layer>`.input_sensor_type | ALL | Input sensor type either ALL (automatic selection), VARIABLE (min range != max range), or FIXED (min range == max range) |
119137

120138
## voxel_layer plugin
121139

nav2_costmap_2d/CMakeLists.txt

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@ find_package(tf2 REQUIRED)
2222
find_package(tf2_ros REQUIRED)
2323
find_package(tf2_sensor_msgs REQUIRED)
2424
find_package(visualization_msgs REQUIRED)
25+
find_package(angles REQUIRED)
2526

2627
remove_definitions(-DDISABLE_LIBUSB-1.0)
2728
find_package(Eigen3 REQUIRED)
@@ -72,6 +73,7 @@ set(dependencies
7273
tf2_ros
7374
tf2_sensor_msgs
7475
visualization_msgs
76+
angles
7577
)
7678

7779
ament_target_dependencies(nav2_costmap_2d_core
@@ -84,6 +86,7 @@ add_library(layers SHARED
8486
plugins/obstacle_layer.cpp
8587
src/observation_buffer.cpp
8688
plugins/voxel_layer.cpp
89+
plugins/range_sensor_layer.cpp
8790
)
8891
ament_target_dependencies(layers
8992
${dependencies}

nav2_costmap_2d/costmap_plugins.xml

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,9 @@
1212
<class type="nav2_costmap_2d::VoxelLayer" base_class_type="nav2_costmap_2d::Layer">
1313
<description>Similar to obstacle costmap, but uses 3D voxel grid to store data.</description>
1414
</class>
15+
<class type="nav2_costmap_2d::RangeSensorLayer" base_class_type="nav2_costmap_2d::Layer">
16+
<description>A range-sensor (sonar, IR) based obstacle layer for costmap_2d</description>
17+
</class>
1518
</library>
1619
</class_libraries>
1720

Lines changed: 138 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,138 @@
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.h"
51+
#include "sensor_msgs/msg/range.hpp"
52+
53+
namespace nav2_costmap_2d
54+
{
55+
56+
class RangeSensorLayer : public CostmapLayer
57+
{
58+
public:
59+
enum class InputSensorType
60+
{
61+
VARIABLE,
62+
FIXED,
63+
ALL
64+
};
65+
66+
RangeSensorLayer();
67+
68+
virtual void onInitialize();
69+
virtual void updateBounds(
70+
double robot_x, double robot_y, double robot_yaw,
71+
double * min_x, double * min_y, double * max_x, double * max_y);
72+
virtual void updateCosts(
73+
nav2_costmap_2d::Costmap2D & master_grid, int min_i,
74+
int min_j, int max_i, int max_j);
75+
virtual void reset();
76+
virtual void deactivate();
77+
virtual void activate();
78+
79+
void bufferIncomingRangeMsg(const sensor_msgs::msg::Range::SharedPtr range_message);
80+
81+
private:
82+
void updateCostmap();
83+
void updateCostmap(sensor_msgs::msg::Range & range_message, bool clear_sensor_cone);
84+
85+
void processRangeMsg(sensor_msgs::msg::Range & range_message);
86+
void processFixedRangeMsg(sensor_msgs::msg::Range & range_message);
87+
void processVariableRangeMsg(sensor_msgs::msg::Range & range_message);
88+
89+
void resetRange();
90+
91+
inline double gamma(double theta);
92+
inline double delta(double phi);
93+
inline double sensor_model(double r, double phi, double theta);
94+
95+
inline void get_deltas(double angle, double * dx, double * dy);
96+
inline void update_cell(
97+
double ox, double oy, double ot,
98+
double r, double nx, double ny, bool clear);
99+
100+
inline double to_prob(unsigned char c)
101+
{
102+
return static_cast<double>(c) / nav2_costmap_2d::LETHAL_OBSTACLE;
103+
}
104+
inline unsigned char to_cost(double p)
105+
{
106+
return static_cast<unsigned char>(p * nav2_costmap_2d::LETHAL_OBSTACLE);
107+
}
108+
109+
std::function<void(sensor_msgs::msg::Range & range_message)> processRangeMessageFunc_;
110+
std::mutex range_message_mutex_;
111+
std::list<sensor_msgs::msg::Range> range_msgs_buffer_;
112+
113+
double max_angle_, phi_v_;
114+
double inflate_cone_;
115+
std::string global_frame_;
116+
117+
double clear_threshold_, mark_threshold_;
118+
bool clear_on_max_reading_;
119+
120+
tf2::Duration transform_tolerance_;
121+
double no_readings_timeout_;
122+
rclcpp::Time last_reading_time_;
123+
unsigned int buffered_readings_;
124+
std::vector<rclcpp::Subscription<sensor_msgs::msg::Range>::SharedPtr> range_subs_;
125+
double min_x_, min_y_, max_x_, max_y_;
126+
127+
float area(int x1, int y1, int x2, int y2, int x3, int y3)
128+
{
129+
return fabs((x1 * (y2 - y3) + x2 * (y3 - y1) + x3 * (y1 - y2)) / 2.0);
130+
}
131+
132+
int orient2d(int Ax, int Ay, int Bx, int By, int Cx, int Cy)
133+
{
134+
return (Bx - Ax) * (Cy - Ay) - (By - Ay) * (Cx - Ax);
135+
}
136+
};
137+
} // namespace nav2_costmap_2d
138+
#endif // NAV2_COSTMAP_2D__RANGE_SENSOR_LAYER_HPP_

nav2_costmap_2d/plugins/inflation_layer.cpp

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,8 @@
4040
#include <limits>
4141
#include <map>
4242
#include <vector>
43+
#include <algorithm>
44+
#include <utility>
4345

4446
#include "nav2_costmap_2d/costmap_math.hpp"
4547
#include "nav2_costmap_2d/footprint.hpp"
@@ -163,7 +165,7 @@ InflationLayer::updateCosts(
163165
}
164166

165167
// make sure the inflation list is empty at the beginning of the cycle (should always be true)
166-
for (auto & dist:inflation_cells_) {
168+
for (auto & dist : inflation_cells_) {
167169
RCLCPP_FATAL_EXPRESSION(
168170
rclcpp::get_logger("nav2_costmap_2d"),
169171
!dist.empty(), "The inflation list must be empty at the beginning of inflation");
@@ -215,9 +217,10 @@ InflationLayer::updateCosts(
215217
// Process cells by increasing distance; new cells are appended to the
216218
// corresponding distance bin, so they
217219
// can overtake previously inserted but farther away cells
218-
for (const auto & dist_bin: inflation_cells_) {
220+
for (const auto & dist_bin : inflation_cells_) {
219221
for (std::size_t i = 0; i < dist_bin.size(); ++i) {
220-
// Do not use iterator or for-range based loops to iterate though dist_bin, since it's size might
222+
// Do not use iterator or for-range based loops to
223+
// iterate though dist_bin, since it's size might
221224
// change when a new cell is enqueued, invalidating all iterators
222225
unsigned int index = dist_bin[i].index_;
223226

@@ -260,7 +263,7 @@ InflationLayer::updateCosts(
260263
}
261264
}
262265

263-
for (auto & dist:inflation_cells_) {
266+
for (auto & dist : inflation_cells_) {
264267
dist.clear();
265268
dist.reserve(200);
266269
}

0 commit comments

Comments
 (0)