public.cc
Go to the documentation of this file.
1 
37 #include <stdlib.h>
38 #include <algorithm>
39 
41 
44 
49 
52 
61 
65 
67 
71 
74 
77 
99 
104 
107 
108 namespace crl {
109 namespace multisense {
110 namespace details {
111 
112 //
113 // The user may "hold on" to the buffer back-end
114 // of a datum within a callback thread.
115 
117 
118 //
119 //
120 // Public API follows
121 //
122 //
123 
124 //
125 // Adds a new image listener
126 
128  DataSource imageSourceMask,
129  void *userDataP)
130 {
131  try {
132 
134  m_imageListeners.push_back(new ImageListener(callback,
135  imageSourceMask,
136  userDataP,
138 
139  } catch (const std::exception& e) {
140  CRL_DEBUG("exception: %s\n", e.what());
141  return Status_Exception;
142  }
143  return Status_Ok;
144 }
145 
146 //
147 // Adds a new laser listener
148 
150  void *userDataP)
151 {
152  try {
153 
155  m_lidarListeners.push_back(new LidarListener(callback,
156  0,
157  userDataP,
159 
160  } catch (const std::exception& e) {
161  CRL_DEBUG("exception: %s\n", e.what());
162  return Status_Exception;
163  }
164  return Status_Ok;
165 }
166 
167 //
168 // Adds a new PPS listener
169 
171  void *userDataP)
172 {
173  try {
174 
176  m_ppsListeners.push_back(new PpsListener(callback,
177  0,
178  userDataP,
180 
181  } catch (const std::exception& e) {
182  CRL_DEBUG("exception: %s\n", e.what());
183  return Status_Exception;
184  }
185  return Status_Ok;
186 }
187 
188 //
189 // Adds a new IMU listener
190 
192  void *userDataP)
193 {
194  try {
195 
197  m_imuListeners.push_back(new ImuListener(callback,
198  0,
199  userDataP,
201 
202  } catch (const std::exception& e) {
203  CRL_DEBUG("exception: %s\n", e.what());
204  return Status_Exception;
205  }
206  return Status_Ok;
207 }
208 
209 //
210 // Adds a new Compressed Image listener
211 
213  DataSource imageSourceMask,
214  void *userDataP)
215 {
216  try {
217 
220  imageSourceMask,
221  userDataP,
223 
224  } catch (const std::exception& e) {
225  CRL_DEBUG("exception: %s\n", e.what());
226  return Status_Exception;
227  }
228  return Status_Ok;
229 }
230 
231 //
232 // Adds a new Ground Surface listener
233 
235  void *userDataP)
236 {
237  try {
238 
241  0,
242  userDataP,
244 
245  } catch (const std::exception& e) {
246  CRL_DEBUG("exception: %s\n", e.what());
247  return Status_Exception;
248  }
249  return Status_Ok;
250 }
251 
252 //
253 // Adds a new april tag listener
254 
256  void *userDataP)
257 {
258  try {
259 
262  0,
263  userDataP,
265 
266  } catch (const std::exception& e) {
267  CRL_DEBUG("exception: %s\n", e.what());
268  return Status_Exception;
269  }
270  return Status_Ok;
271 }
272 
273 //
274 // Removes an image listener
275 
277 {
278  try {
280 
281  std::list<ImageListener*>::iterator it;
282  for(it = m_imageListeners.begin();
283  it != m_imageListeners.end();
284  it ++) {
285 
286  if ((*it)->callback() == callback) {
287  delete *it;
288  m_imageListeners.erase(it);
289  return Status_Ok;
290  }
291  }
292 
293  } catch (const std::exception& e) {
294  CRL_DEBUG("exception: %s\n", e.what());
295  return Status_Exception;
296  }
297 
298  return Status_Error;
299 }
300 
301 //
302 // Removes a lidar listener
303 
305 {
306  try {
308 
309  std::list<LidarListener*>::iterator it;
310  for(it = m_lidarListeners.begin();
311  it != m_lidarListeners.end();
312  it ++) {
313 
314  if ((*it)->callback() == callback) {
315  delete *it;
316  m_lidarListeners.erase(it);
317  return Status_Ok;
318  }
319  }
320 
321  } catch (const std::exception& e) {
322  CRL_DEBUG("exception: %s\n", e.what());
323  return Status_Exception;
324  }
325 
326  return Status_Error;
327 }
328 
329 //
330 // Removes a PPS listener
331 
333 {
334  try {
336 
337  std::list<PpsListener*>::iterator it;
338  for(it = m_ppsListeners.begin();
339  it != m_ppsListeners.end();
340  it ++) {
341 
342  if ((*it)->callback() == callback) {
343  delete *it;
344  m_ppsListeners.erase(it);
345  return Status_Ok;
346  }
347  }
348 
349  } catch (const std::exception& e) {
350  CRL_DEBUG("exception: %s\n", e.what());
351  return Status_Exception;
352  }
353 
354  return Status_Error;
355 }
356 
357 //
358 // Removes an IMU listener
359 
361 {
362  try {
364 
365  std::list<ImuListener*>::iterator it;
366  for(it = m_imuListeners.begin();
367  it != m_imuListeners.end();
368  it ++) {
369 
370  if ((*it)->callback() == callback) {
371  delete *it;
372  m_imuListeners.erase(it);
373  return Status_Ok;
374  }
375  }
376 
377  } catch (const std::exception& e) {
378  CRL_DEBUG("exception: %s\n", e.what());
379  return Status_Exception;
380  }
381 
382  return Status_Error;
383 }
384 
385 //
386 // Removes a compressed image listener
387 
389 {
390  try {
392 
393  std::list<CompressedImageListener*>::iterator it;
394  for(it = m_compressedImageListeners.begin();
395  it != m_compressedImageListeners.end();
396  it ++) {
397 
398  if ((*it)->callback() == callback) {
399  delete *it;
400  m_compressedImageListeners.erase(it);
401  return Status_Ok;
402  }
403  }
404 
405  } catch (const std::exception& e) {
406  CRL_DEBUG("exception: %s\n", e.what());
407  return Status_Exception;
408  }
409 
410  return Status_Error;
411 }
412 
413 //
414 // Removes a ground surface listener
415 
417 {
418  try {
420 
421  std::list<GroundSurfaceSplineListener*>::iterator it;
422  for(it = m_groundSurfaceSplineListeners.begin();
423  it != m_groundSurfaceSplineListeners.end();
424  it ++) {
425 
426  if ((*it)->callback() == callback) {
427  delete *it;
429  return Status_Ok;
430  }
431  }
432 
433  } catch (const std::exception& e) {
434  CRL_DEBUG("exception: %s\n", e.what());
435  return Status_Exception;
436  }
437 
438  return Status_Error;
439 }
440 
441 //
442 // Removes a ground surface listener
443 
445 {
446  try {
448 
449  std::list<AprilTagDetectionListener*>::iterator it;
450  for(it = m_aprilTagDetectionListeners.begin();
451  it != m_aprilTagDetectionListeners.end();
452  it ++) {
453 
454  if ((*it)->callback() == callback) {
455  delete *it;
457  return Status_Ok;
458  }
459  }
460 
461  } catch (const std::exception& e) {
462  CRL_DEBUG("exception: %s\n", e.what());
463  return Status_Exception;
464  }
465 
466  return Status_Error;
467 }
468 
469 //
470 // Reserve the current callback buffer being used in a dispatch thread
471 
473 {
474  if (dispatchBufferReferenceTP) {
475 
476  try {
477 
478  return reinterpret_cast<void*>(new utility::BufferStream(*dispatchBufferReferenceTP));
479 
480  } catch (const std::exception& e) {
481 
482  CRL_DEBUG("exception: %s\n", e.what());
483 
484  } catch (...) {
485 
486  CRL_DEBUG_RAW("unknown exception\n");
487  }
488  }
489 
490  return NULL;
491 }
492 
493 //
494 // Release a user reserved buffer back to us
495 
497 {
498  if (referenceP) {
499  try {
500 
501  delete reinterpret_cast<utility::BufferStream*>(referenceP);
502  return Status_Ok;
503 
504  } catch (const std::exception& e) {
505 
506  CRL_DEBUG("exception: %s\n", e.what());
507  return Status_Exception;
508 
509  } catch (...) {
510 
511  CRL_DEBUG_RAW("unknown exception\n");
512  return Status_Exception;
513  }
514  }
515 
516  return Status_Error;
517 }
518 
519 //
520 // Get a copy of the histogram for a particular frame ID
521 
523  image::Histogram& histogram)
524 {
525  try {
526 
528 
529  const wire::ImageMeta *metaP = m_imageMetaCache.find_nolock(frameId);
530  if (NULL == metaP) {
531  CRL_DEBUG("no meta cached for frameId %ld",
532  static_cast<long int>(frameId));
533  return Status_Failed;
534  }
535 
538 
539  const int entries = histogram.channels * histogram.bins;
540  const int sizeBytes = entries * sizeof(uint32_t);
541 
542  histogram.data.resize(entries);
543  memcpy(&(histogram.data[0]), metaP->histogramP, sizeBytes);
544 
545  return Status_Ok;
546 
547  }
548  catch (const std::exception& e) {
549  CRL_DEBUG("exception: %s\n", e.what());
550  return Status_Exception;
551  }
552  catch (...) {
553  CRL_DEBUG ("%s\n", "unknown exception");
554  }
555 
556  return Status_Error;
557 }
558 
559 Status impl::getPtpStatus(int64_t frameId,
560  system::PtpStatus &ptpStatus)
561 {
562  try {
563 
565 
566  const wire::ImageMeta *metaP = m_imageMetaCache.find_nolock(frameId);
567  if (NULL == metaP) {
568  CRL_DEBUG("no meta cached for frameId %ld",
569  static_cast<long int>(frameId));
570  return Status_Failed;
571  }
572 
573  ptpStatus = system::PtpStatus();
574 
575  return Status_Ok;
576 
577  }
578  catch (const std::exception& e) {
579  CRL_DEBUG("exception: %s\n", e.what());
580  return Status_Exception;
581  }
582  catch (...) {
583  CRL_DEBUG ("%s\n", "unknown exception");
584  }
585 
586  return Status_Error;
587 }
588 
589 //
590 // Enable/disable network-based time synchronization
591 
593 {
594  m_networkTimeSyncEnabled = enabled;
595  return Status_Ok;
596 }
597 
598 //
599 // Enable/disable PTP time synchronization
600 
602 {
603  Status status;
604 
605  wire::SysSetPtp cmd;
606  cmd.enable = enabled ? 1 : 0;
607 
608  status = waitAck(cmd);
609 
610  if (Status_Ok == status)
611  m_ptpTimeSyncEnabled = enabled;
612 
613  return status;
614 }
615 
616 //
617 // Primary stream control
618 
620 {
622 
624 
625  cmd.enable(sourceApiToWire(mask));
626 
627  Status status = waitAck(cmd);
628  if (Status_Ok == status)
629  m_streamsEnabled |= mask;
630 
631  return status;
632 }
634 {
636 
638 
639  cmd.disable(sourceApiToWire(mask));
640 
641  Status status = waitAck(cmd);
642  if (Status_Ok == status)
643  m_streamsEnabled &= ~mask;
644 
645  return status;
646 }
648 {
650 
651  mask = m_streamsEnabled;
652 
653  return Status_Ok;
654 }
655 
656 //
657 // Set the trigger source
658 
660 {
661  uint32_t wireSource;
662 
663  switch(s) {
664  case Trigger_Internal:
665 
667  break;
668 
669  case Trigger_External:
670 
672  break;
673 
675 
677  break;
678 
679  case Trigger_PTP:
680 
682  break;
683 
684  default:
685 
686  return Status_Error;
687  }
688 
689  return waitAck(wire::CamSetTriggerSource(wireSource));
690 }
691 
692 //
693 // Set the motor speed
694 
696 {
697  return waitAck(wire::LidarSetMotor(rpm));
698 }
699 
700 //
701 // Get/set the lighting configuration
702 
704 {
705  Status status;
706  wire::LedStatus data;
707 
708  status = waitData(wire::LedGetStatus(), data);
709  if (Status_Ok != status)
710  return status;
711 
712  for(uint32_t i=0; i<lighting::MAX_LIGHTS; i++) {
713  float duty=0.0f;
714  if ((1<<i) & data.available)
715  duty = (data.intensity[i] * 100.0f) / 255;
716  c.setDutyCycle(i, duty);
717  }
718 
719  c.setFlash(data.flash != 0);
720 
722 
724 
725  c.setInvertPulse(data.invert_pulse != 0);
726 
728 
729  return Status_Ok;
730 }
731 
733 {
734  wire::LedSet msg;
735 
736  msg.flash = c.getFlash() ? 1 : 0;
737  for(uint32_t i=0; i<lighting::MAX_LIGHTS; i++) {
738 
739  float duty = c.getDutyCycle(i);
740  if (duty >= 0.0f) { // less than zero == not set
741  msg.mask |= (1<<i);
742  msg.intensity[i] = static_cast<uint8_t> (255.0f * (utility::boundValue(duty, 0.0f, 100.0f) / 100.0f));
743  }
744  }
745 
746  msg.led_delay_us = c.getStartupTime();
747 
749 
750  msg.invert_pulse = c.getInvertPulse() ? 1 : 0;
751 
753 
754  return waitAck(msg);
755 }
756 
758 {
759  Status requestStatus;
761 
762  requestStatus = waitData(wire::LedGetSensorStatus(), data);
763  if (Status_Ok != requestStatus)
764  return requestStatus;
765 
767 
768  return Status_Ok;
769 }
770 
771 //
772 // Requests version from sensor
773 
775 {
777  return Status_Ok;
778 }
779 
780 //
781 // Version of this API
782 
784 {
785  version = API_VERSION;
786  return Status_Ok;
787 }
788 
789 //
790 // Requests all versioning information
791 
793 {
794  v.apiBuildDate = std::string(__DATE__ ", " __TIME__);
801 
802  return Status_Ok;
803 }
804 
805 //
806 // Query camera configuration
807 
809 {
810  Status status;
812 
813  status = waitData(wire::CamGetConfig(), d);
814  if (Status_Ok != status)
815  return status;
816 
817  // for access to protected calibration members
818  class ConfigAccess : public image::Config {
819  public:
820  void setCal(float fx, float fy, float cx, float cy,
821  float tx, float ty, float tz,
822  float r, float p, float w) {
823  m_fx = fx; m_fy = fy; m_cx = cx; m_cy = cy;
824  m_tx = tx; m_ty = ty; m_tz = tz;
825  m_roll = r; m_pitch = p; m_yaw = w;
826  };
827  };
828 
829  // what is the proper c++ cast for this?
830  ConfigAccess& a = *((ConfigAccess *) &config);
831 
832  a.setResolution(d.width, d.height);
833  if (-1 == d.disparities) { // pre v2.3 firmware
834  if (1024 == d.width) // TODO: check for monocular
835  d.disparities = 128;
836  else
837  d.disparities = 0;
838  }
839  a.setDisparities(d.disparities);
840  a.setFps(d.framesPerSecond);
841  a.setGain(d.gain);
842 
843  a.setExposure(d.exposure);
844  a.setAutoExposure(d.autoExposure != 0);
845  a.setAutoExposureMax(d.autoExposureMax);
846  a.setAutoExposureDecay(d.autoExposureDecay);
847  a.setAutoExposureTargetIntensity(d.autoExposureTargetIntensity);
848  a.setAutoExposureThresh(d.autoExposureThresh);
849  a.setGain(d.gain);
850 
851  a.setWhiteBalance(d.whiteBalanceRed, d.whiteBalanceBlue);
852  a.setAutoWhiteBalance(d.autoWhiteBalance != 0);
853  a.setAutoWhiteBalanceDecay(d.autoWhiteBalanceDecay);
854  a.setAutoWhiteBalanceThresh(d.autoWhiteBalanceThresh);
855  a.setStereoPostFilterStrength(d.stereoPostFilterStrength);
856  a.setHdr(d.hdrEnabled);
857 
858  a.setAutoExposureRoi(d.autoExposureRoiX, d.autoExposureRoiY,
860 
861  a.setCal(d.fx, d.fy, d.cx, d.cy,
862  d.tx, d.ty, d.tz,
863  d.roll, d.pitch, d.yaw);
864 
865  a.setCameraProfile(static_cast<CameraProfile>(d.cameraProfile));
866 
867  a.setGamma(d.gamma);
868 
869  return Status_Ok;
870 }
871 
873 {
874  Status status;
876 
877  // for access to protected calibration members
878  class ConfigAccess : public image::AuxConfig {
879  public:
880  void setCal(float fx, float fy, float cx, float cy) {
881  m_fx = fx; m_fy = fy; m_cx = cx; m_cy = cy;
882  };
883  };
884 
885  // what is the proper c++ cast for this?
886  ConfigAccess& a = *((ConfigAccess *) &config);
887 
888  status = waitData(wire::AuxCamGetConfig(), d);
889  if (Status_Ok != status)
890  return status;
891 
892  a.setGain(d.gain);
893 
894  a.setExposure(d.exposure);
895  a.setAutoExposure(d.autoExposure != 0);
896  a.setAutoExposureMax(d.autoExposureMax);
897  a.setAutoExposureDecay(d.autoExposureDecay);
898  a.setAutoExposureTargetIntensity(d.autoExposureTargetIntensity);
899  a.setAutoExposureThresh(d.autoExposureThresh);
900 
901  a.setGain(d.gain);
902 
903  a.setWhiteBalance(d.whiteBalanceRed, d.whiteBalanceBlue);
904  a.setAutoWhiteBalance(d.autoWhiteBalance != 0);
905  a.setAutoWhiteBalanceDecay(d.autoWhiteBalanceDecay);
906  a.setAutoWhiteBalanceThresh(d.autoWhiteBalanceThresh);
907  a.setHdr(d.hdrEnabled);
908 
909  a.setAutoExposureRoi(d.autoExposureRoiX, d.autoExposureRoiY,
911 
912  a.setCal(d.fx, d.fy, d.cx, d.cy);
913 
914  a.setCameraProfile(static_cast<CameraProfile>(d.cameraProfile));
915 
916  a.setGamma(d.gamma);
917 
918  a.enableSharpening(d.sharpeningEnable);
919  a.setSharpeningPercentage(d.sharpeningPercentage);
920  a.setSharpeningLimit(d.sharpeningLimit);
921 
922  return Status_Ok;
923 }
924 
925 //
926 // Set camera configuration
927 //
928 // Currently several sensor messages are combined and presented
929 // to the user as one.
930 
932 {
933  Status status;
934 
935  status = waitAck(wire::CamSetResolution(c.width(),
936  c.height(),
937  c.disparities()));
938  if (Status_Ok != status)
939  return status;
940 
941  wire::CamControl cmd;
942 
943  cmd.framesPerSecond = c.fps();
944  cmd.gain = c.gain();
945 
946  cmd.exposure = c.exposure();
947  cmd.autoExposure = c.autoExposure() ? 1 : 0;
952 
955  cmd.autoWhiteBalance = c.autoWhiteBalance() ? 1 : 0;
959  cmd.hdrEnabled = c.hdrEnabled();
960 
965 
966  cmd.cameraProfile = static_cast<uint32_t>(c.cameraProfile());
967 
968  cmd.gamma = c.gamma();
969 
970  return waitAck(cmd);
971 }
972 
974 {
976 
977  cmd.gain = c.gain();
978 
979  cmd.exposure = c.exposure();
980  cmd.autoExposure = c.autoExposure() ? 1 : 0;
985 
988  cmd.autoWhiteBalance = c.autoWhiteBalance() ? 1 : 0;
991  cmd.hdrEnabled = c.hdrEnabled();
992 
997 
998  cmd.cameraProfile = static_cast<uint32_t>(c.cameraProfile());
999 
1000  cmd.gamma = c.gamma();
1003  cmd.sharpeningLimit = c.sharpeningLimit();
1004 
1005  return waitAck(cmd);
1006 }
1007 
1008 //
1009 // Get Remote Head Configuration
1011 {
1012  Status status;
1014 
1015  status = waitData(wire::RemoteHeadGetConfig(), r);
1016  if (Status_Ok != status)
1017  return status;
1018 
1021 
1024 
1025  return status;
1026 }
1027 
1028 //
1029 // Set Remote Head Configuration
1031 {
1033 
1038 
1039  return waitAck(cmd);
1040 }
1041 
1042 
1043 
1044 //
1045 // Get camera calibration
1046 
1048 {
1050 
1052  if (Status_Ok != status)
1053  return status;
1054 
1055  CPY_ARRAY_2(c.left.M, d.left.M, 3, 3);
1056  CPY_ARRAY_1(c.left.D, d.left.D, 8);
1057  CPY_ARRAY_2(c.left.R, d.left.R, 3, 3);
1058  CPY_ARRAY_2(c.left.P, d.left.P, 3, 4);
1059 
1060  CPY_ARRAY_2(c.right.M, d.right.M, 3, 3);
1061  CPY_ARRAY_1(c.right.D, d.right.D, 8);
1062  CPY_ARRAY_2(c.right.R, d.right.R, 3, 3);
1063  CPY_ARRAY_2(c.right.P, d.right.P, 3, 4);
1064 
1065  CPY_ARRAY_2(c.aux.M, d.aux.M, 3, 3);
1066  CPY_ARRAY_1(c.aux.D, d.aux.D, 8);
1067  CPY_ARRAY_2(c.aux.R, d.aux.R, 3, 3);
1068  CPY_ARRAY_2(c.aux.P, d.aux.P, 3, 4);
1069 
1070  return Status_Ok;
1071 }
1072 
1073 //
1074 // Set camera calibration
1075 
1077 {
1079 
1080  CPY_ARRAY_2(d.left.M, c.left.M, 3, 3);
1081  CPY_ARRAY_1(d.left.D, c.left.D, 8);
1082  CPY_ARRAY_2(d.left.R, c.left.R, 3, 3);
1083  CPY_ARRAY_2(d.left.P, c.left.P, 3, 4);
1084 
1085  CPY_ARRAY_2(d.right.M, c.right.M, 3, 3);
1086  CPY_ARRAY_1(d.right.D, c.right.D, 8);
1087  CPY_ARRAY_2(d.right.R, c.right.R, 3, 3);
1088  CPY_ARRAY_2(d.right.P, c.right.P, 3, 4);
1089 
1090  CPY_ARRAY_2(d.aux.M, c.aux.M, 3, 3);
1091  CPY_ARRAY_1(d.aux.D, c.aux.D, 8);
1092  CPY_ARRAY_2(d.aux.R, c.aux.R, 3, 3);
1093  CPY_ARRAY_2(d.aux.P, c.aux.P, 3, 4);
1094 
1095  return waitAck(d);
1096 }
1097 
1098 //
1099 // Get sensor calibration
1100 
1102 {
1104 
1105  Status status = waitData(wire::SysGetTransmitDelay(), d);
1106  if (Status_Ok != status)
1107  return status;
1108  c.delay = d.delay;
1109 
1110  return Status_Ok;
1111 }
1112 
1113 //
1114 // Set sensor calibration
1115 
1117 {
1119 
1120  d.delay = c.delay;;
1121 
1122  return waitAck(d);
1123 }
1124 
1125 //
1126 // Get lidar calibration
1127 
1129 {
1131 
1133  if (Status_Ok != status)
1134  return status;
1135 
1138 
1139  return Status_Ok;
1140 }
1141 
1142 //
1143 // Set lidar calibration
1144 
1146 {
1148 
1151 
1152  return waitAck(d);
1153 }
1154 
1155 //
1156 // Get a list of supported image formats / data sources
1157 
1158 Status impl::getDeviceModes(std::vector<system::DeviceMode>& modes)
1159 {
1161 
1162  Status status = waitData(wire::SysGetDeviceModes(), d);
1163  if (Status_Ok != status)
1164  return Status_Error;
1165 
1166  modes.resize(d.modes.size());
1167  for(uint32_t i=0; i<d.modes.size(); i++) {
1168 
1169  system::DeviceMode& a = modes[i];
1170  const wire::DeviceMode& w = d.modes[i];
1171 
1172  a.width = w.width;
1173  a.height = w.height;
1175  if (m_sensorVersion.firmwareVersion >= 0x0203)
1176  a.disparities = w.disparities;
1177  else
1178  a.disparities = (a.width == 1024) ? 128 : 0;
1179  }
1180 
1181  return Status_Ok;
1182 }
1183 
1184 //
1185 // Set/get the mtu
1186 
1187 Status impl::setMtu(int32_t mtu)
1188 {
1189  Status status = Status_Ok;
1190 
1191  //
1192  // Firmware v2.3 or better will send us an MTU-sized
1193  // response packet, which can be used to verify the
1194  // MTU setting before we actually make the change.
1195 
1196  if (m_sensorVersion.firmwareVersion <= 0x0202)
1197  status = waitAck(wire::SysMtu(mtu));
1198  else {
1200  status = waitData(wire::SysTestMtu(mtu), resp);
1201  if (Status_Ok == status)
1202  status = waitAck(wire::SysMtu(mtu));
1203  }
1204 
1205  if (Status_Ok == status)
1206  m_sensorMtu = mtu;
1207 
1208  return status;
1209 }
1210 
1211 Status impl::getMtu(int32_t& mtu)
1212 {
1213  wire::SysMtu resp;
1214 
1215  Status status = waitData(wire::SysGetMtu(), resp);
1216  if (Status_Ok == status)
1217  mtu = resp.mtu;
1218 
1219  return status;
1220 }
1221 
1223 {
1224  wire::MotorPoll resp;
1225 
1226  Status status = waitData(wire::LidarPollMotor(), resp);
1227  if (Status_Ok == status)
1228  pos = resp.angleStart;
1229 
1230  return status;
1231 }
1232 
1233 //
1234 // Set/get the network configuration
1235 
1237 {
1239  c.ipv4Gateway,
1240  c.ipv4Netmask));
1241 }
1242 
1244 {
1245  wire::SysNetwork resp;
1246 
1247  Status status = waitData(wire::SysGetNetwork(), resp);
1248  if (Status_Ok == status) {
1249  c.ipv4Address = resp.address;
1250  c.ipv4Gateway = resp.gateway;
1251  c.ipv4Netmask = resp.netmask;
1252  }
1253 
1254  return status;
1255 }
1256 
1257 //
1258 // Get device info from sensor
1259 
1261 {
1263 
1264  Status status = waitData(wire::SysGetDeviceInfo(), w);
1265  if (Status_Ok != status)
1266  return status;
1267 
1268  info.name = w.name;
1269  info.buildDate = w.buildDate;
1270  info.serialNumber = w.serialNumber;
1272  info.pcbs.clear();
1273 
1274  for(uint8_t i=0; i<w.numberOfPcbs; i++) {
1275  system::PcbInfo pcb;
1276 
1277  pcb.name = w.pcbs[i].name;
1278  pcb.revision = w.pcbs[i].revision;
1279 
1280  info.pcbs.push_back(pcb);
1281  }
1282 
1283  info.imagerName = w.imagerName;
1285  info.imagerWidth = w.imagerWidth;
1286  info.imagerHeight = w.imagerHeight;
1287  info.lensName = w.lensName;
1288  info.lensType = w.lensType;
1292  info.lightingType = w.lightingType;
1293  info.numberOfLights = w.numberOfLights;
1294  info.laserName = w.laserName;
1295  info.laserType = w.laserType;
1296  info.motorName = w.motorName;
1297  info.motorType = w.motorType;
1299 
1300  return Status_Ok;
1301 }
1302 
1303 
1305 {
1307  return m_getStatusReturnStatus;
1308  }
1309 
1310  status.uptime = static_cast<double>(m_statusResponseMessage.uptime.getNanoSeconds()) * 1e-9;
1311 
1326 
1331 
1337 
1338  return Status_Ok;
1339 }
1340 
1342 {
1344 
1346  if (Status_Ok != status)
1347  return status;
1348 
1349  calibration.x = d.calibration[0];
1350  calibration.y = d.calibration[1];
1351  calibration.z = d.calibration[2];
1352  calibration.roll = d.calibration[3];
1353  calibration.pitch = d.calibration[4];
1354  calibration.yaw = d.calibration[5];
1355 
1356  return Status_Ok;
1357 }
1358 
1360 {
1362 
1363  w.calibration[0] = calibration.x;
1364  w.calibration[1] = calibration.y;
1365  w.calibration[2] = calibration.z;
1366  w.calibration[3] = calibration.roll;
1367  w.calibration[4] = calibration.pitch;
1368  w.calibration[5] = calibration.yaw;
1369 
1370  return waitAck(w);
1371 }
1372 
1374 {
1376 
1393 
1394  return waitAck(w);
1395 }
1396 
1398 {
1399  (void)params;
1401 
1402  w.family = params.family;
1403  w.max_hamming = params.max_hamming;
1409 
1410  return waitAck(w);
1411 }
1412 //
1413 // Sets the device info
1414 
1415 Status impl::setDeviceInfo(const std::string& key,
1416  const system::DeviceInfo& info)
1417 {
1419 
1420  w.key = key; // must match device firmware key
1421  w.name = info.name;
1422  w.buildDate = info.buildDate;
1423  w.serialNumber = info.serialNumber;
1425  w.numberOfPcbs = std::min((uint8_t) info.pcbs.size(),
1427  for(uint32_t i=0; i<w.numberOfPcbs; i++) {
1428  w.pcbs[i].name = info.pcbs[i].name;
1429  w.pcbs[i].revision = info.pcbs[i].revision;
1430  }
1431 
1432  w.imagerName = info.imagerName;
1434  w.imagerWidth = info.imagerWidth;
1435  w.imagerHeight = info.imagerHeight;
1436  w.lensName = info.lensName;
1437  w.lensType = info.lensType;
1441  w.lightingType = info.lightingType;
1442  w.numberOfLights = info.numberOfLights;
1443  w.laserName = info.laserName;
1444  w.laserType = info.laserType;
1445  w.motorName = info.motorName;
1446  w.motorType = info.motorType;
1448 
1449  return waitAck(w);
1450 }
1451 
1452 //
1453 // Flash the bitstream file (dangerous!)
1454 
1455 Status impl::flashBitstream(const std::string& filename)
1456 {
1457  return doFlashOp(filename,
1460 }
1461 
1462 //
1463 // Flash the firmware file (dangerous!)
1464 
1465 Status impl::flashFirmware(const std::string& filename)
1466 {
1467  return doFlashOp(filename,
1470 }
1471 
1472 //
1473 // Verify the bitstream file
1474 
1475 Status impl::verifyBitstream(const std::string& filename)
1476 {
1477  return doFlashOp(filename,
1480 }
1481 
1482 //
1483 // Verify the firmware file
1484 
1485 Status impl::verifyFirmware(const std::string& filename)
1486 {
1487  return doFlashOp(filename,
1490 }
1491 
1492 //
1493 // Get IMU information
1494 
1495 Status impl::getImuInfo(uint32_t& maxSamplesPerMessage,
1496  std::vector<imu::Info>& info)
1497 {
1498  wire::ImuInfo w;
1499 
1500  Status status = waitData(wire::ImuGetInfo(), w);
1501  if (Status_Ok != status)
1502  return status;
1503 
1504  //
1505  // Wire --> API
1506 
1507  maxSamplesPerMessage = w.maxSamplesPerMessage;
1508  info.resize(w.details.size());
1509  for(uint32_t i=0; i<w.details.size(); i++) {
1510 
1511  const wire::imu::Details& d = w.details[i];
1512 
1513  info[i].name = d.name;
1514  info[i].device = d.device;
1515  info[i].units = d.units;
1516 
1517  info[i].rates.resize(d.rates.size());
1518  for(uint32_t j=0; j<d.rates.size(); j++) {
1519  info[i].rates[j].sampleRate = d.rates[j].sampleRate;
1520  info[i].rates[j].bandwidthCutoff = d.rates[j].bandwidthCutoff;
1521  }
1522  info[i].ranges.resize(d.ranges.size());
1523  for(uint32_t j=0; j<d.ranges.size(); j++) {
1524  info[i].ranges[j].range = d.ranges[j].range;
1525  info[i].ranges[j].resolution = d.ranges[j].resolution;
1526  }
1527  }
1528 
1529  return Status_Ok;
1530 }
1531 
1532 //
1533 // Get IMU configuration
1534 
1535 Status impl::getImuConfig(uint32_t& samplesPerMessage,
1536  std::vector<imu::Config>& c)
1537 {
1538  wire::ImuConfig w;
1539 
1540  Status status = waitData(wire::ImuGetConfig(), w);
1541  if (Status_Ok != status)
1542  return status;
1543 
1544  //
1545  // Wire --> API
1546 
1547  samplesPerMessage = w.samplesPerMessage;
1548  c.resize(w.configs.size());
1549  for(uint32_t i=0; i<w.configs.size(); i++) {
1550  c[i].name = w.configs[i].name;
1551  c[i].enabled = (w.configs[i].flags & wire::imu::Config::FLAGS_ENABLED);
1552  c[i].rateTableIndex = w.configs[i].rateTableIndex;
1553  c[i].rangeTableIndex = w.configs[i].rangeTableIndex;
1554  }
1555 
1556  return Status_Ok;
1557 }
1558 
1559 //
1560 // Set IMU configuration
1561 
1562 Status impl::setImuConfig(bool storeSettingsInFlash,
1563  uint32_t samplesPerMessage,
1564  const std::vector<imu::Config>& c)
1565 {
1566  wire::ImuConfig w;
1567 
1568  //
1569  // API --> wire
1570 
1571  w.storeSettingsInFlash = storeSettingsInFlash ? 1 : 0;
1572  w.samplesPerMessage = samplesPerMessage;
1573  w.configs.resize(c.size());
1574  for(uint32_t i=0; i<c.size(); i++) {
1575  w.configs[i].name = c[i].name;
1576  w.configs[i].flags = c[i].enabled ? wire::imu::Config::FLAGS_ENABLED : 0;
1577  w.configs[i].rateTableIndex = c[i].rateTableIndex;
1578  w.configs[i].rangeTableIndex = c[i].rangeTableIndex;
1579  }
1580 
1581  return waitAck(w);
1582 }
1583 
1584 //
1585 // Get recommended large buffer pool count/size
1586 
1587 Status impl::getLargeBufferDetails(uint32_t& bufferCount,
1588  uint32_t& bufferSize)
1589 {
1590  bufferCount = RX_POOL_LARGE_BUFFER_COUNT;
1591  bufferSize = RX_POOL_LARGE_BUFFER_SIZE;
1592 
1593  return Status_Ok;
1594 }
1595 
1596 //
1597 // Replace internal large buffers with user supplied
1598 
1599 Status impl::setLargeBuffers(const std::vector<uint8_t*>& buffers,
1600  uint32_t bufferSize)
1601 {
1602  if (buffers.size() < RX_POOL_LARGE_BUFFER_COUNT)
1603  CRL_DEBUG("WARNING: supplying less than recommended number of large buffers: %ld/%ld\n",
1604  static_cast<long int>(buffers.size()),
1605  static_cast<long int>(RX_POOL_LARGE_BUFFER_COUNT));
1606  if (bufferSize < RX_POOL_LARGE_BUFFER_SIZE)
1607  CRL_DEBUG("WARNING: supplying smaller than recommended large buffers: %ld/%ld bytes\n",
1608  static_cast<long int>(bufferSize),
1609  static_cast<long int>(RX_POOL_LARGE_BUFFER_SIZE));
1610 
1611  try {
1612 
1613  utility::ScopedLock lock(m_rxLock); // halt potential pool traversal
1614 
1615  //
1616  // Deletion is safe even if the buffer is in use elsewhere
1617  // (BufferStream is reference counted.)
1618 
1619  BufferPool::const_iterator it;
1620  for(it = m_rxLargeBufferPool.begin();
1621  it != m_rxLargeBufferPool.end();
1622  ++it)
1623  delete *it;
1624 
1625  m_rxLargeBufferPool.clear();
1626 
1627  for(uint32_t i=0; i<buffers.size(); i++)
1628  m_rxLargeBufferPool.push_back(new utility::BufferStreamWriter(buffers[i], bufferSize));
1629 
1630  } catch (const std::exception& e) {
1631  CRL_DEBUG("exception: %s\n", e.what());
1632  return Status_Exception;
1633  }
1634 
1635  return Status_Ok;
1636 }
1637 
1638 //
1639 // Retrieve the system-assigned local UDP port
1640 
1642 {
1643  port = m_serverSocketPort;
1644  return Status_Ok;
1645 }
1646 }}} // namespaces
d
std::list< ImageListener * > m_imageListeners
Definition: channel.hh:458
static uint32_t imagerWireToApi(uint32_t h)
Definition: channel.cc:580
virtual Status setNetworkConfig(const system::NetworkConfig &c)
Definition: public.cc:1236
static CRL_CONSTEXPR uint32_t OP_PROGRAM
Listener< image::Header, image::Callback > ImageListener
Definition: listeners.hh:226
static uint32_t hardwareWireToApi(uint32_t h)
Definition: channel.cc:540
#define CRL_DEBUG_RAW(fmt)
Definition: Exception.hh:78
virtual Status getPtpStatus(int64_t frameId, system::PtpStatus &ptpStatus)
Definition: public.cc:559
virtual Status getMtu(int32_t &mtu)
Definition: public.cc:1211
virtual Status verifyBitstream(const std::string &file)
Definition: public.cc:1475
virtual Status getLocalUdpPort(uint16_t &port)
Definition: public.cc:1641
virtual Status setImuConfig(bool storeSettingsInFlash, uint32_t samplesPerMessage, const std::vector< imu::Config > &c)
Definition: public.cc:1562
CRL_THREAD_LOCAL utility::BufferStream * dispatchBufferReferenceTP
Definition: public.cc:116
virtual Status verifyFirmware(const std::string &file)
Definition: public.cc:1485
static CRL_CONSTEXPR uint32_t HISTOGRAM_CHANNELS
virtual Status setTriggerSource(TriggerSource s)
Definition: public.cc:659
virtual Status getMotorPos(int32_t &mtu)
Definition: public.cc:1222
Listener< pps::Header, pps::Callback > PpsListener
Definition: listeners.hh:228
virtual Status getExternalCalibration(system::ExternalCalibration &calibration)
Definition: public.cc:1341
f
static CRL_CONSTEXPR TriggerSource Trigger_Internal
virtual Status getLightingSensorStatus(lighting::SensorStatus &status)
Definition: public.cc:757
Listener< apriltag::Header, apriltag::Callback > AprilTagDetectionListener
Definition: listeners.hh:232
static CRL_CONSTEXPR TriggerSource Trigger_PTP
virtual Status networkTimeSynchronization(bool enabled)
Definition: public.cc:592
uint8_t intensity[lighting::MAX_LIGHTS]
virtual Status removeIsolatedCallback(image::Callback callback)
Definition: public.cc:276
virtual Status setRemoteHeadConfig(const image::RemoteHeadConfig &c)
Definition: public.cc:1030
void(* Callback)(const Header &header, void *userDataP)
virtual Status ptpTimeSynchronization(bool enabled)
Definition: public.cc:601
virtual Status setExternalCalibration(const system::ExternalCalibration &calibration)
Definition: public.cc:1359
virtual Status getLightingConfig(lighting::Config &c)
Definition: public.cc:703
virtual Status getImageConfig(image::Config &c)
Definition: public.cc:808
static CRL_CONSTEXPR TriggerSource Trigger_External
wire::StatusResponse m_statusResponseMessage
Definition: channel.hh:498
virtual Status setLidarCalibration(const lidar::Calibration &c)
Definition: public.cc:1145
static wire::SourceType sourceApiToWire(DataSource mask)
Definition: channel.cc:438
virtual Status setGroundSurfaceParams(const system::GroundSurfaceParams &params)
Definition: public.cc:1373
std::list< PpsListener * > m_ppsListeners
Definition: channel.hh:460
virtual Status getLargeBufferDetails(uint32_t &bufferCount, uint32_t &bufferSize)
Definition: public.cc:1587
virtual Status setMotorSpeed(float rpm)
Definition: public.cc:695
std::list< AprilTagDetectionListener * > m_aprilTagDetectionListeners
Definition: channel.hh:464
DepthCache< int64_t, wire::ImageMeta > m_imageMetaCache
Definition: channel.hh:420
static CRL_CONSTEXPR Status Status_Failed
void(* Callback)(const Header &header, void *userDataP)
virtual Status getAuxImageConfig(image::AuxConfig &c)
Definition: public.cc:872
virtual Status setMtu(int32_t mtu)
Definition: public.cc:1187
virtual Status getDeviceStatus(system::StatusMessage &status)
Definition: public.cc:1304
void(* Callback)(const Header &header, void *userDataP)
virtual Status stopStreams(DataSource mask)
Definition: public.cc:633
virtual Status getNetworkConfig(system::NetworkConfig &c)
Definition: public.cc:1243
static CRL_CONSTEXPR uint32_t MAX_USER_APRILTAG_QUEUE_SIZE
Definition: channel.hh:322
Listener< ground_surface::Header, ground_surface::Callback > GroundSurfaceSplineListener
Definition: listeners.hh:231
void(* Callback)(const Header &header, void *userDataP)
#define CPY_ARRAY_1(d_, s_, n_)
Definition: Protocol.hh:323
RemoteHeadChannel syncPair1Responder() const
static CRL_CONSTEXPR uint32_t RGN_FIRMWARE
static CRL_CONSTEXPR uint32_t MAX_USER_GROUND_SURFACE_QUEUE_SIZE
Definition: channel.hh:321
virtual Status addIsolatedCallback(image::Callback callback, DataSource imageSourceMask, void *userDataP)
Definition: public.cc:127
bool setInvertPulse(const bool invert)
static CRL_CONSTEXPR uint32_t MAX_USER_COMPRESSED_IMAGE_QUEUE_SIZE
Definition: channel.hh:307
utility::Mutex m_dispatchLock
Definition: channel.hh:432
static CRL_CONSTEXPR uint32_t MAX_USER_PPS_QUEUE_SIZE
Definition: channel.hh:319
virtual Status getVersionInfo(system::VersionInfo &v)
Definition: public.cc:792
#define CPY_ARRAY_2(d_, s_, n_, m_)
Definition: Protocol.hh:327
virtual Status setApriltagParams(const system::ApriltagParams &params)
Definition: public.cc:1397
virtual Status getSensorVersion(VersionType &version)
Definition: public.cc:774
static CRL_CONSTEXPR uint32_t OP_VERIFY
static CRL_CONSTEXPR VersionType API_VERSION
Definition: channel.hh:269
bool getRollingShutterLedSynchronizationStatus(void) const
Definition: channel.cc:58
virtual Status getImuConfig(uint32_t &samplesPerMessage, std::vector< imu::Config > &c)
Definition: public.cc:1535
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:281
static CRL_CONSTEXPR Status Status_Ok
RemoteHeadChannel syncPair2Responder() const
virtual Status getEnabledStreams(DataSource &mask)
Definition: public.cc:647
wire::VersionResponse m_sensorVersion
Definition: channel.hh:493
static CRL_CONSTEXPR uint32_t MAX_USER_IMU_QUEUE_SIZE
Definition: channel.hh:320
std::list< CompressedImageListener * > m_compressedImageListeners
Definition: channel.hh:462
virtual Status getImageHistogram(int64_t frameId, image::Histogram &histogram)
Definition: public.cc:522
static CRL_CONSTEXPR TriggerSource Trigger_External_Inverted
std::list< GroundSurfaceSplineListener * > m_groundSurfaceSplineListeners
Definition: channel.hh:463
static uint32_t imagerApiToWire(uint32_t h)
Definition: channel.cc:564
utility::Mutex m_streamLock
Definition: channel.hh:437
Listener< compressed_image::Header, compressed_image::Callback > CompressedImageListener
Definition: listeners.hh:230
CameraProfile cameraProfile() const
virtual Status startStreams(DataSource mask)
Definition: public.cc:619
Listener< lidar::Header, lidar::Callback > LidarListener
Definition: listeners.hh:227
virtual Status setDeviceInfo(const std::string &key, const system::DeviceInfo &i)
Definition: public.cc:1415
virtual void * reserveCallbackBuffer()
Definition: public.cc:472
virtual Status getApiVersion(VersionType &version)
Definition: public.cc:783
virtual Status setImageCalibration(const image::Calibration &c)
Definition: public.cc:1076
static CRL_CONSTEXPR uint32_t MAX_USER_LASER_QUEUE_SIZE
Definition: channel.hh:306
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
bool enableRollingShutterLedSynchronization(const bool enabled)
#define CRL_DEBUG(fmt,...)
Definition: Exception.hh:71
virtual Status getImageCalibration(image::Calibration &c)
Definition: public.cc:1047
bool setStartupTime(uint32_t ledTransientResponse_us)
static CRL_CONSTEXPR uint32_t RX_POOL_LARGE_BUFFER_SIZE
Definition: channel.hh:280
std::list< LidarListener * > m_lidarListeners
Definition: channel.hh:459
virtual Status getImuInfo(uint32_t &maxSamplesPerMessage, std::vector< imu::Info > &info)
Definition: public.cc:1495
static CRL_CONSTEXPR uint32_t MAX_LIGHTS
Listener< imu::Header, imu::Callback > ImuListener
Definition: listeners.hh:229
virtual Status getDeviceModes(std::vector< system::DeviceMode > &modes)
Definition: public.cc:1158
virtual Status getRemoteHeadConfig(image::RemoteHeadConfig &c)
Definition: public.cc:1010
static uint32_t hardwareApiToWire(uint32_t h)
Definition: channel.cc:516
bool setNumberOfPulses(const uint32_t numPulses)
void(* Callback)(const Header &header, void *userDataP)
virtual Status flashBitstream(const std::string &file)
Definition: public.cc:1455
void(* Callback)(const Header &header, void *userDataP)
virtual Status setLargeBuffers(const std::vector< uint8_t *> &buffers, uint32_t bufferSize)
Definition: public.cc:1599
virtual Status setTransmitDelay(const image::TransmitDelay &c)
Definition: public.cc:1116
std::list< ImuListener * > m_imuListeners
Definition: channel.hh:461
static CRL_CONSTEXPR Status Status_Exception
RemoteHeadChannel syncPair2Controller() const
virtual Status getLidarCalibration(lidar::Calibration &c)
Definition: public.cc:1128
virtual Status getTransmitDelay(image::TransmitDelay &c)
Definition: public.cc:1101
static CRL_CONSTEXPR uint32_t MAX_USER_IMAGE_QUEUE_SIZE
Definition: channel.hh:305
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:1465
static CRL_CONSTEXPR Status Status_Error
uint8_t intensity[lighting::MAX_LIGHTS]
static CRL_CONSTEXPR uint32_t RGN_BITSTREAM
virtual Status setLightingConfig(const lighting::Config &c)
Definition: public.cc:732
std::vector< imu::Details > details
RemoteHeadChannel syncPair1Controller() const
virtual Status setAuxImageConfig(const image::AuxConfig &c)
Definition: public.cc:973
virtual Status setImageConfig(const image::Config &c)
Definition: public.cc:931
float getDutyCycle(uint32_t i) const
static DataSource sourceWireToApi(wire::SourceType mask)
Definition: channel.cc:477
Status doFlashOp(const std::string &filename, uint32_t operation, uint32_t region)
Definition: flash.cc:185
virtual Status getDeviceInfo(system::DeviceInfo &info)
Definition: public.cc:1260
void(* Callback)(const Header &header, void *userDataP)
virtual Status releaseCallbackBuffer(void *referenceP)
Definition: public.cc:496


multisense_lib
Author(s):
autogenerated on Sat Jun 24 2023 03:01:21