Definition at line 38 of file tof_camera_viewer.cpp.
◆ CobTofCameraViewerNode()
| CobTofCameraViewerNode::CobTofCameraViewerNode |
( |
const ros::NodeHandle & |
node_handle | ) |
|
|
inline |
◆ ~CobTofCameraViewerNode()
| CobTofCameraViewerNode::~CobTofCameraViewerNode |
( |
| ) |
|
|
inline |
Destructor.
Do not release m_GrayImage32F3 Do not release xyz_image_32F3_ Image allocation is managed by Cv_Bridge object
Definition at line 73 of file tof_camera_viewer.cpp.
◆ greyImageCallback()
| void CobTofCameraViewerNode::greyImageCallback |
( |
const sensor_msgs::ImageConstPtr & |
grey_image_msg | ) |
|
|
inline |
Topic callback functions. Function will be called when a new message arrives on a topic.
- Parameters
-
| grey_image_msg | The gray values of point cloud, saved in a 32bit, 1 channel OpenCV IplImage |
Do not release m_GrayImage32F3 Image allocation is managed by Cv_Bridge object
Definition at line 101 of file tof_camera_viewer.cpp.
◆ init()
| bool CobTofCameraViewerNode::init |
( |
| ) |
|
|
inline |
initialize tof camera viewer.
- Returns
false on failure, true otherwise
Create viewer windows
Definition at line 85 of file tof_camera_viewer.cpp.
◆ xyzImageCallback()
| void CobTofCameraViewerNode::xyzImageCallback |
( |
const sensor_msgs::ImageConstPtr & |
xyz_image_msg | ) |
|
|
inline |
Topic callback functions. Function will be called when a new message arrives on a topic.
- Parameters
-
| xyz_image_msg | The point cloud, saved in a 32bit, 3 channel OpenCV IplImage |
Do not release xyz_image_32F3_ Image allocation is managed by Cv_Bridge object
Definition at line 139 of file tof_camera_viewer.cpp.
◆ cv_bridge_0_
| sensor_msgs::CvBridge CobTofCameraViewerNode::cv_bridge_0_ |
|
private |
◆ cv_bridge_1_
| sensor_msgs::CvBridge CobTofCameraViewerNode::cv_bridge_1_ |
|
private |
◆ grey_image_32F1_
| IplImage* CobTofCameraViewerNode::grey_image_32F1_ |
|
private |
◆ grey_image_counter_
| int CobTofCameraViewerNode::grey_image_counter_ |
|
private |
OpenCV image holding the transformed 8bit RGB amplitude values.
Definition at line 55 of file tof_camera_viewer.cpp.
◆ grey_image_subscriber_
◆ grey_mat_8U3_
| cv::Mat CobTofCameraViewerNode::grey_mat_8U3_ |
|
private |
◆ image_transport_
◆ m_NodeHandle
◆ xyz_image_32F3_
| IplImage* CobTofCameraViewerNode::xyz_image_32F3_ |
|
private |
◆ xyz_image_subscriber_
◆ xyz_mat_8U3_
| cv::Mat CobTofCameraViewerNode::xyz_mat_8U3_ |
|
private |
The documentation for this class was generated from the following file: