Public Member Functions | |
void | cameraallCB (const sensor_msgs::ImageConstPtr &img_c, const sensor_msgs::ImageConstPtr &img_i, const sensor_msgs::ImageConstPtr &img_d, const sensor_msgs::CameraInfoConstPtr &info) |
void | cameraleftCB (const sensor_msgs::ImageConstPtr &img, const sensor_msgs::CameraInfoConstPtr &info) |
void | camerarangeCB (const sensor_msgs::ImageConstPtr &img, const sensor_msgs::CameraInfoConstPtr &info) |
void | camerarightCB (const sensor_msgs::ImageConstPtr &img, const sensor_msgs::CameraInfoConstPtr &info) |
void | config_cb (cr_capture::CRCaptureConfig &config, uint32_t level) |
CRCaptureNode () | |
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 |
image_transport::CameraSubscriber | camera_sub_depth_ |
image_transport::CameraSubscriber | camera_sub_l_ |
image_transport::CameraSubscriber | camera_sub_r_ |
ros::Publisher | cloud2_pub_ |
ros::Publisher | cloud_pub_ |
CRLib | cr_lib_ |
message_filters::Subscriber < sensor_msgs::Image > | image_conf_sub_ |
message_filters::Subscriber < sensor_msgs::Image > | image_depth_sub_ |
message_filters::Subscriber < sensor_msgs::Image > | image_intent_sub_ |
ros::Publisher | index_pub_ |
message_filters::Subscriber < sensor_msgs::CameraInfo > | info_sub_ |
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::TimeSynchronizer < sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > | sync_ |
bool | use_images |
Definition at line 36 of file cr_node.cpp.
typedef dynamic_reconfigure::Server<cr_capture::CRCaptureConfig> CRCaptureNode::ReconfigureServer [private] |
Definition at line 66 of file cr_node.cpp.
CRCaptureNode::CRCaptureNode | ( | ) | [inline] |
Definition at line 73 of file cr_node.cpp.
void CRCaptureNode::cameraallCB | ( | const sensor_msgs::ImageConstPtr & | img_c, |
const sensor_msgs::ImageConstPtr & | img_i, | ||
const sensor_msgs::ImageConstPtr & | img_d, | ||
const sensor_msgs::CameraInfoConstPtr & | info | ||
) | [inline] |
Definition at line 251 of file cr_node.cpp.
void CRCaptureNode::cameraleftCB | ( | const sensor_msgs::ImageConstPtr & | img, |
const sensor_msgs::CameraInfoConstPtr & | info | ||
) | [inline] |
Definition at line 223 of file cr_node.cpp.
void CRCaptureNode::camerarangeCB | ( | const sensor_msgs::ImageConstPtr & | img, |
const sensor_msgs::CameraInfoConstPtr & | info | ||
) | [inline] |
Definition at line 271 of file cr_node.cpp.
void CRCaptureNode::camerarightCB | ( | const sensor_msgs::ImageConstPtr & | img, |
const sensor_msgs::CameraInfoConstPtr & | info | ||
) | [inline] |
Definition at line 237 of file cr_node.cpp.
void CRCaptureNode::config_cb | ( | cr_capture::CRCaptureConfig & | config, |
uint32_t | level | ||
) | [inline] |
Definition at line 203 of file cr_node.cpp.
void CRCaptureNode::publishCloud | ( | const std_msgs::Header & | header | ) | [inline] |
Definition at line 287 of file cr_node.cpp.
bool CRCaptureNode::pullData | ( | cr_capture::PullRawDataRequest & | req, |
cr_capture::PullRawDataResponse & | res | ||
) | [inline] |
Definition at line 195 of file cr_node.cpp.
bool CRCaptureNode::calc_pixelpos [private] |
Definition at line 57 of file cr_node.cpp.
Definition at line 40 of file cr_node.cpp.
Definition at line 40 of file cr_node.cpp.
Definition at line 40 of file cr_node.cpp.
ros::Publisher CRCaptureNode::cloud2_pub_ [private] |
Definition at line 42 of file cr_node.cpp.
ros::Publisher CRCaptureNode::cloud_pub_ [private] |
Definition at line 41 of file cr_node.cpp.
CRLib CRCaptureNode::cr_lib_ [private] |
Definition at line 63 of file cr_node.cpp.
message_filters::Subscriber<sensor_msgs::Image> CRCaptureNode::image_conf_sub_ [private] |
Definition at line 49 of file cr_node.cpp.
message_filters::Subscriber<sensor_msgs::Image> CRCaptureNode::image_depth_sub_ [private] |
Definition at line 51 of file cr_node.cpp.
message_filters::Subscriber<sensor_msgs::Image> CRCaptureNode::image_intent_sub_ [private] |
Definition at line 50 of file cr_node.cpp.
ros::Publisher CRCaptureNode::index_pub_ [private] |
Definition at line 43 of file cr_node.cpp.
message_filters::Subscriber<sensor_msgs::CameraInfo> CRCaptureNode::info_sub_ [private] |
Definition at line 52 of file cr_node.cpp.
Definition at line 39 of file cr_node.cpp.
std::string CRCaptureNode::left_ns_ [private] |
Definition at line 46 of file cr_node.cpp.
ros::NodeHandle CRCaptureNode::nh_ [private] |
Definition at line 38 of file cr_node.cpp.
bool CRCaptureNode::pull_raw_data [private] |
Definition at line 59 of file cr_node.cpp.
std::string CRCaptureNode::range_ns_ [private] |
Definition at line 46 of file cr_node.cpp.
Definition at line 70 of file cr_node.cpp.
Definition at line 44 of file cr_node.cpp.
Definition at line 67 of file cr_node.cpp.
std::string CRCaptureNode::right_ns_ [private] |
Definition at line 46 of file cr_node.cpp.
SRCalibratedLib CRCaptureNode::sr_lib_ [private] |
Definition at line 62 of file cr_node.cpp.
message_filters::TimeSynchronizer<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo> CRCaptureNode::sync_ [private] |
Definition at line 54 of file cr_node.cpp.
bool CRCaptureNode::use_images [private] |
Definition at line 58 of file cr_node.cpp.