| rgbd
    | 

| Public Member Functions | |
| ClientRosNodelet (ros::NodeHandle &nh) | |
| const Image * | getImage () | 
| message_filters::Synchronizer< RGBDApproxPolicy > * | getSync () | 
| bool | imageCallback (const sensor_msgs::ImageConstPtr &rgb_image_msg, const sensor_msgs::ImageConstPtr &depth_image_msg) | 
| Callback for synched rgb and depth image.  More... | |
| ~ClientRosNodelet () | |
|  Public Member Functions inherited from rgbd::ClientROSBase | |
| ClientROSBase (ros::NodeHandle nh) | |
| Constructor.  More... | |
| bool | deinitialize () | 
| Clears the subscribers. initialized will now return false.  More... | |
| bool | initialize (const std::string &rgb_image_topic, const std::string &depth_image_topic, const std::string &cam_info_topic) | 
| Initialize the subscriber.  More... | |
| bool | initialized () | 
| Check if the client is initialized. nextImage will not return an image if client is not initialized.  More... | |
| virtual | ~ClientROSBase () | 
| Destructor.  More... | |
| Additional Inherited Members | |
|  Protected Member Functions inherited from rgbd::ClientROSBase | |
| void | camInfoCallback (const sensor_msgs::CameraInfoConstPtr &cam_info_msg) | 
| Callback for CameraInfo, will unsubscribe after succesfully receiving first message.  More... | |
| bool | imageCallback (const sensor_msgs::ImageConstPtr &rgb_image_msg, const sensor_msgs::ImageConstPtr &depth_image_msg) | 
| Callback for synched rgb and depth image.  More... | |
|  Protected Attributes inherited from rgbd::ClientROSBase | |
| image_geometry::PinholeCameraModel | cam_model_ | 
| Image * | image_ptr_ | 
| image_ptr_ Pointer to image. Image could be provided by reference or the pointer will be wrapped in a shared_ptr. Either this class will never take ownership.  More... | |
| bool | new_image_ | 
| new_image_ Track if image is updated in a callback.  More... | |
| ros::NodeHandle | nh_ | 
| ros::Subscriber | sub_cam_info_ | 
| std::unique_ptr< message_filters::Subscriber< sensor_msgs::Image > > | sub_depth_sync_ | 
| std::unique_ptr< message_filters::Subscriber< sensor_msgs::Image > > | sub_rgb_sync_ | 
| std::unique_ptr< message_filters::Synchronizer< RGBDApproxPolicy > > | sync_ | 
Definition at line 19 of file nodelets/ros_to_rgbd.cpp.
| 
 | inline | 
Definition at line 22 of file nodelets/ros_to_rgbd.cpp.
| 
 | inline | 
Definition at line 26 of file nodelets/ros_to_rgbd.cpp.
| 
 | inline | 
Definition at line 30 of file nodelets/ros_to_rgbd.cpp.
| 
 | inline | 
Definition at line 35 of file nodelets/ros_to_rgbd.cpp.
| bool rgbd::ClientROSBase::imageCallback | 
Callback for synched rgb and depth image.
| rgb_image_msg | rgb image message | 
| depth_image_msg | depth image message | 
Definition at line 71 of file client_ros_base.cpp.
 1.8.17
 1.8.17