bta_tof_driver.cpp
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright (c) 2016
3  * VoXel Interaction Design GmbH
4  *
5  * @author Angel Merino Sastre
6  *
7  * Permission is hereby granted, free of charge, to any person obtaining a copy
8  * of this software and associated documentation files (the "Software"), to deal
9  * in the Software without restriction, including without limitation the rights
10  * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
11  * copies of the Software, and to permit persons to whom the Software is
12  * furnished to do so, subject to the following conditions:
13  *
14  * The above copyright notice and this permission notice shall be included in
15  * all copies or substantial portions of the Software.
16  *
17  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
18  * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
19  * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
20  * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
21  * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
22  * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
23  * THE SOFTWARE.
24  *
25  ******************************************************************************/
26 
28 
29 namespace bta_tof_driver
30 {
31 
33  ros::NodeHandle nh_private,
34  std::string nodeName) :
35  nh_(nh_camera),
36  nh_private_(nh_private),
37  it_(nh_camera),
38  cim_tof_(nh_camera),
39  nodeName_(nodeName),
40  config_init_(false),
41  _xyz (new sensor_msgs::PointCloud2)
42 {
43  //Set log to debug to test capturing. Remove if not needed.
44  /*
45  if( ros::console::set_logger_level(
46  ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Info) )
47  {
48  ros::console::notifyLoggerLevelsChanged();
49  }*/
50  transformStamped.header.stamp = ros::Time::now();
51  transformStamped.header.frame_id = "world";
52  transformStamped.child_frame_id = "cloud";
53  transformStamped.transform.translation.x = 0.0;
54  transformStamped.transform.translation.y = 0.0;
55  transformStamped.transform.translation.z = 0.0;
57  q.setRPY(0, 0, 0);
58  transformStamped.transform.rotation.x = q.x();
59  transformStamped.transform.rotation.y = q.y();
60  transformStamped.transform.rotation.z = q.z();
61  transformStamped.transform.rotation.w = q.w();
63 }
64 
66 {
67  ROS_INFO("closing.");
68  close();
69 }
70 
72 {
73  ROS_DEBUG("Close called");
74  if (BTAisConnected(handle_)) {
75  ROS_DEBUG("Closing..");
76  BTA_Status status;
77  status = BTAclose(&handle_);
78  printf("done: %d \n", status);
79  }
80 
81  return;
82 }
83 
84 
85 void BtaRos::callback(bta_tof_driver::bta_tof_driverConfig &config_, uint32_t level)
86 {
87  BTA_Status status;
88  // Check the configuretion parameters with those given in the initialization
89  int it;
90  double fr;
91  uint32_t usValue;
92 
93  if (!config_init_) {
94  if (nh_private_.getParam(nodeName_+"/integrationTime",it)) {
95  usValue = (uint32_t)it;
96  status = BTAsetIntegrationTime(handle_, usValue);
97  if (status != BTA_StatusOk)
98  ROS_WARN_STREAM("Error setting IntegrationTime:: " << status << "---------------");
99  } else {
100  status = BTAgetIntegrationTime(handle_, &usValue);
101  if (status != BTA_StatusOk)
102  ROS_WARN_STREAM("Error reading IntegrationTime: " << status << "---------------");
103  else
104  nh_private_.setParam(nodeName_+"/integrationTime", (int)usValue);
105  }
106  nh_private_.getParam(nodeName_+"/integrationTime",config_.Integration_Time);
107 
108  if (nh_private_.getParam(nodeName_+"/frameRate",fr)) {
109  status = BTAsetFrameRate(handle_, fr);
110  if (status != BTA_StatusOk)
111  ROS_WARN_STREAM("Error setting FrameRate: " << status << "---------------");
112  } else {
113  float fr_f;
114  status = BTAgetFrameRate(handle_, &fr_f);
115  fr = fr_f;
116  if (status != BTA_StatusOk)
117  ROS_WARN_STREAM("Error reading FrameRate: " << status << "---------------");
118  else
119  nh_private_.setParam(nodeName_+"/frameRate", fr);
120  }
121  nh_private_.getParam(nodeName_+"/frameRate",config_.Frame_rate);
122  config_init_ = true;
123  return;
124  }
125 
126 
127  nh_private_.getParam(nodeName_+"/integrationTime",it);
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 << "---------------");
133  else
134  nh_private_.setParam(nodeName_+"/integrationTime", config_.Integration_Time);
135  }
136 
137  nh_private_.getParam(nodeName_+"/frameRate",fr);
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 << "---------------");
143  else
144  nh_private_.setParam(nodeName_+"/frameRate", config_.Frame_rate);
145  }
146 
147  if(config_.Read_reg) {
148  try {
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);
154  }
155  ss<<"";
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 &) {
160  ROS_WARN_STREAM("Wrong address: " << config_.Reg_addr << " " << it);
161  }
162  config_.Read_reg = false;
163  }
164  if(config_.Write_reg) {
165  //std::stringstream ss;
166  it = strtoul(config_.Reg_addr.c_str(), NULL, 0);
167  usValue = strtoul(config_.Reg_val.c_str(), NULL, 0);
168 
169  status = BTAwriteRegister(handle_, it, &usValue, 0);
170  if (status != BTA_StatusOk) {
171  ROS_WARN_STREAM("Could not write reg: " <<
172  config_.Reg_addr <<
173  " with val: " <<
174  config_.Reg_val <<
175  ". Status: " << status);
176  }
177  ROS_INFO_STREAM("Written register: " << config_.Reg_addr << ". Value: " << config_.Reg_val);
178  BTAgetIntegrationTime(handle_, &usValue);
179  config_.Integration_Time = usValue;
180  BTAsetFrameRate(handle_, fr);
181  config_.Frame_rate = fr;
182  config_.Write_reg = false;
183 
184  }
185 
186 }
187 
188 size_t BtaRos::getDataSize(BTA_DataFormat dataFormat) {
189  switch (dataFormat) {
190  case BTA_DataFormatUInt16:
191  return sizeof(uint16_t);
192  break;
193  case BTA_DataFormatSInt16:
194  return sizeof(int16_t);
195  break;
196  case BTA_DataFormatFloat32:
197  return sizeof(float);
198  break;
199  default:
200  std::cerr << "BtaRos::getDataSize(): Unknown data size!" << std::endl;
201  return 0;
202  }
203 }
204 static std::string unknownDataType="UNKNOWN_DATA_TYPE";
205 
206 std::string BtaRos::getDataType(BTA_DataFormat dataFormat) {
207  switch (dataFormat) {
208  case BTA_DataFormatUInt16:
210  break;
211  case BTA_DataFormatSInt16:
213  break;
214  case BTA_DataFormatFloat32:
216  break;
217  default:
218  std::cerr << "BtaRos::getDataType(): Unknown data type!" << std::endl;
219  return unknownDataType;
220  }
221 }
222 
223 float BtaRos::getUnit2Meters(BTA_Unit unit) {
224  //ROS_INFO_STREAM("BTA_Unit: " << unit);
225  switch (unit) {
226  /*case BTA_UnitCentimeter:
227  return 1/100.;
228  break;*/
229  case BTA_UnitMillimeter:
230  return 1/1000.;
231  break;
232  default:
233  return 1.0;
234  break;
235  }
236 }
237 
239 {
240  if (
241  (pub_amp_.getNumSubscribers() == 0) &&
242  (pub_dis_.getNumSubscribers() == 0) &&
243  (pub_xyz_.getNumSubscribers() == 0)
244  ) return;
245 
246  BTA_Status status;
247 
248  BTA_Frame *frame;
249  BTA_FrameMode frameMode;
250  status = BTAgetFrame(handle_, &frame, 3000);
251  if (status != BTA_StatusOk) {
252  return;
253  }
254  status = BTAgetFrameMode(handle_, &frameMode);
255  if (status != BTA_StatusOk) {
256  return;
257  }
258 
259  ROS_DEBUG(" frameArrived FrameCounter %d", frame->frameCounter);
260 
261  BTA_DataFormat dataFormat;
262  BTA_Unit unit;
263  uint16_t xRes, yRes;
264  sensor_msgs::CameraInfoPtr ci_tof(new sensor_msgs::CameraInfo(cim_tof_.getCameraInfo()));
265  ci_tof->header.frame_id = nodeName_+"/tof_camera";
266 
267 
268  void *distances;
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;
277  dis->height = yRes;
278  dis->width = xRes;
279  dis->encoding = getDataType(dataFormat);
280  dis->step = xRes*getDataSize(dataFormat);
281  dis->data.resize(xRes*yRes*getDataSize(dataFormat));
282  memcpy ( &dis->data[0], distances, xRes*yRes*getDataSize(dataFormat) );
283 
284  dis->header.frame_id = "distances";
285  pub_dis_.publish(dis,ci_tof);
286  }
287 
288  bool ampOk = false;
289  void *amplitudes;
290  BTA_DataFormat amDataFormat;
291  status = BTAgetAmplitudes(frame, &amplitudes,
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";
300  amp->height = yRes;
301  amp->width = xRes;
302  amp->encoding = getDataType(amDataFormat);
303  amp->step = xRes*getDataSize(amDataFormat);
304  amp->data.resize(xRes*yRes*getDataSize(amDataFormat));
305  memcpy ( &amp->data[0], amplitudes, xRes*yRes*getDataSize(amDataFormat) );
306 
307  amp->header.frame_id = "amplitudes";//nodeName_+"/tof_camera";
308  pub_amp_.publish(amp,ci_tof);
309  ampOk = true;
310  }
311 
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) {
316  _xyz->width = xRes;
317  _xyz->height = yRes;
319  modifier.setPointCloud2Fields(4, "x", 1, sensor_msgs::PointField::FLOAT32,
320  "y", 1, sensor_msgs::PointField::FLOAT32,
321  "z", 1, sensor_msgs::PointField::FLOAT32,
322  "intensity", 1, sensor_msgs::PointField::UINT16);
323  modifier.resize(_xyz->height * _xyz->width);
324  _xyz->header.frame_id = "cloud";
325  _xyz->is_dense = true;
326  }
327  //if (_cloud.size() != yRes*xRes) {
328  // _cloud.resize(yRes*xRes);
329  //}
330  /* else {
331  pub_xyz_.publish(_xyz);
332  return;
333  }*/
334  float conv = getUnit2Meters(unit);
339  if (dataFormat == BTA_DataFormatSInt16) {
340  /*short *xC, *yC, *zC;
341  xC = (short *)xCoordinates;
342  yC = (short *)yCoordinates;
343  zC = (short *)zCoordinates;*/
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;
348  if (ampOk) {
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];
353  }
354  } else
355  *_i = 255;
356  }
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;
362  if (ampOk) {
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];
367  }
368  } else
369  *_i = 255;
370  }
371  } else {
372  ROS_WARN_STREAM("Unhandled BTA_DataFormat: " << dataFormat);
373  return;
374  }
375  //pcl::toROSMsg(_cloud, *_xyz);
376 
377  _xyz->header.seq = frame->frameCounter;
378  _xyz->header.stamp.sec = frame->timeStamp;
379 
380  //Keeping until resolving problem with rviz
381  /*
382  xyz->width = xRes;
383  xyz->height = yRes;
384  sensor_msgs::PointCloud2Modifier modifier(*xyz);
385  ROS_DEBUG_STREAM("MAL? " << unit);
386 
387  modifier.setPointCloud2Fields(3, "x", 1, sensor_msgs::PointField::INT16,
388  "y", 1, sensor_msgs::PointField::INT16,
389  "z", 1, sensor_msgs::PointField::INT16/*,
390  "intensity", 1, sensor_msgs::PointField::UINT16* /);
391  ROS_DEBUG_STREAM("MAL? " << modifier.size());
392  short *xC, *yC, *zC;
393  xC = (short *)xCoordinates;
394  yC = (short *)yCoordinates;
395  zC = (short *)zCoordinates;
396  std::vector<short> test;
397  for (size_t i = 0; i < yRes*xRes; i++) {
398  test.push_back(xC[i]);
399  test.push_back(yC[i]);
400  test.push_back(zC[i]);
401  //memcpy ( &xyz->data[i*xyz->point_step], &xCoordinates[i*getDataSize(dataFormat)], getDataSize(dataFormat) );
402  //memcpy ( &xyz->data[i*xyz->point_step+getDataSize(dataFormat) ], &yCoordinates[i*getDataSize(dataFormat)], getDataSize(dataFormat) );
403  //memcpy ( &xyz->data[i*xyz->point_step+2*getDataSize(dataFormat) ], &zCoordinates[i*getDataSize(dataFormat)], getDataSize(dataFormat) );
404  //memcpy ( &xyz->data[i*xyz->point_step+3*getDataSize(dataFormat)], &amplitudes[i*getDataSize(amDataFormat)], getDataSize(amDataFormat) );
405  //ROS_DEBUG_STREAM("ox: " << (short)xCoordinates[i*getDataSize(dataFormat)] << " y: " << (short)yCoordinates[i*getDataSize(dataFormat)] << " z: " << (short)zCoordinates[i*getDataSize(dataFormat)]);
406  //ROS_DEBUG_STREAM("x: " << (short)xyz->data[i*xyz->point_step] << " y: " << (short)xyz->data[i*xyz->point_step+getDataSize(dataFormat) ] << " z: " << (short)xyz->data[i*xyz->point_step+2*getDataSize(dataFormat) ]);
407  }
408  memcpy ( &xyz->data[0], &test[0], test.size());
409  ROS_DEBUG_STREAM("MAL? " << modifier.size());
410  */
411 
413  }
414 
415  void *colorBuffer;
416  BTA_DataFormat dataFormat;
417  BTA_Unit unit;
418  uint16_t xRes;
419  uint16_t yRes;
420  status = BTAgetColors(frame, &colorBuffer, &dataFormat, &unit, &xRes, &yRes);
421  if (status == BTA_StatusOk) {
422  }
423 
424 
425  BTAfreeFrame(&frame);
426 }
427 
428 /*void BtaRos::ampCb(const sensor_msgs::ImagePtr& amp)
429  {
430  sensor_msgs::CameraInfoPtr ci_tof(new sensor_msgs::CameraInfo(cim_tof_.getCameraInfo()));
431  ci_tof->header.frame_id = nodeName_+"/tof_camera";
432  amp->header.frame_id = nodeName_+"/tof_camera";
433 
434  pub_amp_.publish(amp,ci_tof);
435  }
436 
437  void BtaRos::disCb(const sensor_msgs::ImagePtr& dis)
438  {
439  sensor_msgs::CameraInfoPtr ci_tof(new sensor_msgs::CameraInfo(cim_tof_.getCameraInfo()));
440  ci_tof->header.frame_id = nodeName_+"/tof_camera";
441  dis->header.frame_id = nodeName_+"/tof_camera";
442 
443  pub_dis_.publish(dis,ci_tof);
444  }*/
445 
447  int iusValue;
448  if(nh_private_.getParam(nodeName_+"/udpDataIpAddrLen",iusValue)) {
449  config_.udpDataIpAddrLen = (uint8_t)iusValue;
450  ROS_DEBUG_STREAM("config_.udpDataIpAddrLen: " << (int)config_.udpDataIpAddrLen);
451  }
452  if (nh_private_.hasParam(nodeName_+"/udpDataIpAddr")) {
453  ROS_DEBUG_STREAM("config_.udpDataIpAddr:");
454  for (int i = 1; i <= config_.udpDataIpAddrLen; i++) {
455  std::ostringstream to_string;
456  to_string << "";
457  to_string << nodeName_ << "/udpDataIpAddr/n" << i;
458  nh_private_.getParam(to_string.str(),iusValue);
459  udpDataIpAddr_[i-1] = (uint8_t)iusValue;
460  ROS_DEBUG_STREAM((int)udpDataIpAddr_[i-1] << ",");
461  }
462  config_.udpDataIpAddr = udpDataIpAddr_;
463  }
464  if(nh_private_.getParam(nodeName_+"/udpDataPort",iusValue)) {
465  config_.udpDataPort = (uint16_t)iusValue;
466  ROS_DEBUG_STREAM("config_.udpDataPort: " << config_.udpDataPort);
467  }
468 
469  if(nh_private_.getParam(nodeName_+"/udpControlOutIpAddrLen",iusValue)) {
470  config_.udpControlOutIpAddrLen = (uint8_t)iusValue;
471  ROS_DEBUG_STREAM("config_.udpControlOutIpAddrLen: " << (int)config_.udpControlOutIpAddrLen);
472  }
473  if (nh_private_.hasParam(nodeName_+"/udpControlOutIpAddr")) {
474  ROS_DEBUG_STREAM("config_.udpControlOutIpAddr:");
475  for (int i = 1; i <= config_.udpControlOutIpAddrLen; i++) {
476  std::ostringstream to_string;
477  to_string << "";
478  to_string << nodeName_ << "/udpControlOutIpAddr/n" << i;
479  nh_private_.getParam(to_string.str(),iusValue);
480  udpControlOutIpAddr_[i-1] = (uint8_t)iusValue;
481  ROS_DEBUG_STREAM((int)udpControlOutIpAddr_[i-1] << ",");
482  }
483  config_.udpControlOutIpAddr = udpControlOutIpAddr_;
484  }
485  if(nh_private_.getParam(nodeName_+"/udpControlPort",iusValue)) {
486  config_.udpControlPort = (uint16_t)iusValue;
487  ROS_DEBUG_STREAM("config_.udpControlPort: " << (int)config_.udpControlPort);
488  }
489 
490  if(nh_private_.getParam(nodeName_+"/udpControlInIpAddrLen",iusValue)) {
491  config_.udpControlInIpAddrLen = (uint8_t)iusValue;
492  ROS_DEBUG_STREAM("config_.udpControlInIpAddrLen: " << (int)config_.udpControlInIpAddrLen);
493  }
494  if (nh_private_.hasParam(nodeName_+"/udpControlInIpAddr")) {
495 
496  ROS_DEBUG_STREAM("config_.udpControlInIpAddr:");
497  for (int i = 1; i <= config_.udpControlInIpAddrLen; i++) {
498  std::ostringstream to_string;
499  to_string << "";
500  to_string << nodeName_ << "/udpControlInIpAddr/n" << i;
501  nh_private_.getParam(to_string.str(),iusValue);
502  udpControlInIpAddr_[i-1] = (uint8_t)iusValue;
503  ROS_DEBUG_STREAM((int)udpControlInIpAddr_[i-1] << ",");
504  }
505  config_.udpControlInIpAddr = udpControlInIpAddr_;
506  }
507  if(nh_private_.getParam(nodeName_+"/udpControlCallbackPort",iusValue)) {
508  config_.udpControlCallbackPort = (uint16_t)iusValue;
509  ROS_DEBUG_STREAM("config_.udpControlCallbackPort: " << (int)config_.udpControlCallbackPort);
510  }
511 
512  if(nh_private_.getParam(nodeName_+"/tcpDeviceIpAddrLen",iusValue)) {
513  config_.tcpDeviceIpAddrLen = (uint8_t)iusValue;
514  ROS_DEBUG_STREAM("config_.tcpDeviceIpAddrLen: " << (int)config_.tcpDeviceIpAddrLen);
515  }
516  if (nh_private_.hasParam(nodeName_+"/tcpDeviceIpAddr")) {
517  ROS_DEBUG_STREAM("TCP address:");
518  for (int i = 1; i <= config_.tcpDeviceIpAddrLen; i++) {
519  std::ostringstream to_string;
520  to_string << "";
521  to_string << nodeName_ << "/tcpDeviceIpAddr/n" << i;
522  nh_private_.getParam(to_string.str(),iusValue);
523  tcpDeviceIpAddr_[i-1] = (uint8_t)iusValue;
524  ROS_DEBUG_STREAM((int)tcpDeviceIpAddr_[i-1] << ",");
525  }
526  config_.tcpDeviceIpAddr = tcpDeviceIpAddr_;
527  }
528  if(nh_private_.getParam(nodeName_+"/tcpControlPort",iusValue)) {
529  config_.tcpControlPort = (uint16_t)iusValue;
530  ROS_DEBUG_STREAM("config_.tcpControlPort: " << config_.tcpControlPort);
531  }
532 
533  if (nh_private_.getParam(nodeName_+"/tcpDataPort",iusValue))
534  config_.tcpDataPort = (uint16_t)iusValue;
535 
536  nh_private_.getParam(nodeName_+"/uartPortName",uartPortName_);
537  config_.uartPortName = (uint8_t *)uartPortName_.c_str();
538 
539  if(nh_private_.getParam(nodeName_+"/uartBaudRate",iusValue))
540  config_.uartBaudRate = (uint32_t)iusValue;
541  if(nh_private_.getParam(nodeName_+"/uartDataBits",iusValue))
542  config_.uartDataBits = (uint8_t)iusValue;
543  if(nh_private_.getParam(nodeName_+"/uartStopBits",iusValue))
544  config_.uartStopBits = (uint8_t)iusValue;
545  if(nh_private_.getParam(nodeName_+"/uartParity",iusValue))
546  config_.uartParity = (uint8_t)iusValue;
547  if(nh_private_.getParam(nodeName_+"/uartTransmitterAddress",iusValue))
548  config_.uartTransmitterAddress = (uint8_t)iusValue;
549  if(nh_private_.getParam(nodeName_+"/uartReceiverAddress",iusValue))
550  config_.uartReceiverAddress = (uint8_t)iusValue;
551  if(nh_private_.getParam(nodeName_+"/serialNumber",iusValue))
552  config_.serialNumber = (uint32_t)iusValue;
553 
554  nh_private_.getParam(nodeName_+"/calibFileName",calibFileName_);
555  config_.calibFileName = (uint8_t *)calibFileName_.c_str();
556 
557  int32_t frameMode;
558  if (nh_private_.getParam(nodeName_+"/frameMode",frameMode))
559  config_.frameMode = (BTA_FrameMode)frameMode;
560 
561  if (nh_private_.getParam(nodeName_+"/verbosity",iusValue))
562  config_.verbosity = (uint8_t)iusValue;
563 
564  if(nh_private_.getParam(nodeName_+"/frameQueueLength",iusValue))
565  config_.frameQueueLength = (uint16_t)iusValue;
566 
567  int32_t frameQueueMode;
568  if (nh_private_.getParam(nodeName_+"/frameQueueMode",frameQueueMode))
569  config_.frameQueueMode = (BTA_QueueMode)frameQueueMode;
570 
571  int32_t deviceType;
572  if(nh_private_.getParam(nodeName_+"/deviceType",deviceType))
573  config_.deviceType = (BTA_DeviceType)deviceType;
574 
575  //config_.frameArrived = &frameArrived;
576  config_.infoEvent = &infoEventCb;
577 }
578 
579 
580 
582  BTA_Status status;
583  BTA_DeviceInfo *deviceInfo;
584 
585  // Init camera connection
586  //ros::Duration().sleep();
587  status = (BTA_Status)-1;
588  for (int i=0; i<10; i++) {
589  ROS_INFO_STREAM("Connecting... try " << i+1);
590  status = BTAopen(&config_, &handle_);
591  if (status != BTA_StatusOk) {
592  if (!nh_private_.ok() && ros::isShuttingDown())
593  return -1;
594  ROS_WARN_STREAM("Could not connect to the camera. status: " << status);
595  continue;
596  }
597  break;
598  }
599  if (!BTAisConnected(handle_)) {
600  ROS_WARN_STREAM("Could not connect to the camera.");
601  return -1;
602  }
603 
604  ROS_INFO_STREAM("Camera connected sucessfully. status: " << status);
605  status = BTAgetDeviceInfo(handle_, &deviceInfo);
606  if (status != BTA_StatusOk) {
607  ROS_WARN_STREAM("Could not get device info. status: " << status);
608  return status;
609  }
610 
611  ROS_INFO_STREAM("Retrieved device info: \n"
612  << "deviceType: " << deviceInfo->deviceType << "\n"
613  << "serialNumber: " << deviceInfo->serialNumber << "\n"
614  << "firmwareVersionMajor: " << deviceInfo->firmwareVersionMajor << "\n"
615  << "firmwareVersionMinor: " << deviceInfo->firmwareVersionMinor << "\n"
616  << "firmwareVersionNonFunc: " << deviceInfo->firmwareVersionNonFunc
617  << "\n");
618 
619  ROS_INFO_STREAM("Service running: " << (int)BTAisRunning(handle_));
620  ROS_INFO_STREAM("Connection up: " << (int)BTAisConnected(handle_));
621 
622  BTAfreeDeviceInfo(deviceInfo);
623  return 1;
624 }
625 
627 {
628 
629  /*
630  * Camera config
631  */
632 
633  BTAinitConfig(&config_);
634 
635  parseConfig();
636 
637  /*
638  * Camera Initialization
639  */
640  ROS_DEBUG_STREAM("Config Readed sucessfully");
641 
642  BTA_Status status;
643  if (connectCamera() < 0)
644  return -1;
645 
647  reconfigure_server_->setCallback(boost::bind(&BtaRos::callback, this, _1, _2));
648 
649  while (!config_init_)
650  {
651  ROS_DEBUG("Waiting for dynamic reconfigure configuration.");
652  boost::this_thread::sleep(boost::posix_time::milliseconds(100));
653  }
654  ROS_DEBUG("Dynamic reconfigure configuration received.");
655 
656  /*
657  * ROS Node Initialization
658  */
659  {
660  // Advertise all published topics
663  /*camera_info_url_*/"package://bta_tof_driver/calib.yml")) {
664  cim_tof_.loadCameraInfo("package://bta_tof_driver/calib.yml");
665  ROS_INFO_STREAM("Loaded camera calibration from " <<
666  "package://bta_tof_driver/calib.yml" );
667  } else {
668  ROS_WARN_STREAM("Camera info at: " <<
669  "package://bta_tof_driver/calib.yml" <<
670  " not found. Using an uncalibrated config_.");
671  }
672 
673  pub_amp_ = it_.advertiseCamera(nodeName_ + "/tof_camera/image_raw", 1);
674  pub_dis_ = it_.advertiseCamera(nodeName_ + "/tof_camera/compressedDepth", 1);
675  pub_xyz_ = nh_private_.advertise<sensor_msgs::PointCloud2> (nodeName_ + "/tof_camera/point_cloud_xyz", 1);
676 
677  //sub_amp_ = nh_private_.subscribe("bta_node_amp", 1, &BtaRos::ampCb, this);
678  //sub_dis_ = nh_private_.subscribe("bta_node_dis", 1, &BtaRos::disCb, this);
679  }
680 
681  while (nh_private_.ok() && !ros::isShuttingDown()) {
682  if (!BTAisConnected(handle_)) {
683  ROS_WARN_STREAM("The camera got disconnected." << BTAisConnected(handle_));
684  if (connectCamera() < 0)
685  break;
686  }
687 
688  publishData();
689  ros::spinOnce ();
690  }
691  return 0;
692 }
693 }
694 
image_transport::CameraPublisher pub_amp_
void close()
Closes the connection to the device.
sensor_msgs::CameraInfo getCameraInfo(void)
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_
geometry_msgs::TransformStamped transformStamped
boost::shared_ptr< ReconfigureServer > reconfigure_server_
image_transport::CameraPublisher pub_dis_
void setPointCloud2Fields(int n_fields,...)
sensor_msgs::PointCloud2Ptr _xyz
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.
#define ROS_INFO(...)
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.
static Time now()
void sendTransform(const geometry_msgs::TransformStamped &transform)
uint32_t getNumSubscribers() const
ROSCPP_DECL void spinOnce()
bool ok() const
BtaRos(ros::NodeHandle nh_camera, ros::NodeHandle nh_private, std::string nodeName)
Class constructor.
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...
#define ROS_DEBUG(...)
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.


bta_tof_driver
Author(s): Angel Merino , Simon Vogl
autogenerated on Sun Jun 26 2022 02:45:00