34 std::string nodeName) :
36 nh_private_(nh_private),
78 printf(
"done: %d \n", status);
95 usValue = (uint32_t)it;
96 status = BTAsetIntegrationTime(
handle_, usValue);
97 if (status != BTA_StatusOk)
98 ROS_WARN_STREAM(
"Error setting IntegrationTime:: " << status <<
"---------------");
100 status = BTAgetIntegrationTime(
handle_, &usValue);
101 if (status != BTA_StatusOk)
102 ROS_WARN_STREAM(
"Error reading IntegrationTime: " << status <<
"---------------");
109 status = BTAsetFrameRate(
handle_, fr);
110 if (status != BTA_StatusOk)
111 ROS_WARN_STREAM(
"Error setting FrameRate: " << status <<
"---------------");
114 status = BTAgetFrameRate(
handle_, &fr_f);
116 if (status != BTA_StatusOk)
117 ROS_WARN_STREAM(
"Error reading FrameRate: " << status <<
"---------------");
128 if(it != config_.Integration_Time) {
129 usValue = (uint32_t)config_.Integration_Time;
130 status = BTAsetIntegrationTime(
handle_, usValue);
131 if (status != BTA_StatusOk)
132 ROS_WARN_STREAM(
"Error setting IntegrationTime: " << status <<
"---------------");
138 if(fr != config_.Frame_rate) {
139 usValue = (uint32_t)config_.Frame_rate;
140 status = BTAsetFrameRate(
handle_, usValue);
141 if (status != BTA_StatusOk)
142 ROS_WARN_STREAM(
"Error setting FrameRate: " << status <<
"---------------");
147 if(config_.Read_reg) {
149 std::stringstream ss;
150 it = strtoul(config_.Reg_addr.c_str(), NULL, 0);
151 status = BTAreadRegister(
handle_, it, &usValue, 0);
152 if (status != BTA_StatusOk) {
153 ROS_WARN_STREAM(
"Could not read reg: " << config_.Reg_addr <<
". Status: " << status);
156 ss <<
"0x"<< std::hex << usValue;
157 ss >> config_.Reg_val;
158 ROS_INFO_STREAM(
"Read register: " << config_.Reg_addr <<
". Value: " << ss.str());
159 }
catch(
const boost::bad_lexical_cast &) {
162 config_.Read_reg =
false;
164 if(config_.Write_reg) {
166 it = strtoul(config_.Reg_addr.c_str(), NULL, 0);
167 usValue = strtoul(config_.Reg_val.c_str(), NULL, 0);
169 status = BTAwriteRegister(
handle_, it, &usValue, 0);
170 if (status != BTA_StatusOk) {
175 ". Status: " << status);
177 ROS_INFO_STREAM(
"Written register: " << config_.Reg_addr <<
". Value: " << config_.Reg_val);
178 BTAgetIntegrationTime(
handle_, &usValue);
179 config_.Integration_Time = usValue;
181 config_.Frame_rate = fr;
182 config_.Write_reg =
false;
189 switch (dataFormat) {
190 case BTA_DataFormatUInt16:
191 return sizeof(uint16_t);
193 case BTA_DataFormatSInt16:
194 return sizeof(int16_t);
196 case BTA_DataFormatFloat32:
197 return sizeof(float);
200 std::cerr <<
"BtaRos::getDataSize(): Unknown data size!" << std::endl;
207 switch (dataFormat) {
208 case BTA_DataFormatUInt16:
211 case BTA_DataFormatSInt16:
214 case BTA_DataFormatFloat32:
218 std::cerr <<
"BtaRos::getDataType(): Unknown data type!" << std::endl;
229 case BTA_UnitMillimeter:
249 BTA_FrameMode frameMode;
250 status = BTAgetFrame(
handle_, &frame, 3000);
251 if (status != BTA_StatusOk) {
254 status = BTAgetFrameMode(
handle_, &frameMode);
255 if (status != BTA_StatusOk) {
259 ROS_DEBUG(
" frameArrived FrameCounter %d", frame->frameCounter);
261 BTA_DataFormat dataFormat;
265 ci_tof->header.frame_id =
nodeName_+
"/tof_camera";
269 status = BTAgetDistances(frame, &distances, &dataFormat, &unit, &xRes, &yRes);
270 if (status == BTA_StatusOk) {
271 sensor_msgs::ImagePtr dis (
new sensor_msgs::Image);
272 ci_tof->header.seq = frame->frameCounter;
273 ci_tof->header.stamp.sec = frame->timeStamp;
274 ci_tof->header.frame_id =
"distances";
275 dis->header.seq = frame->frameCounter;
276 dis->header.stamp.sec = frame->timeStamp;
281 dis->data.resize(xRes*yRes*
getDataSize(dataFormat));
282 memcpy ( &dis->data[0], distances, xRes*yRes*getDataSize(dataFormat) );
284 dis->header.frame_id =
"distances";
290 BTA_DataFormat amDataFormat;
291 status = BTAgetAmplitudes(frame, &litudes,
292 &amDataFormat, &unit, &xRes, &yRes);
293 if (status == BTA_StatusOk) {
294 sensor_msgs::ImagePtr amp (
new sensor_msgs::Image);
295 ci_tof->header.seq = frame->frameCounter;
296 ci_tof->header.stamp.sec = frame->timeStamp;
297 amp->header.seq = frame->frameCounter;
298 amp->header.stamp.sec = frame->timeStamp;
299 ci_tof->header.frame_id =
"amplitudes";
304 amp->data.resize(xRes*yRes*
getDataSize(amDataFormat));
305 memcpy ( &->data[0], amplitudes, xRes*yRes*getDataSize(amDataFormat) );
307 amp->header.frame_id =
"amplitudes";
312 void *xCoordinates, *yCoordinates, *zCoordinates;
313 status = BTAgetXYZcoordinates(frame, &xCoordinates, &yCoordinates, &zCoordinates, &dataFormat, &unit, &xRes, &yRes);
314 if (status == BTA_StatusOk) {
315 if (
_xyz->width != xRes ||
_xyz->height != yRes ||
_xyz->fields.size() != 4) {
320 "y", 1, sensor_msgs::PointField::FLOAT32,
321 "z", 1, sensor_msgs::PointField::FLOAT32,
322 "intensity", 1, sensor_msgs::PointField::UINT16);
324 _xyz->header.frame_id =
"cloud";
325 _xyz->is_dense =
true;
339 if (dataFormat == BTA_DataFormatSInt16) {
344 for (
size_t i = 0; i < yRes*xRes; i++, ++_x, ++_y, ++_z, ++_i) {
345 *_x =
static_cast<short *
>(xCoordinates)[i]*conv;
346 *_y =
static_cast<short *
>(yCoordinates)[i]*conv;
347 *_z =
static_cast<short *
>(zCoordinates)[i]*conv;
349 if(amDataFormat == BTA_DataFormatUInt16) {
350 *_i =
static_cast<unsigned short *
>(amplitudes)[i];
351 }
else if(amDataFormat == BTA_DataFormatFloat32) {
352 *_i =
static_cast<float *
>(amplitudes)[i];
357 }
else if (dataFormat == BTA_DataFormatFloat32) {
358 for (
size_t i = 0; i < yRes*xRes; i++, ++_x, ++_y, ++_z, ++_i) {
359 *_x =
static_cast<float *
>(xCoordinates)[i]*conv;
360 *_y =
static_cast<float *
>(yCoordinates)[i]*conv;
361 *_z =
static_cast<float *
>(zCoordinates)[i]*conv;
363 if(amDataFormat == BTA_DataFormatUInt16) {
364 *_i =
static_cast<unsigned short *
>(amplitudes)[i];
365 }
else if(amDataFormat == BTA_DataFormatFloat32) {
366 *_i =
static_cast<float *
>(amplitudes)[i];
377 _xyz->header.seq = frame->frameCounter;
378 _xyz->header.stamp.sec = frame->timeStamp;
416 BTA_DataFormat dataFormat;
420 status = BTAgetColors(frame, &colorBuffer, &dataFormat, &unit, &xRes, &yRes);
421 if (status == BTA_StatusOk) {
425 BTAfreeFrame(&frame);
449 config_.udpDataIpAddrLen = (uint8_t)iusValue;
454 for (
int i = 1; i <=
config_.udpDataIpAddrLen; i++) {
455 std::ostringstream to_string;
457 to_string <<
nodeName_ <<
"/udpDataIpAddr/n" << i;
465 config_.udpDataPort = (uint16_t)iusValue;
470 config_.udpControlOutIpAddrLen = (uint8_t)iusValue;
475 for (
int i = 1; i <=
config_.udpControlOutIpAddrLen; i++) {
476 std::ostringstream to_string;
478 to_string <<
nodeName_ <<
"/udpControlOutIpAddr/n" << i;
486 config_.udpControlPort = (uint16_t)iusValue;
491 config_.udpControlInIpAddrLen = (uint8_t)iusValue;
497 for (
int i = 1; i <=
config_.udpControlInIpAddrLen; i++) {
498 std::ostringstream to_string;
500 to_string <<
nodeName_ <<
"/udpControlInIpAddr/n" << i;
508 config_.udpControlCallbackPort = (uint16_t)iusValue;
513 config_.tcpDeviceIpAddrLen = (uint8_t)iusValue;
518 for (
int i = 1; i <=
config_.tcpDeviceIpAddrLen; i++) {
519 std::ostringstream to_string;
521 to_string <<
nodeName_ <<
"/tcpDeviceIpAddr/n" << i;
529 config_.tcpControlPort = (uint16_t)iusValue;
534 config_.tcpDataPort = (uint16_t)iusValue;
540 config_.uartBaudRate = (uint32_t)iusValue;
542 config_.uartDataBits = (uint8_t)iusValue;
544 config_.uartStopBits = (uint8_t)iusValue;
546 config_.uartParity = (uint8_t)iusValue;
548 config_.uartTransmitterAddress = (uint8_t)iusValue;
550 config_.uartReceiverAddress = (uint8_t)iusValue;
552 config_.serialNumber = (uint32_t)iusValue;
559 config_.frameMode = (BTA_FrameMode)frameMode;
562 config_.verbosity = (uint8_t)iusValue;
565 config_.frameQueueLength = (uint16_t)iusValue;
567 int32_t frameQueueMode;
569 config_.frameQueueMode = (BTA_QueueMode)frameQueueMode;
573 config_.deviceType = (BTA_DeviceType)deviceType;
583 BTA_DeviceInfo *deviceInfo;
587 status = (BTA_Status)-1;
588 for (
int i=0; i<10; i++) {
591 if (status != BTA_StatusOk) {
594 ROS_WARN_STREAM(
"Could not connect to the camera. status: " << status);
599 if (!BTAisConnected(
handle_)) {
605 status = BTAgetDeviceInfo(
handle_, &deviceInfo);
606 if (status != BTA_StatusOk) {
612 <<
"deviceType: " << deviceInfo->deviceType <<
"\n" 613 <<
"serialNumber: " << deviceInfo->serialNumber <<
"\n" 614 <<
"firmwareVersionMajor: " << deviceInfo->firmwareVersionMajor <<
"\n" 615 <<
"firmwareVersionMinor: " << deviceInfo->firmwareVersionMinor <<
"\n" 616 <<
"firmwareVersionNonFunc: " << deviceInfo->firmwareVersionNonFunc
622 BTAfreeDeviceInfo(deviceInfo);
651 ROS_DEBUG(
"Waiting for dynamic reconfigure configuration.");
652 boost::this_thread::sleep(boost::posix_time::milliseconds(100));
654 ROS_DEBUG(
"Dynamic reconfigure configuration received.");
663 "package://bta_tof_driver/calib.yml")) {
666 "package://bta_tof_driver/calib.yml" );
669 "package://bta_tof_driver/calib.yml" <<
670 " not found. Using an uncalibrated config_.");
682 if (!BTAisConnected(
handle_)) {
std::string calibFileName_
image_transport::CameraPublisher pub_amp_
void close()
Closes the connection to the device.
sensor_msgs::CameraInfo getCameraInfo(void)
uint8_t tcpDeviceIpAddr_[6]
camera_info_manager::CameraInfoManager cim_tof_
bool loadCameraInfo(const std::string &url)
static void BTA_CALLCONV infoEventCb(BTA_EventId eventId, int8_t *msg)
ros::NodeHandle nh_private_
uint8_t udpControlOutIpAddr_[6]
geometry_msgs::TransformStamped transformStamped
boost::shared_ptr< ReconfigureServer > reconfigure_server_
image_transport::CameraPublisher pub_dis_
void setPointCloud2Fields(int n_fields,...)
sensor_msgs::PointCloud2Ptr _xyz
uint8_t udpDataIpAddr_[6]
virtual ~BtaRos()
Class destructor.
int connectCamera()
Helper for connect to the device.
bool validateURL(const std::string &url)
size_t getDataSize(BTA_DataFormat dataFormat)
Returns the size of the data based in BTA_DataFormat.
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
void publish(const boost::shared_ptr< M > &message) const
static std::string unknownDataType
uint32_t getNumSubscribers() const
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
void publishData()
Publish the data based on set up parameters.
bool getParam(const std::string &key, std::string &s) const
const std::string TYPE_32FC1
const std::string TYPE_16UC1
ROSCPP_DECL bool isShuttingDown()
dynamic_reconfigure::Server< Config > ReconfigureServer
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
void parseConfig()
Reads configuration from the server parameters.
bool hasParam(const std::string &key) const
image_transport::ImageTransport it_
#define ROS_INFO_STREAM(args)
tf2_ros::StaticTransformBroadcaster pub_tf
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
float getUnit2Meters(BTA_Unit unit)
Gives the conversion value to meters from the BTA_Unit.
uint32_t getNumSubscribers() const
ROSCPP_DECL void spinOnce()
BtaRos(ros::NodeHandle nh_camera, ros::NodeHandle nh_private, std::string nodeName)
Class constructor.
std::string uartPortName_
uint8_t udpControlInIpAddr_[6]
bool setCameraName(const std::string &cname)
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...
const std::string TYPE_16SC1
std::string getDataType(BTA_DataFormat dataFormat)
Returns the data encoding flat based in BTA_DataFormat.
int initialize()
Initializes the device and parameters.