#include <bta_ros.hpp>
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_ros::bta_rosConfig | Config |
| typedef dynamic_reconfigure::Server < Config > | ReconfigureServer |
Private Member Functions | |
| void | callback (bta_ros::bta_rosConfig &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] |
Definition at line 82 of file bta_ros.hpp.
typedef bta_ros::bta_rosConfig bta_ros::BtaRos::Config [private] |
Definition at line 85 of file bta_ros.hpp.
typedef dynamic_reconfigure::Server<Config> bta_ros::BtaRos::ReconfigureServer [private] |
Definition at line 86 of file bta_ros.hpp.
| bta_ros::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_ros.cpp.
| bta_ros::BtaRos::~BtaRos | ( | ) | [virtual] |
Class destructor.
Definition at line 81 of file bta_ros.cpp.
| void bta_ros::BtaRos::callback | ( | bta_ros::bta_rosConfig & | config, |
| uint32_t | level | ||
| ) | [private] |
Callback for rqt_reconfigure. It is called any time we change a parameter in the visual interface.
| [in] | bta_ros::bta_rosConfig | |
| [in] | uint32_t |
Definition at line 101 of file bta_ros.cpp.
| void bta_ros::BtaRos::close | ( | ) |
Closes the connection to the device.
Definition at line 87 of file bta_ros.cpp.
| int bta_ros::BtaRos::connectCamera | ( | ) |
Helper for connect to the device.
Definition at line 571 of file bta_ros.cpp.
| size_t bta_ros::BtaRos::getDataSize | ( | BTA_DataFormat | dataFormat | ) | [private] |
Returns the size of the data based in BTA_DataFormat.
Definition at line 204 of file bta_ros.cpp.
| std::string bta_ros::BtaRos::getDataType | ( | BTA_DataFormat | dataFormat | ) | [private] |
Returns the data encoding flat based in BTA_DataFormat.
Definition at line 218 of file bta_ros.cpp.
| float bta_ros::BtaRos::getUnit2Meters | ( | BTA_Unit | unit | ) | [private] |
Gives the conversion value to meters from the BTA_Unit.
| unit |
Definition at line 232 of file bta_ros.cpp.
| static void BTA_CALLCONV bta_ros::BtaRos::infoEventCb | ( | BTA_EventId | eventId, |
| int8_t * | msg | ||
| ) | [inline, static] |
Definition at line 141 of file bta_ros.hpp.
| int bta_ros::BtaRos::initialize | ( | ) |
Initializes the device and parameters.
Definition at line 616 of file bta_ros.cpp.
| void bta_ros::BtaRos::parseConfig | ( | ) | [private] |
Reads configuration from the server parameters.
Definition at line 434 of file bta_ros.cpp.
| void bta_ros::BtaRos::publishData | ( | ) |
Publish the data based on set up parameters.
Definition at line 247 of file bta_ros.cpp.
sensor_msgs::PointCloud2Ptr bta_ros::BtaRos::_xyz [private] |
Definition at line 165 of file bta_ros.hpp.
std::string bta_ros::BtaRos::calibFileName_ [private] |
Definition at line 163 of file bta_ros.hpp.
Definition at line 148 of file bta_ros.hpp.
BTA_Config bta_ros::BtaRos::config_ [private] |
Definition at line 168 of file bta_ros.hpp.
bool bta_ros::BtaRos::config_init_ [private] |
Definition at line 156 of file bta_ros.hpp.
boost::mutex bta_ros::BtaRos::connect_mutex_ [private] |
Definition at line 158 of file bta_ros.hpp.
BTA_Handle bta_ros::BtaRos::handle_ [private] |
Definition at line 167 of file bta_ros.hpp.
Definition at line 149 of file bta_ros.hpp.
ros::NodeHandle bta_ros::BtaRos::nh_ [private] |
Definition at line 146 of file bta_ros.hpp.
ros::NodeHandle bta_ros::BtaRos::nh_private_ [private] |
Definition at line 146 of file bta_ros.hpp.
std::string bta_ros::BtaRos::nodeName_ [private] |
Definition at line 147 of file bta_ros.hpp.
Definition at line 150 of file bta_ros.hpp.
Definition at line 150 of file bta_ros.hpp.
Definition at line 151 of file bta_ros.hpp.
ros::Publisher bta_ros::BtaRos::pub_xyz_ [private] |
Definition at line 153 of file bta_ros.hpp.
boost::shared_ptr<ReconfigureServer> bta_ros::BtaRos::reconfigure_server_ [private] |
Definition at line 155 of file bta_ros.hpp.
uint8_t bta_ros::BtaRos::tcpDeviceIpAddr_[6] [private] |
Definition at line 161 of file bta_ros.hpp.
geometry_msgs::TransformStamped bta_ros::BtaRos::transformStamped [private] |
Definition at line 152 of file bta_ros.hpp.
std::string bta_ros::BtaRos::uartPortName_ [private] |
Definition at line 163 of file bta_ros.hpp.
uint8_t bta_ros::BtaRos::udpControlInIpAddr_[6] [private] |
Definition at line 161 of file bta_ros.hpp.
uint8_t bta_ros::BtaRos::udpControlOutIpAddr_[6] [private] |
Definition at line 161 of file bta_ros.hpp.
uint8_t bta_ros::BtaRos::udpDataIpAddr_[6] [private] |
Definition at line 161 of file bta_ros.hpp.