38 #ifndef NAV2_COSTMAP_2D__VOXEL_LAYER_HPP_
39 #define NAV2_COSTMAP_2D__VOXEL_LAYER_HPP_
42 #include "message_filters/subscriber.h"
44 #include <rclcpp/rclcpp.hpp>
45 #include <nav2_costmap_2d/layer.hpp>
46 #include <nav2_costmap_2d/layered_costmap.hpp>
47 #include <nav2_costmap_2d/observation_buffer.hpp>
48 #include <nav_msgs/msg/occupancy_grid.hpp>
49 #include <nav2_msgs/msg/voxel_grid.hpp>
50 #include <sensor_msgs/msg/laser_scan.hpp>
51 #include <laser_geometry/laser_geometry.hpp>
52 #include <sensor_msgs/msg/point_cloud.hpp>
53 #include <sensor_msgs/msg/point_cloud2.hpp>
54 #include <nav2_costmap_2d/obstacle_layer.hpp>
55 #include <nav2_voxel_grid/voxel_grid.hpp>
71 : voxel_grid_(0, 0, 0)
97 double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
105 void updateOrigin(
double new_origin_x,
double new_origin_y);
123 virtual void reset();
141 double * min_x,
double * min_y,
146 rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::VoxelGrid>::SharedPtr voxel_pub_;
148 double z_resolution_, origin_z_;
149 int unknown_threshold_, mark_threshold_, size_z_;
150 rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::PointCloud2>::SharedPtr
151 clearing_endpoints_pub_;
157 double wx,
double wy,
double wz,
double & mx,
double & my,
160 if (wx < origin_x_ || wy < origin_y_ || wz < origin_z_) {
163 mx = ((wx - origin_x_) / resolution_);
164 my = ((wy - origin_y_) / resolution_);
165 mz = ((wz - origin_z_) / z_resolution_);
166 if (mx < size_x_ && my < size_y_ && mz < size_z_) {
177 double wx,
double wy,
double wz,
unsigned int & mx,
unsigned int & my,
180 if (wx < origin_x_ || wy < origin_y_ || wz < origin_z_) {
184 mx =
static_cast<unsigned int>((wx - origin_x_) / resolution_);
185 my =
static_cast<unsigned int>((wy - origin_y_) / resolution_);
186 mz =
static_cast<unsigned int>((wz - origin_z_) / z_resolution_);
188 if (mx < size_x_ && my < size_y_ && mz < (
unsigned int)size_z_) {
199 unsigned int mx,
unsigned int my,
unsigned int mz,
double & wx,
204 wx = origin_x_ + (mx + 0.5) * resolution_;
205 wy = origin_y_ + (my + 0.5) * resolution_;
206 wz = origin_z_ + (mz + 0.5) * z_resolution_;
212 inline double dist(
double x0,
double y0,
double z0,
double x1,
double y1,
double z1)
214 return sqrt((x1 - x0) * (x1 - x0) + (y1 - y0) * (y1 - y0) + (z1 - z0) * (z1 - z0));
222 return (size_z_ - 1 + 0.5) * z_resolution_;
229 rcl_interfaces::msg::SetParametersResult
233 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
Stores an observation in terms of a point cloud and the origin of the source.
Takes in laser and pointcloud data to populate into 2D costmap.
Takes laser and pointcloud data to populate a 3D voxel representation of the environment.
void mapToWorld3D(unsigned int mx, unsigned int my, unsigned int mz, double &wx, double &wy, double &wz)
Covert map coordinates into world coordinates.
virtual void onInitialize()
Initialization process of layer on startup.
virtual ~VoxelLayer()
Voxel Layer destructor.
double getSizeInMetersZ() const
Get the height of the voxel sizes in meters.
virtual bool isClearable()
If clearing operations should be processed on this layer or not.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
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.
void updateOrigin(double new_origin_x, double new_origin_y)
Update the layer's origin to a new pose, often when in a rolling costmap.
bool worldToMap3DFloat(double wx, double wy, double wz, double &mx, double &my, double &mz)
Covert world coordinates into map coordinates.
bool worldToMap3D(double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz)
Covert world coordinates into map coordinates.
virtual void resetMaps()
Reset internal maps.
virtual void matchSize()
Match the size of the master costmap.
virtual void reset()
Reset this costmap.
double dist(double x0, double y0, double z0, double x1, double y1, double z1)
Find L2 norm distance in 3D.
VoxelLayer()
Voxel Layer constructor.
virtual void raytraceFreespace(const nav2_costmap_2d::Observation &clearing_observation, double *min_x, double *min_y, double *max_x, double *max_y)
Use raycasting between 2 points to clear freespace.
bool isDiscretized()
If layer is discretely populated.