Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add in range sensor costmap layer #1888

Merged
Merged
Show file tree
Hide file tree
Changes from 23 commits
Commits
Show all changes
26 commits
Select commit Hold shift + click to select a range
0496e0c
Merge pull request #1 from ros-planning/master
Michael-Equi Jul 25, 2020
c614bef
Merge pull request #2 from BytesRobotics/master
Michael-Equi Jul 25, 2020
a44c09a
range costmap building
Michael-Equi Jul 26, 2020
51bbbe7
range sensor layer working
Michael-Equi Jul 26, 2020
509732f
nav2 costmap pass linter and uncrustify tests
Michael-Equi Jul 26, 2020
a79b521
Added back semicolon to range class
Michael-Equi Jul 26, 2020
8424871
Added docs
Michael-Equi Jul 26, 2020
86cd844
Added angles dependency
Michael-Equi Jul 26, 2020
b46c66a
Added BSD license
Michael-Equi Jul 29, 2020
25fde5c
Added BSD license
Michael-Equi Jul 29, 2020
9bc8ff4
Made functions inline
Michael-Equi Jul 29, 2020
6bb1536
revmoed get_clock
Michael-Equi Jul 29, 2020
2275f05
added input_sensor_type to docs
Michael-Equi Jul 29, 2020
a2c27fe
Made defualt topic name empty to cause error
Michael-Equi Jul 29, 2020
72b1e33
using chorno literal to denote time units
Michael-Equi Jul 29, 2020
cefd1fe
Added small initial test
Michael-Equi Jul 29, 2020
57df641
Fixed linter error, line breaks, enum, logger level, and transform_to…
Michael-Equi Jul 30, 2020
99bd8e5
fixed segmentation fault in test and added transfrom tolerances to tf…
Michael-Equi Jul 30, 2020
3061c28
Got test to pass
Michael-Equi Jul 31, 2020
46f992a
Added more tests
Michael-Equi Jul 31, 2020
4b24898
removed incorrect parameter declaration
Michael-Equi Aug 1, 2020
e841cdf
Improved marking while moving tests and added clearing tests
Michael-Equi Aug 1, 2020
91d2086
removed general clearing test
Michael-Equi Aug 6, 2020
d8a220c
Merge branch 'master' of https://github.com/ros-planning/navigation2 …
Michael-Equi Aug 6, 2020
a34c557
Merge branch 'ros-planning-master' into range-sensor-costmap
Michael-Equi Aug 6, 2020
18fa0cc
changed testing helper import in test
Michael-Equi Aug 6, 2020
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
22 changes: 20 additions & 2 deletions doc/parameters/param_list.md
Original file line number Diff line number Diff line change
Expand Up @@ -51,11 +51,13 @@ For example:
```yaml
local_costmap:
ros__parameters:
plugins: ["obstacle_layer", "voxel_layer", "inflation_layer"]
plugins: ["obstacle_layer", "voxel_layer", "sonar_layer", "inflation_layer"]
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
voxel_layer:
plugin: "nav2_costmap_2d::VoxelLayer"
sonar_layer:
plugin: "nav2_costmap_2d::RangeSensorLayer"
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
```
Expand Down Expand Up @@ -114,7 +116,23 @@ When `plugins` parameter is not overridden, the following default plugins are lo
| `<data source>`.marking | true | Whether source should mark in costmap |
| `<data source>`.clearing | false | Whether source should raytrace clear in costmap |
| `<data source>`.obstacle_range | 2.5 | Maximum range to mark obstacles in costmap |
| `<data source>`.raytrace_range | 3.0 | Maximum range to raytrace clear obstacles from costmap |
| `<data source>`.raytrace_range | 3.0 | Maximum range to raytrace clear obstacles from costmap |

## range_sensor_layer plugin

* `<range layer>`: Name corresponding to the `nav2_costmap_2d::RangeSensorLayer` plugin. This name gets defined in `plugin_names`.

