Go to the documentation of this file.
69 voxel_dsrv_ =
new dynamic_reconfigure::Server<costmap_2d::NonPersistentVoxelPluginConfig>(nh);
70 dynamic_reconfigure::Server<costmap_2d::NonPersistentVoxelPluginConfig>::CallbackType cb = boost::bind(
95 double* max_x,
double* max_y)
132 double* min_y,
double* max_x,
double* max_y)
152 std::vector<Observation> observations;
159 for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it)
168 for (; it_x != it_x.
end(); ++it_x, ++it_y, ++it_z)
175 double sq_dist = (*it_x - obs.
origin_.x) * (*it_x - obs.
origin_.x)
180 if (sq_dist >= sq_obstacle_range)
184 unsigned int mx, my, mz;
190 else if (!
worldToMap3D(*it_x, *it_y, *it_z, mx, my, mz))
198 unsigned int index =
getIndex(mx, my);
201 touch((
double)*it_x, (
double)*it_y, min_x, min_y, max_x, max_y);
208 costmap_2d::VoxelGrid grid_msg;
213 grid_msg.data.resize(size);
228 updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
234 int cell_ox, cell_oy;
double getSizeInMetersX() const
virtual void deactivate()
bool getMarkingObservations(std::vector< costmap_2d::Observation > &marking_observations) const
void transformFootprint(double x, double y, double theta, const std::vector< geometry_msgs::Point > &footprint_spec, geometry_msgs::PolygonStamped &oriented_footprint)
std::string global_frame_
void updateOrigin(double new_origin_x, double new_origin_y)
PointCloud2ConstIterator< T > end() const
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
double getSizeInMetersY() const
virtual ~NonPersistentVoxelLayer()
static const unsigned char NO_INFORMATION
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
virtual void onInitialize()
sensor_msgs::PointCloud2 * cloud_
virtual void setupDynamicReconfigure(ros::NodeHandle &nh)
double max_obstacle_height_
dynamic_reconfigure::Server< costmap_2d::NonPersistentVoxelPluginConfig > * voxel_dsrv_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool worldToMap3D(double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz)
void resize(unsigned int size_x, unsigned int size_y, unsigned int size_z)
std::vector< geometry_msgs::Point > transformed_footprint_
ros::Publisher voxel_pub_
virtual void onInitialize()
static const unsigned char LETHAL_OBSTACLE
const std::vector< geometry_msgs::Point > & getFootprint() const
unsigned int unknown_threshold_
void useExtraBounds(double *min_x, double *min_y, double *max_x, double *max_y)
unsigned int mark_threshold_
void reconfigureCB(costmap_2d::NonPersistentVoxelPluginConfig &config, uint32_t level)
void touch(double x, double y, double *min_x, double *min_y, double *max_x, double *max_y)
T param(const std::string ¶m_name, const T &default_val) const
voxel_grid::VoxelGrid voxel_grid_
geometry_msgs::Point origin_
bool setConvexPolygonCost(const std::vector< geometry_msgs::Point > &polygon, unsigned char cost_value)
unsigned int getIndex(unsigned int mx, unsigned int my) const
static const unsigned char FREE_SPACE
bool markVoxelInMap(unsigned int x, unsigned int y, unsigned int z, unsigned int marked_threshold)
bool footprint_clearing_enabled_
void updateFootprint(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)