41 #include <boost/thread.hpp> 58 void VoxelLayer::onInitialize()
60 ObstacleLayer::onInitialize();
63 std::string costmap_name = name_.substr(0, name_.find(
"/"));
66 private_nh.
param(
"publish_voxel_map", publish_voxel_,
false);
68 pnh.
param(
"robot_base_frame", robot_base_frame_, std::string(
"base_link"));
71 voxel_pub_ = private_nh.
advertise < costmap_2d::VoxelGrid > (
"voxel_grid", 1);
73 clearing_endpoints_pub_ = private_nh.
advertise<sensor_msgs::PointCloud>(
"clearing_endpoints", 1);
78 voxel_dsrv_ =
new dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig>(nh);
79 dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig>::CallbackType cb = boost::bind(
80 &VoxelLayer::reconfigureCB,
this, _1, _2);
81 voxel_dsrv_->setCallback(cb);
84 VoxelLayer::~VoxelLayer()
90 void VoxelLayer::reconfigureCB(costmap_2d::VoxelPluginConfig &config,
uint32_t level)
92 enabled_ = config.enabled;
93 footprint_clearing_enabled_ = config.footprint_clearing_enabled;
94 max_obstacle_height_ = config.max_obstacle_height;
95 size_z_ = config.z_voxels;
96 origin_z_ = config.origin_z;
97 z_resolution_ = config.z_resolution;
98 unknown_threshold_ = config.unknown_threshold + (
VOXEL_BITS - size_z_);
99 mark_threshold_ = config.mark_threshold;
100 combination_method_ = config.combination_method;
104 void VoxelLayer::matchSize()
106 ObstacleLayer::matchSize();
107 voxel_grid_.resize(size_x_, size_y_, size_z_);
108 ROS_ASSERT(voxel_grid_.sizeX() == size_x_ && voxel_grid_.sizeY() == size_y_);
111 void VoxelLayer::reset()
119 void VoxelLayer::resetMaps()
121 Costmap2D::resetMaps();
125 void VoxelLayer::updateBounds(
double robot_x,
double robot_y,
double robot_yaw,
double* min_x,
126 double* min_y,
double* max_x,
double* max_y)
129 updateOrigin(robot_x - getSizeInMetersX() / 2, robot_y - getSizeInMetersY() / 2);
132 useExtraBounds(min_x, min_y, max_x, max_y);
135 std::vector<Observation> observations, clearing_observations;
138 current = getMarkingObservations(observations) && current;
141 current = getClearingObservations(clearing_observations) && current;
147 for (
unsigned int i = 0; i < clearing_observations.size(); ++i)
149 raytraceFreespace(clearing_observations[i], min_x, min_y, max_x, max_y);
153 for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it)
155 const Observation& obs = *it;
157 #ifdef COSTMAP_2D_POINTCLOUD2 158 const sensor_msgs::PointCloud2& cloud = *(obs.
cloud_);
165 for (
unsigned int i = 0; iter_x != iter_x.
end(); ++iter_x, ++iter_y, ++iter_z) {
166 const double x = *iter_x;
167 const double y = *iter_y;
168 const double z = *iter_z;
170 pcl::PointCloud<pcl::PointXYZ>::const_iterator point_it = obs.
cloud_->begin();
171 for (;point_it < obs.
cloud_->end(); ++point_it) {
172 const double x = point_it->x;
173 const double y = point_it->y;
174 const double z = point_it->z;
177 unsigned int mx, my, mz;
179 if (!worldToMap3D(x, y, z, mx, my, mz))
182 if (voxel_grid_.markVoxelInMap(mx, my, mz, mark_threshold_))
184 unsigned int index = getIndex(mx, my);
186 costmap_[index] = LETHAL_OBSTACLE;
187 touch(x, y, min_x, min_y, max_x, max_y);
194 costmap_2d::VoxelGrid grid_msg;
195 unsigned int size = voxel_grid_.sizeX() * voxel_grid_.sizeY();
196 grid_msg.size_x = voxel_grid_.sizeX();
197 grid_msg.size_y = voxel_grid_.sizeY();
198 grid_msg.size_z = voxel_grid_.sizeZ();
199 grid_msg.data.resize(size);
200 memcpy(&grid_msg.data[0], voxel_grid_.getData(), size *
sizeof(
unsigned int));
202 grid_msg.origin.x = origin_x_;
203 grid_msg.origin.y = origin_y_;
204 grid_msg.origin.z = origin_z_;
206 grid_msg.resolutions.x = resolution_;
207 grid_msg.resolutions.y = resolution_;
208 grid_msg.resolutions.z = z_resolution_;
209 grid_msg.header.frame_id = global_frame_;
211 voxel_pub_.publish(grid_msg);
214 updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
217 void VoxelLayer::clearNonLethal(
double wx,
double wy,
double w_size_x,
double w_size_y,
bool clear_no_info)
221 if (!worldToMap(wx, wy, mx, my))
225 double start_x = wx - w_size_x / 2;
226 double start_y = wy - w_size_y / 2;
227 double end_x = start_x + w_size_x;
228 double end_y = start_y + w_size_y;
231 start_x =
std::max(origin_x_, start_x);
232 start_y =
std::max(origin_y_, start_y);
234 end_x =
std::min(origin_x_ + getSizeInMetersX(), end_x);
235 end_y =
std::min(origin_y_ + getSizeInMetersY(), end_y);
238 unsigned int map_sx, map_sy, map_ex, map_ey;
241 if (!worldToMap(start_x, start_y, map_sx, map_sy) || !worldToMap(end_x, end_y, map_ex, map_ey))
245 unsigned int index = getIndex(map_sx, map_sy);
246 unsigned char* current = &costmap_[index];
247 for (
unsigned int j = map_sy; j <= map_ey; ++j)
249 for (
unsigned int i = map_sx; i <= map_ex; ++i)
252 if (*current != LETHAL_OBSTACLE)
254 if (clear_no_info || *current != NO_INFORMATION)
256 *current = FREE_SPACE;
257 voxel_grid_.clearVoxelColumn(index);
263 current += size_x_ - (map_ex - map_sx) - 1;
264 index += size_x_ - (map_ex - map_sx) - 1;
268 void VoxelLayer::raytraceFreespace(
const Observation& clearing_observation,
double* min_x,
double* min_y,
269 double* max_x,
double* max_y)
271 size_t clearing_observation_cloud_size = clearing_observation.
cloud_->height * clearing_observation.
cloud_->width;
272 if (clearing_observation_cloud_size == 0)
275 double sensor_x, sensor_y, sensor_z;
276 double ox = clearing_observation.
origin_.x;
277 double oy = clearing_observation.
origin_.y;
278 double oz = clearing_observation.
origin_.z;
280 if (!worldToMap3DFloat(ox, oy, oz, sensor_x, sensor_y, sensor_z))
284 "The origin for the sensor at (%.2f, %.2f, %.2f) is out of map bounds. So, the costmap cannot raytrace for it.",
289 bool publish_clearing_points = (clearing_endpoints_pub_.getNumSubscribers() > 0);
290 if (publish_clearing_points)
292 clearing_endpoints_.points.clear();
293 clearing_endpoints_.points.reserve(clearing_observation_cloud_size);
297 double map_end_x = origin_x_ + getSizeInMetersX();
298 double map_end_y = origin_y_ + getSizeInMetersY();
299 double map_end_z = origin_z_ + size_z_ * z_resolution_;
301 #ifdef COSTMAP_2D_POINTCLOUD2 306 for (;iter_x != iter_x.
end(); ++iter_x, ++iter_y, ++iter_z)
308 double wpx = *iter_x;
309 double wpy = *iter_y;
310 double wpz = *iter_z;
312 pcl::PointCloud<pcl::PointXYZ>::const_iterator point_it = clearing_observation.
cloud_->begin();
313 for (;point_it < clearing_observation.
cloud_->end(); ++point_it) {
314 double wpx = point_it->x;
315 double wpy = point_it->y;
316 double wpz = point_it->z;
319 double distance = dist(ox, oy, oz, wpx, wpy, wpz);
320 double scaling_fact = 1.0, scaling_fact_z = 1.0;
321 scaling_fact =
std::max(
std::min(scaling_fact, (distance - 2 * resolution_) / distance), 0.0);
322 scaling_fact_z =
std::max(
std::min(scaling_fact_z, (distance - 2 * z_resolution_) / distance), 0.0);
323 wpx = scaling_fact * (wpx - ox) + ox;
324 wpy = scaling_fact * (wpy - oy) + oy;
325 wpz = scaling_fact_z * (wpz - oz) + oz;
335 t =
std::min(t, (origin_z_ - oz) / c);
339 t =
std::min(t, (origin_x_ - ox) / a);
343 t =
std::min(t, (origin_y_ - oy) / b);
349 t =
std::min(t, (map_end_x - ox) / a);
353 t =
std::min(t, (map_end_y - oy) / b);
357 t =
std::min(t, (map_end_z - oz) / c);
364 double point_x, point_y, point_z;
365 if (worldToMap3DFloat(wpx, wpy, wpz, point_x, point_y, point_z))
367 unsigned int cell_raytrace_range = cellDistance(clearing_observation.
raytrace_range_);
370 voxel_grid_.clearVoxelLineInMap(sensor_x, sensor_y, sensor_z, point_x, point_y, point_z, costmap_,
371 unknown_threshold_, mark_threshold_, FREE_SPACE, NO_INFORMATION,
372 cell_raytrace_range);
374 updateRaytraceBounds(ox, oy, wpx, wpy, clearing_observation.
raytrace_range_, min_x, min_y, max_x, max_y);
376 if (publish_clearing_points)
378 geometry_msgs::Point32 point;
382 clearing_endpoints_.points.push_back(point);
387 if (publish_clearing_points)
389 clearing_endpoints_.header.frame_id = global_frame_;
390 #ifdef COSTMAP_2D_POINTCLOUD2 391 clearing_endpoints_.header.stamp = clearing_observation.
cloud_->header.stamp;
395 clearing_endpoints_.header.seq = clearing_observation.
cloud_->header.seq;
397 clearing_endpoints_pub_.publish(clearing_endpoints_);
401 void VoxelLayer::updateOrigin(
double new_origin_x,
double new_origin_y)
408 #ifdef COSTMAP_2D_POINTCLOUD2 415 const double robot_z = transformStamped.transform.translation.z;
416 const double z_grid_height = z_resolution_ * size_z_;
417 const double new_origin_z = robot_z - z_grid_height / 2;
418 cell_oz = int((new_origin_z - origin_z_) / z_resolution_);
420 #ifdef COSTMAP_2D_POINTCLOUD2 432 int cell_ox, cell_oy;
433 cell_ox = int((new_origin_x - origin_x_) / resolution_);
434 cell_oy = int((new_origin_y - origin_y_) / resolution_);
438 double new_grid_ox, new_grid_oy, new_grid_oz;
439 new_grid_ox = origin_x_ + cell_ox * resolution_;
440 new_grid_oy = origin_y_ + cell_oy * resolution_;
441 new_grid_oz = origin_z_ + cell_oz * z_resolution_;
444 int size_x = size_x_;
445 int size_y = size_y_;
448 int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
454 unsigned int cell_size_x = upper_right_x - lower_left_x;
455 unsigned int cell_size_y = upper_right_y - lower_left_y;
458 unsigned char* local_map =
new unsigned char[cell_size_x * cell_size_y];
459 unsigned int* local_voxel_map =
new unsigned int[cell_size_x * cell_size_y];
460 unsigned int* voxel_map = voxel_grid_.getData();
463 copyMapRegion(costmap_, lower_left_x, lower_left_y, size_x_, local_map, 0, 0, cell_size_x, cell_size_x, cell_size_y);
464 copyMapRegion(voxel_map, lower_left_x, lower_left_y, size_x_, local_voxel_map, 0, 0, cell_size_x, cell_size_x,
471 origin_x_ = new_grid_ox;
472 origin_y_ = new_grid_oy;
473 origin_z_ = new_grid_oz;
476 int start_x = lower_left_x - cell_ox;
477 int start_y = lower_left_y - cell_oy;
480 copyMapRegion(local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x, cell_size_y);
481 copyMapRegion3D(local_voxel_map, 0, 0, cell_size_x, voxel_map, start_x, start_y, size_x_, cell_size_x, cell_size_y, cell_oz);
485 delete[] local_voxel_map;
geometry_msgs::Point origin_
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
#define ROS_WARN_THROTTLE(rate,...)
pcl::PointCloud< pcl::PointXYZ > * cloud_
GLM_FUNC_DECL genType::value_type distance(genType const &p0, genType const &p1)
geometry_msgs::TransformStamped t
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
PointCloud2ConstIterator< T > end() const
static void transformStampedTFToMsg(const StampedTransform &bt, geometry_msgs::TransformStamped &msg)
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)