Public Member Functions | |
CobTofCameraNode (const ros::NodeHandle &node_handle) | |
Constructor. | |
bool | imageSrvCallback (cob_camera_sensors::GetTOFImages::Request &req, cob_camera_sensors::GetTOFImages::Response &res) |
bool | init () |
bool | loadParameters () |
void | publishPointCloud (ros::Time now) |
void | publishPointCloud2 (ros::Time now) |
bool | setCameraInfo (sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp) |
bool | spin () |
Continuously advertises xyz and grey images. | |
~CobTofCameraNode () | |
Destructor. | |
Private Types | |
enum | t_Mode { MODE_TOPIC = 0, MODE_SERVICE } |
Private Attributes | |
sensor_msgs::CameraInfo | camera_info_msg_ |
ROS camera information message (e.g. holding intrinsic parameters) | |
ros::ServiceServer | camera_info_service_ |
Service to set/modify camera parameters. | |
std::string | config_directory_ |
Directory of related IPA configuration file. | |
bool | filter_xyz_by_amplitude_ |
bool | filter_xyz_tearoff_edges_ |
cv::Mat | grey_image_32F1_ |
OpenCV image holding the point cloud. | |
image_transport::CameraPublisher | grey_image_publisher_ |
Publishes grey image data. | |
ros::ServiceServer | image_service_ |
image_transport::ImageTransport | image_transport_ |
Image transport instance. | |
int | lower_amplitude_threshold_ |
ros::NodeHandle | node_handle_ |
Node handle. | |
bool | publish_point_cloud_ |
bool | publish_point_cloud_2_ |
CobTofCameraNode::t_Mode | ros_node_mode_ |
OpenCV image holding the amplitude values. | |
boost::mutex | service_mutex_ |
double | tearoff_tear_half_fraction_ |
AbstractRangeImagingSensorPtr | tof_camera_ |
Time-of-flight camera instance. | |
int | tof_camera_index_ |
Camera index of the color camera for IPA configuration file. | |
ipa_CameraSensors::t_cameraType | tof_camera_type_ |
Type of tof camera. | |
ros::Publisher | topicPub_pointCloud2_ |
ros::Publisher | topicPub_pointCloud_ |
int | upper_amplitude_threshold_ |
cv::Mat | xyz_image_32F3_ |
image_transport::CameraPublisher | xyz_image_publisher_ |
Publishes xyz image data. |
Definition at line 84 of file tof_camera.cpp.
enum CobTofCameraNode::t_Mode [private] |
Definition at line 86 of file tof_camera.cpp.
CobTofCameraNode::CobTofCameraNode | ( | const ros::NodeHandle & | node_handle | ) | [inline] |
CobTofCameraNode::~CobTofCameraNode | ( | ) | [inline] |
Destructor.
Definition at line 141 of file tof_camera.cpp.
bool CobTofCameraNode::imageSrvCallback | ( | cob_camera_sensors::GetTOFImages::Request & | req, |
cob_camera_sensors::GetTOFImages::Response & | res | ||
) | [inline] |
Definition at line 385 of file tof_camera.cpp.
bool CobTofCameraNode::init | ( | ) | [inline] |
Initializes and opens the time-of-flight camera sensor.
false
on failure, true
otherwise Read camera properties of range tof sensor
Setup camera toolbox
Advertise service for other nodes to set intrinsic calibration parameters
Definition at line 148 of file tof_camera.cpp.
bool CobTofCameraNode::loadParameters | ( | ) | [inline] |
Parameters are set within the launch file
Parameters are set within the launch file
Parameters are set within the launch file
Parameters are set within the launch file
Parameters are set within the launch file
Parameters are set within the launch file
Parameters are set within the launch file
Parameters are set within the launch file
Parameters are set within the launch file
Definition at line 411 of file tof_camera.cpp.
void CobTofCameraNode::publishPointCloud | ( | ros::Time | now | ) | [inline] |
Definition at line 311 of file tof_camera.cpp.
void CobTofCameraNode::publishPointCloud2 | ( | ros::Time | now | ) | [inline] |
Definition at line 338 of file tof_camera.cpp.
bool CobTofCameraNode::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
TODO: Enable the setting of intrinsic parameters
Definition at line 234 of file tof_camera.cpp.
bool CobTofCameraNode::spin | ( | ) | [inline] |
Continuously advertises xyz and grey images.
Filter images by amplitude and remove tear-off edges
Set time stamp
publish message
Definition at line 247 of file tof_camera.cpp.
sensor_msgs::CameraInfo CobTofCameraNode::camera_info_msg_ [private] |
ROS camera information message (e.g. holding intrinsic parameters)
Definition at line 101 of file tof_camera.cpp.
Service to set/modify camera parameters.
Definition at line 103 of file tof_camera.cpp.
std::string CobTofCameraNode::config_directory_ [private] |
Directory of related IPA configuration file.
Definition at line 108 of file tof_camera.cpp.
bool CobTofCameraNode::filter_xyz_by_amplitude_ [private] |
Definition at line 111 of file tof_camera.cpp.
bool CobTofCameraNode::filter_xyz_tearoff_edges_ [private] |
Definition at line 112 of file tof_camera.cpp.
cv::Mat CobTofCameraNode::grey_image_32F1_ [private] |
OpenCV image holding the point cloud.
Definition at line 118 of file tof_camera.cpp.
image_transport::CameraPublisher CobTofCameraNode::grey_image_publisher_ [private] |
Publishes grey image data.
Definition at line 97 of file tof_camera.cpp.
Definition at line 104 of file tof_camera.cpp.
image_transport::ImageTransport CobTofCameraNode::image_transport_ [private] |
Image transport instance.
Definition at line 95 of file tof_camera.cpp.
int CobTofCameraNode::lower_amplitude_threshold_ [private] |
Definition at line 113 of file tof_camera.cpp.
Node handle.
Definition at line 93 of file tof_camera.cpp.
bool CobTofCameraNode::publish_point_cloud_ [private] |
Definition at line 123 of file tof_camera.cpp.
bool CobTofCameraNode::publish_point_cloud_2_ [private] |
Definition at line 124 of file tof_camera.cpp.
OpenCV image holding the amplitude values.
Specifies if node is started as topic or service
Definition at line 120 of file tof_camera.cpp.
boost::mutex CobTofCameraNode::service_mutex_ [private] |
Definition at line 121 of file tof_camera.cpp.
double CobTofCameraNode::tearoff_tear_half_fraction_ [private] |
Definition at line 115 of file tof_camera.cpp.
Time-of-flight camera instance.
Definition at line 106 of file tof_camera.cpp.
int CobTofCameraNode::tof_camera_index_ [private] |
Camera index of the color camera for IPA configuration file.
Definition at line 109 of file tof_camera.cpp.
ipa_CameraSensors::t_cameraType CobTofCameraNode::tof_camera_type_ [private] |
Type of tof camera.
Definition at line 110 of file tof_camera.cpp.
Definition at line 99 of file tof_camera.cpp.
Definition at line 98 of file tof_camera.cpp.
int CobTofCameraNode::upper_amplitude_threshold_ [private] |
Definition at line 114 of file tof_camera.cpp.
cv::Mat CobTofCameraNode::xyz_image_32F3_ [private] |
Definition at line 117 of file tof_camera.cpp.
image_transport::CameraPublisher CobTofCameraNode::xyz_image_publisher_ [private] |
Publishes xyz image data.
Definition at line 96 of file tof_camera.cpp.