Private Types | Private Member Functions | Private Attributes
depth_image_proc::RegisterNodelet Class Reference
Inheritance diagram for depth_image_proc::RegisterNodelet:
Inheritance graph
[legend]

List of all members.

Private Types

typedef
message_filters::Synchronizer
< SyncPolicy
Synchronizer
typedef ApproximateTime
< sensor_msgs::Image,
sensor_msgs::CameraInfo,
sensor_msgs::CameraInfo > 
SyncPolicy

Private Member Functions

void connectCb ()
template<typename T >
void convert (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImagePtr &registered_msg, const Eigen::Affine3d &depth_to_rgb)
void imageCb (const sensor_msgs::ImageConstPtr &depth_image_msg, const sensor_msgs::CameraInfoConstPtr &depth_info_msg, const sensor_msgs::CameraInfoConstPtr &rgb_info_msg)
virtual void onInit ()

Private Attributes

boost::mutex connect_mutex_
image_geometry::PinholeCameraModel depth_model_
boost::shared_ptr
< image_transport::ImageTransport
it_depth_
ros::NodeHandlePtr nh_depth_
ros::NodeHandlePtr nh_rgb_
image_transport::CameraPublisher pub_registered_
image_geometry::PinholeCameraModel rgb_model_
image_transport::SubscriberFilter sub_depth_image_
message_filters::Subscriber
< sensor_msgs::CameraInfo > 
sub_depth_info_
message_filters::Subscriber
< sensor_msgs::CameraInfo > 
sub_rgb_info_
boost::shared_ptr< Synchronizersync_
boost::shared_ptr
< tf2_ros::TransformListener
tf_
boost::shared_ptr
< tf2_ros::Buffer
tf_buffer_

Detailed Description

Definition at line 54 of file register.cpp.


Member Typedef Documentation

Definition at line 65 of file register.cpp.

typedef ApproximateTime<sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> depth_image_proc::RegisterNodelet::SyncPolicy [private]

Definition at line 64 of file register.cpp.


Member Function Documentation

Definition at line 118 of file register.cpp.

template<typename T >
void depth_image_proc::RegisterNodelet::convert ( const sensor_msgs::ImageConstPtr &  depth_msg,
const sensor_msgs::ImagePtr &  registered_msg,
const Eigen::Affine3d &  depth_to_rgb 
) [private]
Todo:
When RGB is higher res, interpolate by rasterizing depth triangles onto the registered image
Todo:
Combine all operations into one matrix multiply on (u,v,d)

Definition at line 195 of file register.cpp.

void depth_image_proc::RegisterNodelet::imageCb ( const sensor_msgs::ImageConstPtr &  depth_image_msg,
const sensor_msgs::CameraInfoConstPtr &  depth_info_msg,
const sensor_msgs::CameraInfoConstPtr &  rgb_info_msg 
) [private]
Todo:
Can take on order of a minute to register a disconnect callback when we don't call publish() in this cb. What's going on roscpp?

Definition at line 136 of file register.cpp.

void depth_image_proc::RegisterNodelet::onInit ( ) [private, virtual]

Implements nodelet::Nodelet.

Definition at line 88 of file register.cpp.


Member Data Documentation

Definition at line 69 of file register.cpp.

Definition at line 72 of file register.cpp.

Definition at line 57 of file register.cpp.

Definition at line 56 of file register.cpp.

Definition at line 56 of file register.cpp.

Definition at line 70 of file register.cpp.

Definition at line 72 of file register.cpp.

Definition at line 60 of file register.cpp.

Definition at line 61 of file register.cpp.

Definition at line 61 of file register.cpp.

Definition at line 66 of file register.cpp.

Definition at line 63 of file register.cpp.

Definition at line 62 of file register.cpp.


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


depth_image_proc
Author(s): Patrick Mihelich
autogenerated on Wed May 1 2019 02:51:42