Public Member Functions | Private Attributes
AllCameraViewer Class Reference

List of all members.

Public Member Functions

 AllCameraViewer (const ros::NodeHandle &node_handle)
 Constructor.
void allModeSrvCallback (const sensor_msgs::ImageConstPtr &left_camera_data, const sensor_msgs::ImageConstPtr &right_camera_data, const sensor_msgs::ImageConstPtr &tof_camera_grey_data)
void connectCallback ()
 Subscribe to camera topics if not already done.
void disconnectCallback ()
 Unsubscribe from camera topics if possible.
bool init ()
unsigned long loadParameters ()
bool saveCameraImagesServiceCallback (cob_camera_sensors::AcquireCalibrationImages::Request &req, cob_camera_sensors::AcquireCalibrationImages::Response &res)
void sharedModeSrvCallback (const sensor_msgs::ImageConstPtr &right_camera_data, const sensor_msgs::ImageConstPtr &tof_camera_grey_data)
void stereoModeSrvCallback (const sensor_msgs::ImageConstPtr &left_camera_data, const sensor_msgs::ImageConstPtr &right_camera_data)
void updateTofGreyscaleData ()
 ~AllCameraViewer ()
 Destructor.

Private Attributes

std::string absolute_output_directory_path_
 Directory, where camera images are saved.
message_filters::TimeSynchronizer
< sensor_msgs::Image,
sensor_msgs::Image,
sensor_msgs::Image > 
all_sub_sync_
sensor_msgs::Image color_image_msg_
 Number of accumulated tog greyscale images.
sensor_msgs::Image confidence_mask_msg_
sensor_msgs::CvBridge cv_bridge_0_
 Converts ROS image messages to openCV IplImages.
sensor_msgs::CvBridge cv_bridge_1_
 Converts ROS image messages to openCV IplImages.
sensor_msgs::CvBridge cv_bridge_2_
 Converts ROS image messages to openCV IplImages.
IplImage * grey_image_32F1_
 Received gray values from tof sensor.
cv::Mat grey_mat_32F1_
 Received gray values from tof sensor.
cv::Mat grey_mat_8U1_
 Received gray values from tof sensor.
int image_counter_
 Counts the number of images saved to the hard disk.
image_transport::ImageTransport image_transport_
message_filters::Subscriber
< sensor_msgs::CameraInfo > 
left_camera_info_sub_
 Left camera information service.
image_transport::SubscriberFilter left_color_camera_image_sub_
 Left color camera image topic.
IplImage * left_color_image_8U3_
 Received color image of the left camera.
cv::Mat left_color_mat_8U3_
 Received color image of the left camera.
boost::mutex m_ServiceMutex
ros::NodeHandle node_handle_
message_filters::Subscriber
< sensor_msgs::CameraInfo > 
right_camera_info_sub_
 Right camera information service.
image_transport::SubscriberFilter right_color_camera_image_sub_
 Right color camera image topic.
IplImage * right_color_image_8U3_
 Received color image of the right camera.
cv::Mat right_color_mat_8U3_
 Received color image of the right camera.
ros::ServiceServer save_camera_images_service_
message_filters::TimeSynchronizer
< sensor_msgs::Image,
sensor_msgs::Image,
sensor_msgs::Image > 
shared_sub_sync_
message_filters::TimeSynchronizer
< sensor_msgs::Image,
sensor_msgs::Image > 
stereo_sub_sync_
image_transport::Subscriber sub
int sub_counter_
image_transport::SubscriberFilter tof_camera_grey_image_sub_
 Tof camera intensity image topic.
int tof_image_counter_
 Number of subscribers to topic.
bool use_left_color_camera_
bool use_right_color_camera_
bool use_tof_camera_
std::vector< cv::Mat > vec_grey_mat_32F1_
 Accumulated tof greyscale images for noise reduction.
IplImage * xyz_image_32F3_
 Received point cloud form tof sensor.
sensor_msgs::Image xyz_image_msg_
cv::Mat xyz_mat_32F3_
 Received point cloud form tof sensor.

Detailed Description

This node gathers images from either 'two color cameras' or 'one color camera and ont time-of-flight sensor' of 'two color cameras and one time-of-flight sensor' of 'a single camera and odometry commands' to create a coloured point cloud out of the provided information

Definition at line 61 of file all_camera_viewer.cpp.


Constructor & Destructor Documentation

AllCameraViewer::AllCameraViewer ( const ros::NodeHandle node_handle) [inline]

Constructor.

Definition at line 125 of file all_camera_viewer.cpp.

Destructor.

Definition at line 151 of file all_camera_viewer.cpp.


Member Function Documentation

void AllCameraViewer::allModeSrvCallback ( const sensor_msgs::ImageConstPtr &  left_camera_data,
const sensor_msgs::ImageConstPtr &  right_camera_data,
const sensor_msgs::ImageConstPtr &  tof_camera_grey_data 
) [inline]

Definition at line 254 of file all_camera_viewer.cpp.

Subscribe to camera topics if not already done.

Definition at line 205 of file all_camera_viewer.cpp.

Unsubscribe from camera topics if possible.

Definition at line 230 of file all_camera_viewer.cpp.

bool AllCameraViewer::init ( ) [inline]

Initialize sensor fusion node. Setup publisher of point cloud and corresponding color data, setup camera toolboxes and colored point cloud toolbox

Returns:
true on success, false otherwise

Definition at line 159 of file all_camera_viewer.cpp.

unsigned long AllCameraViewer::loadParameters ( ) [inline]

Parameters are set within the launch file

Definition at line 474 of file all_camera_viewer.cpp.

