Definition at line 14 of file cr_synchronizer.cpp.
CRSynchronizer::CRSynchronizer | ( | ) | [inline] |
Definition at line 31 of file cr_synchronizer.cpp.
void CRSynchronizer::imageCB | ( | const sensor_msgs::ImageConstPtr & | image_left, |
const sensor_msgs::CameraInfoConstPtr & | info_left, | ||
const sensor_msgs::ImageConstPtr & | image_right, | ||
const sensor_msgs::CameraInfoConstPtr & | info_right, | ||
const sensor_msgs::ImageConstPtr & | image_depth, | ||
const sensor_msgs::ImageConstPtr & | image_intent, | ||
const sensor_msgs::ImageConstPtr & | image_confi, | ||
const sensor_msgs::CameraInfoConstPtr & | info_range | ||
) | [inline] |
Definition at line 70 of file cr_synchronizer.cpp.
Definition at line 21 of file cr_synchronizer.cpp.
Definition at line 21 of file cr_synchronizer.cpp.
Definition at line 21 of file cr_synchronizer.cpp.
Definition at line 20 of file cr_synchronizer.cpp.
Definition at line 20 of file cr_synchronizer.cpp.
message_filters::Subscriber<sensor_msgs::CameraInfo> CRSynchronizer::info_sub_left_ [private] |
Definition at line 22 of file cr_synchronizer.cpp.
message_filters::Subscriber<sensor_msgs::CameraInfo> CRSynchronizer::info_sub_range_ [private] |
Definition at line 22 of file cr_synchronizer.cpp.
message_filters::Subscriber<sensor_msgs::CameraInfo> CRSynchronizer::info_sub_right_ [private] |
Definition at line 22 of file cr_synchronizer.cpp.
Definition at line 17 of file cr_synchronizer.cpp.
Definition at line 17 of file cr_synchronizer.cpp.
Definition at line 17 of file cr_synchronizer.cpp.
Definition at line 17 of file cr_synchronizer.cpp.
std::string CRSynchronizer::left_ns_ [private] |
Definition at line 29 of file cr_synchronizer.cpp.
ros::NodeHandle CRSynchronizer::nh_ [private] |
Definition at line 16 of file cr_synchronizer.cpp.
Definition at line 19 of file cr_synchronizer.cpp.
Definition at line 19 of file cr_synchronizer.cpp.
Definition at line 18 of file cr_synchronizer.cpp.
Definition at line 18 of file cr_synchronizer.cpp.
Definition at line 18 of file cr_synchronizer.cpp.
std::string CRSynchronizer::range_ns_ [private] |
Definition at line 29 of file cr_synchronizer.cpp.
std::string CRSynchronizer::right_ns_ [private] |
Definition at line 29 of file cr_synchronizer.cpp.
message_filters::Synchronizer< message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo> > CRSynchronizer::sync_ [private] |
Definition at line 28 of file cr_synchronizer.cpp.