69 voxel_dsrv_ =
new dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig>(nh);
70 dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig>::CallbackType cb = boost::bind(
117 double* min_y,
double* max_x,
double* max_y)
126 std::vector<Observation> observations, clearing_observations;
138 for (
unsigned int i = 0; i < clearing_observations.size(); ++i)
144 for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it)
148 const sensor_msgs::PointCloud2& cloud = *(obs.
cloud_);
156 for (
unsigned int i = 0; iter_x != iter_x.
end(); ++iter_x, ++iter_y, ++iter_z)
163 double sq_dist = (*iter_x - obs.
origin_.x) * (*iter_x - obs.
origin_.x)
168 if (sq_dist >= sq_obstacle_range)
172 unsigned int mx, my, mz;
178 else if (!
worldToMap3D(*iter_x, *iter_y, *iter_z, mx, my, mz))
186 unsigned int index =
getIndex(mx, my);
189 touch(
double(*iter_x),
double(*iter_y), min_x, min_y, max_x, max_y);
196 costmap_2d::VoxelGrid grid_msg;
201 grid_msg.data.resize(size);
216 updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
227 double start_x = wx - w_size_x / 2;
228 double start_y = wy - w_size_y / 2;
229 double end_x = start_x + w_size_x;
230 double end_y = start_y + w_size_y;
240 unsigned int map_sx, map_sy, map_ex, map_ey;
247 unsigned int index =
getIndex(map_sx, map_sy);
248 unsigned char* current = &
costmap_[index];
249 for (
unsigned int j = map_sy; j <= map_ey; ++j)
251 for (
unsigned int i = map_sx; i <= map_ex; ++i)
265 current +=
size_x_ - (map_ex - map_sx) - 1;
266 index +=
size_x_ - (map_ex - map_sx) - 1;
271 double* max_x,
double* max_y)
273 size_t clearing_observation_cloud_size = clearing_observation.
cloud_->height * clearing_observation.
cloud_->width;
274 if (clearing_observation_cloud_size == 0)
277 double sensor_x, sensor_y, sensor_z;
278 double ox = clearing_observation.
origin_.x;
279 double oy = clearing_observation.
origin_.y;
280 double oz = clearing_observation.
origin_.z;
286 "The origin for the sensor at (%.2f, %.2f, %.2f) is out of map bounds. So, the costmap cannot raytrace for it.",
292 if (publish_clearing_points)
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;
313 double scaling_fact = 1.0;
314 scaling_fact = std::max(std::min(scaling_fact, (distance - 2 *
resolution_) / distance), 0.0);
315 wpx = scaling_fact * (wpx - ox) + ox;
316 wpy = scaling_fact * (wpy - oy) + oy;
317 wpz = scaling_fact * (wpz - oz) + oz;
350 t = std::min(t, (map_end_x - ox) / a);
354 t = std::min(t, (map_end_y - oy) / b);
361 double point_x, point_y, point_z;
369 cell_raytrace_range);
373 if (publish_clearing_points)
375 geometry_msgs::Point32 point;
384 if (publish_clearing_points)
397 int cell_ox, cell_oy;
403 double new_grid_ox, new_grid_oy;
412 int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
413 lower_left_x = std::min(std::max(cell_ox, 0), size_x);
414 lower_left_y = std::min(std::max(cell_oy, 0), size_y);
415 upper_right_x = std::min(std::max(cell_ox + size_x, 0), size_x);
416 upper_right_y = std::min(std::max(cell_oy + size_y, 0), size_y);
418 unsigned int cell_size_x = upper_right_x - lower_left_x;
419 unsigned int cell_size_y = upper_right_y - lower_left_y;
422 unsigned char* local_map =
new unsigned char[cell_size_x * cell_size_y];
423 unsigned int* local_voxel_map =
new unsigned int[cell_size_x * cell_size_y];
428 copyMapRegion(voxel_map, lower_left_x, lower_left_y,
size_x_, local_voxel_map, 0, 0, cell_size_x, cell_size_x,
439 int start_x = lower_left_x - cell_ox;
440 int start_y = lower_left_y - cell_oy;
444 copyMapRegion(local_voxel_map, 0, 0, cell_size_x, voxel_map, start_x, start_y,
size_x_, cell_size_x, cell_size_y);
448 delete[] local_voxel_map;
double getSizeInMetersX() const
Accessor for the x size of the costmap in meters.
geometry_msgs::Point origin_
unsigned int unknown_threshold_
bool getMarkingObservations(std::vector< costmap_2d::Observation > &marking_observations) const
Get the observations used to mark space.
sensor_msgs::PointCloud clearing_endpoints_
virtual void resetMaps()
Resets the costmap and static_map to be unknown space.
void clearNonLethal(double wx, double wy, double w_size_x, double w_size_y, bool clear_no_info)
ros::Publisher voxel_pub_
unsigned int cellDistance(double world_dist)
Given distance in the world... convert it to cells.
virtual void deactivate()
Stop publishers.
ros::Publisher clearing_endpoints_pub_
unsigned int mark_threshold_
void updateRaytraceBounds(double ox, double oy, double wx, double wy, double range, double *min_x, double *min_y, double *max_x, double *max_y)
bool markVoxelInMap(unsigned int x, unsigned int y, unsigned int z, unsigned int marked_threshold)
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
voxel_grid::VoxelGrid voxel_grid_
Stores an observation in terms of a point cloud and the origin of the source.
virtual void matchSize()
Implement this to make this layer match the size of the parent costmap.
static const unsigned char FREE_SPACE
double getSizeInMetersY() const
Accessor for the y size of the costmap in meters.
geometry_msgs::TransformStamped t
void useExtraBounds(double *min_x, double *min_y, double *max_x, double *max_y)
void clearVoxelLineInMap(double x0, double y0, double z0, double x1, double y1, double z1, unsigned char *map_2d, unsigned int unknown_threshold, unsigned int mark_threshold, unsigned char free_cost=0, unsigned char unknown_cost=255, unsigned int max_length=UINT_MAX)
void copyMapRegion(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)
Copy a region of a source map into a destination map.
double dist(double x0, double y0, double z0, double x1, double y1, double z1)
double max_obstacle_height_
Max Obstacle Height.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void resize(unsigned int size_x, unsigned int size_y, unsigned int size_z)
void publish(const boost::shared_ptr< M > &message) const
double distance(double x0, double y0, double x1, double y1)
virtual void activate()
Restart publishers if they've been stopped.
Takes in point clouds from sensors, transforms them to the desired frame, and stores them...
void updateOrigin(double new_origin_x, double new_origin_y)
Move the origin of the costmap to a new location.... keeping data when it can.
virtual void setupDynamicReconfigure(ros::NodeHandle &nh)
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization...
#define ROS_WARN_THROTTLE(period,...)
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
This is called by the LayeredCostmap to poll this plugin as to how much of the costmap it needs to up...
bool worldToMap3D(double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz)
PointCloud2ConstIterator< T > end() const
virtual void resetMaps()
Resets the costmap and static_map to be unknown space.
dynamic_reconfigure::Server< costmap_2d::VoxelPluginConfig > * voxel_dsrv_
bool footprint_clearing_enabled_
virtual void raytraceFreespace(const costmap_2d::Observation &clearing_observation, double *min_x, double *min_y, double *max_x, double *max_y)
Clear freespace based on one observation.
virtual void matchSize()
Implement this to make this layer match the size of the parent costmap.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void updateFootprint(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
bool enabled_
Currently this var is managed by subclasses. TODO: make this managed by this class and/or container c...
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization...
sensor_msgs::PointCloud2 * cloud_
static const unsigned char LETHAL_OBSTACLE
static const unsigned char NO_INFORMATION
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
void clearVoxelColumn(unsigned int index)
void touch(double x, double y, double *min_x, double *min_y, double *max_x, double *max_y)
bool worldToMap3DFloat(double wx, double wy, double wz, double &mx, double &my, double &mz)
uint32_t getNumSubscribers() const
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool getClearingObservations(std::vector< costmap_2d::Observation > &clearing_observations) const
Get the observations used to clear space.
std::string global_frame_
The global frame for the costmap.
void reconfigureCB(costmap_2d::VoxelPluginConfig &config, uint32_t level)