| Parameter | Default | Description |
| ----------| --------| ------------|
| `<range layer>`.enabled | true | Whether it is enabled |
| `<range layer>`.topics | [""] | Range topics to subscribe to |
| `<range layer>`.phi | 1.2 | Phi value |
| `<range layer>`.inflate_cone | 1.0 | Inflate the triangular area covered by the sensor (percentage) |
| `<range layer>`.no_readings_timeout | 0.0 | No Readings Timeout |
| `<range layer>`.clear_threshold | 0.2 | Probability below which cells are marked as free |
| `<range layer>`.mark_threshold | 0.8 | Probability above which cells are marked as occupied |
| `<range layer>`.clear_on_max_reading | false | Clear on max reading |
| `<range layer>`.input_sensor_type | ALL | Input sensor type either ALL (automatic selection), VARIABLE (min range != max range), or FIXED (min range == max range) |

## voxel_layer plugin

Expand Down
3 changes: 3 additions & 0 deletions nav2_costmap_2d/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@ find_package(tf2 REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(tf2_sensor_msgs REQUIRED)
find_package(visualization_msgs REQUIRED)
find_package(angles REQUIRED)

remove_definitions(-DDISABLE_LIBUSB-1.0)
find_package(Eigen3 REQUIRED)
Expand Down Expand Up @@ -72,6 +73,7 @@ set(dependencies
tf2_ros
tf2_sensor_msgs
visualization_msgs
angles
)

ament_target_dependencies(nav2_costmap_2d_core
Expand All @@ -84,6 +86,7 @@ add_library(layers SHARED
plugins/obstacle_layer.cpp
src/observation_buffer.cpp
plugins/voxel_layer.cpp
plugins/range_sensor_layer.cpp
)
ament_target_dependencies(layers
${dependencies}
Expand Down
3 changes: 3 additions & 0 deletions nav2_costmap_2d/costmap_plugins.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,9 @@
<class type="nav2_costmap_2d::VoxelLayer" base_class_type="nav2_costmap_2d::Layer">
<description>Similar to obstacle costmap, but uses 3D voxel grid to store data.</description>
</class>
<class type="nav2_costmap_2d::RangeSensorLayer" base_class_type="nav2_costmap_2d::Layer">
<description>A range-sensor (sonar, IR) based obstacle layer for costmap_2d</description>
</class>
</library>
</class_libraries>

138 changes: 138 additions & 0 deletions nav2_costmap_2d/include/nav2_costmap_2d/range_sensor_layer.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,138 @@
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2018 David V. Lu!!
* Copyright (c) 2020, Bytes Robotics
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef NAV2_COSTMAP_2D__RANGE_SENSOR_LAYER_HPP_
#define NAV2_COSTMAP_2D__RANGE_SENSOR_LAYER_HPP_

#include <list>
#include <string>
#include <vector>
#include <mutex>

#include "map_msgs/msg/occupancy_grid_update.hpp"
#include "message_filters/subscriber.h"
#include "nav2_costmap_2d/costmap_layer.hpp"
#include "nav2_costmap_2d/layered_costmap.hpp"
#include "nav_msgs/msg/occupancy_grid.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"
#include "sensor_msgs/msg/range.hpp"

namespace nav2_costmap_2d
{

class RangeSensorLayer : public CostmapLayer
{
public:
enum class InputSensorType
{
VARIABLE,
FIXED,
ALL
};

RangeSensorLayer();

virtual void onInitialize();
virtual void updateBounds(
double robot_x, double robot_y, double robot_yaw,
double * min_x, double * min_y, double * max_x, double * max_y);
virtual void updateCosts(
nav2_costmap_2d::Costmap2D & master_grid, int min_i,
int min_j, int max_i, int max_j);
virtual void reset();
virtual void deactivate();
virtual void activate();

void bufferIncomingRangeMsg(const sensor_msgs::msg::Range::SharedPtr range_message);

private:
void updateCostmap();
void updateCostmap(sensor_msgs::msg::Range & range_message, bool clear_sensor_cone);

void processRangeMsg(sensor_msgs::msg::Range & range_message);
void processFixedRangeMsg(sensor_msgs::msg::Range & range_message);
void processVariableRangeMsg(sensor_msgs::msg::Range & range_message);

void resetRange();

inline double gamma(double theta);
inline double delta(double phi);
inline double sensor_model(double r, double phi, double theta);

inline void get_deltas(double angle, double * dx, double * dy);
inline void update_cell(
double ox, double oy, double ot,
double r, double nx, double ny, bool clear);

inline double to_prob(unsigned char c)
{
return static_cast<double>(c) / nav2_costmap_2d::LETHAL_OBSTACLE;
}
inline unsigned char to_cost(double p)
{
return static_cast<unsigned char>(p * nav2_costmap_2d::LETHAL_OBSTACLE);
}

std::function<void(sensor_msgs::msg::Range & range_message)> processRangeMessageFunc_;
std::mutex range_message_mutex_;
std::list<sensor_msgs::msg::Range> range_msgs_buffer_;

double max_angle_, phi_v_;
double inflate_cone_;
std::string global_frame_;

double clear_threshold_, mark_threshold_;
bool clear_on_max_reading_;

tf2::Duration transform_tolerance_;
double no_readings_timeout_;
rclcpp::Time last_reading_time_;
unsigned int buffered_readings_;
std::vector<rclcpp::Subscription<sensor_msgs::msg::Range>::SharedPtr> range_subs_;
double min_x_, min_y_, max_x_, max_y_;

float area(int x1, int y1, int x2, int y2, int x3, int y3)
{
return fabs((x1 * (y2 - y3) + x2 * (y3 - y1) + x3 * (y1 - y2)) / 2.0);
}

int orient2d(int Ax, int Ay, int Bx, int By, int Cx, int Cy)
{
return (Bx - Ax) * (Cy - Ay) - (By - Ay) * (Cx - Ax);
}
};
} // namespace nav2_costmap_2d
#endif // NAV2_COSTMAP_2D__RANGE_SENSOR_LAYER_HPP_
11 changes: 11 additions & 0 deletions nav2_costmap_2d/include/nav2_costmap_2d/testing_helper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include "nav2_costmap_2d/cost_values.hpp"
#include "nav2_costmap_2d/costmap_2d.hpp"
#include "nav2_costmap_2d/static_layer.hpp"
#include "nav2_costmap_2d/range_sensor_layer.hpp"
#include "nav2_costmap_2d/obstacle_layer.hpp"
#include "nav2_costmap_2d/inflation_layer.hpp"
#include "nav2_util/lifecycle_node.hpp"
Expand Down Expand Up @@ -97,6 +98,16 @@ void addObstacleLayer(
layers.addPlugin(std::shared_ptr<nav2_costmap_2d::Layer>(olayer));
}

void addRangeLayer(
nav2_costmap_2d::LayeredCostmap & layers,
tf2_ros::Buffer & tf, nav2_util::LifecycleNode::SharedPtr node,
std::shared_ptr<nav2_costmap_2d::RangeSensorLayer> & rlayer)
{
rlayer = std::make_shared<nav2_costmap_2d::RangeSensorLayer>();
rlayer->initialize(&layers, "range", &tf, node, nullptr, nullptr /*TODO*/);
layers.addPlugin(std::shared_ptr<nav2_costmap_2d::Layer>(rlayer));
}

void addObservation(
std::shared_ptr<nav2_costmap_2d::ObstacleLayer> olayer, double x, double y, double z = 0.0,
double ox = 0.0, double oy = 0.0, double oz = MAX_Z, bool marking = true, bool clearing = true)
Expand Down
11 changes: 7 additions & 4 deletions nav2_costmap_2d/plugins/inflation_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,8 @@
#include <limits>
#include <map>
#include <vector>
#include <algorithm>
#include <utility>

#include "nav2_costmap_2d/costmap_math.hpp"
#include "nav2_costmap_2d/footprint.hpp"
Expand Down Expand Up @@ -163,7 +165,7 @@ InflationLayer::updateCosts(
}

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

Expand Down Expand Up @@ -260,7 +263,7 @@ InflationLayer::updateCosts(
}
}

for (auto & dist:inflation_cells_) {
for (auto & dist : inflation_cells_) {
dist.clear();
dist.reserve(200);
}
Expand Down
Loading