Public Member Functions | |
void | config_cb (cr_capture::CRCaptureConfig &config, uint32_t level) |
CRCaptureSyncNode () | |
void | imageCB (const sensor_msgs::ImageConstPtr &pimage_left, const sensor_msgs::CameraInfoConstPtr &pinfo_left, const sensor_msgs::ImageConstPtr &pimage_right, const sensor_msgs::CameraInfoConstPtr &pinfo_right, const sensor_msgs::ImageConstPtr &pimage_confi, const sensor_msgs::ImageConstPtr &pimage_intent, const sensor_msgs::ImageConstPtr &pimage_depth, const sensor_msgs::CameraInfoConstPtr &pinfo_range) |
void | publishCloud (const std_msgs::Header &header) |
bool | pullData (cr_capture::PullRawDataRequest &req, cr_capture::PullRawDataResponse &res) |
Private Types | |
typedef dynamic_reconfigure::Server < cr_capture::CRCaptureConfig > | ReconfigureServer |
Private Attributes | |
bool | calc_pixelpos |
ros::Publisher | cloud2_pub_ |
ros::Publisher | cloud_pub_ |
CRLib | cr_lib_ |
image_transport::SubscriberFilter | image_sub_confi_ |
image_transport::SubscriberFilter | image_sub_depth_ |
image_transport::SubscriberFilter | image_sub_intent_ |
image_transport::SubscriberFilter | image_sub_left_ |
image_transport::SubscriberFilter | image_sub_right_ |
ros::Publisher | index_pub_ |
message_filters::Subscriber < sensor_msgs::CameraInfo > | info_sub_left_ |
message_filters::Subscriber < sensor_msgs::CameraInfo > | info_sub_range_ |
message_filters::Subscriber < sensor_msgs::CameraInfo > | info_sub_right_ |
image_transport::ImageTransport | it_ |
std::string | left_ns_ |
ros::NodeHandle | nh_ |
bool | pull_raw_data |
std::string | range_ns_ |
cr_capture::RawCloudData | raw_cloud_ |
ros::ServiceServer | rawdata_service_ |
ReconfigureServer | reconfigure_server_ |
std::string | right_ns_ |
SRCalibratedLib | sr_lib_ |
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 > > | sync_ |
bool | use_images |
Definition at line 37 of file cr_node_sync.cpp.
typedef dynamic_reconfigure::Server<cr_capture::CRCaptureConfig> CRCaptureSyncNode::ReconfigureServer [private] |
Definition at line 69 of file cr_node_sync.cpp.
CRCaptureSyncNode::CRCaptureSyncNode | ( | ) | [inline] |
Definition at line 76 of file cr_node_sync.cpp.
void CRCaptureSyncNode::config_cb | ( | cr_capture::CRCaptureConfig & | config, |
uint32_t | level | ||
) | [inline] |
Definition at line 203 of file cr_node_sync.cpp.
void CRCaptureSyncNode::imageCB | ( | const sensor_msgs::ImageConstPtr & | pimage_left, |
const sensor_msgs::CameraInfoConstPtr & | pinfo_left, | ||
const sensor_msgs::ImageConstPtr & | pimage_right, | ||
const sensor_msgs::CameraInfoConstPtr & | pinfo_right, | ||
const sensor_msgs::ImageConstPtr & | pimage_confi, | ||
const sensor_msgs::ImageConstPtr & | pimage_intent, | ||
const sensor_msgs::ImageConstPtr & | pimage_depth, | ||
const sensor_msgs::CameraInfoConstPtr & | pinfo_range | ||
) | [inline] |
Definition at line 224 of file cr_node_sync.cpp.
void CRCaptureSyncNode::publishCloud | ( | const std_msgs::Header & | header | ) | [inline] |
Definition at line 256 of file cr_node_sync.cpp.
bool CRCaptureSyncNode::pullData | ( | cr_capture::PullRawDataRequest & | req, |
cr_capture::PullRawDataResponse & | res | ||
) | [inline] |
Definition at line 195 of file cr_node_sync.cpp.
bool CRCaptureSyncNode::calc_pixelpos [private] |
Definition at line 60 of file cr_node_sync.cpp.
ros::Publisher CRCaptureSyncNode::cloud2_pub_ [private] |
Definition at line 43 of file cr_node_sync.cpp.
ros::Publisher CRCaptureSyncNode::cloud_pub_ [private] |
Definition at line 42 of file cr_node_sync.cpp.
CRLib CRCaptureSyncNode::cr_lib_ [private] |
Definition at line 66 of file cr_node_sync.cpp.
Definition at line 51 of file cr_node_sync.cpp.
Definition at line 51 of file cr_node_sync.cpp.
Definition at line 51 of file cr_node_sync.cpp.
Definition at line 50 of file cr_node_sync.cpp.
Definition at line 50 of file cr_node_sync.cpp.
ros::Publisher CRCaptureSyncNode::index_pub_ [private] |
Definition at line 44 of file cr_node_sync.cpp.
message_filters::Subscriber<sensor_msgs::CameraInfo> CRCaptureSyncNode::info_sub_left_ [private] |
Definition at line 52 of file cr_node_sync.cpp.
message_filters::Subscriber<sensor_msgs::CameraInfo> CRCaptureSyncNode::info_sub_range_ [private] |
Definition at line 52 of file cr_node_sync.cpp.
message_filters::Subscriber<sensor_msgs::CameraInfo> CRCaptureSyncNode::info_sub_right_ [private] |
Definition at line 52 of file cr_node_sync.cpp.
Definition at line 40 of file cr_node_sync.cpp.
std::string CRCaptureSyncNode::left_ns_ [private] |
Definition at line 47 of file cr_node_sync.cpp.
ros::NodeHandle CRCaptureSyncNode::nh_ [private] |
Definition at line 39 of file cr_node_sync.cpp.
bool CRCaptureSyncNode::pull_raw_data [private] |
Definition at line 62 of file cr_node_sync.cpp.
std::string CRCaptureSyncNode::range_ns_ [private] |
Definition at line 47 of file cr_node_sync.cpp.
Definition at line 73 of file cr_node_sync.cpp.
Definition at line 45 of file cr_node_sync.cpp.
Definition at line 70 of file cr_node_sync.cpp.
std::string CRCaptureSyncNode::right_ns_ [private] |
Definition at line 47 of file cr_node_sync.cpp.
SRCalibratedLib CRCaptureSyncNode::sr_lib_ [private] |
Definition at line 65 of file cr_node_sync.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> > CRCaptureSyncNode::sync_ [private] |
Definition at line 58 of file cr_node_sync.cpp.
bool CRCaptureSyncNode::use_images [private] |
Definition at line 61 of file cr_node_sync.cpp.