Public Member Functions | Static Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
bta_tof_driver::BtaRos Class Reference

#include <bta_tof_driver.hpp>

Public Member Functions

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

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< ConfigReconfigureServer
 

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. More...
 
size_t getDataSize (BTA_DataFormat dataFormat)
 Returns the size of the data based in BTA_DataFormat. More...
 
std::string getDataType (BTA_DataFormat dataFormat)
 Returns the data encoding flat based in BTA_DataFormat. More...
 
float getUnit2Meters (BTA_Unit unit)
 Gives the conversion value to meters from the BTA_Unit. More...
 
void parseConfig ()
 Reads configuration from the server parameters. More...
 

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< ReconfigureServerreconfigure_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

◆ Config

typedef bta_tof_driver::bta_tof_driverConfig bta_tof_driver::BtaRos::Config
private

Definition at line 86 of file bta_tof_driver.hpp.

◆ ReconfigureServer

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

Definition at line 87 of file bta_tof_driver.hpp.

Constructor & Destructor Documentation

◆ BtaRos()

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 32 of file bta_tof_driver.cpp.

◆ ~BtaRos()

bta_tof_driver::BtaRos::~BtaRos ( )
virtual

Class destructor.

Definition at line 65 of file bta_tof_driver.cpp.

Member Function Documentation

◆ callback()

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]configa reference to a bta tof driver configuration struct
[in]level

Definition at line 85 of file bta_tof_driver.cpp.

◆ close()

void bta_tof_driver::BtaRos::close ( )

Closes the connection to the device.

Definition at line 71 of file bta_tof_driver.cpp.

◆ connectCamera()

int bta_tof_driver::BtaRos::connectCamera ( )

Helper for connect to the device.

Definition at line 581 of file bta_tof_driver.cpp.

◆ getDataSize()

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

Returns the size of the data based in BTA_DataFormat.

Definition at line 188 of file bta_tof_driver.cpp.

◆ getDataType()

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

Returns the data encoding flat based in BTA_DataFormat.

Definition at line 206 of file bta_tof_driver.cpp.

◆ getUnit2Meters()

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 223 of file bta_tof_driver.cpp.

◆ infoEventCb()

static void BTA_CALLCONV bta_tof_driver::BtaRos::infoEventCb ( BTA_EventId  eventId,
int8_t *  msg 
)
inlinestatic

Definition at line 142 of file bta_tof_driver.hpp.

◆ initialize()

int bta_tof_driver::BtaRos::initialize ( )

Initializes the device and parameters.

Definition at line 626 of file bta_tof_driver.cpp.

◆ parseConfig()

void bta_tof_driver::BtaRos::parseConfig ( )
private

Reads configuration from the server parameters.

Definition at line 446 of file bta_tof_driver.cpp.

◆ publishData()

void bta_tof_driver::BtaRos::publishData ( )

Publish the data based on set up parameters.

Definition at line 238 of file bta_tof_driver.cpp.

Member Data Documentation

◆ _xyz

sensor_msgs::PointCloud2Ptr bta_tof_driver::BtaRos::_xyz
private

Definition at line 166 of file bta_tof_driver.hpp.

◆ calibFileName_

std::string bta_tof_driver::BtaRos::calibFileName_
private

Definition at line 164 of file bta_tof_driver.hpp.

◆ cim_tof_

camera_info_manager::CameraInfoManager bta_tof_driver::BtaRos::cim_tof_
private

Definition at line 149 of file bta_tof_driver.hpp.

◆ config_

BTA_Config bta_tof_driver::BtaRos::config_
private

Definition at line 169 of file bta_tof_driver.hpp.

◆ config_init_

bool bta_tof_driver::BtaRos::config_init_
private

Definition at line 157 of file bta_tof_driver.hpp.

◆ connect_mutex_

boost::mutex bta_tof_driver::BtaRos::connect_mutex_
private

Definition at line 159 of file bta_tof_driver.hpp.

◆ handle_

BTA_Handle bta_tof_driver::BtaRos::handle_
private

Definition at line 168 of file bta_tof_driver.hpp.

◆ it_

image_transport::ImageTransport bta_tof_driver::BtaRos::it_
private

Definition at line 150 of file bta_tof_driver.hpp.

◆ nh_

ros::NodeHandle bta_tof_driver::BtaRos::nh_
private

Definition at line 147 of file bta_tof_driver.hpp.

◆ nh_private_

ros::NodeHandle bta_tof_driver::BtaRos::nh_private_
private

Definition at line 147 of file bta_tof_driver.hpp.

◆ nodeName_

std::string bta_tof_driver::BtaRos::nodeName_
private

Definition at line 148 of file bta_tof_driver.hpp.

◆ pub_amp_

image_transport::CameraPublisher bta_tof_driver::BtaRos::pub_amp_
private

Definition at line 151 of file bta_tof_driver.hpp.

◆ pub_dis_

image_transport::CameraPublisher bta_tof_driver::BtaRos::pub_dis_
private

Definition at line 151 of file bta_tof_driver.hpp.

◆ pub_tf

tf2_ros::StaticTransformBroadcaster bta_tof_driver::BtaRos::pub_tf
private

Definition at line 152 of file bta_tof_driver.hpp.

◆ pub_xyz_

ros::Publisher bta_tof_driver::BtaRos::pub_xyz_
private

Definition at line 154 of file bta_tof_driver.hpp.

◆ reconfigure_server_

boost::shared_ptr<ReconfigureServer> bta_tof_driver::BtaRos::reconfigure_server_
private

Definition at line 156 of file bta_tof_driver.hpp.

◆ tcpDeviceIpAddr_

uint8_t bta_tof_driver::BtaRos::tcpDeviceIpAddr_[6]
private

Definition at line 162 of file bta_tof_driver.hpp.

◆ transformStamped

geometry_msgs::TransformStamped bta_tof_driver::BtaRos::transformStamped
private

Definition at line 153 of file bta_tof_driver.hpp.

◆ uartPortName_

std::string bta_tof_driver::BtaRos::uartPortName_
private

Definition at line 164 of file bta_tof_driver.hpp.

◆ udpControlInIpAddr_

uint8_t bta_tof_driver::BtaRos::udpControlInIpAddr_[6]
private

Definition at line 162 of file bta_tof_driver.hpp.

◆ udpControlOutIpAddr_

uint8_t bta_tof_driver::BtaRos::udpControlOutIpAddr_[6]
private

Definition at line 162 of file bta_tof_driver.hpp.

◆ udpDataIpAddr_

uint8_t bta_tof_driver::BtaRos::udpDataIpAddr_[6]
private

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 Sun Jun 26 2022 02:45:01