channel.cc
Go to the documentation of this file.
1 
37 #include "details/channel.hh"
38 #include "details/query.hh"
39 
47 
49 
50 #ifndef WIN32
51 #include <netdb.h>
52 #endif
53 #include <errno.h>
54 #include <fcntl.h>
55 
56 namespace crl {
57 namespace multisense {
58 namespace details {
59 
60 //
61 // Implementation constructor
62 
63 impl::impl(const std::string& address) :
64  m_serverSocket(INVALID_SOCKET),
65  m_serverSocketPort(0),
66  m_sensorAddress(),
67  m_sensorMtu(MAX_MTU_SIZE),
68  m_incomingBuffer(MAX_MTU_SIZE),
69  m_txSeqId(0),
70  m_lastRxSeqId(-1),
71  m_unWrappedRxSeqId(0),
72  m_udpTrackerCache(UDP_TRACKER_CACHE_DEPTH, 0),
73  m_rxLargeBufferPool(),
74  m_rxSmallBufferPool(),
75  m_imageMetaCache(IMAGE_META_CACHE_DEPTH, 0),
76  m_udpAssemblerMap(),
77  m_dispatchLock(),
78  m_streamLock(),
79  m_threadsRunning(false),
80  m_rxThreadP(NULL),
81  m_rxLock(),
82  m_statusThreadP(NULL),
83  m_imageListeners(),
84  m_lidarListeners(),
85  m_ppsListeners(),
86  m_imuListeners(),
87  m_watch(),
88  m_messages(),
89  m_streamsEnabled(0),
90  m_timeLock(),
91  m_timeOffsetInit(false),
92  m_timeOffset(0),
93  m_networkTimeSyncEnabled(true),
94  m_ptpTimeSyncEnabled(false),
95  m_sensorVersion()
96 {
97 #if WIN32
98  WSADATA wsaData;
99  int result = WSAStartup (MAKEWORD (0x02, 0x02), &wsaData);
100  if (result != 0)
101  CRL_EXCEPTION("WSAStartup() failed: %d", result);
102 #endif
103 
104  //
105  // Make sure the sensor address is sane
106 
107  struct hostent *hostP = gethostbyname(address.c_str());
108  if (NULL == hostP)
109  CRL_EXCEPTION("unable to resolve \"%s\": %s",
110  address.c_str(), strerror(errno));
111 
112  //
113  // Set up the address for transmission
114 
115  in_addr addr;
116 
117  memcpy(&(addr.s_addr), hostP->h_addr, hostP->h_length);
118  memset(&m_sensorAddress, 0, sizeof(m_sensorAddress));
119 
120  m_sensorAddress.sin_family = AF_INET;
121  m_sensorAddress.sin_port = htons(DEFAULT_SENSOR_TX_PORT);
122  m_sensorAddress.sin_addr = addr;
123 
124  //
125  // Create a pool of RX buffers
126 
127  for(uint32_t i=0; i<RX_POOL_LARGE_BUFFER_COUNT; i++)
129  for(uint32_t i=0; i<RX_POOL_SMALL_BUFFER_COUNT; i++)
131 
132  //
133  // Bind to the port
134 
135  bind();
136 
137  //
138  // Register any special UDP reassemblers
139 
141 
142  //
143  // Create UDP reception thread
144 
145  m_threadsRunning = true;
146  m_rxThreadP = new utility::Thread(rxThread, this);
147 
148  //
149  // Request the current operating MTU of the device
150 
151  wire::SysMtu mtu;
152 
153  Status status = waitData(wire::SysGetMtu(), mtu);
154  if (Status_Ok != status) {
155  cleanup();
156  CRL_EXCEPTION("failed to establish comms with the sensor at \"%s\"",
157  address.c_str());
158  } else {
159 
160  //
161  // Use the same MTU for TX
162 
163  m_sensorMtu = mtu.mtu;
164  }
165 
166  //
167  // Request version info from the device
168 
170  if (Status_Ok != status) {
171  cleanup();
172  CRL_EXCEPTION("failed to request version info from sensor at \"%s\"",
173  address.c_str());
174  }
175 
176  //
177  // Create status thread
178 
180 }
181 
182 //
183 // Implementation cleanup
184 
186 {
187  m_threadsRunning = false;
188 
189  if (m_rxThreadP)
190  delete m_rxThreadP;
191  if (m_statusThreadP)
192  delete m_statusThreadP;
193 
194  std::list<ImageListener*>::const_iterator iti;
195  for(iti = m_imageListeners.begin();
196  iti != m_imageListeners.end();
197  iti ++)
198  delete *iti;
199  std::list<LidarListener*>::const_iterator itl;
200  for(itl = m_lidarListeners.begin();
201  itl != m_lidarListeners.end();
202  itl ++)
203  delete *itl;
204  std::list<PpsListener*>::const_iterator itp;
205  for(itp = m_ppsListeners.begin();
206  itp != m_ppsListeners.end();
207  itp ++)
208  delete *itp;
209  std::list<ImuListener*>::const_iterator itm;
210  for(itm = m_imuListeners.begin();
211  itm != m_imuListeners.end();
212  itm ++)
213  delete *itm;
214 
215  BufferPool::const_iterator it;
216  for(it = m_rxLargeBufferPool.begin();
217  it != m_rxLargeBufferPool.end();
218  ++it)
219  delete *it;
220  for(it = m_rxSmallBufferPool.begin();
221  it != m_rxSmallBufferPool.end();
222  ++it)
223  delete *it;
224 
225  if (m_serverSocket > 0)
227 
228 #if WIN32
229  WSACleanup ();
230 #endif
231 }
232 
233 //
234 // Implementation destructor
235 
237 {
238  cleanup();
239 }
240 
241 //
242 // Binds the communications channel, preparing it to send/receive data
243 // over the network.
244 
246 {
247  //
248  // Create the socket.
249 
250  m_serverSocket = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP);
251  if (m_serverSocket < 0)
252  CRL_EXCEPTION("failed to create the UDP socket: %s",
253  strerror(errno));
254 
255  //
256  // Turn non-blocking on.
257 #if WIN32
258  u_long ioctl_arg = 1;
259  if (0 != ioctlsocket(m_serverSocket, FIONBIO, &ioctl_arg))
260  CRL_EXCEPTION("failed to make a socket non-blocking: %d",WSAGetLastError ());
261 #else
262  const int flags = fcntl(m_serverSocket, F_GETFL, 0);
263 
264  if (0 != fcntl(m_serverSocket, F_SETFL, flags | O_NONBLOCK))
265  CRL_EXCEPTION("failed to make a socket non-blocking: %s",
266  strerror(errno));
267 #endif
268 
269  //
270  // Allow reusing sockets.
271 
272  int reuseSocket = 1;
273 
274  if (0 != setsockopt(m_serverSocket, SOL_SOCKET, SO_REUSEADDR, (char*) &reuseSocket,
275  sizeof(reuseSocket)))
276  CRL_EXCEPTION("failed to turn on socket reuse flag: %s",
277  strerror(errno));
278 
279  //
280  // We want very large buffers to store several images
281 
282 #if __APPLE__
283  // MacOS cannot reliably allocate a buffer larger than this
284  int bufferSize = 4 * 1024 * 1024;
285 #else
286  int bufferSize = 48 * 1024 * 1024;
287 #endif
288 
289  if (0 != setsockopt(m_serverSocket, SOL_SOCKET, SO_RCVBUF, (char*) &bufferSize,
290  sizeof(bufferSize)) ||
291  0 != setsockopt(m_serverSocket, SOL_SOCKET, SO_SNDBUF, (char*) &bufferSize,
292  sizeof(bufferSize)))
293  CRL_EXCEPTION("failed to adjust socket buffer sizes (%d bytes): %s",
294  bufferSize, strerror(errno));
295 
296  //
297  // Bind the connection to the port.
298 
299  struct sockaddr_in address;
300 
301  address.sin_family = AF_INET;
302  address.sin_port = htons(0); // system assigned
303  address.sin_addr.s_addr = htonl(INADDR_ANY);
304 
305  if (0 != ::bind(m_serverSocket, (struct sockaddr*) &address, sizeof(address)))
306  CRL_EXCEPTION("failed to bind the server socket to system-assigned port: %s",
307  strerror(errno));
308 
309  //
310  // Retrieve the system assigned local UDP port
311 #if WIN32
312  int len = sizeof(address);
313 #else
314  socklen_t len = sizeof(address);
315 #endif
316  if (0 != getsockname(m_serverSocket, (struct sockaddr*) &address, &len))
317  CRL_EXCEPTION("getsockname() failed: %s", strerror(errno));
318  m_serverSocketPort = htons(address.sin_port);
319 }
320 
321 //
322 // Publish a stream to the sensor
323 
325 {
326  //
327  // Install the header
328 
329  wire::Header& header = *(reinterpret_cast<wire::Header*>(stream.data()));
330 
331  header.magic = wire::HEADER_MAGIC;
332  header.version = wire::HEADER_VERSION;
333  header.group = wire::HEADER_GROUP;
334  header.flags = 0;
335 #if WIN32
336  // TBD: This returns the post-incremented value
337  header.sequenceIdentifier = InterlockedIncrement16((short*)&m_txSeqId);
338 #else
339  // TBD: This returns the pre-incremented value
340  header.sequenceIdentifier = __sync_fetch_and_add(&m_txSeqId, 1);
341 #endif
342  header.messageLength = static_cast<uint32_t> (stream.tell() - sizeof(wire::Header));
343  header.byteOffset = 0;
344 
345  //
346  // Send the packet along
347 
348 // disable MSVC warning for narrowing conversion.
349 #ifdef WIN32
350 #pragma warning (push)
351 #pragma warning (disable : 4267)
352 #endif
353  const int32_t ret = sendto(m_serverSocket, (char*)stream.data(), stream.tell(), 0,
354  (struct sockaddr *) &m_sensorAddress,
355  sizeof(m_sensorAddress));
356 #ifdef WIN32
357 #pragma warning (pop)
358 #endif
359 
360  if (static_cast<size_t>(ret) != stream.tell())
361  CRL_EXCEPTION("error sending data to sensor, %d/%d bytes written: %s",
362  ret, stream.tell(), strerror(errno));
363 }
364 
365 //
366 // Convert data source types from wire<->API. These match 1:1 right now, but we
367 // want the freedom to change the wire protocol as we see fit.
368 
370 {
371  wire::SourceType wire_mask = 0;
372 
373  if (mask & Source_Raw_Left) wire_mask |= wire::SOURCE_RAW_LEFT;
374  if (mask & Source_Raw_Right) wire_mask |= wire::SOURCE_RAW_RIGHT;
375  if (mask & Source_Raw_Aux) wire_mask |= wire::SOURCE_RAW_AUX;
376  if (mask & Source_Luma_Left) wire_mask |= wire::SOURCE_LUMA_LEFT;
377  if (mask & Source_Luma_Right) wire_mask |= wire::SOURCE_LUMA_RIGHT;
378  if (mask & Source_Luma_Aux) wire_mask |= wire::SOURCE_LUMA_AUX;
381  if (mask & Source_Luma_Rectified_Aux) wire_mask |= wire::SOURCE_LUMA_RECT_AUX;
382  if (mask & Source_Chroma_Left) wire_mask |= wire::SOURCE_CHROMA_LEFT;
383  if (mask & Source_Chroma_Right) wire_mask |= wire::SOURCE_CHROMA_RIGHT;
385  if (mask & Source_Chroma_Aux) wire_mask |= wire::SOURCE_CHROMA_AUX;
386  if (mask & Source_Disparity) wire_mask |= wire::SOURCE_DISPARITY;
387  if (mask & Source_Disparity_Right) wire_mask |= wire::SOURCE_DISPARITY_RIGHT;
388  if (mask & Source_Disparity_Aux) wire_mask |= wire::SOURCE_DISPARITY_AUX;
389  if (mask & Source_Disparity_Cost) wire_mask |= wire::SOURCE_DISPARITY_COST;
390  if (mask & Source_Jpeg_Left) wire_mask |= wire::SOURCE_JPEG_LEFT;
391  if (mask & Source_Rgb_Left) wire_mask |= wire::SOURCE_RGB_LEFT;
392  if (mask & Source_Lidar_Scan) wire_mask |= wire::SOURCE_LIDAR_SCAN;
393  if (mask & Source_Imu) wire_mask |= wire::SOURCE_IMU;
394  if (mask & Source_Pps) wire_mask |= wire::SOURCE_PPS;
395 
396  return wire_mask;
397 }
398 
400 {
401  DataSource api_mask = 0;
402 
403  if (mask & wire::SOURCE_RAW_LEFT) api_mask |= Source_Raw_Left;
404  if (mask & wire::SOURCE_RAW_RIGHT) api_mask |= Source_Raw_Right;
405  if (mask & wire::SOURCE_RAW_AUX) api_mask |= Source_Raw_Aux;
406  if (mask & wire::SOURCE_LUMA_LEFT) api_mask |= Source_Luma_Left;
407  if (mask & wire::SOURCE_LUMA_RIGHT) api_mask |= Source_Luma_Right;
408  if (mask & wire::SOURCE_LUMA_AUX) api_mask |= Source_Luma_Aux;
412  if (mask & wire::SOURCE_CHROMA_LEFT) api_mask |= Source_Chroma_Left;
413  if (mask & wire::SOURCE_CHROMA_RIGHT) api_mask |= Source_Chroma_Right;
414  if (mask & wire::SOURCE_CHROMA_AUX) api_mask |= Source_Chroma_Aux;
416  if (mask & wire::SOURCE_DISPARITY) api_mask |= Source_Disparity;
418  if (mask & wire::SOURCE_DISPARITY_AUX) api_mask |= Source_Disparity_Aux;
419  if (mask & wire::SOURCE_DISPARITY_COST) api_mask |= Source_Disparity_Cost;
420  if (mask & wire::SOURCE_JPEG_LEFT) api_mask |= Source_Jpeg_Left;
421  if (mask & wire::SOURCE_RGB_LEFT) api_mask |= Source_Rgb_Left;
422  if (mask & wire::SOURCE_LIDAR_SCAN) api_mask |= Source_Lidar_Scan;
423  if (mask & wire::SOURCE_IMU) api_mask |= Source_Imu;
424  if (mask & wire::SOURCE_PPS) api_mask |= Source_Pps;
425 
426  return api_mask;
427 }
428 
429 uint32_t impl::hardwareApiToWire(uint32_t a)
430 {
431  switch(a) {
444  default:
445  CRL_DEBUG("unknown API hardware type \"%d\"\n", a);
446  return a; // pass through
447  }
448 }
449 uint32_t impl::hardwareWireToApi(uint32_t w)
450 {
451  switch(w) {
464  default:
465  CRL_DEBUG("unknown WIRE hardware type \"%d\"\n", w);
466  return w; // pass through
467  }
468 }
469 uint32_t impl::imagerApiToWire(uint32_t a)
470 {
471  switch(a) {
479  default:
480  CRL_DEBUG("unknown API imager type \"%d\"\n", a);
481  return a; // pass through
482  }
483 }
484 uint32_t impl::imagerWireToApi(uint32_t w)
485 {
486  switch(w) {
494  default:
495  CRL_DEBUG("unknown WIRE imager type \"%d\"\n", w);
496  return w; // pass through
497  }
498 }
499 
500 //
501 // Apply a time offset correction
502 
503 void impl::applySensorTimeOffset(const double& offset)
504 {
506 
507  if (false == m_timeOffsetInit) {
508  m_timeOffset = offset; // seed
509  m_timeOffsetInit = true;
510  return;
511  }
512 
513  const double samples = static_cast<double>(TIME_SYNC_OFFSET_DECAY);
514 
516 }
517 
518 //
519 // Return the corrected time
520 
521 double impl::sensorToLocalTime(const double& sensorTime)
522 {
524  return m_timeOffset + sensorTime;
525 }
526 
527 //
528 // Correct the time, populate seconds/microseconds
529 
530 void impl::sensorToLocalTime(const double& sensorTime,
531  uint32_t& seconds,
532  uint32_t& microseconds)
533 {
534  double corrected = sensorToLocalTime(sensorTime);
535  seconds = static_cast<uint32_t>(corrected);
536  microseconds = static_cast<uint32_t>(1e6 * (corrected - static_cast<double>(seconds)));
537 }
538 
539 //
540 // An internal thread for status/time-synchroniziation
541 
542 #ifdef WIN32
543 DWORD impl::statusThread(void *userDataP)
544 #else
545 void *impl::statusThread(void *userDataP)
546 #endif
547 {
548  impl *selfP = reinterpret_cast<impl*>(userDataP);
549 
550  //
551  // Loop until shutdown
552 
553  while(selfP->m_threadsRunning) {
554 
555  try {
556 
557  //
558  // Setup handler for the status response
559 
561 
562  //
563  // Send the status request, recording the (approx) local time
564 
565  const double ping = utility::TimeStamp::getCurrentTime();
566  selfP->publish(wire::StatusRequest());
567 
568  //
569  // Wait for the response
570 
571  Status status;
572  if (ack.wait(status, 0.010)) {
573 
574  //
575  // Record (approx) time of response
576 
577  const double pong = utility::TimeStamp::getCurrentTime();
578 
579  //
580  // Extract the response payload
581 
583  selfP->m_messages.extract(msg);
584 
585 
586  //
587  // Estimate 'msg.uptime' capture using half of the round trip period
588 
589  const double latency = (pong - ping) / 2.0;
590 
591  //
592  // Compute and apply the estimated time offset
593 
594  const double offset = (ping + latency) - static_cast<double>(msg.uptime);
595  selfP->applySensorTimeOffset(offset);
596 
597  //
598  // Cache the status message
599 
600  selfP->m_statusResponseMessage = msg;
601  }
602 
603  } catch (const std::exception& e) {
604 
605  CRL_DEBUG("exception: %s\n", e.what());
606 
607  } catch (...) {
608 
609  CRL_DEBUG_RAW("unknown exception\n");
610  }
611 
612  //
613  // Recompute offset at ~1Hz
614 
615  usleep(static_cast<unsigned int> (1e6));
616  }
617 
618  return NULL;
619 }
620 
621 } // namespace details
622 
623 Channel* Channel::Create(const std::string& address)
624 {
625  try {
626 
627  return new details::impl(address);
628 
629  } catch (const std::exception& e) {
630 
631  CRL_DEBUG("exception: %s\n", e.what());
632  return NULL;
633  }
634 }
635 
636 void Channel::Destroy(Channel *instanceP)
637 {
638  try {
639 
640  if (instanceP)
641  delete static_cast<details::impl*>(instanceP);
642 
643  } catch (const std::exception& e) {
644 
645  CRL_DEBUG("exception: %s\n", e.what());
646  }
647 }
648 
649 const char *Channel::statusString(Status status)
650 {
651  switch(status) {
652  case Status_Ok: return "Ok";
653  case Status_TimedOut: return "Timed out";
654  case Status_Error: return "Error";
655  case Status_Failed: return "Failed";
656  case Status_Unsupported: return "Unsupported";
657  case Status_Unknown: return "Unknown command";
658  case Status_Exception: return "Exception";
659  }
660 
661  return "Unknown Error";
662 }
663 
664 } // namespace multisense
665 } // namespace crl
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_KS21
static CRL_CONSTEXPR DataSource Source_Disparity_Cost
std::list< ImageListener * > m_imageListeners
Definition: channel.hh:427
static CRL_CONSTEXPR SourceType SOURCE_LUMA_RECT_AUX
Definition: Protocol.h:247
static uint32_t imagerWireToApi(uint32_t h)
Definition: channel.cc:484
static CRL_CONSTEXPR DataSource Source_Luma_Aux
static CRL_CONSTEXPR SourceType SOURCE_LUMA_AUX
Definition: Protocol.h:246
#define CRL_EXCEPTION(fmt,...)
Definition: Exception.hh:71
static uint32_t hardwareWireToApi(uint32_t h)
Definition: channel.cc:449
#define CRL_DEBUG_RAW(fmt)
Definition: Exception.hh:90
static CRL_CONSTEXPR SourceType SOURCE_DISPARITY
Definition: Protocol.h:235
static CRL_CONSTEXPR SourceType SOURCE_RAW_AUX
Definition: Protocol.h:245
static CRL_CONSTEXPR DataSource Source_Disparity_Right
double sensorToLocalTime(const double &sensorTime)
Definition: channel.cc:521
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_SL
static CRL_CONSTEXPR SourceType SOURCE_DISPARITY_AUX
Definition: Protocol.h:249
static CRL_CONSTEXPR DataSource Source_Jpeg_Left
static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV4000_COLOR
static const char * statusString(Status status)
Definition: channel.cc:649
static CRL_CONSTEXPR DataSource Source_Disparity
static CRL_CONSTEXPR SourceType SOURCE_CHROMA_RECT_AUX
Definition: Protocol.h:234
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_KS21
struct sockaddr_in m_sensorAddress
Definition: channel.hh:354
static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV2000_GREY
static CRL_CONSTEXPR SourceType SOURCE_DISPARITY_RIGHT
Definition: Protocol.h:237
static CRL_CONSTEXPR DataSource Source_Chroma_Left
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S21
UdpAssemblerMap m_udpAssemblerMap
Definition: channel.hh:396
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_ST21
static Channel * Create(const std::string &sensorAddress)
Definition: channel.cc:623
static CRL_CONSTEXPR Status Status_Unsupported
void applySensorTimeOffset(const double &offset)
Definition: channel.cc:503
wire::StatusResponse m_statusResponseMessage
Definition: channel.hh:464
static wire::SourceType sourceApiToWire(DataSource mask)
Definition: channel.cc:369
static CRL_CONSTEXPR DataSource Source_Luma_Left
std::list< PpsListener * > m_ppsListeners
Definition: channel.hh:429
static CRL_CONSTEXPR uint32_t IMAGER_TYPE_AR0234_GREY
std_msgs::Header * header(M &m)
#define closesocket
Definition: Portability.hh:102
static CRL_CONSTEXPR Status Status_Failed
static CRL_CONSTEXPR SourceType SOURCE_LUMA_LEFT
Definition: Protocol.h:228
utility::Thread * m_rxThreadP
Definition: channel.hh:416
static CRL_CONSTEXPR uint16_t HEADER_VERSION
Definition: Protocol.h:76
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S7
static CRL_CONSTEXPR SourceType SOURCE_CHROMA_RIGHT
Definition: Protocol.h:233
static CRL_CONSTEXPR uint32_t RX_POOL_SMALL_BUFFER_COUNT
Definition: channel.hh:268
#define MSG_ID(x)
Definition: Protocol.h:273
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_C6S2_S27
static CRL_CONSTEXPR DataSource Source_Luma_Rectified_Aux
static CRL_CONSTEXPR uint32_t RX_POOL_SMALL_BUFFER_SIZE
Definition: channel.hh:267
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_SL
static CRL_CONSTEXPR SourceType SOURCE_LUMA_RECT_RIGHT
Definition: Protocol.h:231
static CRL_CONSTEXPR DataSource Source_Lidar_Scan
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_M
static CRL_CONSTEXPR DataSource Source_Luma_Right
#define INVALID_SOCKET
Definition: channel.hh:66
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MONO
static CRL_CONSTEXPR uint32_t IMAGER_TYPE_AR0234_GREY
static CRL_CONSTEXPR DataSource Source_Imu
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S30
static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV4000_GREY
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S7S
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_ST21
static CRL_CONSTEXPR uint16_t DEFAULT_SENSOR_TX_PORT
Definition: channel.hh:264
static CRL_CONSTEXPR uint32_t IMAGER_TYPE_IMX104_COLOR
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S21
Definition: channel.cc:56
static CRL_CONSTEXPR SourceType SOURCE_CHROMA_LEFT
Definition: Protocol.h:232
static CRL_CONSTEXPR Status Status_TimedOut
static CRL_CONSTEXPR uint32_t RX_POOL_LARGE_BUFFER_COUNT
Definition: channel.hh:266
static CRL_CONSTEXPR Status Status_Ok
static CRL_CONSTEXPR DataSource Source_Chroma_Aux
static CRL_CONSTEXPR SourceType SOURCE_RAW_RIGHT
Definition: Protocol.h:227
static CRL_CONSTEXPR DataSource Source_Pps
static CRL_CONSTEXPR DataSource Source_Rgb_Left
wire::VersionResponse m_sensorVersion
Definition: channel.hh:459
static CRL_CONSTEXPR uint32_t IMAGER_TYPE_AR0239_COLOR
static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV4000_GREY
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S7S
static CRL_CONSTEXPR SourceType SOURCE_IMU
Definition: Protocol.h:243
static uint32_t imagerApiToWire(uint32_t h)
Definition: channel.cc:469
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S30
static CRL_CONSTEXPR uint32_t HARDWARE_REV_BCAM
static CRL_CONSTEXPR SourceType SOURCE_LUMA_RECT_LEFT
Definition: Protocol.h:230
static CRL_CONSTEXPR uint16_t HEADER_MAGIC
Definition: Protocol.h:75
static CRL_CONSTEXPR SourceType SOURCE_DISPARITY_COST
Definition: Protocol.h:238
static CRL_CONSTEXPR uint32_t IMAGER_TYPE_AR0239_COLOR
static CRL_CONSTEXPR DataSource Source_Chroma_Rectified_Aux
static CRL_CONSTEXPR DataSource Source_Raw_Right
#define CRL_DEBUG(fmt,...)
Definition: Exception.hh:83
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S7AR
static CRL_CONSTEXPR SourceType SOURCE_RGB_LEFT
Definition: Protocol.h:240
static CRL_CONSTEXPR uint32_t RX_POOL_LARGE_BUFFER_SIZE
Definition: channel.hh:265
std::list< LidarListener * > m_lidarListeners
Definition: channel.hh:428
static CRL_CONSTEXPR DataSource Source_Raw_Left
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_C6S2_S27
bool wait(Status &status, const double &timeout)
Definition: signal.hh:125
static uint32_t hardwareApiToWire(uint32_t h)
Definition: channel.cc:429
static void Destroy(Channel *instanceP)
Definition: channel.cc:636
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S7AR
impl(const std::string &address)
Definition: channel.cc:63
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_M
static CRL_CONSTEXPR uint16_t HEADER_GROUP
Definition: Protocol.h:81
static void assembler(utility::BufferStreamWriter &stream, const uint8_t *dataP, uint32_t offset, uint32_t length)
static CRL_CONSTEXPR DataSource Source_Luma_Rectified_Right
void publish(const T &message)
Definition: query.hh:50
static CRL_CONSTEXPR SourceType SOURCE_RAW_LEFT
Definition: Protocol.h:226
static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV2000_GREY
static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV4000_COLOR
static CRL_CONSTEXPR SourceType SOURCE_LIDAR_SCAN
Definition: Protocol.h:242
static CRL_CONSTEXPR SourceType SOURCE_PPS
Definition: Protocol.h:244
static void * rxThread(void *userDataP)
Definition: dispatch.cc:690
static CRL_CONSTEXPR SourceType SOURCE_LUMA_RIGHT
Definition: Protocol.h:229
std::list< ImuListener * > m_imuListeners
Definition: channel.hh:430
static CRL_CONSTEXPR Status Status_Exception
Type decayedAverage(Type const &previous, Type const &samples, Type const &newest)
Definition: Functional.hh:67
static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV2000_COLOR
static CRL_CONSTEXPR uint32_t TIME_SYNC_OFFSET_DECAY
Definition: channel.hh:274
static CRL_CONSTEXPR DataSource Source_Raw_Aux
static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV2000_COLOR
static CRL_CONSTEXPR DataSource Source_Disparity_Aux
Status waitData(const T &command, U &data, const double &timeout=DEFAULT_ACK_TIMEOUT(), int32_t attempts=DEFAULT_ACK_ATTEMPTS)
Definition: query.hh:120
static void * statusThread(void *userDataP)
Definition: channel.cc:545
static CRL_CONSTEXPR Status Status_Error
static CRL_CONSTEXPR uint32_t IMAGER_TYPE_IMX104_COLOR
static CRL_CONSTEXPR SourceType SOURCE_JPEG_LEFT
Definition: Protocol.h:239
utility::Thread * m_statusThreadP
Definition: channel.hh:422
static DataSource sourceWireToApi(wire::SourceType mask)
Definition: channel.cc:399
static CRL_CONSTEXPR DataSource Source_Chroma_Right
static CRL_CONSTEXPR Status Status_Unknown
static CRL_CONSTEXPR SourceType SOURCE_CHROMA_AUX
Definition: Protocol.h:248
static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S7
static CRL_CONSTEXPR DataSource Source_Luma_Rectified_Left


multisense_lib
Author(s):
autogenerated on Sun Mar 14 2021 02:34:50