|
| 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_ |
0 commit comments