Go to the documentation of this file.
   96 #define __STDC_FORMAT_MACROS 
  108 void defaultUdpAssembler(utility::BufferStreamWriter& stream,
 
  109                          const uint8_t               *dataP,
 
  114     stream.write(dataP, length);
 
  127     std::list<ImageListener*>::const_iterator it;
 
  132         (*it)->dispatch(buffer, 
header);
 
  146     std::list<LidarListener*>::const_iterator it;
 
  151         (*it)->dispatch(buffer, 
header);
 
  163     std::list<PpsListener*>::const_iterator it;
 
  181     std::list<ImuListener*>::const_iterator it;
 
  200     std::list<CompressedImageListener*>::const_iterator it;
 
  205         (*it)->dispatch(buffer, 
header);
 
  218     std::list<GroundSurfaceSplineListener*>::const_iterator it;
 
  236     std::list<AprilTagDetectionListener*>::const_iterator it;
 
  255     std::list<SecondaryAppListener*>::const_iterator it;
 
  260         (*it)->dispatch(buffer, 
header);
 
  301         const uint32_t maxRange = 
static_cast<uint32_t
> (30.0 * 1e3); 
 
  323         header.maxRange          = maxRange;
 
  459         for(uint32_t i=0; i<imu.
samples.size(); i++) {
 
  489             a.
x = w.
x; a.
y = w.
y; a.
z = w.
z;
 
  539         for (
unsigned int i = 0; i < 2; i++)
 
  547         for (
unsigned int i = 0; i < 6; i++)
 
  569         for (
size_t index = 0 ; index < apriltag.
detections.size() ; ++index)
 
  573             apriltag::Header::ApriltagDetection outgoing;
 
  575             outgoing.family = std::string(incoming.
family);
 
  576             outgoing.id = incoming.
id;
 
  577             outgoing.hamming = incoming.
hamming;
 
  580             for (
unsigned int i = 0; i < 3; i++)
 
  582                 for (
unsigned int j = 0; j < 3; j++)
 
  588             outgoing.center[0] = incoming.
center[0];
 
  589             outgoing.center[1] = incoming.
center[1];
 
  591             for (
unsigned int i = 0; i < 4; i++)
 
  593                 for (
unsigned int j = 0; j < 2; j++)
 
  595                     outgoing.corners[i][j] = incoming.
corners[i][j];
 
  599             header.detections.push_back(outgoing);
 
  718         CRL_DEBUG(
"unknown message received: id=%d, version=%d\n",
 
  754     stream & messageType;
 
  764         return defaultUdpAssembler;
 
  785     BufferPool::const_iterator it = bP->begin();
 
  786     for(; it != bP->end(); it++)
 
  787         if (
false == (*it)->shared())
 
  790     CRL_EXCEPTION(
"no free RX buffers (%d in use by consumers)\n", bP->size());
 
  803         CRL_CONSTEXPR uint16_t ID_MAX  = std::numeric_limits<uint16_t>::max();
 
  817         else if (((wireId & ID_MASK) == ID_LOW) &&
 
  850 #if defined(WIN32) && !defined(__MINGW64__) 
  851 #pragma warning (push) 
  852 #pragma warning (disable : 4267) 
  858 #if defined(WIN32) && !defined(__MINGW64__) 
  859 #pragma warning (pop) 
  878         const uint8_t *inP = 
reinterpret_cast<const uint8_t*
>(
m_incomingBuffer.data());
 
  911             if (0 != 
header.byteOffset) {
 
  913 #ifdef UDP_ASSEMBLER_DEBUG 
  914                     CRL_DEBUG(
"Unexpected packet without header: sequence=%" PRId64 
" byteOffset=%u\n", sequence, 
header.byteOffset);
 
  955         } 
else if (1 == trP->
packets()) {
 
  962             if (willBeDropped.first)
 
  964 #ifdef UDP_ASSEMBLER_DEBUG 
  965                 CRL_DEBUG(
"UDP Assembler dropping sequence=%" PRId64 
"\n", willBeDropped.second);
 
  984     impl     *selfP  = 
reinterpret_cast<impl*
>(userDataP);
 
  997         FD_SET(server, &readSet);
 
 1002         struct timeval tv = {0, 200000}; 
 
 1005         const int result = select (1, &readSet, NULL, NULL, &tv);
 
 1007         const int result = select (server + 1, &readSet, NULL, NULL, &tv);
 
 1019         } 
catch (
const std::exception& e) {
 
 1021             CRL_DEBUG(
"exception while decoding packet: %s\n", e.what());
 
 1029 #if defined(__MINGW64__) 
  
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR IdType ID
std::list< CompressedImageListener * > m_compressedImageListeners
static CRL_CONSTEXPR IdType ID
std::size_t numDispatchedGroundSurfaceSpline
static CRL_CONSTEXPR IdType ID
std::size_t numDispatchedSecondary
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR IdType ID
std::vector< ApriltagDetection > detections
#define CRL_DEBUG(fmt,...)
std::list< PpsListener * > m_ppsListeners
static CRL_CONSTEXPR IdType ID
bool m_networkTimeSyncEnabled
static CRL_CONSTEXPR uint16_t HEADER_MAGIC
std::size_t numDispatchedImu
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR IdType ID
uint32_t timeMicroSeconds
void * controlPointsDataP
static CRL_CONSTEXPR uint16_t TYPE_GYRO
static CRL_CONSTEXPR IdType ID
void dispatchPps(pps::Header &header)
static CRL_CONSTEXPR DataSource Source_Disparity
system::ChannelStatistics m_channelStatistics
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR uint16_t HEADER_VERSION
DepthCache< int64_t, UdpTracker > m_udpTrackerCache
void dispatchCompressedImage(utility::BufferStream &buffer, compressed_image::Header &header)
static CRL_CONSTEXPR IdType ID
int64_t m_unWrappedRxSeqId
utility::Mutex m_dispatchLock
static CRL_CONSTEXPR IdType ID
#define CRL_DEBUG_RAW(fmt)
std::list< SecondaryAppListener * > m_secondaryAppListeners
BufferPool m_rxLargeBufferPool
static CRL_CONSTEXPR IdType ID
std::vector< uint8_t > m_incomingBuffer
void signal(wire::IdType id, Status status=Status_Ok)
static CRL_CONSTEXPR IdType ID
#define CRL_EXCEPTION(fmt,...)
std::size_t numDispatchedPps
static CRL_CONSTEXPR IdType ID
std::size_t numDispatchedCompressedImage
void dispatchGroundSurfaceSpline(ground_surface::Header &header)
DepthCache< int64_t, wire::SecondaryAppMetadata > m_secondaryAppMetaCache
void seek(std::size_t idx)
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR IdType ID
const int64_t & unwrapSequenceId(uint16_t id)
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR Type Type_Gyroscope
void dispatchAprilTagDetections(apriltag::Header &header)
DepthCache< int64_t, wire::ImageMeta > m_imageMetaCache
void dispatchSecondaryApplication(utility::BufferStream &buffer, secondary_app::Header &header)
static CRL_CONSTEXPR uint32_t RX_POOL_SMALL_BUFFER_SIZE
void dispatchImage(utility::BufferStream &buffer, image::Header &header)
static CRL_CONSTEXPR Type Type_Accelerometer
static CRL_CONSTEXPR uint16_t HEADER_GROUP
void dispatchImu(imu::Header &header)
static CRL_CONSTEXPR IdType ID
void dispatch(utility::BufferStreamWriter &buffer)
bool m_ptpTimeSyncEnabled
std::list< LidarListener * > m_lidarListeners
static CRL_CONSTEXPR uint32_t RX_POOL_LARGE_BUFFER_SIZE
double tagToImageHomography[3][3]
static void * rxThread(void *userDataP)
std::list< ImuListener * > m_imuListeners
std_msgs::Header const * header(const M &m)
void getImageTime(const WireT *wire, uint32_t &seconds, uint32_t µSeconds)
static CRL_CONSTEXPR IdType ID
static CRL_CONSTEXPR IdType ID
#define CRL_EXCEPTION_RAW(fmt)
static CRL_CONSTEXPR IdType ID
std::list< AprilTagDetectionListener * > m_aprilTagDetectionListeners
Type degreesToRadians(Type const &value)
std::list< GroundSurfaceSplineListener * > m_groundSurfaceSplineListeners
std::vector< utility::BufferStreamWriter * > BufferPool
static CRL_CONSTEXPR Type Type_Magnetometer
utility::BufferStreamWriter & findFreeBuffer(uint32_t messageLength)
static CRL_CONSTEXPR IdType ID
std::list< ImageListener * > m_imageListeners
static CRL_CONSTEXPR uint16_t TYPE_ACCEL
static CRL_CONSTEXPR uint16_t TYPE_MAG
bool assemble(uint32_t bytes, uint32_t offset, const uint8_t *dataP)
std::vector< ImuSample > samples
int64_t m_lastUnexpectedSequenceId
utility::Mutex m_statisticsLock
static CRL_CONSTEXPR IdType ID
UdpAssembler getUdpAssembler(const uint8_t *udpDatagramP, uint32_t length)
void toHeaderTime(T nanoSeconds, uint32_t &seconds, uint32_t µSeconds) const
std::size_t numImageMetaData
std::size_t numDispatchedLidar
void(* UdpAssembler)(utility::BufferStreamWriter &stream, const uint8_t *dataP, uint32_t offset, uint32_t length)
utility::TimeStamp sensorToLocalTime(const utility::TimeStamp &sensorTime)
static CRL_CONSTEXPR IdType ID
utility::BufferStreamWriter & stream()
BufferPool m_rxSmallBufferPool
static CRL_CONSTEXPR IdType ID
std::size_t numDispatchedImage
std::size_t numDroppedAssemblers
UdpAssemblerMap m_udpAssemblerMap
void dispatchLidar(utility::BufferStream &buffer, lidar::Header &header)