A costmap layer that extracts ground plane and clears it. More...
#include <depth_layer.h>
Public Member Functions | |
FetchDepthLayer () | |
Constructor. | |
virtual void | onInitialize () |
Initialization function for the DepthLayer. | |
virtual | ~FetchDepthLayer () |
Destructor for the depth costmap layer. | |
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::ObservationBuffer > | clearing_buf_ |
ros::Publisher | clearing_pub_ |
cv::Ptr< DepthCleaner > | depth_cleaner_ |
boost::shared_ptr < tf::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::ObservationBuffer > | marking_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_ |
A costmap layer that extracts ground plane and clears it.
Definition at line 64 of file depth_layer.h.
Constructor.
Definition at line 40 of file depth_layer.cpp.
costmap_2d::FetchDepthLayer::~FetchDepthLayer | ( | ) | [virtual] |
Destructor for the depth costmap layer.
Definition at line 154 of file depth_layer.cpp.
void costmap_2d::FetchDepthLayer::cameraInfoCallback | ( | const sensor_msgs::CameraInfo::ConstPtr & | msg | ) | [private] |
Definition at line 158 of file depth_layer.cpp.
void costmap_2d::FetchDepthLayer::depthImageCallback | ( | const sensor_msgs::Image::ConstPtr & | msg | ) | [private] |
Definition at line 191 of file depth_layer.cpp.
void costmap_2d::FetchDepthLayer::onInitialize | ( | ) | [virtual] |
Initialization function for the DepthLayer.
Reimplemented from costmap_2d::VoxelLayer.
Definition at line 44 of file depth_layer.cpp.
Definition at line 124 of file depth_layer.h.
bool costmap_2d::FetchDepthLayer::clear_nans_ [private] |
Definition at line 106 of file depth_layer.h.
bool costmap_2d::FetchDepthLayer::clear_with_skipped_rays_ [private] |
Definition at line 115 of file depth_layer.h.
boost::shared_ptr<costmap_2d::ObservationBuffer> costmap_2d::FetchDepthLayer::clearing_buf_ [private] |
Definition at line 89 of file depth_layer.h.
Definition at line 127 of file depth_layer.h.
cv::Ptr<DepthCleaner> costmap_2d::FetchDepthLayer::depth_cleaner_ [private] |
Definition at line 137 of file depth_layer.h.
boost::shared_ptr< tf::MessageFilter<sensor_msgs::Image> > costmap_2d::FetchDepthLayer::depth_image_filter_ [private] |
Definition at line 120 of file depth_layer.h.
boost::shared_ptr< message_filters::Subscriber<sensor_msgs::Image> > costmap_2d::FetchDepthLayer::depth_image_sub_ [private] |
Definition at line 119 of file depth_layer.h.
bool costmap_2d::FetchDepthLayer::find_ground_plane_ [private] |
Definition at line 99 of file depth_layer.h.
double costmap_2d::FetchDepthLayer::ground_threshold_ [private] |
Definition at line 103 of file depth_layer.h.
cv::Mat costmap_2d::FetchDepthLayer::K_ [private] |
Definition at line 134 of file depth_layer.h.
boost::shared_ptr<costmap_2d::ObservationBuffer> costmap_2d::FetchDepthLayer::marking_buf_ [private] |
Definition at line 88 of file depth_layer.h.
Definition at line 130 of file depth_layer.h.
boost::mutex costmap_2d::FetchDepthLayer::mutex_K_ [private] |
Definition at line 133 of file depth_layer.h.
cv::Ptr<RgbdNormals> costmap_2d::FetchDepthLayer::normals_estimator_ [private] |
Definition at line 140 of file depth_layer.h.
double costmap_2d::FetchDepthLayer::observations_threshold_ [private] |
Definition at line 96 of file depth_layer.h.
cv::Ptr<RgbdPlane> costmap_2d::FetchDepthLayer::plane_estimator_ [private] |
Definition at line 141 of file depth_layer.h.
bool costmap_2d::FetchDepthLayer::publish_observations_ [private] |
Definition at line 92 of file depth_layer.h.
int costmap_2d::FetchDepthLayer::skip_rays_bottom_ [private] |
Definition at line 109 of file depth_layer.h.
int costmap_2d::FetchDepthLayer::skip_rays_left_ [private] |
Definition at line 111 of file depth_layer.h.
int costmap_2d::FetchDepthLayer::skip_rays_right_ [private] |
Definition at line 112 of file depth_layer.h.
int costmap_2d::FetchDepthLayer::skip_rays_top_ [private] |
Definition at line 110 of file depth_layer.h.