public.cc
Go to the documentation of this file.
1 
37 #include <stdlib.h>
38 #include <algorithm>
39 
41 
42 #include "details/channel.hh"
43 #include "details/query.hh"
44 
49 
53 
59 
61 
65 
68 
88 
93 
96 
97 namespace crl {
98 namespace multisense {
99 namespace details {
100 
101 //
102 // The user may "hold on" to the buffer back-end
103 // of a datum within a callback thread.
104 
106 
107 //
108 //
109 // Public API follows
110 //
111 //
112 
113 //
114 // Adds a new image listener
115 
117  DataSource imageSourceMask,
118  void *userDataP)
119 {
120  try {
121 
123  m_imageListeners.push_back(new ImageListener(callback,
124  imageSourceMask,
125  userDataP,
127 
128  } catch (const std::exception& e) {
129  CRL_DEBUG("exception: %s\n", e.what());
130  return Status_Exception;
131  }
132  return Status_Ok;
133 }
134 
135 //
136 // Adds a new laser listener
137 
139  void *userDataP)
140 {
141  try {
142 
144  m_lidarListeners.push_back(new LidarListener(callback,
145  0,
146  userDataP,
148 
149  } catch (const std::exception& e) {
150  CRL_DEBUG("exception: %s\n", e.what());
151  return Status_Exception;
152  }
153  return Status_Ok;
154 }
155 
156 //
157 // Adds a new PPS listener
158 
160  void *userDataP)
161 {
162  try {
163 
165  m_ppsListeners.push_back(new PpsListener(callback,
166  0,
167  userDataP,
169 
170  } catch (const std::exception& e) {
171  CRL_DEBUG("exception: %s\n", e.what());
172  return Status_Exception;
173  }
174  return Status_Ok;
175 }
176 
177 //
178 // Adds a new IMU listener
179 
181  void *userDataP)
182 {
183  try {
184 
186  m_imuListeners.push_back(new ImuListener(callback,
187  0,
188  userDataP,
190 
191  } catch (const std::exception& e) {
192  CRL_DEBUG("exception: %s\n", e.what());
193  return Status_Exception;
194  }
195  return Status_Ok;
196 }
197 
198 //
199 // Removes an image listener
200 
202 {
203  try {
205 
206  std::list<ImageListener*>::iterator it;
207  for(it = m_imageListeners.begin();
208  it != m_imageListeners.end();
209  it ++) {
210 
211  if ((*it)->callback() == callback) {
212  delete *it;
213  m_imageListeners.erase(it);
214  return Status_Ok;
215  }
216  }
217 
218  } catch (const std::exception& e) {
219  CRL_DEBUG("exception: %s\n", e.what());
220  return Status_Exception;
221  }
222 
223  return Status_Error;
224 }
225 
226 //
227 // Removes a lidar listener
228 
230 {
231  try {
233 
234  std::list<LidarListener*>::iterator it;
235  for(it = m_lidarListeners.begin();
236  it != m_lidarListeners.end();
237  it ++) {
238 
239  if ((*it)->callback() == callback) {
240  delete *it;
241  m_lidarListeners.erase(it);
242  return Status_Ok;
243  }
244  }
245 
246  } catch (const std::exception& e) {
247  CRL_DEBUG("exception: %s\n", e.what());
248  return Status_Exception;
249  }
250 
251  return Status_Error;
252 }
253 
254 //
255 // Removes a PPS listener
256 
258 {
259  try {
261 
262  std::list<PpsListener*>::iterator it;
263  for(it = m_ppsListeners.begin();
264  it != m_ppsListeners.end();
265  it ++) {
266 
267  if ((*it)->callback() == callback) {
268  delete *it;
269  m_ppsListeners.erase(it);
270  return Status_Ok;
271  }
272  }
273 
274  } catch (const std::exception& e) {
275  CRL_DEBUG("exception: %s\n", e.what());
276  return Status_Exception;
277  }
278 
279  return Status_Error;
280 }
281 
282 //
283 // Removes an IMU listener
284 
286 {
287  try {
289 
290  std::list<ImuListener*>::iterator it;
291  for(it = m_imuListeners.begin();
292  it != m_imuListeners.end();
293  it ++) {
294 
295  if ((*it)->callback() == callback) {
296  delete *it;
297  m_imuListeners.erase(it);
298  return Status_Ok;
299  }
300  }
301 
302  } catch (const std::exception& e) {
303  CRL_DEBUG("exception: %s\n", e.what());
304  return Status_Exception;
305  }
306 
307  return Status_Error;
308 }
309 
310 //
311 // Reserve the current callback buffer being used in a dispatch thread
312 
314 {
315  if (dispatchBufferReferenceTP) {
316 
317  try {
318 
319  return reinterpret_cast<void*>(new utility::BufferStream(*dispatchBufferReferenceTP));
320 
321  } catch (const std::exception& e) {
322 
323  CRL_DEBUG("exception: %s\n", e.what());
324 
325  } catch (...) {
326 
327  CRL_DEBUG("unknown exception\n");
328  }
329  }
330 
331  return NULL;
332 }
333 
334 //
335 // Release a user reserved buffer back to us
336 
338 {
339  if (referenceP) {
340  try {
341 
342  delete reinterpret_cast<utility::BufferStream*>(referenceP);
343  return Status_Ok;
344 
345  } catch (const std::exception& e) {
346 
347  CRL_DEBUG("exception: %s\n", e.what());
348  return Status_Exception;
349 
350  } catch (...) {
351 
352  CRL_DEBUG("unknown exception\n");
353  return Status_Exception;
354  }
355  }
356 
357  return Status_Error;
358 }
359 
360 //
361 // Get a copy of the histogram for a particular frame ID
362 
364  image::Histogram& histogram)
365 {
366  try {
367 
369 
370  const wire::ImageMeta *metaP = m_imageMetaCache.find_nolock(frameId);
371  if (NULL == metaP) {
372  CRL_DEBUG("no meta cached for frameId %ld",
373  static_cast<long int>(frameId));
374  return Status_Failed;
375  }
376 
379 
380  const int entries = histogram.channels * histogram.bins;
381  const int sizeBytes = entries * sizeof(uint32_t);
382 
383  histogram.data.resize(entries);
384  memcpy(&(histogram.data[0]), metaP->histogramP, sizeBytes);
385 
386  return Status_Ok;
387 
388  } catch (const std::exception& e) {
389  CRL_DEBUG("exception: %s\n", e.what());
390  return Status_Exception;
391  }
392 
393  return Status_Error;
394 }
395 
396 //
397 // Enable/disable network-based time synchronization
398 
400 {
401  m_networkTimeSyncEnabled = enabled;
402  return Status_Ok;
403 }
404 
405 //
406 // Primary stream control
407 
409 {
411 
413 
414  cmd.enable(sourceApiToWire(mask));
415 
416  Status status = waitAck(cmd);
417  if (Status_Ok == status)
418  m_streamsEnabled |= mask;
419 
420  return status;
421 }
423 {
425 
427 
428  cmd.disable(sourceApiToWire(mask));
429 
430  Status status = waitAck(cmd);
431  if (Status_Ok == status)
432  m_streamsEnabled &= ~mask;
433 
434  return status;
435 }
437 {
439 
440  mask = m_streamsEnabled;
441 
442  return Status_Ok;
443 }
444 
445 //
446 // Secondary stream control
447 
449 {
451 
452  cmd.streams.push_back(wire::DirectedStream(stream.mask,
453  stream.address,
454  stream.udpPort,
455  stream.fpsDecimation));
456  return waitAck(cmd);
457 }
458 
459 Status impl::startDirectedStreams(const std::vector<DirectedStream>& streams)
460 {
462 
463  for (uint32_t index = 0 ; index < streams.size() ; ++index) {
464  DirectedStream stream = streams[index];
465 
466  cmd.streams.push_back(wire::DirectedStream(stream.mask,
467  stream.address,
468  stream.udpPort,
469  stream.fpsDecimation));
470  }
471  return waitAck(cmd);
472 }
473 
475 {
477 
478  cmd.streams.push_back(wire::DirectedStream(stream.mask,
479  stream.address,
480  stream.udpPort,
481  stream.fpsDecimation));
482  return waitAck(cmd);
483 }
484 
485 Status impl::getDirectedStreams(std::vector<DirectedStream>& streams)
486 {
487  Status status;
489 
490  streams.clear();
491 
492  status = waitData(wire::SysGetDirectedStreams(), rsp);
493  if (Status_Ok != status)
494  return status;
495 
496  std::vector<wire::DirectedStream>::const_iterator it = rsp.streams.begin();
497  for(; it != rsp.streams.end(); ++it)
498  streams.push_back(DirectedStream((*it).mask,
499  (*it).address,
500  (*it).udpPort,
501  (*it).fpsDecimation));
502  return Status_Ok;
503 }
504 
506 {
507  maximum = MAX_DIRECTED_STREAMS;
508  return Status_Ok;
509 }
510 
511 //
512 // Set the trigger source
513 
515 {
516  uint32_t wireSource;
517 
518  switch(s) {
519  case Trigger_Internal:
520 
522  break;
523 
524  case Trigger_External:
525 
527  break;
528 
529  default:
530 
531  return Status_Error;
532  }
533 
534  return waitAck(wire::CamSetTriggerSource(wireSource));
535 }
536 
537 //
538 // Set the motor speed
539 
541 {
542  return waitAck(wire::LidarSetMotor(rpm));
543 }
544 
545 //
546 // Get/set the lighting configuration
547 
549 {
550  Status status;
551  wire::LedStatus data;
552 
553  status = waitData(wire::LedGetStatus(), data);
554  if (Status_Ok != status)
555  return status;
556 
557  for(uint32_t i=0; i<lighting::MAX_LIGHTS; i++) {
558  float duty=0.0f;
559  if ((1<<i) & data.available)
560  duty = (data.intensity[i] * 100.0f) / 255;
561  c.setDutyCycle(i, duty);
562  }
563 
564  c.setFlash(data.flash != 0);
565 
566  return Status_Ok;
567 }
568 
570 {
571  wire::LedSet msg;
572 
573  msg.flash = c.getFlash() ? 1 : 0;
574  for(uint32_t i=0; i<lighting::MAX_LIGHTS; i++) {
575 
576  float duty = c.getDutyCycle(i);
577  if (duty >= 0.0f) { // less than zero == not set
578  msg.mask |= (1<<i);
579  msg.intensity[i] = static_cast<uint8_t> (255.0f * (utility::boundValue(duty, 0.0f, 100.0f) / 100.0f));
580  }
581  }
582 
583  return waitAck(msg);
584 }
585 
587 {
588  Status requestStatus;
590 
591  requestStatus = waitData(wire::LedGetSensorStatus(), data);
592  if (Status_Ok != requestStatus)
593  return requestStatus;
594 
596 
597  return Status_Ok;
598 }
599 
600 //
601 // Requests version from sensor
602 
604 {
606  return Status_Ok;
607 }
608 
609 //
610 // Version of this API
611 
613 {
614  version = API_VERSION;
615  return Status_Ok;
616 }
617 
618 //
619 // Requests all versioning information
620 
622 {
623  v.apiBuildDate = std::string(__DATE__ ", " __TIME__);
630 
631  return Status_Ok;
632 }
633 
634 //
635 // Query camera configuration
636 
638 {
639  Status status;
641 
642  status = waitData(wire::CamGetConfig(), d);
643  if (Status_Ok != status)
644  return status;
645 
646  // for access to protected calibration members
647  class ConfigAccess : public image::Config {
648  public:
649  void setCal(float fx, float fy, float cx, float cy,
650  float tx, float ty, float tz,
651  float r, float p, float w) {
652  m_fx = fx; m_fy = fy; m_cx = cx; m_cy = cy;
653  m_tx = tx; m_ty = ty; m_tz = tz;
654  m_roll = r; m_pitch = p; m_yaw = w;
655  };
656  };
657 
658  // what is the proper c++ cast for this?
659  ConfigAccess& a = *((ConfigAccess *) &config);
660 
661  a.setResolution(d.width, d.height);
662  if (-1 == d.disparities) { // pre v2.3 firmware
663  if (1024 == d.width) // TODO: check for monocular
664  d.disparities = 128;
665  else
666  d.disparities = 0;
667  }
668  a.setDisparities(d.disparities);
669  a.setFps(d.framesPerSecond);
670  a.setGain(d.gain);
671 
672  a.setExposure(d.exposure);
673  a.setAutoExposure(d.autoExposure != 0);
674  a.setAutoExposureMax(d.autoExposureMax);
675  a.setAutoExposureDecay(d.autoExposureDecay);
676  a.setAutoExposureThresh(d.autoExposureThresh);
677 
678  a.setWhiteBalance(d.whiteBalanceRed, d.whiteBalanceBlue);
679  a.setAutoWhiteBalance(d.autoWhiteBalance != 0);
680  a.setAutoWhiteBalanceDecay(d.autoWhiteBalanceDecay);
681  a.setAutoWhiteBalanceThresh(d.autoWhiteBalanceThresh);
682  a.setStereoPostFilterStrength(d.stereoPostFilterStrength);
683  a.setHdr(d.hdrEnabled);
684 
685  a.setCal(d.fx, d.fy, d.cx, d.cy,
686  d.tx, d.ty, d.tz,
687  d.roll, d.pitch, d.yaw);
688 
689  return Status_Ok;
690 }
691 
692 //
693 // Set camera configuration
694 //
695 // Currently several sensor messages are combined and presented
696 // to the user as one.
697 
699 {
700  Status status;
701 
702  status = waitAck(wire::CamSetResolution(c.width(),
703  c.height(),
704  c.disparities(),
705  c.camMode(),
706  c.offset()));
707  if (Status_Ok != status)
708  return status;
709 
710  wire::CamControl cmd;
711 
712  cmd.framesPerSecond = c.fps();
713  cmd.gain = c.gain();
714 
715  cmd.exposure = c.exposure();
716  cmd.autoExposure = c.autoExposure() ? 1 : 0;
720 
723  cmd.autoWhiteBalance = c.autoWhiteBalance() ? 1 : 0;
727  cmd.hdrEnabled = c.hdrEnabled();
728 
729  return waitAck(cmd);
730 }
731 
732 //
733 // Get camera calibration
734 
736 {
738 
740  if (Status_Ok != status)
741  return status;
742 
743  CPY_ARRAY_2(c.left.M, d.left.M, 3, 3);
744  CPY_ARRAY_1(c.left.D, d.left.D, 8);
745  CPY_ARRAY_2(c.left.R, d.left.R, 3, 3);
746  CPY_ARRAY_2(c.left.P, d.left.P, 3, 4);
747 
748  CPY_ARRAY_2(c.right.M, d.right.M, 3, 3);
749  CPY_ARRAY_1(c.right.D, d.right.D, 8);
750  CPY_ARRAY_2(c.right.R, d.right.R, 3, 3);
751  CPY_ARRAY_2(c.right.P, d.right.P, 3, 4);
752 
753  return Status_Ok;
754 }
755 
756 //
757 // Set camera calibration
758 
760 {
762 
763  CPY_ARRAY_2(d.left.M, c.left.M, 3, 3);
764  CPY_ARRAY_1(d.left.D, c.left.D, 8);
765  CPY_ARRAY_2(d.left.R, c.left.R, 3, 3);
766  CPY_ARRAY_2(d.left.P, c.left.P, 3, 4);
767 
768  CPY_ARRAY_2(d.right.M, c.right.M, 3, 3);
769  CPY_ARRAY_1(d.right.D, c.right.D, 8);
770  CPY_ARRAY_2(d.right.R, c.right.R, 3, 3);
771  CPY_ARRAY_2(d.right.P, c.right.P, 3, 4);
772 
773  return waitAck(d);
774 }
775 
776 //
777 // Get sensor calibration
778 
780 {
782 
784  if (Status_Ok != status)
785  return status;
786  CPY_ARRAY_1(c.adc_gain, d.adc_gain, 2);
788 
789  return Status_Ok;
790 }
791 
792 //
793 // Set sensor calibration
794 
796 {
798 
799  CPY_ARRAY_1(d.adc_gain, c.adc_gain, 2);
801 
802  return waitAck(d);
803 }
804 
805 //
806 // Get sensor calibration
807 
809 {
811 
813  if (Status_Ok != status)
814  return status;
815  c.delay = d.delay;
816 
817  return Status_Ok;
818 }
819 
820 //
821 // Set sensor calibration
822 
824 {
826 
827  d.delay = c.delay;;
828 
829  return waitAck(d);
830 }
831 
832 //
833 // Get lidar calibration
834 
836 {
838 
840  if (Status_Ok != status)
841  return status;
842 
845 
846  return Status_Ok;
847 }
848 
849 //
850 // Set lidar calibration
851 
853 {
855 
858 
859  return waitAck(d);
860 }
861 
862 //
863 // Get a list of supported image formats / data sources
864 
865 Status impl::getDeviceModes(std::vector<system::DeviceMode>& modes)
866 {
868 
869  Status status = waitData(wire::SysGetDeviceModes(), d);
870  if (Status_Ok != status)
871  return Status_Error;
872 
873  modes.resize(d.modes.size());
874  for(uint32_t i=0; i<d.modes.size(); i++) {
875 
876  system::DeviceMode& a = modes[i];
877  const wire::DeviceMode& w = d.modes[i];
878 
879  a.width = w.width;
880  a.height = w.height;
882  if (m_sensorVersion.firmwareVersion >= 0x0203)
883  a.disparities = w.disparities;
884  else
885  a.disparities = (a.width == 1024) ? 128 : 0;
886  }
887 
888  return Status_Ok;
889 }
890 
891 //
892 // Set/get the mtu
893 
894 Status impl::setMtu(int32_t mtu)
895 {
896  Status status = Status_Ok;
897 
898  //
899  // Firmware v2.3 or better will send us an MTU-sized
900  // response packet, which can be used to verify the
901  // MTU setting before we actually make the change.
902 
903  if (m_sensorVersion.firmwareVersion <= 0x0202)
904  status = waitAck(wire::SysMtu(mtu));
905  else {
906 
908  status = waitData(wire::SysTestMtu(mtu), resp);
909  if (Status_Ok == status)
910  status = waitAck(wire::SysMtu(mtu));
911  }
912 
913  if (Status_Ok == status)
914  m_sensorMtu = mtu;
915 
916  return status;
917 }
918 
919 Status impl::getMtu(int32_t& mtu)
920 {
921  wire::SysMtu resp;
922 
923  Status status = waitData(wire::SysGetMtu(), resp);
924  if (Status_Ok == status)
925  mtu = resp.mtu;
926 
927  return status;
928 }
929 
930 //
931 // Set/get the network configuration
932 
934 {
936  c.ipv4Gateway,
937  c.ipv4Netmask));
938 }
939 
941 {
942  wire::SysNetwork resp;
943 
944  Status status = waitData(wire::SysGetNetwork(), resp);
945  if (Status_Ok == status) {
946  c.ipv4Address = resp.address;
947  c.ipv4Gateway = resp.gateway;
948  c.ipv4Netmask = resp.netmask;
949  }
950 
951  return status;
952 }
953 
954 //
955 // Get device info from sensor
956 
958 {
960 
961  Status status = waitData(wire::SysGetDeviceInfo(), w);
962  if (Status_Ok != status)
963  return status;
964 
965  info.name = w.name;
966  info.buildDate = w.buildDate;
967  info.serialNumber = w.serialNumber;
969  info.pcbs.clear();
970 
971  for(uint8_t i=0; i<w.numberOfPcbs; i++) {
972  system::PcbInfo pcb;
973 
974  pcb.name = w.pcbs[i].name;
975  pcb.revision = w.pcbs[i].revision;
976 
977  info.pcbs.push_back(pcb);
978  }
979 
980  info.imagerName = w.imagerName;
982  info.imagerWidth = w.imagerWidth;
983  info.imagerHeight = w.imagerHeight;
984  info.lensName = w.lensName;
985  info.lensType = w.lensType;
989  info.lightingType = w.lightingType;
991  info.laserName = w.laserName;
992  info.laserType = w.laserType;
993  info.motorName = w.motorName;
994  info.motorType = w.motorType;
996 
997  return Status_Ok;
998 }
999 
1000 
1002 {
1004 
1019 
1024 
1030 
1031  return Status_Ok;
1032 }
1033 
1035 {
1037 
1039  if (Status_Ok != status)
1040  return status;
1041 
1042  calibration.x = d.calibration[0];
1043  calibration.y = d.calibration[1];
1044  calibration.z = d.calibration[2];
1045  calibration.roll = d.calibration[3];
1046  calibration.pitch = d.calibration[4];
1047  calibration.yaw = d.calibration[5];
1048 
1049  return Status_Ok;
1050 }
1051 
1053 {
1055 
1056  w.calibration[0] = calibration.x;
1057  w.calibration[1] = calibration.y;
1058  w.calibration[2] = calibration.z;
1059  w.calibration[3] = calibration.roll;
1060  w.calibration[4] = calibration.pitch;
1061  w.calibration[5] = calibration.yaw;
1062 
1063  return waitAck(w);
1064 
1065  return Status_Ok;
1066 }
1067 
1068 //
1069 // Sets the device info
1070 
1071 Status impl::setDeviceInfo(const std::string& key,
1072  const system::DeviceInfo& info)
1073 {
1075 
1076  w.key = key; // must match device firmware key
1077  w.name = info.name;
1078  w.buildDate = info.buildDate;
1079  w.serialNumber = info.serialNumber;
1081  w.numberOfPcbs = std::min((uint32_t) info.pcbs.size(),
1082  (uint32_t) wire::SysDeviceInfo::MAX_PCBS);
1083  for(uint32_t i=0; i<w.numberOfPcbs; i++) {
1084  w.pcbs[i].name = info.pcbs[i].name;
1085  w.pcbs[i].revision = info.pcbs[i].revision;
1086  }
1087 
1088  w.imagerName = info.imagerName;
1090  w.imagerWidth = info.imagerWidth;
1091  w.imagerHeight = info.imagerHeight;
1092  w.lensName = info.lensName;
1093  w.lensType = info.lensType;
1097  w.lightingType = info.lightingType;
1098  w.numberOfLights = info.numberOfLights;
1099  w.laserName = info.laserName;
1100  w.laserType = info.laserType;
1101  w.motorName = info.motorName;
1102  w.motorType = info.motorType;
1104 
1105  return waitAck(w);
1106 }
1107 
1108 //
1109 // Flash the bitstream file (dangerous!)
1110 
1111 Status impl::flashBitstream(const std::string& filename)
1112 {
1113  return doFlashOp(filename,
1116 }
1117 
1118 //
1119 // Flash the firmware file (dangerous!)
1120 
1121 Status impl::flashFirmware(const std::string& filename)
1122 {
1123  return doFlashOp(filename,
1126 }
1127 
1128 //
1129 // Verify the bitstream file
1130 
1131 Status impl::verifyBitstream(const std::string& filename)
1132 {
1133  return doFlashOp(filename,
1136 }
1137 
1138 //
1139 // Verify the firmware file
1140 
1141 Status impl::verifyFirmware(const std::string& filename)
1142 {
1143  return doFlashOp(filename,
1146 }
1147 
1148 //
1149 // Get IMU information
1150 
1151 Status impl::getImuInfo(uint32_t& maxSamplesPerMessage,
1152  std::vector<imu::Info>& info)
1153 {
1154  wire::ImuInfo w;
1155 
1156  Status status = waitData(wire::ImuGetInfo(), w);
1157  if (Status_Ok != status)
1158  return status;
1159 
1160  //
1161  // Wire --> API
1162 
1163  maxSamplesPerMessage = w.maxSamplesPerMessage;
1164  info.resize(w.details.size());
1165  for(uint32_t i=0; i<w.details.size(); i++) {
1166 
1167  const wire::imu::Details& d = w.details[i];
1168 
1169  info[i].name = d.name;
1170  info[i].device = d.device;
1171  info[i].units = d.units;
1172 
1173  info[i].rates.resize(d.rates.size());
1174  for(uint32_t j=0; j<d.rates.size(); j++) {
1175  info[i].rates[j].sampleRate = d.rates[j].sampleRate;
1176  info[i].rates[j].bandwidthCutoff = d.rates[j].bandwidthCutoff;
1177  }
1178  info[i].ranges.resize(d.ranges.size());
1179  for(uint32_t j=0; j<d.ranges.size(); j++) {
1180  info[i].ranges[j].range = d.ranges[j].range;
1181  info[i].ranges[j].resolution = d.ranges[j].resolution;
1182  }
1183  }
1184 
1185  return Status_Ok;
1186 }
1187 
1188 //
1189 // Get IMU configuration
1190 
1191 Status impl::getImuConfig(uint32_t& samplesPerMessage,
1192  std::vector<imu::Config>& c)
1193 {
1194  wire::ImuConfig w;
1195 
1196  Status status = waitData(wire::ImuGetConfig(), w);
1197  if (Status_Ok != status)
1198  return status;
1199 
1200  //
1201  // Wire --> API
1202 
1203  samplesPerMessage = w.samplesPerMessage;
1204  c.resize(w.configs.size());
1205  for(uint32_t i=0; i<w.configs.size(); i++) {
1206  c[i].name = w.configs[i].name;
1207  c[i].enabled = (w.configs[i].flags & wire::imu::Config::FLAGS_ENABLED);
1208  c[i].rateTableIndex = w.configs[i].rateTableIndex;
1209  c[i].rangeTableIndex = w.configs[i].rangeTableIndex;
1210  }
1211 
1212  return Status_Ok;
1213 }
1214 
1215 //
1216 // Set IMU configuration
1217 
1218 Status impl::setImuConfig(bool storeSettingsInFlash,
1219  uint32_t samplesPerMessage,
1220  const std::vector<imu::Config>& c)
1221 {
1222  wire::ImuConfig w;
1223 
1224  //
1225  // API --> wire
1226 
1227  w.storeSettingsInFlash = storeSettingsInFlash ? 1 : 0;
1228  w.samplesPerMessage = samplesPerMessage;
1229  w.configs.resize(c.size());
1230  for(uint32_t i=0; i<c.size(); i++) {
1231  w.configs[i].name = c[i].name;
1232  w.configs[i].flags = c[i].enabled ? wire::imu::Config::FLAGS_ENABLED : 0;
1233  w.configs[i].rateTableIndex = c[i].rateTableIndex;
1234  w.configs[i].rangeTableIndex = c[i].rangeTableIndex;
1235  }
1236 
1237  return waitAck(w);
1238 }
1239 
1240 //
1241 // Get recommended large buffer pool count/size
1242 
1243 Status impl::getLargeBufferDetails(uint32_t& bufferCount,
1244  uint32_t& bufferSize)
1245 {
1246  bufferCount = RX_POOL_LARGE_BUFFER_COUNT;
1247  bufferSize = RX_POOL_LARGE_BUFFER_SIZE;
1248 
1249  return Status_Ok;
1250 }
1251 
1252 //
1253 // Replace internal large buffers with user supplied
1254 
1255 Status impl::setLargeBuffers(const std::vector<uint8_t*>& buffers,
1256  uint32_t bufferSize)
1257 {
1258  if (buffers.size() < RX_POOL_LARGE_BUFFER_COUNT)
1259  CRL_DEBUG("WARNING: supplying less than recommended number of large buffers: %ld/%ld\n",
1260  static_cast<long int>(buffers.size()),
1261  static_cast<long int>(RX_POOL_LARGE_BUFFER_COUNT));
1262  if (bufferSize < RX_POOL_LARGE_BUFFER_SIZE)
1263  CRL_DEBUG("WARNING: supplying smaller than recommended large buffers: %ld/%ld bytes\n",
1264  static_cast<long int>(bufferSize),
1265  static_cast<long int>(RX_POOL_LARGE_BUFFER_SIZE));
1266 
1267  try {
1268 
1269  utility::ScopedLock lock(m_rxLock); // halt potential pool traversal
1270 
1271  //
1272  // Deletion is safe even if the buffer is in use elsewhere
1273  // (BufferStream is reference counted.)
1274 
1275  BufferPool::const_iterator it;
1276  for(it = m_rxLargeBufferPool.begin();
1277  it != m_rxLargeBufferPool.end();
1278  ++it)
1279  delete *it;
1280 
1281  m_rxLargeBufferPool.clear();
1282 
1283  for(uint32_t i=0; i<buffers.size(); i++)
1284  m_rxLargeBufferPool.push_back(new utility::BufferStreamWriter(buffers[i], bufferSize));
1285 
1286  } catch (const std::exception& e) {
1287  CRL_DEBUG("exception: %s\n", e.what());
1288  return Status_Exception;
1289  }
1290 
1291  return Status_Ok;
1292 }
1293 
1294 //
1295 // Retrieve the system-assigned local UDP port
1296 
1298 {
1299  port = m_serverSocketPort;
1300  return Status_Ok;
1301 }
1302 }}}; // namespaces
d
std::list< ImageListener * > m_imageListeners
Definition: channel.hh:363
static uint32_t imagerWireToApi(uint32_t h)
Definition: channel.cc:446
virtual Status setNetworkConfig(const system::NetworkConfig &c)
Definition: public.cc:933
static CRL_CONSTEXPR uint32_t OP_PROGRAM
Listener< image::Header, image::Callback > ImageListener
Definition: listeners.hh:211
static uint32_t hardwareWireToApi(uint32_t h)
Definition: channel.cc:418
virtual Status getMtu(int32_t &mtu)
Definition: public.cc:919
virtual Status verifyBitstream(const std::string &file)
Definition: public.cc:1131
virtual Status getLocalUdpPort(uint16_t &port)
Definition: public.cc:1297
virtual Status setImuConfig(bool storeSettingsInFlash, uint32_t samplesPerMessage, const std::vector< imu::Config > &c)
Definition: public.cc:1218
CRL_THREAD_LOCAL utility::BufferStream * dispatchBufferReferenceTP
Definition: public.cc:105
virtual Status verifyFirmware(const std::string &file)
Definition: public.cc:1141
static CRL_CONSTEXPR uint32_t HISTOGRAM_CHANNELS
virtual Status setTriggerSource(TriggerSource s)
Definition: public.cc:514
Listener< pps::Header, pps::Callback > PpsListener
Definition: listeners.hh:213
virtual Status getExternalCalibration(system::ExternalCalibration &calibration)
Definition: public.cc:1034
f
static CRL_CONSTEXPR TriggerSource Trigger_Internal
static CRL_CONSTEXPR uint32_t MAX_DIRECTED_STREAMS
Definition: channel.hh:232
virtual Status getLightingSensorStatus(lighting::SensorStatus &status)
Definition: public.cc:586
virtual Status networkTimeSynchronization(bool enabled)
Definition: public.cc:399
uint8_t intensity[lighting::MAX_LIGHTS]
virtual Status removeIsolatedCallback(image::Callback callback)
Definition: public.cc:201
void(* Callback)(const Header &header, void *userDataP)
virtual Status setExternalCalibration(const system::ExternalCalibration &calibration)
Definition: public.cc:1052
virtual Status getLightingConfig(lighting::Config &c)
Definition: public.cc:548
virtual Status getImageConfig(image::Config &c)
Definition: public.cc:637
float getDutyCycle(uint32_t i) const
static CRL_CONSTEXPR TriggerSource Trigger_External
wire::StatusResponse m_statusResponseMessage
Definition: channel.hh:399
virtual Status setLidarCalibration(const lidar::Calibration &c)
Definition: public.cc:852
static wire::SourceType sourceApiToWire(DataSource mask)
Definition: channel.cc:355
std::list< PpsListener * > m_ppsListeners
Definition: channel.hh:365
virtual Status getLargeBufferDetails(uint32_t &bufferCount, uint32_t &bufferSize)
Definition: public.cc:1243
virtual Status startDirectedStream(const DirectedStream &stream)
Definition: public.cc:448
virtual Status setMotorSpeed(float rpm)
Definition: public.cc:540
DepthCache< int64_t, wire::ImageMeta > m_imageMetaCache
Definition: channel.hh:325
static CRL_CONSTEXPR Status Status_Failed
virtual Status setMtu(int32_t mtu)
Definition: public.cc:894
virtual Status getDeviceStatus(system::StatusMessage &status)
Definition: public.cc:1001
void(* Callback)(const Header &header, void *userDataP)
virtual Status stopStreams(DataSource mask)
Definition: public.cc:422
virtual Status getNetworkConfig(system::NetworkConfig &c)
Definition: public.cc:940
uint32_t autoWhiteBalanceDecay() const
virtual Status getSensorCalibration(image::SensorCalibration &c)
Definition: public.cc:779
virtual Status setSensorCalibration(const image::SensorCalibration &c)
Definition: public.cc:795
virtual Status startDirectedStreams(const std::vector< DirectedStream > &streams)
Definition: public.cc:459
static CRL_CONSTEXPR uint32_t RGN_FIRMWARE
virtual Status addIsolatedCallback(image::Callback callback, DataSource imageSourceMask, void *userDataP)
Definition: public.cc:116
utility::Mutex m_dispatchLock
Definition: channel.hh:337
static CRL_CONSTEXPR uint32_t MAX_USER_PPS_QUEUE_SIZE
Definition: channel.hh:226
virtual Status getVersionInfo(system::VersionInfo &v)
Definition: public.cc:621
#define CPY_ARRAY_2(d_, s_, n_, m_)
Definition: Protocol.h:264
virtual Status getSensorVersion(VersionType &version)
Definition: public.cc:603
static CRL_CONSTEXPR uint32_t OP_VERIFY
static CRL_CONSTEXPR VersionType API_VERSION
Definition: channel.hh:194
static CRL_CONSTEXPR uint32_t HISTOGRAM_BINS
Definition: channel.cc:56
virtual Status getImuConfig(uint32_t &samplesPerMessage, std::vector< imu::Config > &c)
Definition: public.cc:1191
static CRL_CONSTEXPR uint32_t FLAGS_ENABLED
Type boundValue(Type const &value, Type const &minimum, Type const &maximum)
Definition: Functional.hh:61
static CRL_CONSTEXPR uint32_t RX_POOL_LARGE_BUFFER_COUNT
Definition: channel.hh:202
static CRL_CONSTEXPR Status Status_Ok
virtual Status getEnabledStreams(DataSource &mask)
Definition: public.cc:436
wire::VersionResponse m_sensorVersion
Definition: channel.hh:394
static CRL_CONSTEXPR uint32_t MAX_USER_IMU_QUEUE_SIZE
Definition: channel.hh:227
virtual Status getImageHistogram(int64_t frameId, image::Histogram &histogram)
Definition: public.cc:363
virtual Status setLargeBuffers(const std::vector< uint8_t * > &buffers, uint32_t bufferSize)
Definition: public.cc:1255
static CRL_CONSTEXPR uint32_t STATUS_EXTERNAL_LED_OK
static uint32_t imagerApiToWire(uint32_t h)
Definition: channel.cc:433
utility::Mutex m_streamLock
Definition: channel.hh:342
virtual Status startStreams(DataSource mask)
Definition: public.cc:408
Listener< lidar::Header, lidar::Callback > LidarListener
Definition: listeners.hh:212
virtual Status setDeviceInfo(const std::string &key, const system::DeviceInfo &i)
Definition: public.cc:1071
virtual void * reserveCallbackBuffer()
Definition: public.cc:313
virtual Status getApiVersion(VersionType &version)
Definition: public.cc:612
virtual Status setImageCalibration(const image::Calibration &c)
Definition: public.cc:759
static CRL_CONSTEXPR uint32_t MAX_USER_LASER_QUEUE_SIZE
Definition: channel.hh:220
#define CPY_ARRAY_1(d_, s_, n_)
Definition: Protocol.h:260
Status waitAck(const T &msg, wire::IdType id=MSG_ID(T::ID), const double &timeout=DEFAULT_ACK_TIMEOUT(), int32_t attempts=DEFAULT_ACK_ATTEMPTS)
Definition: query.hh:89
virtual Status stopDirectedStream(const DirectedStream &stream)
Definition: public.cc:474
#define CRL_DEBUG(fmt,...)
Definition: Exception.hh:77
virtual Status getImageCalibration(image::Calibration &c)
Definition: public.cc:735
static CRL_CONSTEXPR uint32_t RX_POOL_LARGE_BUFFER_SIZE
Definition: channel.hh:201
std::list< LidarListener * > m_lidarListeners
Definition: channel.hh:364
virtual Status getImuInfo(uint32_t &maxSamplesPerMessage, std::vector< imu::Info > &info)
Definition: public.cc:1151
virtual Status maxDirectedStreams(uint32_t &maximum)
Definition: public.cc:505
static CRL_CONSTEXPR uint32_t MAX_LIGHTS
Listener< imu::Header, imu::Callback > ImuListener
Definition: listeners.hh:214
virtual Status getDeviceModes(std::vector< system::DeviceMode > &modes)
Definition: public.cc:865
static uint32_t hardwareApiToWire(uint32_t h)
Definition: channel.cc:403
virtual Status flashBitstream(const std::string &file)
Definition: public.cc:1111
void(* Callback)(const Header &header, void *userDataP)
virtual Status setTransmitDelay(const image::TransmitDelay &c)
Definition: public.cc:823
std::list< ImuListener * > m_imuListeners
Definition: channel.hh:366
static CRL_CONSTEXPR Status Status_Exception
virtual Status getLidarCalibration(lidar::Calibration &c)
Definition: public.cc:835
virtual Status getTransmitDelay(image::TransmitDelay &c)
Definition: public.cc:808
static CRL_CONSTEXPR uint32_t MAX_USER_IMAGE_QUEUE_SIZE
Definition: channel.hh:219
Status waitData(const T &command, U &data, const double &timeout=DEFAULT_ACK_TIMEOUT(), int32_t attempts=DEFAULT_ACK_ATTEMPTS)
Definition: query.hh:120
virtual Status flashFirmware(const std::string &file)
Definition: public.cc:1121
static CRL_CONSTEXPR Status Status_Error
uint8_t intensity[lighting::MAX_LIGHTS]
Definition: LedSetMessage.h:63
static CRL_CONSTEXPR uint32_t RGN_BITSTREAM
virtual Status setLightingConfig(const lighting::Config &c)
Definition: public.cc:569
std::vector< imu::Details > details
virtual Status setImageConfig(const image::Config &c)
Definition: public.cc:698
virtual Status getDirectedStreams(std::vector< DirectedStream > &streams)
Definition: public.cc:485
static DataSource sourceWireToApi(wire::SourceType mask)
Definition: channel.cc:379
Status doFlashOp(const std::string &filename, uint32_t operation, uint32_t region)
Definition: flash.cc:184
virtual Status getDeviceInfo(system::DeviceInfo &info)
Definition: public.cc:957
void(* Callback)(const Header &header, void *userDataP)
virtual Status releaseCallbackBuffer(void *referenceP)
Definition: public.cc:337


multisense_lib
Author(s):
autogenerated on Sat Apr 6 2019 02:16:46