Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
rtabmap_ros::PointCloudToDepthImage Class Reference
Inheritance diagram for rtabmap_ros::PointCloudToDepthImage:
Inheritance graph
[legend]

Public Member Functions

 PointCloudToDepthImage ()
 
virtual ~PointCloudToDepthImage ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Private Types

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::CameraInfo > MyApproxSyncPolicy
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::CameraInfo > MyExactSyncPolicy
 

Private Member Functions

void callback (const sensor_msgs::PointCloud2ConstPtr &pointCloud2Msg, const sensor_msgs::CameraInfoConstPtr &cameraInfoMsg)
 
virtual void onInit ()
 

Private Attributes

message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
 
ros::Publisher cameraInfo16Pub_
 
ros::Publisher cameraInfo32Pub_
 
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
 
int decimation_
 
image_transport::Publisher depthImage16Pub_
 
image_transport::Publisher depthImage32Pub_
 
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
 
double fillHolesError_
 
int fillHolesSize_
 
int fillIterations_
 
std::string fixedFrameId_
 
tf::TransformListenerlistener_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > pointCloudSub_
 
ros::Publisher pointCloudTransformedPub_
 
bool upscale_
 
double upscaleDepthErrorRatio_
 
double waitForTransform_
 

Additional Inherited Members

- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::stringgetName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Detailed Description

Definition at line 58 of file pointcloud_to_depthimage.cpp.

Member Typedef Documentation

◆ MyApproxSyncPolicy

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, sensor_msgs::CameraInfo> rtabmap_ros::PointCloudToDepthImage::MyApproxSyncPolicy
private

Definition at line 304 of file pointcloud_to_depthimage.cpp.

◆ MyExactSyncPolicy

typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2, sensor_msgs::CameraInfo> rtabmap_ros::PointCloudToDepthImage::MyExactSyncPolicy
private

Definition at line 306 of file pointcloud_to_depthimage.cpp.

Constructor & Destructor Documentation

◆ PointCloudToDepthImage()

rtabmap_ros::PointCloudToDepthImage::PointCloudToDepthImage ( )
inline

Definition at line 61 of file pointcloud_to_depthimage.cpp.

◆ ~PointCloudToDepthImage()

virtual rtabmap_ros::PointCloudToDepthImage::~PointCloudToDepthImage ( )
inlinevirtual

Definition at line 74 of file pointcloud_to_depthimage.cpp.

Member Function Documentation

◆ callback()

void rtabmap_ros::PointCloudToDepthImage::callback ( const sensor_msgs::PointCloud2ConstPtr &  pointCloud2Msg,
const sensor_msgs::CameraInfoConstPtr &  cameraInfoMsg 
)
inlineprivate

Definition at line 150 of file pointcloud_to_depthimage.cpp.

◆ onInit()

virtual void rtabmap_ros::PointCloudToDepthImage::onInit ( )
inlineprivatevirtual

Implements nodelet::Nodelet.

Definition at line 88 of file pointcloud_to_depthimage.cpp.

Member Data Documentation

◆ approxSync_

message_filters::Synchronizer<MyApproxSyncPolicy>* rtabmap_ros::PointCloudToDepthImage::approxSync_
private

Definition at line 305 of file pointcloud_to_depthimage.cpp.

◆ cameraInfo16Pub_

ros::Publisher rtabmap_ros::PointCloudToDepthImage::cameraInfo16Pub_
private

Definition at line 289 of file pointcloud_to_depthimage.cpp.

◆ cameraInfo32Pub_

ros::Publisher rtabmap_ros::PointCloudToDepthImage::cameraInfo32Pub_
private

Definition at line 290 of file pointcloud_to_depthimage.cpp.

◆ cameraInfoSub_

message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_ros::PointCloudToDepthImage::cameraInfoSub_
private

Definition at line 293 of file pointcloud_to_depthimage.cpp.

◆ decimation_

int rtabmap_ros::PointCloudToDepthImage::decimation_
private

Definition at line 300 of file pointcloud_to_depthimage.cpp.

◆ depthImage16Pub_

image_transport::Publisher rtabmap_ros::PointCloudToDepthImage::depthImage16Pub_
private

Definition at line 287 of file pointcloud_to_depthimage.cpp.

◆ depthImage32Pub_

image_transport::Publisher rtabmap_ros::PointCloudToDepthImage::depthImage32Pub_
private

Definition at line 288 of file pointcloud_to_depthimage.cpp.

◆ exactSync_

message_filters::Synchronizer<MyExactSyncPolicy>* rtabmap_ros::PointCloudToDepthImage::exactSync_
private

Definition at line 307 of file pointcloud_to_depthimage.cpp.

◆ fillHolesError_

double rtabmap_ros::PointCloudToDepthImage::fillHolesError_
private

Definition at line 298 of file pointcloud_to_depthimage.cpp.

◆ fillHolesSize_

int rtabmap_ros::PointCloudToDepthImage::fillHolesSize_
private

Definition at line 297 of file pointcloud_to_depthimage.cpp.

◆ fillIterations_

int rtabmap_ros::PointCloudToDepthImage::fillIterations_
private

Definition at line 299 of file pointcloud_to_depthimage.cpp.

◆ fixedFrameId_

std::string rtabmap_ros::PointCloudToDepthImage::fixedFrameId_
private

Definition at line 294 of file pointcloud_to_depthimage.cpp.

◆ listener_

tf::TransformListener* rtabmap_ros::PointCloudToDepthImage::listener_
private

Definition at line 295 of file pointcloud_to_depthimage.cpp.

◆ pointCloudSub_

message_filters::Subscriber<sensor_msgs::PointCloud2> rtabmap_ros::PointCloudToDepthImage::pointCloudSub_
private

Definition at line 292 of file pointcloud_to_depthimage.cpp.

◆ pointCloudTransformedPub_

ros::Publisher rtabmap_ros::PointCloudToDepthImage::pointCloudTransformedPub_
private

Definition at line 291 of file pointcloud_to_depthimage.cpp.

◆ upscale_

bool rtabmap_ros::PointCloudToDepthImage::upscale_
private

Definition at line 301 of file pointcloud_to_depthimage.cpp.

◆ upscaleDepthErrorRatio_

double rtabmap_ros::PointCloudToDepthImage::upscaleDepthErrorRatio_
private

Definition at line 302 of file pointcloud_to_depthimage.cpp.

◆ waitForTransform_

double rtabmap_ros::PointCloudToDepthImage::waitForTransform_
private

Definition at line 296 of file pointcloud_to_depthimage.cpp.


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


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Tue Jan 24 2023 04:04:40