CobAllCamerasNode Class Reference

List of all members.

Public Member Functions

 CobAllCamerasNode (const ros::NodeHandle &node_handle)
bool init ()
 Opens the camera sensor.
bool loadParameters ()
bool setCameraInfo (sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp)
void spin ()
 Callback function for image requests on topic 'request_image'.
 ~CobAllCamerasNode ()

Private Attributes

std::string config_directory_
 Directory of the configuration files.
cv::Mat grey_tof_image_32F1_
 OpenCV image holding the point cloud from tof sensor.
image_transport::CameraPublisher grey_tof_image_publisher_
 Publishes grey image data.
image_transport::ImageTransport image_transport_
 OpenCV image holding the amplitude values of the point cloud.
AbstractColorCameraPtr left_color_camera_
 Color camera instance.
sensor_msgs::CameraInfo left_color_camera_info_msg_
 ROS camera information message (e.g. holding intrinsic parameters).
ros::ServiceServer left_color_camera_info_service_
int left_color_camera_intrinsic_id_
 Instrinsic matrix id of left color camera.
ipa_CameraSensors::t_cameraType left_color_camera_intrinsic_type_
 Instrinsic matrix type of left color camera.
std::string left_color_camera_ns_
 Namespace name of left color camera.
cv::Mat left_color_image_8U3_
 color image of left camera
image_transport::CameraPublisher left_color_image_publisher_
 Publishes grey image data.
ros::NodeHandle node_handle_
AbstractColorCameraPtr right_color_camera_
 Color camera instance.
sensor_msgs::CameraInfo right_color_camera_info_msg_
 ROS camera information message (e.g. holding intrinsic parameters).
ros::ServiceServer right_color_camera_info_service_
int right_color_camera_intrinsic_id_
 Instrinsic matrix id of right color camera.
ipa_CameraSensors::t_cameraType right_color_camera_intrinsic_type_
 Instrinsic matrix type of right color camera.
std::string right_color_camera_ns_
 Namespace name of left color camera.
cv::Mat right_color_image_8U3_
 color image of right camera
image_transport::CameraPublisher right_color_image_publisher_
 Publishes grey image data.
AbstractRangeImagingSensorPtr tof_camera_
 Time-of-flight camera instance.
sensor_msgs::CameraInfo tof_camera_info_msg_
 ROS camera information message (e.g. holding intrinsic parameters).
ros::ServiceServer tof_camera_info_service_
int tof_camera_intrinsic_id_
 Instrinsic matrix id of tof camera.
ipa_CameraSensors::t_cameraType tof_camera_intrinsic_type_
 Instrinsic matrix type of tof camera.
std::string tof_camera_ns_
 Namespace name of left color camera.
cv::Mat xyz_tof_image_32F3_
image_transport::CameraPublisher xyz_tof_image_publisher_
 Publishes xyz image data.

Detailed Description

Definition at line 80 of file all_cameras.cpp.


Constructor & Destructor Documentation

CobAllCamerasNode::CobAllCamerasNode ( const ros::NodeHandle &  node_handle  )  [inline]

Void

Definition at line 123 of file all_cameras.cpp.

CobAllCamerasNode::~CobAllCamerasNode (  )  [inline]

Definition at line 137 of file all_cameras.cpp.


Member Function Documentation

bool CobAllCamerasNode::init (  )  [inline]

Opens the camera sensor.

Read camera properties of range tof sensor

Setup camera toolbox

Read camera properties of range tof sensor

Setup camera toolbox

Read camera properties of range tof sensor

Setup camera toolbox

Topics and Services to publish

Definition at line 158 of file all_cameras.cpp.

bool CobAllCamerasNode::loadParameters (  )  [inline]

Parameters are set within the launch file

Definition at line 495 of file all_cameras.cpp.

bool CobAllCamerasNode::setCameraInfo ( sensor_msgs::SetCameraInfo::Request &  req,
sensor_msgs::SetCameraInfo::Response &  rsp 
) [inline]

Enables the user to modify camera parameters.

Parameters:
req Requested camera parameters
rsp Response, telling if requested parameters have been set
Returns:
True

: Enable the setting of intrinsic parameters

Definition at line 348 of file all_cameras.cpp.

void CobAllCamerasNode::spin (  )  [inline]

Callback function for image requests on topic 'request_image'.

Acquire new image

Acquire new image

