Public Member Functions | Static Public Member Functions | Private Types | Private Member Functions | Private Attributes
bta_tof_driver::BtaRos Class Reference

#include <bta_tof_driver.hpp>

List of all members.

Public Member Functions

 BtaRos (ros::NodeHandle nh_camera, ros::NodeHandle nh_private, std::string nodeName)
 Class constructor.
void close ()
 Closes the connection to the device.
int connectCamera ()
 Helper for connect to the device.
int initialize ()
 Initializes the device and parameters.
void publishData ()
 Publish the data based on set up parameters.
virtual ~BtaRos ()
 Class destructor.

Static Public Member Functions

static void BTA_CALLCONV infoEventCb (BTA_EventId eventId, int8_t *msg)

Private Types

typedef
bta_tof_driver::bta_tof_driverConfig 
Config
typedef
dynamic_reconfigure::Server
< Config
ReconfigureServer

Private Member Functions

void callback (bta_tof_driver::bta_tof_driverConfig &config, uint32_t level)
 Callback for rqt_reconfigure. It is called any time we change a parameter in the visual interface.
size_t getDataSize (BTA_DataFormat dataFormat)
 Returns the size of the data based in BTA_DataFormat.
std::string getDataType (BTA_DataFormat dataFormat)
 Returns the data encoding flat based in BTA_DataFormat.
float getUnit2Meters (BTA_Unit unit)
 Gives the conversion value to meters from the BTA_Unit.
void parseConfig ()
 Reads configuration from the server parameters.

Private Attributes

sensor_msgs::PointCloud2Ptr _xyz
std::string calibFileName_
camera_info_manager::CameraInfoManager cim_tof_
BTA_Config config_
bool config_init_
boost::mutex connect_mutex_
BTA_Handle handle_
image_transport::ImageTransport it_
ros::NodeHandle nh_
ros::NodeHandle nh_private_
std::string nodeName_
image_transport::CameraPublisher pub_amp_
image_transport::CameraPublisher pub_dis_
tf2_ros::StaticTransformBroadcaster pub_tf
ros::Publisher pub_xyz_
boost::shared_ptr
< ReconfigureServer
reconfigure_server_
uint8_t tcpDeviceIpAddr_ [6]
geometry_msgs::TransformStamped transformStamped
std::string uartPortName_
uint8_t udpControlInIpAddr_ [6]
uint8_t udpControlOutIpAddr_ [6]
uint8_t udpDataIpAddr_ [6]

Detailed Description

Definition at line 83 of file bta_tof_driver.hpp.


Member Typedef Documentation

typedef bta_tof_driver::bta_tof_driverConfig bta_tof_driver::BtaRos::Config [private]

Definition at line 86 of file bta_tof_driver.hpp.

typedef dynamic_reconfigure::Server<Config> bta_tof_driver::BtaRos::ReconfigureServer [private]

Definition at line 87 of file bta_tof_driver.hpp.


Constructor & Destructor Documentation

bta_tof_driver::BtaRos::BtaRos ( ros::NodeHandle  nh_camera,
ros::NodeHandle  nh_private,
std::string  nodeName 
)

Class constructor.

param [in] ros::NodeHandle param [in] ros::NodeHandle param [in] std::string

Definition at line 48 of file bta_tof_driver.cpp.

Class destructor.

Definition at line 81 of file bta_tof_driver.cpp.


Member Function Documentation

void bta_tof_driver::BtaRos::callback ( bta_tof_driver::bta_tof_driverConfig &  config,
uint32_t  level 
) [private]

Callback for rqt_reconfigure. It is called any time we change a parameter in the visual interface.

Parameters:
[in]bta_tof_driver::bta_tof_driverConfig
[in]uint32_t

Definition at line 101 of file bta_tof_driver.cpp.

Closes the connection to the device.

Definition at line 87 of file bta_tof_driver.cpp.

Helper for connect to the device.

Definition at line 571 of file bta_tof_driver.cpp.

size_t bta_tof_driver::BtaRos::getDataSize ( BTA_DataFormat  dataFormat) [private]

Returns the size of the data based in BTA_DataFormat.

Definition at line 204 of file bta_tof_driver.cpp.

std::string bta_tof_driver::BtaRos::getDataType ( BTA_DataFormat  dataFormat) [private]

Returns the data encoding flat based in BTA_DataFormat.

Definition at line 218 of file bta_tof_driver.cpp.

float bta_tof_driver::BtaRos::getUnit2Meters ( BTA_Unit  unit) [private]

Gives the conversion value to meters from the BTA_Unit.

Parameters:
unit
Returns:
the value to multiply to the data.

Definition at line 232 of file bta_tof_driver.cpp.

static void BTA_CALLCONV bta_tof_driver::BtaRos::infoEventCb ( BTA_EventId  eventId,
int8_t *  msg 
) [inline, static]

Definition at line 142 of file bta_tof_driver.hpp.

Initializes the device and parameters.

Definition at line 616 of file bta_tof_driver.cpp.

Reads configuration from the server parameters.

Definition at line 434 of file bta_tof_driver.cpp.

Publish the data based on set up parameters.

Definition at line 247 of file bta_tof_driver.cpp.


Member Data Documentation

sensor_msgs::PointCloud2Ptr bta_tof_driver::BtaRos::_xyz [private]

Definition at line 166 of file bta_tof_driver.hpp.

Definition at line 164 of file bta_tof_driver.hpp.

Definition at line 149 of file bta_tof_driver.hpp.

BTA_Config bta_tof_driver::BtaRos::config_ [private]

Definition at line 169 of file bta_tof_driver.hpp.

Definition at line 157 of file bta_tof_driver.hpp.

Definition at line 159 of file bta_tof_driver.hpp.

BTA_Handle bta_tof_driver::BtaRos::handle_ [private]

Definition at line 168 of file bta_tof_driver.hpp.

Definition at line 150 of file bta_tof_driver.hpp.

Definition at line 147 of file bta_tof_driver.hpp.

Definition at line 147 of file bta_tof_driver.hpp.

std::string bta_tof_driver::BtaRos::nodeName_ [private]

Definition at line 148 of file bta_tof_driver.hpp.

Definition at line 151 of file bta_tof_driver.hpp.

Definition at line 151 of file bta_tof_driver.hpp.

Definition at line 152 of file bta_tof_driver.hpp.

Definition at line 154 of file bta_tof_driver.hpp.

Definition at line 156 of file bta_tof_driver.hpp.

Definition at line 162 of file bta_tof_driver.hpp.

geometry_msgs::TransformStamped bta_tof_driver::BtaRos::transformStamped [private]

Definition at line 153 of file bta_tof_driver.hpp.

Definition at line 164 of file bta_tof_driver.hpp.

Definition at line 162 of file bta_tof_driver.hpp.

Definition at line 162 of file bta_tof_driver.hpp.

Definition at line 162 of file bta_tof_driver.hpp.


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


bta_tof_driver
Author(s): Angel Merino , Simon Vogl
autogenerated on Thu Jun 20 2019 19:58:11