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 
44 
45 namespace bta_tof_driver
46 {
47 
49  ros::NodeHandle nh_private,
50  std::string nodeName) :
51  nh_(nh_camera),
52  nh_private_(nh_private),
53  it_(nh_camera),
54  cim_tof_(nh_camera),
55  nodeName_(nodeName),
56  config_init_(false),
57  _xyz (new sensor_msgs::PointCloud2)
58 {
59  //Set log to debug to test capturing. Remove if not needed.
60  /*
61  if( ros::console::set_logger_level(
62  ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Info) )
63  {
64  ros::console::notifyLoggerLevelsChanged();
65  }*/
66  transformStamped.header.stamp = ros::Time::now();
67  transformStamped.header.frame_id = "world";
68  transformStamped.child_frame_id = "cloud";
69  transformStamped.transform.translation.x = 0.0;
70  transformStamped.transform.translation.y = 0.0;
71  transformStamped.transform.translation.z = 0.0;
73  q.setRPY(0, 0, 0);
74  transformStamped.transform.rotation.x = q.x();
75  transformStamped.transform.rotation.y = q.y();
76  transformStamped.transform.rotation.z = q.z();
77  transformStamped.transform.rotation.w = q.w();
79 }
80 
82 {
83  ROS_INFO("closing.");
84  close();
85 }
86 
88 {
89  ROS_DEBUG("Close called");
90  if (BTAisConnected(handle_)) {
91  ROS_DEBUG("Closing..");
92  BTA_Status status;
93  status = BTAclose(&handle_);
94  printf("done: %d \n", status);
95  }
96 
97  return;
98 }
99 
100 
101 void BtaRos::callback(bta_tof_driver::bta_tof_driverConfig &config_, uint32_t level)
102 {
103  BTA_Status status;
104  // Check the configuretion parameters with those given in the initialization
105  int it;
106  double fr;
107  uint32_t usValue;
108 
109  if (!config_init_) {
110  if (nh_private_.getParam(nodeName_+"/integrationTime",it)) {
111  usValue = (uint32_t)it;
112  status = BTAsetIntegrationTime(handle_, usValue);
113  if (status != BTA_StatusOk)
114  ROS_WARN_STREAM("Error setting IntegrationTime:: " << status << "---------------");
115  } else {
116  status = BTAgetIntegrationTime(handle_, &usValue);
117  if (status != BTA_StatusOk)
118  ROS_WARN_STREAM("Error reading IntegrationTime: " << status << "---------------");
119  else
120  nh_private_.setParam(nodeName_+"/integrationTime", (int)usValue);
121  }
122  nh_private_.getParam(nodeName_+"/integrationTime",config_.Integration_Time);
123 
124  if (nh_private_.getParam(nodeName_+"/frameRate",fr)) {
125  status = BTAsetFrameRate(handle_, fr);
126  if (status != BTA_StatusOk)
127  ROS_WARN_STREAM("Error setting FrameRate: " << status << "---------------");
128  } else {
129  float fr_f;
130  status = BTAgetFrameRate(handle_, &fr_f);
131  fr = fr_f;
132  if (status != BTA_StatusOk)
133  ROS_WARN_STREAM("Error reading FrameRate: " << status << "---------------");
134  else
135  nh_private_.setParam(nodeName_+"/frameRate", fr);
136  }
137  nh_private_.getParam(nodeName_+"/frameRate",config_.Frame_rate);
138  config_init_ = true;
139  return;
140  }
141 
142 
143  nh_private_.getParam(nodeName_+"/integrationTime",it);
144  if(it != config_.Integration_Time) {
145  usValue = (uint32_t)config_.Integration_Time;
146  status = BTAsetIntegrationTime(handle_, usValue);
147  if (status != BTA_StatusOk)
148  ROS_WARN_STREAM("Error setting IntegrationTime: " << status << "---------------");
149  else
150  nh_private_.setParam(nodeName_+"/integrationTime", config_.Integration_Time);
151  }
152 
153  nh_private_.getParam(nodeName_+"/frameRate",fr);
154  if(fr != config_.Frame_rate) {
155  usValue = (uint32_t)config_.Frame_rate;
156  status = BTAsetFrameRate(handle_, usValue);
157  if (status != BTA_StatusOk)
158  ROS_WARN_STREAM("Error setting FrameRate: " << status << "---------------");
159  else
160  nh_private_.setParam(nodeName_+"/frameRate", config_.Frame_rate);
161  }
162 
163  if(config_.Read_reg) {
164  try {
165  std::stringstream ss;
166  it = strtoul(config_.Reg_addr.c_str(), NULL, 0);
167  status = BTAreadRegister(handle_, it, &usValue, 0);
168  if (status != BTA_StatusOk) {
169  ROS_WARN_STREAM("Could not read reg: " << config_.Reg_addr << ". Status: " << status);
170  }
171  ss<<"";
172  ss << "0x"<< std::hex << usValue;
173  ss >> config_.Reg_val;
174  ROS_INFO_STREAM("Read register: " << config_.Reg_addr << ". Value: " << ss.str());
175  } catch(const boost::bad_lexical_cast &) {
176  ROS_WARN_STREAM("Wrong address: " << config_.Reg_addr << " " << it);
177  }
178  config_.Read_reg = false;
179  }
180  if(config_.Write_reg) {
181  //std::stringstream ss;
182  it = strtoul(config_.Reg_addr.c_str(), NULL, 0);
183  usValue = strtoul(config_.Reg_val.c_str(), NULL, 0);
184 
185  status = BTAwriteRegister(handle_, it, &usValue, 0);
186  if (status != BTA_StatusOk) {
187  ROS_WARN_STREAM("Could not write reg: " <<
188  config_.Reg_addr <<
189  " with val: " <<
190  config_.Reg_val <<
191  ". Status: " << status);
192  }
193  ROS_INFO_STREAM("Written register: " << config_.Reg_addr << ". Value: " << config_.Reg_val);
194  BTAgetIntegrationTime(handle_, &usValue);
195  config_.Integration_Time = usValue;
196  BTAsetFrameRate(handle_, fr);
197  config_.Frame_rate = fr;
198  config_.Write_reg = false;
199 
200  }
201 
202 }
203 
204 size_t BtaRos::getDataSize(BTA_DataFormat dataFormat) {
205  switch (dataFormat) {
206  case BTA_DataFormatUInt16:
207  return sizeof(uint16_t);
208  break;
209  case BTA_DataFormatSInt16:
210  return sizeof(int16_t);
211  break;
212  case BTA_DataFormatFloat32:
213  return sizeof(float);
214  break;
215  }
216 }
217 
218 std::string BtaRos::getDataType(BTA_DataFormat dataFormat) {
219  switch (dataFormat) {
220  case BTA_DataFormatUInt16:
222  break;
223  case BTA_DataFormatSInt16:
225  break;
226  case BTA_DataFormatFloat32:
228  break;
229  }
230 }
231 
232 float BtaRos::getUnit2Meters(BTA_Unit unit) {
233  //ROS_INFO_STREAM("BTA_Unit: " << unit);
234  switch (unit) {
235  /*case BTA_UnitCentimeter:
236  return 1/100.;
237  break;*/
238  case BTA_UnitMillimeter:
239  return 1/1000.;
240  break;
241  default:
242  return 1.0;
243  break;
244  }
245 }
246 
248 {
249  if (
250  (pub_amp_.getNumSubscribers() == 0) &&
251  (pub_dis_.getNumSubscribers() == 0) &&
252  (pub_xyz_.getNumSubscribers() == 0)
253  ) return;
254 
255  BTA_Status status;
256 
257  BTA_Frame *frame;
258  status = BTAgetFrame(handle_, &frame, 3000);
259  if (status != BTA_StatusOk) {
260  return;
261  }
262 
263  ROS_DEBUG(" frameArrived FrameCounter %d", frame->frameCounter);
264 
265  BTA_DataFormat dataFormat;
266  BTA_Unit unit;
267  uint16_t xRes, yRes;
268  sensor_msgs::CameraInfoPtr ci_tof(new sensor_msgs::CameraInfo(cim_tof_.getCameraInfo()));
269  ci_tof->header.frame_id = nodeName_+"/tof_camera";
270 
271 
272  void *distances;
273  status = BTAgetDistances(frame, &distances, &dataFormat, &unit, &xRes, &yRes);
274  if (status == BTA_StatusOk) {
275  sensor_msgs::ImagePtr dis (new sensor_msgs::Image);
276  ci_tof->header.seq = frame->frameCounter;
277  ci_tof->header.stamp.sec = frame->timeStamp;
278  ci_tof->header.frame_id = "distances";
279  dis->header.seq = frame->frameCounter;
280  dis->header.stamp.sec = frame->timeStamp;
281  dis->height = yRes;
282  dis->width = xRes;
283  dis->encoding = getDataType(dataFormat);
284  dis->step = xRes*getDataSize(dataFormat);
285  dis->data.resize(xRes*yRes*getDataSize(dataFormat));
286  memcpy ( &dis->data[0], distances, xRes*yRes*getDataSize(dataFormat) );
287 
288  dis->header.frame_id = "distances";
289  pub_dis_.publish(dis,ci_tof);
290  }
291 
292  bool ampOk = false;
293  void *amplitudes;
294  BTA_DataFormat amDataFormat;
295  status = BTAgetAmplitudes(frame, &amplitudes,
296  &amDataFormat, &unit, &xRes, &yRes);
297  if (status == BTA_StatusOk) {
298  sensor_msgs::ImagePtr amp (new sensor_msgs::Image);
299 ci_tof->header.seq = frame->frameCounter;
300  ci_tof->header.stamp.sec = frame->timeStamp;
301  amp->header.seq = frame->frameCounter;
302  amp->header.stamp.sec = frame->timeStamp;
303  ci_tof->header.frame_id = "amplitudes";
304  amp->height = yRes;
305  amp->width = xRes;
306  amp->encoding = getDataType(amDataFormat);
307  amp->step = xRes*getDataSize(amDataFormat);
308  amp->data.resize(xRes*yRes*getDataSize(amDataFormat));
309  memcpy ( &amp->data[0], amplitudes, xRes*yRes*getDataSize(amDataFormat) );
310 
311  amp->header.frame_id = "amplitudes";//nodeName_+"/tof_camera";
312  pub_amp_.publish(amp,ci_tof);
313  ampOk = true;
314  }
315 
316  void *xCoordinates, *yCoordinates, *zCoordinates;
317  status = BTAgetXYZcoordinates(frame, &xCoordinates, &yCoordinates, &zCoordinates, &dataFormat, &unit, &xRes, &yRes);
318  if (status == BTA_StatusOk) {
319  if (_xyz->width != xRes || _xyz->height != yRes || _xyz->fields.size() != 4) {
320  _xyz->width = xRes;
321  _xyz->height = yRes;
323  modifier.setPointCloud2Fields(4, "x", 1, sensor_msgs::PointField::FLOAT32,
324  "y", 1, sensor_msgs::PointField::FLOAT32,
325  "z", 1, sensor_msgs::PointField::FLOAT32,
326  "intensity", 1, sensor_msgs::PointField::UINT16);
327  modifier.resize(_xyz->height * _xyz->width);
328  _xyz->header.frame_id = "cloud";
329  _xyz->is_dense = true;
330  }
331  //if (_cloud.size() != yRes*xRes) {
332  // _cloud.resize(yRes*xRes);
333  //}
334  /* else {
335  pub_xyz_.publish(_xyz);
336  return;
337  }*/
338  float conv = getUnit2Meters(unit);
343  if (dataFormat == BTA_DataFormatSInt16) {
344  /*short *xC, *yC, *zC;
345  xC = (short *)xCoordinates;
346  yC = (short *)yCoordinates;
347  zC = (short *)zCoordinates;*/
348  for (size_t i = 0; i < yRes*xRes; i++, ++_x, ++_y, ++_z, ++_i) {
349  *_x = static_cast<short *>(xCoordinates)[i]*conv;
350  *_y = static_cast<short *>(yCoordinates)[i]*conv;
351  *_z = static_cast<short *>(zCoordinates)[i]*conv;
352  if (ampOk) {
353  if(amDataFormat == BTA_DataFormatUInt16) {
354  *_i = static_cast<unsigned short *>(amplitudes)[i];
355  } else if(amDataFormat == BTA_DataFormatFloat32) {
356  *_i = static_cast<float *>(amplitudes)[i];
357  }
358  } else
359  *_i = 255;
360  }
361  } else if (dataFormat == BTA_DataFormatFloat32) {
362  for (size_t i = 0; i < yRes*xRes; i++, ++_x, ++_y, ++_z, ++_i) {
363  *_x = static_cast<float *>(xCoordinates)[i]*conv;
364  *_y = static_cast<float *>(yCoordinates)[i]*conv;
365  *_z = static_cast<float *>(zCoordinates)[i]*conv;
366  if (ampOk) {
367  if(amDataFormat == BTA_DataFormatUInt16) {
368  *_i = static_cast<unsigned short *>(amplitudes)[i];
369  } else if(amDataFormat == BTA_DataFormatFloat32) {
370  *_i = static_cast<float *>(amplitudes)[i];
371  }
372  } else
373  *_i = 255;
374  }
375  } else {
376  ROS_WARN_STREAM("Unhandled BTA_DataFormat: " << dataFormat);
377  return;
378  }
379  //pcl::toROSMsg(_cloud, *_xyz);
380 
381  _xyz->header.seq = frame->frameCounter;
382  _xyz->header.stamp.sec = frame->timeStamp;
383 
384  //Keeping until resolving problem with rviz
385  /*
386  xyz->width = xRes;
387  xyz->height = yRes;
388  sensor_msgs::PointCloud2Modifier modifier(*xyz);
389  ROS_DEBUG_STREAM("MAL? " << unit);
390 
391  modifier.setPointCloud2Fields(3, "x", 1, sensor_msgs::PointField::INT16,
392  "y", 1, sensor_msgs::PointField::INT16,
393  "z", 1, sensor_msgs::PointField::INT16/*,
394  "intensity", 1, sensor_msgs::PointField::UINT16* /);
395  ROS_DEBUG_STREAM("MAL? " << modifier.size());
396  short *xC, *yC, *zC;
397  xC = (short *)xCoordinates;
398  yC = (short *)yCoordinates;
399  zC = (short *)zCoordinates;
400  std::vector<short> test;
401  for (size_t i = 0; i < yRes*xRes; i++) {
402  test.push_back(xC[i]);
403  test.push_back(yC[i]);
404  test.push_back(zC[i]);
405  //memcpy ( &xyz->data[i*xyz->point_step], &xCoordinates[i*getDataSize(dataFormat)], getDataSize(dataFormat) );
406  //memcpy ( &xyz->data[i*xyz->point_step+getDataSize(dataFormat) ], &yCoordinates[i*getDataSize(dataFormat)], getDataSize(dataFormat) );
407  //memcpy ( &xyz->data[i*xyz->point_step+2*getDataSize(dataFormat) ], &zCoordinates[i*getDataSize(dataFormat)], getDataSize(dataFormat) );
408  //memcpy ( &xyz->data[i*xyz->point_step+3*getDataSize(dataFormat)], &amplitudes[i*getDataSize(amDataFormat)], getDataSize(amDataFormat) );
409  //ROS_DEBUG_STREAM("ox: " << (short)xCoordinates[i*getDataSize(dataFormat)] << " y: " << (short)yCoordinates[i*getDataSize(dataFormat)] << " z: " << (short)zCoordinates[i*getDataSize(dataFormat)]);
410  //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) ]);
411  }
412  memcpy ( &xyz->data[0], &test[0], test.size());
413  ROS_DEBUG_STREAM("MAL? " << modifier.size());
414  */
415 
417  }
418 
419  BTAfreeFrame(&frame);
420 }
421 
422 /*void BtaRos::ampCb(const sensor_msgs::ImagePtr& amp)
423  {
424  sensor_msgs::CameraInfoPtr ci_tof(new sensor_msgs::CameraInfo(cim_tof_.getCameraInfo()));
425  ci_tof->header.frame_id = nodeName_+"/tof_camera";
426  amp->header.frame_id = nodeName_+"/tof_camera";
427 
428  pub_amp_.publish(amp,ci_tof);
429  }
430 
431  void BtaRos::disCb(const sensor_msgs::ImagePtr& dis)
432  {
433  sensor_msgs::CameraInfoPtr ci_tof(new sensor_msgs::CameraInfo(cim_tof_.getCameraInfo()));
434  ci_tof->header.frame_id = nodeName_+"/tof_camera";
435  dis->header.frame_id = nodeName_+"/tof_camera";
436 
437  pub_dis_.publish(dis,ci_tof);
438  }*/
439 
441  int iusValue;
442  if(nh_private_.getParam(nodeName_+"/udpDataIpAddrLen",iusValue)) {
443  config_.udpDataIpAddrLen = (uint8_t)iusValue;
444  ROS_DEBUG_STREAM("config_.udpDataIpAddrLen: " << (int)config_.udpDataIpAddrLen);
445  }
446  if (nh_private_.hasParam(nodeName_+"/udpDataIpAddr")) {
447  ROS_DEBUG_STREAM("config_.udpDataIpAddr:");
448  for (int i = 1; i <= config_.udpDataIpAddrLen; i++) {
449  std::ostringstream to_string;
450  to_string << "";
451  to_string << nodeName_ << "/udpDataIpAddr/n" << i;
452  nh_private_.getParam(to_string.str(),iusValue);
453  udpDataIpAddr_[i-1] = (uint8_t)iusValue;
454  ROS_DEBUG_STREAM((int)udpDataIpAddr_[i-1] << ",");
455  }
456  config_.udpDataIpAddr = udpDataIpAddr_;
457  }
458  if(nh_private_.getParam(nodeName_+"/udpDataPort",iusValue)) {
459  config_.udpDataPort = (uint16_t)iusValue;
460  ROS_DEBUG_STREAM("config_.udpDataPort: " << config_.udpDataPort);
461  }
462 
463  if(nh_private_.getParam(nodeName_+"/udpControlOutIpAddrLen",iusValue)) {
464  config_.udpControlOutIpAddrLen = (uint8_t)iusValue;
465  ROS_DEBUG_STREAM("config_.udpControlOutIpAddrLen: " << (int)config_.udpControlOutIpAddrLen);
466  }
467  if (nh_private_.hasParam(nodeName_+"/udpControlOutIpAddr")) {
468  ROS_DEBUG_STREAM("config_.udpControlOutIpAddr:");
469  for (int i = 1; i <= config_.udpControlOutIpAddrLen; i++) {
470  std::ostringstream to_string;
471  to_string << "";
472  to_string << nodeName_ << "/udpControlOutIpAddr/n" << i;
473  nh_private_.getParam(to_string.str(),iusValue);
474  udpControlOutIpAddr_[i-1] = (uint8_t)iusValue;
475  ROS_DEBUG_STREAM((int)udpControlOutIpAddr_[i-1] << ",");
476  }
477  config_.udpControlOutIpAddr = udpControlOutIpAddr_;
478  }
479  if(nh_private_.getParam(nodeName_+"/udpControlPort",iusValue)) {
480  config_.udpControlPort = (uint16_t)iusValue;
481  ROS_DEBUG_STREAM("config_.udpControlPort: " << (int)config_.udpControlPort);
482  }
483 
484  if(nh_private_.getParam(nodeName_+"/udpControlInIpAddrLen",iusValue)) {
485  config_.udpControlInIpAddrLen = (uint8_t)iusValue;
486  ROS_DEBUG_STREAM("config_.udpControlInIpAddrLen: " << (int)config_.udpControlInIpAddrLen);
487  }
488  if (nh_private_.hasParam(nodeName_+"/udpControlInIpAddr")) {
489 
490  ROS_DEBUG_STREAM("config_.udpControlInIpAddr:");
491  for (int i = 1; i <= config_.udpControlInIpAddrLen; i++) {
492  std::ostringstream to_string;
493  to_string << "";
494  to_string << nodeName_ << "/udpControlInIpAddr/n" << i;
495  nh_private_.getParam(to_string.str(),iusValue);
496  udpControlInIpAddr_[i-1] = (uint8_t)iusValue;
497  ROS_DEBUG_STREAM((int)udpControlInIpAddr_[i-1] << ",");
498  }
499  config_.udpControlInIpAddr = udpControlInIpAddr_;
500  }
501  if(nh_private_.getParam(nodeName_+"/udpControlCallbackPort",iusValue)) {
502  config_.udpControlCallbackPort = (uint16_t)iusValue;
503  ROS_DEBUG_STREAM("config_.udpControlCallbackPort: " << (int)config_.udpControlCallbackPort);
504  }
505 
506  if(nh_private_.getParam(nodeName_+"/tcpDeviceIpAddrLen",iusValue)) {
507  config_.tcpDeviceIpAddrLen = (uint8_t)iusValue;
508  ROS_DEBUG_STREAM("config_.tcpDeviceIpAddrLen: " << (int)config_.tcpDeviceIpAddrLen);
509  }
510  if (nh_private_.hasParam(nodeName_+"/tcpDeviceIpAddr")) {
511  ROS_DEBUG_STREAM("TCP address:");
512  for (int i = 1; i <= config_.tcpDeviceIpAddrLen; i++) {
513  std::ostringstream to_string;
514  to_string << "";
515  to_string << nodeName_ << "/tcpDeviceIpAddr/n" << i;
516  nh_private_.getParam(to_string.str(),iusValue);
517  tcpDeviceIpAddr_[i-1] = (uint8_t)iusValue;
518  ROS_DEBUG_STREAM((int)tcpDeviceIpAddr_[i-1] << ",");
519  }
520  config_.tcpDeviceIpAddr = tcpDeviceIpAddr_;
521  }
522  if(nh_private_.getParam(nodeName_+"/tcpControlPort",iusValue)) {
523  config_.tcpControlPort = (uint16_t)iusValue;
524  ROS_DEBUG_STREAM("config_.tcpControlPort: " << config_.tcpControlPort);
525  }
526 
527  if (nh_private_.getParam(nodeName_+"/tcpDataPort",iusValue))
528  config_.tcpDataPort = (uint16_t)iusValue;
529 
530  nh_private_.getParam(nodeName_+"/uartPortName",uartPortName_);
531  config_.uartPortName = (uint8_t *)uartPortName_.c_str();
532 
533  if(nh_private_.getParam(nodeName_+"/uartBaudRate",iusValue))
534  config_.uartBaudRate = (uint32_t)iusValue;
535  if(nh_private_.getParam(nodeName_+"/uartDataBits",iusValue))
536  config_.uartDataBits = (uint8_t)iusValue;
537  if(nh_private_.getParam(nodeName_+"/uartStopBits",iusValue))
538  config_.uartStopBits = (uint8_t)iusValue;
539  if(nh_private_.getParam(nodeName_+"/uartParity",iusValue))
540  config_.uartParity = (uint8_t)iusValue;
541  if(nh_private_.getParam(nodeName_+"/uartTransmitterAddress",iusValue))
542  config_.uartTransmitterAddress = (uint8_t)iusValue;
543  if(nh_private_.getParam(nodeName_+"/uartReceiverAddress",iusValue))
544  config_.uartReceiverAddress = (uint8_t)iusValue;
545  if(nh_private_.getParam(nodeName_+"/serialNumber",iusValue))
546  config_.serialNumber = (uint32_t)iusValue;
547 
548  nh_private_.getParam(nodeName_+"/calibFileName",calibFileName_);
549  config_.calibFileName = (uint8_t *)calibFileName_.c_str();
550 
551  int32_t frameMode;
552  if (nh_private_.getParam(nodeName_+"/frameMode",frameMode))
553  config_.frameMode = (BTA_FrameMode)frameMode;
554 
555  if (nh_private_.getParam(nodeName_+"/verbosity",iusValue))
556  config_.verbosity = (uint8_t)iusValue;
557 
558  if(nh_private_.getParam(nodeName_+"/frameQueueLength",iusValue))
559  config_.frameQueueLength = (uint16_t)iusValue;
560 
561  int32_t frameQueueMode;
562  if (nh_private_.getParam(nodeName_+"/frameQueueMode",frameQueueMode))
563  config_.frameQueueMode = (BTA_QueueMode)frameQueueMode;
564 
565 #if !defined(BTA_ETH) || !defined(BTA_P100)
566  int32_t deviceType;
567  if(nh_private_.getParam(nodeName_+"/deviceType",deviceType))
568  config_.deviceType = (BTA_DeviceType)deviceType;
569 #endif
570 
571  //config_.frameArrived = &frameArrived;
572  config_.infoEvent = &infoEventCb;
573 }
574 
575 
576 
578  BTA_Status status;
579  BTA_DeviceInfo *deviceInfo;
580 
581  // Init camera connection
582  //ros::Duration().sleep();
583  status = (BTA_Status)-1;
584  for (int i=0; i<10; i++) {
585  ROS_INFO_STREAM("Connecting... try " << i+1);
586  status = BTAopen(&config_, &handle_);
587  if (status != BTA_StatusOk) {
588  if (!nh_private_.ok() && ros::isShuttingDown())
589  return -1;
590  ROS_WARN_STREAM("Could not connect to the camera. status: " << status);
591  continue;
592  }
593  break;
594  }
595  if (!BTAisConnected(handle_)) {
596  ROS_WARN_STREAM("Could not connect to the camera.");
597  return -1;
598  }
599 
600  ROS_INFO_STREAM("Camera connected sucessfully. status: " << status);
601  status = BTAgetDeviceInfo(handle_, &deviceInfo);
602  if (status != BTA_StatusOk) {
603  ROS_WARN_STREAM("Could not get device info. status: " << status);
604  return status;
605  }
606 
607  ROS_INFO_STREAM("Retrieved device info: \n"
608  << "deviceType: " << deviceInfo->deviceType << "\n"
609  << "serialNumber: " << deviceInfo->serialNumber << "\n"
610  << "firmwareVersionMajor: " << deviceInfo->firmwareVersionMajor << "\n"
611  << "firmwareVersionMinor: " << deviceInfo->firmwareVersionMinor << "\n"
612  << "firmwareVersionNonFunc: " << deviceInfo->firmwareVersionNonFunc
613  << "\n");
614 
615  ROS_INFO_STREAM("Service running: " << (int)BTAisRunning(handle_));
616  ROS_INFO_STREAM("Connection up: " << (int)BTAisConnected(handle_));
617 
618  BTAfreeDeviceInfo(deviceInfo);
619  return 1;
620 }
621 
623 {
624 
625  /*
626  * Camera config
627  */
628 
629  BTAinitConfig(&config_);
630 
631  parseConfig();
632 
633  /*
634  * Camera Initialization
635  */
636  ROS_DEBUG_STREAM("Config Readed sucessfully");
637 
638  BTA_Status status;
639  if (connectCamera() < 0)
640  return -1;
641 
643  reconfigure_server_->setCallback(boost::bind(&BtaRos::callback, this, _1, _2));
644 
645  while (!config_init_)
646  {
647  ROS_DEBUG("Waiting for dynamic reconfigure configuration.");
648  boost::this_thread::sleep(boost::posix_time::seconds(0.1));
649  }
650  ROS_DEBUG("Dynamic reconfigure configuration received.");
651 
652  /*
653  * ROS Node Initialization
654  */
655  {
656  // Advertise all published topics
659  /*camera_info_url_*/"package://bta_tof_driver/calib.yml")) {
660  cim_tof_.loadCameraInfo("package://bta_tof_driver/calib.yml");
661  ROS_INFO_STREAM("Loaded camera calibration from " <<
662  "package://bta_tof_driver/calib.yml" );
663  } else {
664  ROS_WARN_STREAM("Camera info at: " <<
665  "package://bta_tof_driver/calib.yml" <<
666  " not found. Using an uncalibrated config_.");
667  }
668 
669  pub_amp_ = it_.advertiseCamera(nodeName_ + "/tof_camera/image_raw", 1);
670  pub_dis_ = it_.advertiseCamera(nodeName_ + "/tof_camera/compressedDepth", 1);
671  pub_xyz_ = nh_private_.advertise<sensor_msgs::PointCloud2> (nodeName_ + "/tof_camera/point_cloud_xyz", 1);
672 
673  //sub_amp_ = nh_private_.subscribe("bta_node_amp", 1, &BtaRos::ampCb, this);
674  //sub_dis_ = nh_private_.subscribe("bta_node_dis", 1, &BtaRos::disCb, this);
675  }
676 
677  while (nh_private_.ok() && !ros::isShuttingDown()) {
678  if (!BTAisConnected(handle_)) {
679  ROS_WARN_STREAM("The camera got disconnected." << BTAisConnected(handle_));
680  if (connectCamera() < 0)
681  break;
682  }
683 
684  publishData();
685  ros::spinOnce ();
686  }
687  return 0;
688 }
689 }
690 
image_transport::CameraPublisher pub_amp_
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
void close()
Closes the connection to the device.
sensor_msgs::CameraInfo getCameraInfo(void)
void publish(const boost::shared_ptr< M > &message) const
camera_info_manager::CameraInfoManager cim_tof_
bool loadCameraInfo(const std::string &url)
uint32_t getNumSubscribers() const
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 setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
void publishData()
Publish the data based on set up parameters.
#define ROS_INFO(...)
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.
image_transport::ImageTransport it_
uint32_t getNumSubscribers() const
#define ROS_INFO_STREAM(args)
tf2_ros::StaticTransformBroadcaster pub_tf
bool getParam(const std::string &key, std::string &s) const
float getUnit2Meters(BTA_Unit unit)
Gives the conversion value to meters from the BTA_Unit.
static Time now()
bool ok() const
bool hasParam(const std::string &key) const
void sendTransform(const geometry_msgs::TransformStamped &transform)
ROSCPP_DECL void spinOnce()
BtaRos(ros::NodeHandle nh_camera, ros::NodeHandle nh_private, std::string nodeName)
Class constructor.
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
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 Sat Nov 23 2019 03:52:25