Processes the raw output of OpenNI sensors to create a stream of RGB-D images. More...
#include <rgbd_image_proc.h>
Public Member Functions | |
| void | RGBDCallback (const ImageMsg::ConstPtr &rgb_msg, const ImageMsg::ConstPtr &depth_msg, const CameraInfoMsg::ConstPtr &rgb_info_msg, const CameraInfoMsg::ConstPtr &depth_info_msg) |
| Main RGBD callback. | |
| RGBDImageProc (const ros::NodeHandle &nh, const ros::NodeHandle &nh_private) | |
| Constructor from ROS nodehandles. | |
| virtual | ~RGBDImageProc () |
| Default destructor. | |
Private Types | |
| typedef RGBDImageProcConfig | ProcConfig |
| typedef dynamic_reconfigure::Server < ProcConfig > | ProcConfigServer |
Private Member Functions | |
| void | initMaps (const CameraInfoMsg::ConstPtr &rgb_info_msg, const CameraInfoMsg::ConstPtr &depth_info_msg) |
| Initializes the rectification maps from CameraInfo messages. | |
| bool | loadCalibration () |
| Loads intrinsic and extrinsic calibration info from files. | |
| bool | loadUnwarpCalibration () |
| Loads depth unwarp calibration info from files. | |
| void | reconfigCallback (ProcConfig &config, uint32_t level) |
| ROS dynamic reconfigure callback function. | |
Private Attributes | |
| std::string | calib_extr_filename_ |
| path to extrinsic calibration yaml file, derived from calib_path_ parameter | |
| std::string | calib_path_ |
| Path to folder where calibration files are stored. | |
| std::string | calib_warp_filename_ |
| path to depth unwarp calibration yaml file, derived from calib_path_ parameter | |
| ros::Publisher | cloud_publisher_ |
| ROS PointCloud publisher. | |
| cv::Mat | coeff_0_ |
| depth unwarp polynomial coefficient matrices | |
| cv::Mat | coeff_0_rect_ |
| depth unwarp polynomial coefficient matrices, after recitfication and resizing | |
| cv::Mat | coeff_1_ |
| cv::Mat | coeff_1_rect_ |
| cv::Mat | coeff_2_ |
| cv::Mat | coeff_2_rect_ |
| ProcConfigServer | config_server_ |
| ROS dynamic reconfigure server. | |
| ImageTransport | depth_image_transport_ |
| ROS image transport for depth message. | |
| ImagePublisher | depth_publisher_ |
| ROS depth image publisher. | |
| CameraInfoMsg | depth_rect_info_msg_ |
| Depth CameraInfo derived from optimal matrices. | |
| int | fit_mode_ |
| Depth unwwarping mode, based on different polynomial fits. | |
| ros::Publisher | info_publisher_ |
| ROS camera info publisher. | |
| bool | initialized_ |
| whether we have initialized from the first image | |
| cv::Mat | intr_rect_depth_ |
| cv::Mat | intr_rect_rgb_ |
| optimal intrinsics after rectification | |
| cv::Mat | ir2rgb_ |
| extrinsic matrix between IR and RGB camera | |
| cv::Mat | map_depth_1_ |
| Depth rectification maps. | |
| cv::Mat | map_depth_2_ |
| cv::Mat | map_rgb_1_ |
| RGB rectification maps. | |
| cv::Mat | map_rgb_2_ |
| boost::mutex | mutex_ |
| state mutex | |
| ros::NodeHandle | nh_ |
| the public nodehandle | |
| ros::NodeHandle | nh_private_ |
| the private nodehandle | |
| bool | publish_cloud_ |
| Whether to calculate and publish the dense PointCloud. | |
| int | queue_size_ |
| ROS subscriber (and publisher) queue size parameter. | |
| ImageTransport | rgb_image_transport_ |
| ROS image transport for rgb message. | |
| ImagePublisher | rgb_publisher_ |
| ROS rgb image publisher. | |
| CameraInfoMsg | rgb_rect_info_msg_ |
| RGB CameraInfo derived from optimal matrices. | |
| double | scale_ |
| Downasampling scale (0, 1]. For example, 2.0 will result in an output image half the size of the input. | |
| cv::Size | size_in_ |
| Size of the incoming images. | |
| ImageSubFilter | sub_depth_ |
| ROS subscriber for depth message. | |
| CameraInfoSubFilter | sub_depth_info_ |
| ROS subscriber for depth camera info. | |
| ImageSubFilter | sub_rgb_ |
| ROS subscriber for rgb message. | |
| CameraInfoSubFilter | sub_rgb_info_ |
| ROS subscriber for rgb camera info. | |
| boost::shared_ptr < RGBDSynchronizer4 > | sync_ |
| ROS 4-topic synchronizer. | |
| bool | unwarp_ |
| Whether to perform depth unwarping based on polynomial model. | |
| bool | verbose_ |
| Whether to print the rectification and unwarping messages. | |
Processes the raw output of OpenNI sensors to create a stream of RGB-D images.
The RGBDImageProc app subscribes to a stream of rgb and depth messages. If performs the following operations on the images:
The app then publishes the resulting pair of RGB and depth images, together with a camera info which has no distortion, and the optimal new camera matrix for both images.
Definition at line 55 of file rgbd_image_proc.h.
typedef RGBDImageProcConfig ccny_rgbd::RGBDImageProc::ProcConfig [private] |
Definition at line 57 of file rgbd_image_proc.h.
typedef dynamic_reconfigure::Server<ProcConfig> ccny_rgbd::RGBDImageProc::ProcConfigServer [private] |
Definition at line 58 of file rgbd_image_proc.h.
| ccny_rgbd::RGBDImageProc::RGBDImageProc | ( | const ros::NodeHandle & | nh, |
| const ros::NodeHandle & | nh_private | ||
| ) |
Constructor from ROS nodehandles.
| nh | the public nodehandle |
| nh_private | the private nodehandle |
Definition at line 28 of file rgbd_image_proc.cpp.
| ccny_rgbd::RGBDImageProc::~RGBDImageProc | ( | ) | [virtual] |
Default destructor.
Definition at line 103 of file rgbd_image_proc.cpp.
| void ccny_rgbd::RGBDImageProc::initMaps | ( | const CameraInfoMsg::ConstPtr & | rgb_info_msg, |
| const CameraInfoMsg::ConstPtr & | depth_info_msg | ||
| ) | [private] |
Initializes the rectification maps from CameraInfo messages.
| rgb_info_msg | input camera info for RGB image |
| depth_info_msg | input camera info for depth image |
Definition at line 146 of file rgbd_image_proc.cpp.
| bool ccny_rgbd::RGBDImageProc::loadCalibration | ( | ) | [private] |
Loads intrinsic and extrinsic calibration info from files.
Definition at line 108 of file rgbd_image_proc.cpp.
| bool ccny_rgbd::RGBDImageProc::loadUnwarpCalibration | ( | ) | [private] |
Loads depth unwarp calibration info from files.
Definition at line 127 of file rgbd_image_proc.cpp.
| void ccny_rgbd::RGBDImageProc::reconfigCallback | ( | ProcConfig & | config, |
| uint32_t | level | ||
| ) | [private] |
ROS dynamic reconfigure callback function.
Definition at line 337 of file rgbd_image_proc.cpp.
| void ccny_rgbd::RGBDImageProc::RGBDCallback | ( | const ImageMsg::ConstPtr & | rgb_msg, |
| const ImageMsg::ConstPtr & | depth_msg, | ||
| const CameraInfoMsg::ConstPtr & | rgb_info_msg, | ||
| const CameraInfoMsg::ConstPtr & | depth_info_msg | ||
| ) |
Main RGBD callback.
| rgb_msg | RGB message (8UC3) |
| depth_msg | Depth message (16UC1, in mm) |
| rgb_info_msg | CameraInfo message, applies to RGB image |
| depth_info_msg | CameraInfo message, applies to RGB image |
Definition at line 223 of file rgbd_image_proc.cpp.
std::string ccny_rgbd::RGBDImageProc::calib_extr_filename_ [private] |
path to extrinsic calibration yaml file, derived from calib_path_ parameter
Definition at line 126 of file rgbd_image_proc.h.
std::string ccny_rgbd::RGBDImageProc::calib_path_ [private] |
Path to folder where calibration files are stored.
Definition at line 113 of file rgbd_image_proc.h.
std::string ccny_rgbd::RGBDImageProc::calib_warp_filename_ [private] |
path to depth unwarp calibration yaml file, derived from calib_path_ parameter
Definition at line 131 of file rgbd_image_proc.h.
ROS PointCloud publisher.
Definition at line 105 of file rgbd_image_proc.h.
cv::Mat ccny_rgbd::RGBDImageProc::coeff_0_ [private] |
depth unwarp polynomial coefficient matrices
Definition at line 149 of file rgbd_image_proc.h.
cv::Mat ccny_rgbd::RGBDImageProc::coeff_0_rect_ [private] |
depth unwarp polynomial coefficient matrices, after recitfication and resizing
Definition at line 154 of file rgbd_image_proc.h.
cv::Mat ccny_rgbd::RGBDImageProc::coeff_1_ [private] |
Definition at line 149 of file rgbd_image_proc.h.
cv::Mat ccny_rgbd::RGBDImageProc::coeff_1_rect_ [private] |
Definition at line 154 of file rgbd_image_proc.h.
cv::Mat ccny_rgbd::RGBDImageProc::coeff_2_ [private] |
Definition at line 149 of file rgbd_image_proc.h.
cv::Mat ccny_rgbd::RGBDImageProc::coeff_2_rect_ [private] |
Definition at line 154 of file rgbd_image_proc.h.
ROS dynamic reconfigure server.
Definition at line 107 of file rgbd_image_proc.h.
ROS image transport for depth message.
Definition at line 94 of file rgbd_image_proc.h.
ROS depth image publisher.
Definition at line 103 of file rgbd_image_proc.h.
Depth CameraInfo derived from optimal matrices.
Definition at line 166 of file rgbd_image_proc.h.
int ccny_rgbd::RGBDImageProc::fit_mode_ [private] |
Depth unwwarping mode, based on different polynomial fits.
See DepthFitMode
Definition at line 144 of file rgbd_image_proc.h.
ROS camera info publisher.
Definition at line 104 of file rgbd_image_proc.h.
bool ccny_rgbd::RGBDImageProc::initialized_ [private] |
whether we have initialized from the first image
Definition at line 135 of file rgbd_image_proc.h.
cv::Mat ccny_rgbd::RGBDImageProc::intr_rect_depth_ [private] |
Definition at line 160 of file rgbd_image_proc.h.
cv::Mat ccny_rgbd::RGBDImageProc::intr_rect_rgb_ [private] |
optimal intrinsics after rectification
Definition at line 160 of file rgbd_image_proc.h.
cv::Mat ccny_rgbd::RGBDImageProc::ir2rgb_ [private] |
extrinsic matrix between IR and RGB camera
Definition at line 157 of file rgbd_image_proc.h.
cv::Mat ccny_rgbd::RGBDImageProc::map_depth_1_ [private] |
Depth rectification maps.
Definition at line 172 of file rgbd_image_proc.h.
cv::Mat ccny_rgbd::RGBDImageProc::map_depth_2_ [private] |
Definition at line 172 of file rgbd_image_proc.h.
cv::Mat ccny_rgbd::RGBDImageProc::map_rgb_1_ [private] |
RGB rectification maps.
Definition at line 169 of file rgbd_image_proc.h.
cv::Mat ccny_rgbd::RGBDImageProc::map_rgb_2_ [private] |
Definition at line 169 of file rgbd_image_proc.h.
boost::mutex ccny_rgbd::RGBDImageProc::mutex_ [private] |
state mutex
Definition at line 136 of file rgbd_image_proc.h.
ros::NodeHandle ccny_rgbd::RGBDImageProc::nh_ [private] |
the public nodehandle
Definition at line 88 of file rgbd_image_proc.h.
the private nodehandle
Definition at line 89 of file rgbd_image_proc.h.
bool ccny_rgbd::RGBDImageProc::publish_cloud_ [private] |
Whether to calculate and publish the dense PointCloud.
Definition at line 116 of file rgbd_image_proc.h.
int ccny_rgbd::RGBDImageProc::queue_size_ [private] |
ROS subscriber (and publisher) queue size parameter.
Definition at line 111 of file rgbd_image_proc.h.
ROS image transport for rgb message.
Definition at line 93 of file rgbd_image_proc.h.
ROS rgb image publisher.
Definition at line 102 of file rgbd_image_proc.h.
RGB CameraInfo derived from optimal matrices.
Definition at line 163 of file rgbd_image_proc.h.
double ccny_rgbd::RGBDImageProc::scale_ [private] |
Downasampling scale (0, 1]. For example, 2.0 will result in an output image half the size of the input.
Definition at line 121 of file rgbd_image_proc.h.
cv::Size ccny_rgbd::RGBDImageProc::size_in_ [private] |
Size of the incoming images.
Definition at line 146 of file rgbd_image_proc.h.
ROS subscriber for depth message.
Definition at line 97 of file rgbd_image_proc.h.
ROS subscriber for depth camera info.
Definition at line 100 of file rgbd_image_proc.h.
ROS subscriber for rgb message.
Definition at line 96 of file rgbd_image_proc.h.
ROS subscriber for rgb camera info.
Definition at line 99 of file rgbd_image_proc.h.
boost::shared_ptr<RGBDSynchronizer4> ccny_rgbd::RGBDImageProc::sync_ [private] |
ROS 4-topic synchronizer.
Definition at line 91 of file rgbd_image_proc.h.
bool ccny_rgbd::RGBDImageProc::unwarp_ [private] |
Whether to perform depth unwarping based on polynomial model.
Definition at line 115 of file rgbd_image_proc.h.
bool ccny_rgbd::RGBDImageProc::verbose_ [private] |
Whether to print the rectification and unwarping messages.
Definition at line 114 of file rgbd_image_proc.h.