Public Member Functions | Private Attributes | List of all members
UndistortTOF Class Reference

Public Member Functions

unsigned long GetCalibratedXYMatlab (int u, int v, float z, float &x, float &y)
 
unsigned long GetCalibratedZSwissranger (int u, int v, int width, float &zCalibrated)
 
void Undistort (const boost::shared_ptr< sensor_msgs::PointCloud2 const > &tof_camera_data, const sensor_msgs::CameraInfoConstPtr &camera_info)
 
 UndistortTOF (const ros::NodeHandle &node_handle)
 

Private Attributes

ros::NodeHandle node_handle_
 
sensor_msgs::PointCloud2 pc2_msg_
 
ros::Publisher pub_pc2_
 
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_pc2_
 
message_filters::Synchronizer< SyncPolicysub_sync_
 

Detailed Description

Definition at line 44 of file undistort_tof.cpp.

Constructor & Destructor Documentation

UndistortTOF::UndistortTOF ( const ros::NodeHandle node_handle)
inline

Definition at line 56 of file undistort_tof.cpp.

Member Function Documentation

unsigned long UndistortTOF::GetCalibratedXYMatlab ( int  u,
int  v,
float  z,
float &  x,
float &  y 
)
inline

Definition at line 76 of file undistort_tof.cpp.

unsigned long UndistortTOF::GetCalibratedZSwissranger ( int  u,
int  v,
int  width,
float &  zCalibrated 
)
inline

Definition at line 68 of file undistort_tof.cpp.

void UndistortTOF::Undistort ( const boost::shared_ptr< sensor_msgs::PointCloud2 const > &  tof_camera_data,
const sensor_msgs::CameraInfoConstPtr &  camera_info 
)
inline

Definition at line 109 of file undistort_tof.cpp.

Member Data Documentation

ros::NodeHandle UndistortTOF::node_handle_
private

Definition at line 47 of file undistort_tof.cpp.

sensor_msgs::PointCloud2 UndistortTOF::pc2_msg_
private

Definition at line 48 of file undistort_tof.cpp.

ros::Publisher UndistortTOF::pub_pc2_
private

Definition at line 53 of file undistort_tof.cpp.

message_filters::Subscriber<sensor_msgs::CameraInfo> UndistortTOF::sub_camera_info_
private

Definition at line 51 of file undistort_tof.cpp.

message_filters::Subscriber<sensor_msgs::PointCloud2> UndistortTOF::sub_pc2_
private

Definition at line 50 of file undistort_tof.cpp.

message_filters::Synchronizer<SyncPolicy> UndistortTOF::sub_sync_
private

Definition at line 52 of file undistort_tof.cpp.


The documentation for this class was generated from the following file:


cob_camera_sensors
Author(s): Jan Fischer , Richard Bormann
autogenerated on Thu Mar 19 2020 03:23:05