38 #ifndef NAV2_COSTMAP_2D__VOXEL_LAYER_HPP_
39 #define NAV2_COSTMAP_2D__VOXEL_LAYER_HPP_
43 #include <rclcpp/rclcpp.hpp>
44 #include <nav2_costmap_2d/layer.hpp>
45 #include <nav2_costmap_2d/layered_costmap.hpp>
46 #include <nav2_costmap_2d/observation_buffer.hpp>
47 #include <nav_msgs/msg/occupancy_grid.hpp>
48 #include <nav2_msgs/msg/voxel_grid.hpp>
49 #include <sensor_msgs/msg/laser_scan.hpp>
50 #include <laser_geometry/laser_geometry.hpp>
51 #include <sensor_msgs/msg/point_cloud.hpp>
52 #include <sensor_msgs/msg/point_cloud2.hpp>
53 #include <nav2_costmap_2d/obstacle_layer.hpp>
54 #include <nav2_voxel_grid/voxel_grid.hpp>
70 : voxel_grid_(0, 0, 0)
96 double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
104 void updateOrigin(
double new_origin_x,
double new_origin_y);
122 virtual void reset();
140 double * min_x,
double * min_y,
145 rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::VoxelGrid>::SharedPtr voxel_pub_;
147 double z_resolution_, origin_z_;
148 int unknown_threshold_, mark_threshold_, size_z_;
149 rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::PointCloud2>::SharedPtr
150 clearing_endpoints_pub_;
156 double wx,
double wy,
double wz,
double & mx,
double & my,
159 if (wx < origin_x_ || wy < origin_y_ || wz < origin_z_) {
162 mx = ((wx - origin_x_) / resolution_);
163 my = ((wy - origin_y_) / resolution_);
164 mz = ((wz - origin_z_) / z_resolution_);
165 if (mx < size_x_ && my < size_y_ && mz < size_z_) {
176 double wx,
double wy,
double wz,
unsigned int & mx,
unsigned int & my,
179 if (wx < origin_x_ || wy < origin_y_ || wz < origin_z_) {
183 mx =
static_cast<unsigned int>((wx - origin_x_) / resolution_);
184 my =
static_cast<unsigned int>((wy - origin_y_) / resolution_);
185 mz =
static_cast<unsigned int>((wz - origin_z_) / z_resolution_);
187 if (mx < size_x_ && my < size_y_ && mz < (
unsigned int)size_z_) {
198 unsigned int mx,
unsigned int my,
unsigned int mz,
double & wx,
203 wx = origin_x_ + (mx + 0.5) * resolution_;
204 wy = origin_y_ + (my + 0.5) * resolution_;
205 wz = origin_z_ + (mz + 0.5) * z_resolution_;
211 inline double dist(
double x0,
double y0,
double z0,
double x1,
double y1,
double z1)
213 return sqrt((x1 - x0) * (x1 - x0) + (y1 - y0) * (y1 - y0) + (z1 - z0) * (z1 - z0));
221 return (size_z_ - 1 + 0.5) * z_resolution_;
228 rcl_interfaces::msg::SetParametersResult
232 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)
Convert 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)
Convert world coordinates into map coordinates.
bool worldToMap3D(double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz)
Convert 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.