bool AllCameraViewer::saveCameraImagesServiceCallback ( cob_camera_sensors::AcquireCalibrationImages::Request &  req,
cob_camera_sensors::AcquireCalibrationImages::Response &  res 
) [inline]

Definition at line 412 of file all_camera_viewer.cpp.

void AllCameraViewer::sharedModeSrvCallback ( const sensor_msgs::ImageConstPtr &  right_camera_data,
const sensor_msgs::ImageConstPtr &  tof_camera_grey_data 
) [inline]

Callback is executed, when shared mode is selected. Left and right is expressed when facing the back of the camera in horitontal orientation.

Definition at line 301 of file all_camera_viewer.cpp.

void AllCameraViewer::stereoModeSrvCallback ( const sensor_msgs::ImageConstPtr &  left_camera_data,
const sensor_msgs::ImageConstPtr &  right_camera_data 
) [inline]

Callback is executed, when stereo mode is selected Left and right is expressed when facing the back of the camera in horizontal orientation.

Definition at line 378 of file all_camera_viewer.cpp.

Accumulates tof greyscale images, computes the average image out of it applies histogram normalization and final performs upscaling to generate better images for calibration

Definition at line 338 of file all_camera_viewer.cpp.


Member Data Documentation

Directory, where camera images are saved.

Definition at line 118 of file all_camera_viewer.cpp.

message_filters::TimeSynchronizer<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image> AllCameraViewer::all_sub_sync_ [private]

Definition at line 86 of file all_camera_viewer.cpp.

sensor_msgs::Image AllCameraViewer::color_image_msg_ [private]

Number of accumulated tog greyscale images.

Definition at line 92 of file all_camera_viewer.cpp.

sensor_msgs::Image AllCameraViewer::confidence_mask_msg_ [private]

Definition at line 94 of file all_camera_viewer.cpp.

sensor_msgs::CvBridge AllCameraViewer::cv_bridge_0_ [private]

Converts ROS image messages to openCV IplImages.

Definition at line 110 of file all_camera_viewer.cpp.

sensor_msgs::CvBridge AllCameraViewer::cv_bridge_1_ [private]

Converts ROS image messages to openCV IplImages.

Definition at line 111 of file all_camera_viewer.cpp.

sensor_msgs::CvBridge AllCameraViewer::cv_bridge_2_ [private]

Converts ROS image messages to openCV IplImages.

Definition at line 112 of file all_camera_viewer.cpp.

IplImage* AllCameraViewer::grey_image_32F1_ [private]

Received gray values from tof sensor.

Definition at line 99 of file all_camera_viewer.cpp.

Received gray values from tof sensor.

Definition at line 104 of file all_camera_viewer.cpp.

cv::Mat AllCameraViewer::grey_mat_8U1_ [private]

Received gray values from tof sensor.

Definition at line 105 of file all_camera_viewer.cpp.

Counts the number of images saved to the hard disk.

Definition at line 108 of file all_camera_viewer.cpp.

Definition at line 66 of file all_camera_viewer.cpp.

Left camera information service.

Definition at line 72 of file all_camera_viewer.cpp.

Left color camera image topic.

Definition at line 69 of file all_camera_viewer.cpp.

Received color image of the left camera.

Definition at line 97 of file all_camera_viewer.cpp.

Received color image of the left camera.

Definition at line 102 of file all_camera_viewer.cpp.

boost::mutex AllCameraViewer::m_ServiceMutex [private]

Definition at line 116 of file all_camera_viewer.cpp.

Definition at line 64 of file all_camera_viewer.cpp.

Right camera information service.

Definition at line 73 of file all_camera_viewer.cpp.

Right color camera image topic.

Definition at line 70 of file all_camera_viewer.cpp.

Received color image of the right camera.

Definition at line 96 of file all_camera_viewer.cpp.

Received color image of the right camera.

Definition at line 101 of file all_camera_viewer.cpp.

Definition at line 114 of file all_camera_viewer.cpp.

message_filters::TimeSynchronizer<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image> AllCameraViewer::shared_sub_sync_ [private]

Definition at line 82 of file all_camera_viewer.cpp.

message_filters::TimeSynchronizer<sensor_msgs::Image, sensor_msgs::Image> AllCameraViewer::stereo_sub_sync_ [private]

Definition at line 84 of file all_camera_viewer.cpp.

Definition at line 74 of file all_camera_viewer.cpp.

Definition at line 89 of file all_camera_viewer.cpp.

Tof camera intensity image topic.

Definition at line 71 of file all_camera_viewer.cpp.

Number of subscribers to topic.

Definition at line 90 of file all_camera_viewer.cpp.

Definition at line 121 of file all_camera_viewer.cpp.

Definition at line 122 of file all_camera_viewer.cpp.

Definition at line 120 of file all_camera_viewer.cpp.

std::vector<cv::Mat> AllCameraViewer::vec_grey_mat_32F1_ [private]

Accumulated tof greyscale images for noise reduction.

Definition at line 106 of file all_camera_viewer.cpp.

IplImage* AllCameraViewer::xyz_image_32F3_ [private]

Received point cloud form tof sensor.

Definition at line 98 of file all_camera_viewer.cpp.

sensor_msgs::Image AllCameraViewer::xyz_image_msg_ [private]

Definition at line 93 of file all_camera_viewer.cpp.

cv::Mat AllCameraViewer::xyz_mat_32F3_ [private]

Received point cloud form tof sensor.

Definition at line 103 of file all_camera_viewer.cpp.


The documentation for this class was generated from the following file:


cob_camera_sensors
Author(s): Jan Fischer , Richard Bormann
autogenerated on Sat Jun 8 2019 21:02:02