Public Member Functions | |
CobColorCameraNode (const ros::NodeHandle &node_handle) | |
bool | init () |
Opens the camera sensor. | |
bool | loadParameters () |
void | pollCallback (polled_camera::GetPolledImage::Request &req, polled_camera::GetPolledImage::Response &res, sensor_msgs::Image &image_msg, sensor_msgs::CameraInfo &info) |
Callback function for image requests on topic 'request_image'. | |
bool | setCameraInfo (sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp) |
~CobColorCameraNode () | |
Private Attributes | |
int | camera_index_ |
Camera index of the color camera for IPA configuration file. | |
sensor_msgs::CameraInfo | camera_info_msg_ |
ROS camera information message (e.g. holding intrinsic parameters) | |
ros::ServiceServer | camera_info_service_ |
AbstractColorCameraPtr | color_camera_ |
Color camera instance. | |
int | color_camera_intrinsic_id_ |
Instrinsic matrix id of left color camera. | |
ipa_CameraSensors::t_cameraType | color_camera_intrinsic_type_ |
Instrinsic matrix type of left color camera. | |
cv::Mat | color_image_8U3_ |
std::string | config_directory_ |
Directory of related IPA configuration file. | |
polled_camera::PublicationServer | image_poll_server_ |
ros::NodeHandle | node_handle_ |
ROS node to interface color cameras.
Definition at line 79 of file color_camera.cpp.
CobColorCameraNode::CobColorCameraNode | ( | const ros::NodeHandle & | node_handle | ) | [inline] |
Void
Definition at line 99 of file color_camera.cpp.
CobColorCameraNode::~CobColorCameraNode | ( | ) | [inline] |
Definition at line 107 of file color_camera.cpp.
bool CobColorCameraNode::init | ( | ) | [inline] |
Opens the camera sensor.
Read camera properties of range tof sensor
Setup camera toolbox
Advertise service for other nodes to set intrinsic calibration parameters
Topics to publish
Definition at line 114 of file color_camera.cpp.
bool CobColorCameraNode::loadParameters | ( | ) | [inline] |
Parameters are set within the launch file
Parameters are set within the launch file
Definition at line 253 of file color_camera.cpp.
void CobColorCameraNode::pollCallback | ( | polled_camera::GetPolledImage::Request & | req, |
polled_camera::GetPolledImage::Response & | res, | ||
sensor_msgs::Image & | image_msg, | ||
sensor_msgs::CameraInfo & | info | ||
) | [inline] |
Callback function for image requests on topic 'request_image'.
Acquire new image
Set time stamp
Definition at line 209 of file color_camera.cpp.
bool CobColorCameraNode::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 196 of file color_camera.cpp.
int CobColorCameraNode::camera_index_ [private] |
Camera index of the color camera for IPA configuration file.
Definition at line 88 of file color_camera.cpp.
sensor_msgs::CameraInfo CobColorCameraNode::camera_info_msg_ [private] |
ROS camera information message (e.g. holding intrinsic parameters)
Definition at line 92 of file color_camera.cpp.
Definition at line 94 of file color_camera.cpp.
Color camera instance.
Definition at line 85 of file color_camera.cpp.
int CobColorCameraNode::color_camera_intrinsic_id_ [private] |
Instrinsic matrix id of left color camera.
Definition at line 89 of file color_camera.cpp.
ipa_CameraSensors::t_cameraType CobColorCameraNode::color_camera_intrinsic_type_ [private] |
Instrinsic matrix type of left color camera.
Definition at line 90 of file color_camera.cpp.
cv::Mat CobColorCameraNode::color_image_8U3_ [private] |
Definition at line 96 of file color_camera.cpp.
std::string CobColorCameraNode::config_directory_ [private] |
Directory of related IPA configuration file.
Definition at line 87 of file color_camera.cpp.
Definition at line 83 of file color_camera.cpp.
Definition at line 82 of file color_camera.cpp.