81 namespace multisense {
88 void defaultUdpAssembler(utility::BufferStreamWriter& stream,
94 stream.write(dataP, length);
107 std::list<ImageListener*>::const_iterator it;
112 (*it)->dispatch(buffer, header);
123 std::list<LidarListener*>::const_iterator it;
128 (*it)->dispatch(buffer, header);
137 std::list<PpsListener*>::const_iterator it;
142 (*it)->dispatch(header);
152 std::list<ImuListener*>::const_iterator it;
157 (*it)->dispatch(header);
194 const uint32_t maxRange =
static_cast<uint32_t
> (30.0 * 1e3);
370 for(uint32_t i=0; i<imu.
samples.size(); i++) {
377 const int64_t oneBillion =
static_cast<int64_t
>(1e9);
381 static_cast<int64_t>(1000));
394 a.
x = w.
x; a.
y = w.
y; a.
z = w.
z;
465 CRL_DEBUG(
"unknown message received: id=%d, version=%d\n",
501 stream & messageType;
511 return defaultUdpAssembler;
532 BufferPool::const_iterator it = bP->begin();
533 for(; it != bP->end(); it++)
534 if (
false == (*it)->shared())
537 CRL_EXCEPTION(
"no free RX buffers (%d in use by consumers)\n", bP->size());
550 const uint16_t ID_MAX = std::numeric_limits<uint16_t>::max();
551 const uint16_t ID_CENTER = ID_MAX / 2;
562 else if (wireId < ID_CENTER &&
576 m_lastRxSeqId = wireId;
614 const uint8_t *inP =
reinterpret_cast<const uint8_t*
>(
m_incomingBuffer.data());
647 if (0 != header.byteOffset)
681 }
else if (1 == trP->
packets()) {
701 impl *selfP =
reinterpret_cast<impl*
>(userDataP);
714 FD_SET(server, &readSet);
719 struct timeval tv = {0, 200000};
720 const int result = select(server+1, &readSet, NULL, NULL, &tv);
731 }
catch (
const std::exception& e) {
733 CRL_DEBUG(
"exception while decoding packet: %s\n", e.what());
737 CRL_DEBUG(
"unknown exception while decoding packet\n");
std::list< ImageListener * > m_imageListeners
int64_t m_unWrappedRxSeqId
#define CRL_EXCEPTION(fmt,...)
static CRL_CONSTEXPR Type Type_Accelerometer
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR IdType ID
BufferPool m_rxLargeBufferPool
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR IdType ID
double sensorToLocalTime(const double &sensorTime)
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR DataSource Source_Disparity
bool assemble(uint32_t bytes, uint32_t offset, const uint8_t *dataP)
UdpAssemblerMap m_udpAssemblerMap
void insert(KEY key, DATA *data)
static CRL_CONSTEXPR IdType ID
std::list< PpsListener * > m_ppsListeners
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR IdType ID
std_msgs::Header * header(M &m)
DepthCache< int64_t, wire::ImageMeta > m_imageMetaCache
static CRL_CONSTEXPR Type Type_Magnetometer
void dispatch(utility::BufferStreamWriter &buffer)
DepthCache< int64_t, UdpTracker > m_udpTrackerCache
static CRL_CONSTEXPR IdType ID
UdpAssembler getUdpAssembler(const uint8_t *udpDatagramP, uint32_t length)
static CRL_CONSTEXPR uint16_t HEADER_VERSION
std::vector< uint8_t > m_incomingBuffer
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR uint32_t RX_POOL_SMALL_BUFFER_SIZE
void signal(wire::IdType id, Status status=Status_Ok)
static CRL_CONSTEXPR IdType ID
void(* UdpAssembler)(utility::BufferStreamWriter &stream, const uint8_t *dataP, uint32_t offset, uint32_t length)
utility::Mutex m_dispatchLock
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR uint16_t TYPE_GYRO
void seek(std::size_t idx)
static CRL_CONSTEXPR uint16_t TYPE_ACCEL
utility::BufferStreamWriter & stream()
const int64_t & unwrapSequenceId(uint16_t id)
utility::BufferStreamWriter & findFreeBuffer(uint32_t messageLength)
bool m_networkTimeSyncEnabled
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR uint16_t HEADER_MAGIC
static CRL_CONSTEXPR IdType ID
void dispatchImu(imu::Header &header)
static CRL_CONSTEXPR IdType ID
void dispatchPps(pps::Header &header)
Type degreesToRadians(Type const &value)
#define CRL_DEBUG(fmt,...)
std::vector< ImuSample > samples
static CRL_CONSTEXPR uint32_t RX_POOL_LARGE_BUFFER_SIZE
BufferPool m_rxSmallBufferPool
std::list< LidarListener * > m_lidarListeners
static CRL_CONSTEXPR IdType ID
uint32_t timeMicroSeconds
static CRL_CONSTEXPR uint16_t HEADER_GROUP
static CRL_CONSTEXPR IdType ID
static void * rxThread(void *userDataP)
void dispatchLidar(utility::BufferStream &buffer, lidar::Header &header)
std::list< ImuListener * > m_imuListeners
std::vector< utility::BufferStreamWriter * > BufferPool
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR uint16_t TYPE_MAG
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR Type Type_Gyroscope
static DataSource sourceWireToApi(wire::SourceType mask)
void dispatchImage(utility::BufferStream &buffer, image::Header &header)
static CRL_CONSTEXPR IdType ID