Public Member Functions | |
CobTofCameraNode (const ros::NodeHandle &node_handle) | |
Constructor. More... | |
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. More... | |
~CobTofCameraNode () | |
Destructor. More... | |
Private Types | |
enum | t_Mode { MODE_TOPIC = 0, MODE_SERVICE } |
Definition at line 49 of file tof_camera.cpp.
|
private |
Enumerator | |
---|---|
MODE_TOPIC | |
MODE_SERVICE |
Definition at line 51 of file tof_camera.cpp.
|
inline |
|
inline |
Destructor.
Definition at line 106 of file tof_camera.cpp.
|
inline |
Definition at line 350 of file tof_camera.cpp.
|
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 113 of file tof_camera.cpp.
|
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 376 of file tof_camera.cpp.
|
inline |
Definition at line 276 of file tof_camera.cpp.
|
inline |
Definition at line 303 of file tof_camera.cpp.
|
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 199 of file tof_camera.cpp.
|
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.
|
private |
ROS camera information message (e.g. holding intrinsic parameters)
Definition at line 66 of file tof_camera.cpp.
|
private |
Service to set/modify camera parameters.
Definition at line 68 of file tof_camera.cpp.
|
private |
Directory of related IPA configuration file.
Definition at line 73 of file tof_camera.cpp.
|
private |
Definition at line 76 of file tof_camera.cpp.
|
private |
Definition at line 77 of file tof_camera.cpp.
|
private |
OpenCV image holding the point cloud.
Definition at line 83 of file tof_camera.cpp.
|
private |
Publishes grey image data.
Definition at line 62 of file tof_camera.cpp.
|
private |
Definition at line 69 of file tof_camera.cpp.
|
private |
Image transport instance.
Definition at line 60 of file tof_camera.cpp.
|
private |
Definition at line 78 of file tof_camera.cpp.
|
private |
Node handle.
Definition at line 58 of file tof_camera.cpp.
|
private |
Definition at line 88 of file tof_camera.cpp.
|
private |
Definition at line 89 of file tof_camera.cpp.
|
private |
OpenCV image holding the amplitude values.
Specifies if node is started as topic or service
Definition at line 85 of file tof_camera.cpp.
|
private |
Definition at line 86 of file tof_camera.cpp.
|
private |
Definition at line 80 of file tof_camera.cpp.
|
private |
Time-of-flight camera instance.
Definition at line 71 of file tof_camera.cpp.
|
private |
Camera index of the color camera for IPA configuration file.
Definition at line 74 of file tof_camera.cpp.
|
private |
Type of tof camera.
Definition at line 75 of file tof_camera.cpp.
|
private |
Definition at line 64 of file tof_camera.cpp.
|
private |
Definition at line 63 of file tof_camera.cpp.
|
private |
Definition at line 79 of file tof_camera.cpp.
|
private |
Definition at line 82 of file tof_camera.cpp.
|
private |
Publishes xyz image data.
Definition at line 61 of file tof_camera.cpp.