Public Member Functions | Private Types | Private Attributes
CobTofCameraNode Class Reference

List of all members.

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.

Detailed Description

Definition at line 49 of file tof_camera.cpp.


Member Enumeration Documentation

enum CobTofCameraNode::t_Mode [private]
Enumerator:
MODE_TOPIC 
MODE_SERVICE 

Definition at line 51 of file tof_camera.cpp.


Constructor & Destructor Documentation

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

Constructor.

Void

Definition at line 93 of file tof_camera.cpp.

Destructor.

Definition at line 106 of file tof_camera.cpp.


Member Function Documentation

bool CobTofCameraNode::imageSrvCallback ( cob_camera_sensors::GetTOFImages::Request &  req,
cob_camera_sensors::GetTOFImages::Response &  res 
) [inline]

Definition at line 350 of file tof_camera.cpp.

bool CobTofCameraNode::init ( ) [inline]

Initializes and opens the time-of-flight camera sensor.

Returns:
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 113 of file tof_camera.cpp.

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 376 of file tof_camera.cpp.

Definition at line 276 of file tof_camera.cpp.

Definition at line 303 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.

Parameters:
reqRequested camera parameters
rspResponse, telling if requested parameters have been set
Returns:
True

TODO: Enable the setting of intrinsic parameters

Definition at line 199 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 212 of file tof_camera.cpp.


Member Data Documentation

sensor_msgs::CameraInfo CobTofCameraNode::camera_info_msg_ [private]

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

Definition at line 66 of file tof_camera.cpp.

Service to set/modify camera parameters.

Definition at line 68 of file tof_camera.cpp.

std::string CobTofCameraNode::config_directory_ [private]

Directory of related IPA configuration file.

Definition at line 73 of file tof_camera.cpp.

Definition at line 76 of file tof_camera.cpp.

Definition at line 77 of file tof_camera.cpp.

OpenCV image holding the point cloud.

Definition at line 83 of file tof_camera.cpp.

Publishes grey image data.

Definition at line 62 of file tof_camera.cpp.

Definition at line 69 of file tof_camera.cpp.

Image transport instance.

Definition at line 60 of file tof_camera.cpp.

Definition at line 78 of file tof_camera.cpp.

Node handle.

Definition at line 58 of file tof_camera.cpp.

Definition at line 88 of file tof_camera.cpp.

Definition at line 89 of file tof_camera.cpp.

OpenCV image holding the amplitude values.

Specifies if node is started as topic or service

Definition at line 85 of file tof_camera.cpp.

boost::mutex CobTofCameraNode::service_mutex_ [private]

Definition at line 86 of file tof_camera.cpp.

Definition at line 80 of file tof_camera.cpp.

AbstractRangeImagingSensorPtr CobTofCameraNode::tof_camera_ [private]

Time-of-flight camera instance.

Definition at line 71 of file tof_camera.cpp.

Camera index of the color camera for IPA configuration file.

Definition at line 74 of file tof_camera.cpp.

Type of tof camera.

Definition at line 75 of file tof_camera.cpp.

Definition at line 64 of file tof_camera.cpp.

Definition at line 63 of file tof_camera.cpp.

Definition at line 79 of file tof_camera.cpp.

Definition at line 82 of file tof_camera.cpp.

Publishes xyz image data.

Definition at line 61 of file tof_camera.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