Definition at line 361 of file all_cameras.cpp.


Member Data Documentation

std::string CobAllCamerasNode::config_directory_ [private]

Directory of the configuration files.

Definition at line 89 of file all_cameras.cpp.

OpenCV image holding the point cloud from tof sensor.

Definition at line 114 of file all_cameras.cpp.

image_transport::CameraPublisher CobAllCamerasNode::grey_tof_image_publisher_ [private]

Publishes grey image data.

Definition at line 118 of file all_cameras.cpp.

image_transport::ImageTransport CobAllCamerasNode::image_transport_ [private]

OpenCV image holding the amplitude values of the point cloud.

Image transport instance

Definition at line 116 of file all_cameras.cpp.

AbstractColorCameraPtr CobAllCamerasNode::left_color_camera_ [private]

Color camera instance.

Definition at line 85 of file all_cameras.cpp.

sensor_msgs::CameraInfo CobAllCamerasNode::left_color_camera_info_msg_ [private]

ROS camera information message (e.g. holding intrinsic parameters).

Definition at line 103 of file all_cameras.cpp.

Definition at line 107 of file all_cameras.cpp.

Instrinsic matrix id of left color camera.

Definition at line 95 of file all_cameras.cpp.

ipa_CameraSensors::t_cameraType CobAllCamerasNode::left_color_camera_intrinsic_type_ [private]

Instrinsic matrix type of left color camera.

Definition at line 99 of file all_cameras.cpp.

Namespace name of left color camera.

Definition at line 91 of file all_cameras.cpp.

color image of left camera

Definition at line 111 of file all_cameras.cpp.

image_transport::CameraPublisher CobAllCamerasNode::left_color_image_publisher_ [private]

Publishes grey image data.

Definition at line 119 of file all_cameras.cpp.

ros::NodeHandle CobAllCamerasNode::node_handle_ [private]

Definition at line 83 of file all_cameras.cpp.

AbstractColorCameraPtr CobAllCamerasNode::right_color_camera_ [private]

Color camera instance.

Definition at line 86 of file all_cameras.cpp.

sensor_msgs::CameraInfo CobAllCamerasNode::right_color_camera_info_msg_ [private]

ROS camera information message (e.g. holding intrinsic parameters).

Definition at line 104 of file all_cameras.cpp.

Definition at line 108 of file all_cameras.cpp.

Instrinsic matrix id of right color camera.

Definition at line 96 of file all_cameras.cpp.

ipa_CameraSensors::t_cameraType CobAllCamerasNode::right_color_camera_intrinsic_type_ [private]

Instrinsic matrix type of right color camera.

Definition at line 100 of file all_cameras.cpp.

Namespace name of left color camera.

Definition at line 92 of file all_cameras.cpp.

color image of right camera

Definition at line 112 of file all_cameras.cpp.

image_transport::CameraPublisher CobAllCamerasNode::right_color_image_publisher_ [private]

Publishes grey image data.

Definition at line 120 of file all_cameras.cpp.

AbstractRangeImagingSensorPtr CobAllCamerasNode::tof_camera_ [private]

Time-of-flight camera instance.

Definition at line 87 of file all_cameras.cpp.

sensor_msgs::CameraInfo CobAllCamerasNode::tof_camera_info_msg_ [private]

ROS camera information message (e.g. holding intrinsic parameters).

Definition at line 105 of file all_cameras.cpp.

ros::ServiceServer CobAllCamerasNode::tof_camera_info_service_ [private]

Definition at line 109 of file all_cameras.cpp.

Instrinsic matrix id of tof camera.

Definition at line 97 of file all_cameras.cpp.

ipa_CameraSensors::t_cameraType CobAllCamerasNode::tof_camera_intrinsic_type_ [private]

Instrinsic matrix type of tof camera.

Definition at line 101 of file all_cameras.cpp.

std::string CobAllCamerasNode::tof_camera_ns_ [private]

Namespace name of left color camera.

Definition at line 93 of file all_cameras.cpp.

Definition at line 113 of file all_cameras.cpp.

image_transport::CameraPublisher CobAllCamerasNode::xyz_tof_image_publisher_ [private]

Publishes xyz image data.

Definition at line 117 of file all_cameras.cpp.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


cob_camera_sensors
Author(s): Jan Fischer
autogenerated on Fri Jan 11 10:01:11 2013