36 #ifndef NAV2_COSTMAP_2D__RANGE_SENSOR_LAYER_HPP_
37 #define NAV2_COSTMAP_2D__RANGE_SENSOR_LAYER_HPP_
44 #include "map_msgs/msg/occupancy_grid_update.hpp"
45 #include "nav2_costmap_2d/costmap_layer.hpp"
46 #include "nav2_costmap_2d/layered_costmap.hpp"
47 #include "nav_msgs/msg/occupancy_grid.hpp"
48 #include "rclcpp/rclcpp.hpp"
49 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
50 #include "sensor_msgs/msg/range.hpp"
62 enum class InputSensorType
90 double robot_x,
double robot_y,
double robot_yaw,
91 double * min_x,
double * min_y,
double * max_x,
double * max_y);
103 int min_j,
int max_i,
int max_j);
108 virtual void reset();
138 void updateCostmap(sensor_msgs::msg::Range & range_message,
bool clear_sensor_cone);
162 inline double gamma(
double theta);
166 inline double delta(
double phi);
170 inline double sensor_model(
double r,
double phi,
double theta);
175 inline void get_deltas(
double angle,
double * dx,
double * dy);
181 double ox,
double oy,
double ot,
182 double r,
double nx,
double ny,
bool clear);
189 return static_cast<double>(c) / nav2_costmap_2d::LETHAL_OBSTACLE;
197 return static_cast<unsigned char>(p * nav2_costmap_2d::LETHAL_OBSTACLE);
200 std::function<void(sensor_msgs::msg::Range & range_message)> processRangeMessageFunc_;
201 std::mutex range_message_mutex_;
202 std::list<sensor_msgs::msg::Range> range_msgs_buffer_;
204 double max_angle_, phi_v_;
205 double inflate_cone_;
206 std::string global_frame_;
208 double clear_threshold_, mark_threshold_;
209 bool clear_on_max_reading_;
212 tf2::Duration transform_tolerance_;
213 double no_readings_timeout_;
214 rclcpp::Time last_reading_time_;
215 unsigned int buffered_readings_;
216 std::vector<nav2::Subscription<sensor_msgs::msg::Range>::SharedPtr> range_subs_;
217 double min_x_, min_y_, max_x_, max_y_;
222 float area(
int x1,
int y1,
int x2,
int y2,
int x3,
int y3)
224 return fabs((x1 * (y2 - y3) + x2 * (y3 - y1) + x3 * (y1 - y2)) / 2.0);
230 int orient2d(
int Ax,
int Ay,
int Bx,
int By,
int Cx,
int Cy)
232 return (Bx - Ax) * (Cy - Ay) - (By - Ay) * (Cx - Ax);
A 2D costmap provides a mapping between points in the world and their associated "costs".
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.
RangeSensorLayer()
A constructor.
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.