Public Member Functions | Private Member Functions | Private Attributes | List of all members
costmap_2d::FetchDepthLayer Class Reference

A costmap layer that extracts ground plane and clears it. More...

#include <depth_layer.h>

Inheritance diagram for costmap_2d::FetchDepthLayer:
Inheritance graph
[legend]

Public Member Functions

 FetchDepthLayer ()
 Constructor. More...
 
virtual void onInitialize ()
 Initialization function for the DepthLayer. More...
 
virtual ~FetchDepthLayer ()
 Destructor for the depth costmap layer. More...
 
- Public Member Functions inherited from costmap_2d::VoxelLayer
bool isDiscretized ()
 
virtual void matchSize ()
 
virtual void reset ()
 
virtual void updateBounds (double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
 
void updateOrigin (double new_origin_x, double new_origin_y)
 
 VoxelLayer ()
 
virtual ~VoxelLayer ()
 
- Public Member Functions inherited from costmap_2d::ObstacleLayer
virtual void activate ()
 
void addStaticObservation (costmap_2d::Observation &obs, bool marking, bool clearing)
 
void clearStaticObservations (bool marking, bool clearing)
 
virtual void deactivate ()
 
void laserScanCallback (const sensor_msgs::LaserScanConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer)
 
void laserScanValidInfCallback (const sensor_msgs::LaserScanConstPtr &message, const boost::shared_ptr< ObservationBuffer > &buffer)
 
 ObstacleLayer ()
 
void pointCloud2Callback (const sensor_msgs::PointCloud2ConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer)
 
void pointCloudCallback (const sensor_msgs::PointCloudConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer)
 
virtual void updateCosts (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
virtual ~ObstacleLayer ()
 
- Public Member Functions inherited from costmap_2d::CostmapLayer
void addExtraBounds (double mx0, double my0, double mx1, double my1)
 
virtual void clearArea (int start_x, int start_y, int end_x, int end_y)
 
 CostmapLayer ()
 
bool isDiscretized ()
 
- Public Member Functions inherited from costmap_2d::Layer
const std::vector< geometry_msgs::Point > & getFootprint () const
 
std::string getName () const
 
void initialize (LayeredCostmap *parent, std::string name, tf2_ros::Buffer *tf)
 
bool isCurrent () const
 
 Layer ()
 
virtual void onFootprintChanged ()
 
virtual ~Layer ()
 
- Public Member Functions inherited from costmap_2d::Costmap2D
unsigned int cellDistance (double world_dist)
 
void convexFillCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
 
bool copyCostmapWindow (const Costmap2D &map, double win_origin_x, double win_origin_y, double win_size_x, double win_size_y)
 
 Costmap2D (unsigned int cells_size_x, unsigned int cells_size_y, double resolution, double origin_x, double origin_y, unsigned char default_value=0)
 
 Costmap2D (const Costmap2D &map)
 
 Costmap2D ()
 
unsigned char * getCharMap () const
 
unsigned char getCost (unsigned int mx, unsigned int my) const
 
unsigned char getDefaultValue ()
 
unsigned int getIndex (unsigned int mx, unsigned int my) const
 
mutex_tgetMutex ()
 
double getOriginX () const
 
double getOriginY () const
 
double getResolution () const
 
unsigned int getSizeInCellsX () const
 
unsigned int getSizeInCellsY () const
 
double getSizeInMetersX () const
 
double getSizeInMetersY () const
 
void indexToCells (unsigned int index, unsigned int &mx, unsigned int &my) const
 
void mapToWorld (unsigned int mx, unsigned int my, double &wx, double &wy) const
 
Costmap2Doperator= (const Costmap2D &map)
 
void polygonOutlineCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
 
void resetMap (unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
 
void resizeMap (unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
 
bool saveMap (std::string file_name)
 
bool setConvexPolygonCost (const std::vector< geometry_msgs::Point > &polygon, unsigned char cost_value)
 
void setCost (unsigned int mx, unsigned int my, unsigned char cost)
 
void setDefaultValue (unsigned char c)
 
bool worldToMap (double wx, double wy, unsigned int &mx, unsigned int &my) const
 
void worldToMapEnforceBounds (double wx, double wy, int &mx, int &my) const
 
void worldToMapNoBounds (double wx, double wy, int &mx, int &my) const
 
virtual ~Costmap2D ()
 

Private Member Functions

void cameraInfoCallback (const sensor_msgs::CameraInfo::ConstPtr &msg)
 
void depthImageCallback (const sensor_msgs::Image::ConstPtr &msg)
 

Private Attributes

ros::Subscriber camera_info_sub_
 
bool clear_nans_
 
bool clear_with_skipped_rays_
 
boost::shared_ptr< costmap_2d::ObservationBufferclearing_buf_
 
ros::Publisher clearing_pub_
 
cv::Ptr< DepthCleaner > depth_cleaner_
 
boost::shared_ptr< tf2_ros::MessageFilter< sensor_msgs::Image > > depth_image_filter_
 
boost::shared_ptr< message_filters::Subscriber< sensor_msgs::Image > > depth_image_sub_
 
bool find_ground_plane_
 
double ground_threshold_
 
cv::Mat K_
 
boost::shared_ptr< costmap_2d::ObservationBuffermarking_buf_
 
ros::Publisher marking_pub_
 
boost::mutex mutex_K_
 
cv::Ptr< RgbdNormals > normals_estimator_
 
double observations_threshold_
 
cv::Ptr< RgbdPlane > plane_estimator_
 
bool publish_observations_
 
int skip_rays_bottom_
 
int skip_rays_left_
 
int skip_rays_right_
 
int skip_rays_top_
 

Additional Inherited Members

- Public Types inherited from costmap_2d::Costmap2D
typedef boost::recursive_mutex mutex_t
 
- Protected Member Functions inherited from costmap_2d::VoxelLayer
virtual void resetMaps ()
 
virtual void setupDynamicReconfigure (ros::NodeHandle &nh)
 
- Protected Member Functions inherited from costmap_2d::ObstacleLayer
bool getClearingObservations (std::vector< costmap_2d::Observation > &clearing_observations) const
 
bool getMarkingObservations (std::vector< costmap_2d::Observation > &marking_observations) const
 
void updateFootprint (double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
 
void updateRaytraceBounds (double ox, double oy, double wx, double wy, double range, double *min_x, double *min_y, double *max_x, double *max_y)
 
- Protected Member Functions inherited from costmap_2d::CostmapLayer
void touch (double x, double y, double *min_x, double *min_y, double *max_x, double *max_y)
 
void updateWithAddition (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
void updateWithMax (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
void updateWithOverwrite (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
void updateWithTrueOverwrite (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
void useExtraBounds (double *min_x, double *min_y, double *max_x, double *max_y)
 
- Protected Member Functions inherited from costmap_2d::Costmap2D
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)
 
virtual void deleteMaps ()
 
virtual void initMaps (unsigned int size_x, unsigned int size_y)
 
void raytraceLine (ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int max_length=UINT_MAX)
 
- Protected Attributes inherited from costmap_2d::ObstacleLayer
std::vector< boost::shared_ptr< costmap_2d::ObservationBuffer > > clearing_buffers_
 
int combination_method_
 
dynamic_reconfigure::Server< costmap_2d::ObstaclePluginConfig > * dsrv_
 
bool footprint_clearing_enabled_
 
std::string global_frame_
 
std::vector< boost::shared_ptr< costmap_2d::ObservationBuffer > > marking_buffers_
 
double max_obstacle_height_
 
std::vector< boost::shared_ptr< costmap_2d::ObservationBuffer > > observation_buffers_
 
std::vector< boost::shared_ptr< tf2_ros::MessageFilterBase > > observation_notifiers_
 
std::vector< boost::shared_ptr< message_filters::SubscriberBase > > observation_subscribers_
 
laser_geometry::LaserProjection projector_
 
bool rolling_window_
 
std::vector< costmap_2d::Observationstatic_clearing_observations_
 
std::vector< costmap_2d::Observationstatic_marking_observations_
 
std::vector< geometry_msgs::Pointtransformed_footprint_
 
- Protected Attributes inherited from costmap_2d::CostmapLayer
bool has_extra_bounds_
 
- Protected Attributes inherited from costmap_2d::Layer
bool current_
 
bool enabled_
 
LayeredCostmaplayered_costmap_
 
std::string name_
 
tf2_ros::Buffertf_
 
- Protected Attributes inherited from costmap_2d::Costmap2D
unsigned char * costmap_
 
unsigned char default_value_
 
double origin_x_
 
double origin_y_
 
double resolution_
 
unsigned int size_x_
 
unsigned int size_y_
 

Detailed Description

A costmap layer that extracts ground plane and clears it.

Definition at line 56 of file depth_layer.h.

Constructor & Destructor Documentation

◆ FetchDepthLayer()

costmap_2d::FetchDepthLayer::FetchDepthLayer ( )

Constructor.

Definition at line 41 of file depth_layer.cpp.

◆ ~FetchDepthLayer()

costmap_2d::FetchDepthLayer::~FetchDepthLayer ( )
virtual

Destructor for the depth costmap layer.

Definition at line 155 of file depth_layer.cpp.

Member Function Documentation

◆ cameraInfoCallback()

void costmap_2d::FetchDepthLayer::cameraInfoCallback ( const sensor_msgs::CameraInfo::ConstPtr &  msg)
private

Definition at line 159 of file depth_layer.cpp.

◆ depthImageCallback()

void costmap_2d::FetchDepthLayer::depthImageCallback ( const sensor_msgs::Image::ConstPtr &  msg)
private

Definition at line 192 of file depth_layer.cpp.

◆ onInitialize()

void costmap_2d::FetchDepthLayer::onInitialize ( )
virtual

Initialization function for the DepthLayer.

Reimplemented from costmap_2d::VoxelLayer.

Definition at line 45 of file depth_layer.cpp.

Member Data Documentation

◆ camera_info_sub_

ros::Subscriber costmap_2d::FetchDepthLayer::camera_info_sub_
private

Definition at line 116 of file depth_layer.h.

◆ clear_nans_

bool costmap_2d::FetchDepthLayer::clear_nans_
private

Definition at line 98 of file depth_layer.h.

◆ clear_with_skipped_rays_

bool costmap_2d::FetchDepthLayer::clear_with_skipped_rays_
private

Definition at line 107 of file depth_layer.h.

◆ clearing_buf_

boost::shared_ptr<costmap_2d::ObservationBuffer> costmap_2d::FetchDepthLayer::clearing_buf_
private

Definition at line 81 of file depth_layer.h.

◆ clearing_pub_

ros::Publisher costmap_2d::FetchDepthLayer::clearing_pub_
private

Definition at line 119 of file depth_layer.h.

◆ depth_cleaner_

cv::Ptr<DepthCleaner> costmap_2d::FetchDepthLayer::depth_cleaner_
private

Definition at line 129 of file depth_layer.h.

◆ depth_image_filter_

boost::shared_ptr< tf2_ros::MessageFilter<sensor_msgs::Image> > costmap_2d::FetchDepthLayer::depth_image_filter_
private

Definition at line 112 of file depth_layer.h.

◆ depth_image_sub_

boost::shared_ptr< message_filters::Subscriber<sensor_msgs::Image> > costmap_2d::FetchDepthLayer::depth_image_sub_
private

Definition at line 111 of file depth_layer.h.

◆ find_ground_plane_

bool costmap_2d::FetchDepthLayer::find_ground_plane_
private

Definition at line 91 of file depth_layer.h.

◆ ground_threshold_

double costmap_2d::FetchDepthLayer::ground_threshold_
private

Definition at line 95 of file depth_layer.h.

◆ K_

cv::Mat costmap_2d::FetchDepthLayer::K_
private

Definition at line 126 of file depth_layer.h.

◆ marking_buf_

boost::shared_ptr<costmap_2d::ObservationBuffer> costmap_2d::FetchDepthLayer::marking_buf_
private

Definition at line 80 of file depth_layer.h.

◆ marking_pub_

ros::Publisher costmap_2d::FetchDepthLayer::marking_pub_
private

Definition at line 122 of file depth_layer.h.

◆ mutex_K_

boost::mutex costmap_2d::FetchDepthLayer::mutex_K_
private

Definition at line 125 of file depth_layer.h.

◆ normals_estimator_

cv::Ptr<RgbdNormals> costmap_2d::FetchDepthLayer::normals_estimator_
private

Definition at line 132 of file depth_layer.h.

◆ observations_threshold_

double costmap_2d::FetchDepthLayer::observations_threshold_
private

Definition at line 88 of file depth_layer.h.

◆ plane_estimator_

cv::Ptr<RgbdPlane> costmap_2d::FetchDepthLayer::plane_estimator_
private

Definition at line 133 of file depth_layer.h.

◆ publish_observations_

bool costmap_2d::FetchDepthLayer::publish_observations_
private

Definition at line 84 of file depth_layer.h.

◆ skip_rays_bottom_

int costmap_2d::FetchDepthLayer::skip_rays_bottom_
private

Definition at line 101 of file depth_layer.h.

◆ skip_rays_left_

int costmap_2d::FetchDepthLayer::skip_rays_left_
private

Definition at line 103 of file depth_layer.h.

◆ skip_rays_right_

int costmap_2d::FetchDepthLayer::skip_rays_right_
private

Definition at line 104 of file depth_layer.h.

◆ skip_rays_top_

int costmap_2d::FetchDepthLayer::skip_rays_top_
private

Definition at line 102 of file depth_layer.h.


The documentation for this class was generated from the following files:


fetch_depth_layer
Author(s): Michael Ferguson
autogenerated on Mon Feb 28 2022 22:23:51