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. |
Definition at line 45 of file all_cameras.cpp.
CobAllCamerasNode::CobAllCamerasNode | ( | const ros::NodeHandle & | node_handle | ) | [inline] |
Void
Definition at line 88 of file all_cameras.cpp.
CobAllCamerasNode::~CobAllCamerasNode | ( | ) | [inline] |
Definition at line 102 of file all_cameras.cpp.
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 123 of file all_cameras.cpp.
bool CobAllCamerasNode::loadParameters | ( | ) | [inline] |
Parameters are set within the launch file
Definition at line 460 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.
req | Requested camera parameters |
rsp | Response, telling if requested parameters have been set |
True
: Enable the setting of intrinsic parameters
Definition at line 313 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 326 of file all_cameras.cpp.
std::string CobAllCamerasNode::config_directory_ [private] |
Directory of the configuration files.
Definition at line 54 of file all_cameras.cpp.
cv::Mat CobAllCamerasNode::grey_tof_image_32F1_ [private] |
OpenCV image holding the point cloud from tof sensor.
Definition at line 79 of file all_cameras.cpp.
Publishes grey image data.
Definition at line 83 of file all_cameras.cpp.
OpenCV image holding the amplitude values of the point cloud.
Image transport instance
Definition at line 81 of file all_cameras.cpp.
AbstractColorCameraPtr CobAllCamerasNode::left_color_camera_ [private] |
Color camera instance.
Definition at line 50 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 68 of file all_cameras.cpp.
Definition at line 72 of file all_cameras.cpp.
int CobAllCamerasNode::left_color_camera_intrinsic_id_ [private] |
Instrinsic matrix id of left color camera.
Definition at line 60 of file all_cameras.cpp.
Instrinsic matrix type of left color camera.
Definition at line 64 of file all_cameras.cpp.
std::string CobAllCamerasNode::left_color_camera_ns_ [private] |
Namespace name of left color camera.
Definition at line 56 of file all_cameras.cpp.
cv::Mat CobAllCamerasNode::left_color_image_8U3_ [private] |
color image of left camera
Definition at line 76 of file all_cameras.cpp.
Publishes grey image data.
Definition at line 84 of file all_cameras.cpp.
Definition at line 48 of file all_cameras.cpp.
AbstractColorCameraPtr CobAllCamerasNode::right_color_camera_ [private] |
Color camera instance.
Definition at line 51 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 69 of file all_cameras.cpp.
Definition at line 73 of file all_cameras.cpp.
int CobAllCamerasNode::right_color_camera_intrinsic_id_ [private] |
Instrinsic matrix id of right color camera.
Definition at line 61 of file all_cameras.cpp.
Instrinsic matrix type of right color camera.
Definition at line 65 of file all_cameras.cpp.
std::string CobAllCamerasNode::right_color_camera_ns_ [private] |
Namespace name of left color camera.
Definition at line 57 of file all_cameras.cpp.
cv::Mat CobAllCamerasNode::right_color_image_8U3_ [private] |
color image of right camera
Definition at line 77 of file all_cameras.cpp.
Publishes grey image data.
Definition at line 85 of file all_cameras.cpp.
AbstractRangeImagingSensorPtr CobAllCamerasNode::tof_camera_ [private] |
Time-of-flight camera instance.
Definition at line 52 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 70 of file all_cameras.cpp.
Definition at line 74 of file all_cameras.cpp.
int CobAllCamerasNode::tof_camera_intrinsic_id_ [private] |
Instrinsic matrix id of tof camera.
Definition at line 62 of file all_cameras.cpp.
Instrinsic matrix type of tof camera.
Definition at line 66 of file all_cameras.cpp.
std::string CobAllCamerasNode::tof_camera_ns_ [private] |
Namespace name of left color camera.
Definition at line 58 of file all_cameras.cpp.
cv::Mat CobAllCamerasNode::xyz_tof_image_32F3_ [private] |
Definition at line 78 of file all_cameras.cpp.
Publishes xyz image data.
Definition at line 82 of file all_cameras.cpp.