38 #ifndef RTABMAP_ROS_VOXEL_LAYER_H_ 39 #define RTABMAP_ROS_VOXEL_LAYER_H_ 44 #include <costmap_2d/VoxelGrid.h> 45 #include <nav_msgs/OccupancyGrid.h> 46 #include <sensor_msgs/LaserScan.h> 48 #include <sensor_msgs/PointCloud.h> 49 #include <sensor_msgs/PointCloud2.h> 52 #include <dynamic_reconfigure/server.h> 53 #include <costmap_2d/VoxelPluginConfig.h> 72 virtual void updateBounds(
double robot_x,
double robot_y,
double robot_yaw,
double* min_x,
double* min_y,
73 double* max_x,
double* max_y);
75 void updateOrigin(
double new_origin_x,
double new_origin_y);
91 void clearNonLethal(
double wx,
double wy,
double w_size_x,
double w_size_y,
bool clear_no_info);
93 double* max_x,
double* max_y);
95 dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig> *
voxel_dsrv_;
106 inline bool worldToMap3DFloat(
double wx,
double wy,
double wz,
double& mx,
double& my,
double& mz)
119 inline bool worldToMap3D(
double wx,
double wy,
double wz,
unsigned int& mx,
unsigned int& my,
unsigned int& mz)
134 inline void mapToWorld3D(
unsigned int mx,
unsigned int my,
unsigned int mz,
double& wx,
double& wy,
double& wz)
142 inline double dist(
double x0,
double y0,
double z0,
double x1,
double y1,
double z1)
144 return sqrt((x1 - x0) * (x1 - x0) + (y1 - y0) * (y1 - y0) + (z1 - z0) * (z1 - z0));
161 template<
typename data_type>
162 void copyMapRegion3D(data_type* source_map,
unsigned int sm_lower_left_x,
unsigned int sm_lower_left_y,
163 unsigned int sm_size_x, data_type* dest_map,
unsigned int dm_lower_left_x,
164 unsigned int dm_lower_left_y,
unsigned int dm_size_x,
unsigned int region_size_x,
165 unsigned int region_size_y,
int z_shift)
169 data_type* sm_index = source_map + (sm_lower_left_y * sm_size_x + sm_lower_left_x);
170 data_type* dm_index = dest_map + (dm_lower_left_y * dm_size_x + dm_lower_left_x);
172 uint32_t marked_bits_mask = (data_type) 0xFFFF0000;
173 uint32_t unknown_bits_mask = (data_type) 0x0000FFFF;
176 for (
unsigned int i = 0; i < region_size_y; ++i)
178 memcpy(dm_index, sm_index, region_size_x *
sizeof(data_type));
179 for (
unsigned int j = 0; j < region_size_x; j++) {
184 ((dm_index[j] & marked_bits_mask) >> z_shift & marked_bits_mask) |
186 (((dm_index[j] & unknown_bits_mask) >> z_shift | (~((data_type) 0) <<
sizeof(data_type) * 4 - z_shift)) & unknown_bits_mask);
188 }
else if (z_shift < 0) {
191 (dm_index[j] & marked_bits_mask) << z_shift * -1 |
193 ((dm_index[j] << z_shift * -1 & unknown_bits_mask) | ~(~((data_type) 0) << z_shift * -1));
197 dm_index += dm_size_x;
198 sm_index += sm_size_x;
205 #endif // RTABMAP_ROS_VOXEL_LAYER_H_
bool worldToMap3DFloat(double wx, double wy, double wz, double &mx, double &my, double &mz)
dynamic_reconfigure::Server< costmap_2d::VoxelPluginConfig > * voxel_dsrv_
void copyMapRegion3D(data_type *source_map, unsigned int sm_lower_left_x, unsigned int sm_lower_left_y, unsigned int sm_size_x, data_type *dest_map, unsigned int dm_lower_left_x, unsigned int dm_lower_left_y, unsigned int dm_size_x, unsigned int region_size_x, unsigned int region_size_y, int z_shift)
Copy a region of a source map into a destination map.
ros::Publisher voxel_pub_
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
bool worldToMap3D(double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz)
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
void clearNonLethal(double wx, double wy, double w_size_x, double w_size_y, bool clear_no_info)
std::string robot_base_frame_
voxel_grid::VoxelGrid voxel_grid_
virtual void raytraceFreespace(const costmap_2d::Observation &clearing_observation, double *min_x, double *min_y, double *max_x, double *max_y)
virtual void setupDynamicReconfigure(ros::NodeHandle &nh)
double dist(double x0, double y0, double z0, double x1, double y1, double z1)
unsigned int mark_threshold_
virtual void onInitialize()
unsigned int unknown_threshold_
void reconfigureCB(costmap_2d::VoxelPluginConfig &config, uint32_t level)
void mapToWorld3D(unsigned int mx, unsigned int my, unsigned int mz, double &wx, double &wy, double &wz)
sensor_msgs::PointCloud clearing_endpoints_
ros::Publisher clearing_endpoints_pub_
void updateOrigin(double new_origin_x, double new_origin_y)