Classes | Public Types | Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | Static Private Attributes | List of all members
crl::multisense::details::impl Class Reference

#include <channel.hh>

Inheritance diagram for crl::multisense::details::impl:
Inheritance graph
[legend]

Classes

class  UdpTracker
 

Public Types

typedef int32_t socket_t
 

Public Member Functions

virtual Status addIsolatedCallback (apriltag::Callback callback, void *userDataP)
 
virtual Status addIsolatedCallback (compressed_image::Callback callback, DataSource imageSourceMask, void *userDataP)
 
virtual Status addIsolatedCallback (ground_surface::Callback callback, void *userDataP)
 
virtual Status addIsolatedCallback (image::Callback callback, DataSource imageSourceMask, void *userDataP)
 
virtual Status addIsolatedCallback (imu::Callback callback, void *userDataP)
 
virtual Status addIsolatedCallback (lidar::Callback callback, void *userDataP)
 
virtual Status addIsolatedCallback (pps::Callback callback, void *userDataP)
 
virtual Status addIsolatedCallback (secondary_app::Callback callback, void *userDataP)
 
virtual Status getApiVersion (VersionType &version)
 
virtual Status getAuxImageConfig (image::AuxConfig &c)
 
virtual Status getDeviceInfo (system::DeviceInfo &info)
 
virtual Status getDeviceModes (std::vector< system::DeviceMode > &modes)
 
virtual Status getDeviceStatus (system::StatusMessage &status)
 
virtual Status getEnabledStreams (DataSource &mask)
 
virtual Status getExternalCalibration (system::ExternalCalibration &calibration)
 
virtual Status getImageCalibration (image::Calibration &c)
 
virtual Status getImageConfig (image::Config &c)
 
virtual Status getImageHistogram (int64_t frameId, image::Histogram &histogram)
 
virtual Status getImuConfig (uint32_t &samplesPerMessage, std::vector< imu::Config > &c)
 
virtual Status getImuInfo (uint32_t &maxSamplesPerMessage, std::vector< imu::Info > &info)
 
virtual Status getLargeBufferDetails (uint32_t &bufferCount, uint32_t &bufferSize)
 
virtual Status getLidarCalibration (lidar::Calibration &c)
 
virtual Status getLightingConfig (lighting::Config &c)
 
virtual Status getLightingSensorStatus (lighting::SensorStatus &status)
 
virtual Status getLocalUdpPort (uint16_t &port)
 
virtual Status getMotorPos (int32_t &mtu)
 
virtual Status getMtu (int32_t &mtu)
 
virtual Status getNetworkConfig (system::NetworkConfig &c)
 
virtual Status getPacketDelay (image::PacketDelay &p)
 
virtual Status getPtpStatus (system::PtpStatus &ptpStatus)
 
virtual Status getRegisteredApps (system::SecondaryAppRegisteredApps &c)
 
virtual Status getRemoteHeadConfig (image::RemoteHeadConfig &c)
 
virtual Status getSecondaryAppConfig (system::SecondaryAppConfig &c)
 
virtual Status getSensorVersion (VersionType &version)
 
virtual system::ChannelStatistics getStats ()
 
virtual Status getTransmitDelay (image::TransmitDelay &c)
 
virtual Status getVersionInfo (system::VersionInfo &v)
 
 impl (const std::string &address, const RemoteHeadChannel &cameraId, const std::string &ifName)
 
virtual Status networkTimeSynchronization (bool enabled)
 
virtual Status ptpTimeSynchronization (bool enabled)
 
virtual Status releaseCallbackBuffer (void *referenceP)
 
virtual Status removeIsolatedCallback (apriltag::Callback callback)
 
virtual Status removeIsolatedCallback (compressed_image::Callback callback)
 
virtual Status removeIsolatedCallback (ground_surface::Callback callback)
 
virtual Status removeIsolatedCallback (image::Callback callback)
 
virtual Status removeIsolatedCallback (imu::Callback callback)
 
virtual Status removeIsolatedCallback (lidar::Callback callback)
 
virtual Status removeIsolatedCallback (pps::Callback callback)
 
virtual Status removeIsolatedCallback (secondary_app::Callback callback)
 
virtual void * reserveCallbackBuffer ()
 
virtual Status secondaryAppActivate (const std::string &s)
 
virtual Status secondaryAppDeactivate (const std::string &s)
 
virtual Status setApriltagParams (const system::ApriltagParams &params)
 
virtual Status setAuxImageConfig (const image::AuxConfig &c)
 
virtual Status setBestMtu ()
 
virtual Status setDeviceInfo (const std::string &key, const system::DeviceInfo &i)
 
virtual Status setExternalCalibration (const system::ExternalCalibration &calibration)
 
virtual Status setGroundSurfaceParams (const system::GroundSurfaceParams &params)
 
virtual Status setImageCalibration (const image::Calibration &c)
 
virtual Status setImageConfig (const image::Config &c)
 
virtual Status setImuConfig (bool storeSettingsInFlash, uint32_t samplesPerMessage, const std::vector< imu::Config > &c)
 
virtual Status setLargeBuffers (const std::vector< uint8_t * > &buffers, uint32_t bufferSize)
 
virtual Status setLidarCalibration (const lidar::Calibration &c)
 
virtual Status setLightingConfig (const lighting::Config &c)
 
virtual Status setMotorSpeed (float rpm)
 
virtual Status setMtu (int32_t mtu)
 
virtual Status setNetworkConfig (const system::NetworkConfig &c)
 
virtual Status setPacketDelay (const image::PacketDelay &p)
 
virtual Status setRemoteHeadConfig (const image::RemoteHeadConfig &c)
 
virtual Status setSecondaryAppConfig (system::SecondaryAppConfig &c)
 
virtual Status setTransmitDelay (const image::TransmitDelay &c)
 
virtual Status setTriggerSource (TriggerSource s)
 
virtual Status startStreams (DataSource mask)
 
virtual Status stopStreams (DataSource mask)
 
 ~impl ()
 
- Public Member Functions inherited from crl::multisense::Channel
virtual ~Channel ()
 

Private Types

typedef std::vector< utility::BufferStreamWriter * > BufferPool
 
typedef void(* UdpAssembler) (utility::BufferStreamWriter &stream, const uint8_t *dataP, uint32_t offset, uint32_t length)
 
typedef std::map< wire::IdType, UdpAssemblerUdpAssemblerMap
 

Private Member Functions

void applySensorTimeOffset (const utility::TimeStamp &offset)
 
void bind (const std::string &ifName)
 
void cleanup ()
 
void dispatch (utility::BufferStreamWriter &buffer)
 
void dispatchAprilTagDetections (apriltag::Header &header)
 
void dispatchCompressedImage (utility::BufferStream &buffer, compressed_image::Header &header)
 
void dispatchGroundSurfaceSpline (ground_surface::Header &header)
 
void dispatchImage (utility::BufferStream &buffer, image::Header &header)
 
void dispatchImu (imu::Header &header)
 
void dispatchLidar (utility::BufferStream &buffer, lidar::Header &header)
 
void dispatchPps (pps::Header &header)
 
void dispatchSecondaryApplication (utility::BufferStream &buffer, secondary_app::Header &header)
 
utility::BufferStreamWriterfindFreeBuffer (uint32_t messageLength)
 
template<class WireT >
void getImageTime (const WireT *wire, uint32_t &seconds, uint32_t &microSeconds)
 
UdpAssembler getUdpAssembler (const uint8_t *udpDatagramP, uint32_t length)
 
void handle ()
 
template<class T >
void publish (const T &message)
 
void publish (const utility::BufferStreamWriter &stream)
 
utility::TimeStamp sensorToLocalTime (const utility::TimeStamp &sensorTime)
 
void sensorToLocalTime (const utility::TimeStamp &sensorTime, uint32_t &seconds, uint32_t &microseconds)
 
template<typename T >
void toHeaderTime (T nanoSeconds, uint32_t &seconds, uint32_t &microSeconds) const
 
const int64_t & unwrapSequenceId (uint16_t id)
 
template<class T >
Status waitAck (const T &msg, wire::IdType id=MSG_ID(T::ID), const double &timeout=DEFAULT_ACK_TIMEOUT(), int32_t attempts=DEFAULT_ACK_ATTEMPTS)
 
template<class T , class U >
Status waitData (const T &command, U &data, const double &timeout=DEFAULT_ACK_TIMEOUT(), int32_t attempts=DEFAULT_ACK_ATTEMPTS)
 

Static Private Member Functions

static double DEFAULT_ACK_TIMEOUT ()
 
static uint32_t hardwareApiToWire (uint32_t h)
 
static uint32_t hardwareWireToApi (uint32_t h)
 
static uint32_t imagerApiToWire (uint32_t h)
 
static uint32_t imagerWireToApi (uint32_t h)
 
static void * rxThread (void *userDataP)
 
static wire::SourceType sourceApiToWire (DataSource mask)
 
static DataSource sourceWireToApi (wire::SourceType mask)
 
static void * statusThread (void *userDataP)
 

Private Attributes

std::list< AprilTagDetectionListener * > m_aprilTagDetectionListeners
 
system::ChannelStatistics m_channelStatistics
 
std::list< CompressedImageListener * > m_compressedImageListeners
 
utility::Mutex m_dispatchLock
 
Status m_getPtpStatusReturnStatus
 
Status m_getStatusReturnStatus
 
std::list< GroundSurfaceSplineListener * > m_groundSurfaceSplineListeners
 
std::list< ImageListener * > m_imageListeners
 
DepthCache< int64_t, wire::ImageMetam_imageMetaCache
 
std::list< ImuListener * > m_imuListeners
 
std::vector< uint8_t > m_incomingBuffer
 
int32_t m_lastRxSeqId
 
int64_t m_lastUnexpectedSequenceId
 
std::list< LidarListener * > m_lidarListeners
 
MessageMap m_messages
 
bool m_networkTimeSyncEnabled
 
std::list< PpsListener * > m_ppsListeners
 
wire::PtpStatusResponse m_ptpStatusResponseMessage
 
bool m_ptpTimeSyncEnabled
 
BufferPool m_rxLargeBufferPool
 
utility::Mutex m_rxLock
 
BufferPool m_rxSmallBufferPool
 
utility::Threadm_rxThreadP
 
std::list< SecondaryAppListener * > m_secondaryAppListeners
 
DepthCache< int64_t, wire::SecondaryAppMetadatam_secondaryAppMetaCache
 
struct sockaddr_in m_sensorAddress
 
int32_t m_sensorMtu
 
wire::VersionResponse m_sensorVersion
 
socket_t m_serverSocket
 
uint16_t m_serverSocketPort
 
utility::Mutex m_statisticsLock
 
wire::StatusResponse m_statusResponseMessage
 
utility::Threadm_statusThreadP
 
utility::Mutex m_streamLock
 
DataSource m_streamsEnabled
 
bool m_threadsRunning
 
utility::Mutex m_timeLock
 
utility::TimeStamp m_timeOffset
 
bool m_timeOffsetInit
 
uint16_t m_txSeqId
 
UdpAssemblerMap m_udpAssemblerMap
 
DepthCache< int64_t, UdpTrackerm_udpTrackerCache
 
int64_t m_unWrappedRxSeqId
 
MessageWatch m_watch
 

Static Private Attributes

static CRL_CONSTEXPR VersionType API_VERSION = 0x0701
 
static CRL_CONSTEXPR uint32_t DEFAULT_ACK_ATTEMPTS = 5
 
static CRL_CONSTEXPR uint16_t DEFAULT_SENSOR_TX_PORT = 9001
 
static CRL_CONSTEXPR uint32_t IMAGE_META_CACHE_DEPTH = 4
 
static CRL_CONSTEXPR uint32_t MAX_BUFFER_ALLOCATION_RETRIES = 5
 
static CRL_CONSTEXPR uint32_t MAX_DIRECTED_STREAMS = 8
 
static CRL_CONSTEXPR uint32_t MAX_MTU_SIZE = 9000
 
static CRL_CONSTEXPR uint32_t MAX_USER_APRILTAG_QUEUE_SIZE = 8
 
static CRL_CONSTEXPR uint32_t MAX_USER_COMPRESSED_IMAGE_QUEUE_SIZE = 8
 
static CRL_CONSTEXPR uint32_t MAX_USER_GROUND_SURFACE_QUEUE_SIZE = 8
 
static CRL_CONSTEXPR uint32_t MAX_USER_IMAGE_QUEUE_SIZE = 8
 
static CRL_CONSTEXPR uint32_t MAX_USER_IMU_QUEUE_SIZE = 64
 
static CRL_CONSTEXPR uint32_t MAX_USER_LASER_QUEUE_SIZE = 8
 
static CRL_CONSTEXPR uint32_t MAX_USER_PPS_QUEUE_SIZE = 2
 
static CRL_CONSTEXPR uint32_t MAX_USER_SECONDARY_APP_QUEUE_SIZE = 8
 
static CRL_CONSTEXPR uint32_t MIN_MTU_SIZE = 1500
 
static CRL_CONSTEXPR uint32_t RX_POOL_LARGE_BUFFER_COUNT = 16
 
static CRL_CONSTEXPR uint32_t RX_POOL_LARGE_BUFFER_SIZE = (10 * (1024 * 1024))
 
static CRL_CONSTEXPR uint32_t RX_POOL_SMALL_BUFFER_COUNT = 256
 
static CRL_CONSTEXPR uint32_t RX_POOL_SMALL_BUFFER_SIZE = (8 * (1024))
 
static CRL_CONSTEXPR uint32_t SECONDARY_APP_META_CACHE_DEPTH = 4
 
static CRL_CONSTEXPR uint32_t TIME_SYNC_OFFSET_DECAY = 8
 
static CRL_CONSTEXPR uint32_t UDP_TRACKER_CACHE_DEPTH = 4
 

Additional Inherited Members

- Static Public Member Functions inherited from crl::multisense::Channel
static ChannelCreate (const std::string &sensorAddress)
 
static ChannelCreate (const std::string &sensorAddress, const RemoteHeadChannel &cameraId)
 
static ChannelCreate (const std::string &sensorAddress, const RemoteHeadChannel &cameraId, const std::string &interfaceName)
 
static ChannelCreate (const std::string &sensorAddress, const std::string &interfaceName)
 
static void Destroy (Channel *instanceP)
 
static const char * statusString (Status status)
 

Detailed Description

Definition at line 88 of file Legacy/include/MultiSense/details/channel.hh.

Member Typedef Documentation

◆ BufferPool

◆ socket_t

Definition at line 94 of file Legacy/include/MultiSense/details/channel.hh.

◆ UdpAssembler

typedef void(* crl::multisense::details::impl::UdpAssembler) (utility::BufferStreamWriter &stream, const uint8_t *dataP, uint32_t offset, uint32_t length)
private

◆ UdpAssemblerMap

Constructor & Destructor Documentation

◆ impl()

crl::multisense::details::impl::impl ( const std::string &  address,
const RemoteHeadChannel cameraId,
const std::string &  ifName 
)

Definition at line 68 of file Legacy/details/channel.cc.

◆ ~impl()

crl::multisense::details::impl::~impl ( )

Definition at line 302 of file Legacy/details/channel.cc.

Member Function Documentation

◆ addIsolatedCallback() [1/8]

virtual Status crl::multisense::details::impl::addIsolatedCallback ( apriltag::Callback  callback,
void *  userDataP 
)
virtual

Add a user defined callback attached to a lidar stream. Each callback will create a unique internal thread dedicated to servicing the callback.

The lidar data passed to the callback are valid only until the callback returns. To reserve image data so that it persists longer than that, see member function reserveCallbackBuffer() below.

Lidar data is queued per-callback. For each lidar callback the maximum queue depth is 20 lidar scans.

Adding multiple callbacks subscribing to the same lidar data is allowed. The same instance of lidar data will be presented to each callback with no copying done.

Parameters
callbackA user defined lidar::Callback to send lidar data to
userDataPA pointer to arbitrary user data.
Returns
A crl::multisense::Status indicating if the callback registration succeeded or failed

Implements crl::multisense::Channel.

◆ addIsolatedCallback() [2/8]

virtual Status crl::multisense::details::impl::addIsolatedCallback ( compressed_image::Callback  callback,
DataSource  imageSourceMask,
void *  userDataP 
)
virtual

Add a user defined callback attached to the image streams specified by imageSourceMask. Each callback will create a unique internal thread dedicated to servicing the callback.

The image data passed to the callback are valid only until the callback returns. To reserve image data so that it persists longer than that, see member function reserveCallbackBuffer() below.

Image data is queued per-callback. For each image callback the internal queue depth is 5 images, but see member functions getLargeBufferDetails() and setLargeBuffers().

Adding multiple callbacks subscribing to the same image data is allowed. The same instance of image data will be presented to each callback with no copying done.

Multiple image types may be subscribed to simultaneously in a single callback by using an imageSourceMask argument that is the bitwise or of the appropriate DataSource values.

Multiple callbacks of differing types may be added in order to isolate image processing by thread.

Parameters
callbackA user defined image::Callback to which image data will be sent.
imageSourceMaskThe specific image types to stream to the user defined callback. Multiple image sources may be combined using the bitwise OR operator.
userDataPA pointer to arbitrary user data. This typically is a pointer to the instance of the object where the callback is defined. See image::Header for a example of this usage
Returns
A crl::multisense::Status indicating if the callback registration succeeded or failed

Implements crl::multisense::Channel.

◆ addIsolatedCallback() [3/8]

virtual Status crl::multisense::details::impl::addIsolatedCallback ( ground_surface::Callback  callback,
void *  userDataP 
)
virtual

Add a user defined callback attached to a lidar stream. Each callback will create a unique internal thread dedicated to servicing the callback.

The lidar data passed to the callback are valid only until the callback returns. To reserve image data so that it persists longer than that, see member function reserveCallbackBuffer() below.

Lidar data is queued per-callback. For each lidar callback the maximum queue depth is 20 lidar scans.

Adding multiple callbacks subscribing to the same lidar data is allowed. The same instance of lidar data will be presented to each callback with no copying done.

Parameters
callbackA user defined lidar::Callback to send lidar data to
userDataPA pointer to arbitrary user data.
Returns
A crl::multisense::Status indicating if the callback registration succeeded or failed

Implements crl::multisense::Channel.

◆ addIsolatedCallback() [4/8]

Status crl::multisense::details::impl::addIsolatedCallback ( image::Callback  callback,
DataSource  imageSourceMask,
void *  userDataP 
)
virtual

Add a user defined callback attached to the image streams specified by imageSourceMask. Each callback will create a unique internal thread dedicated to servicing the callback.

The image data passed to the callback are valid only until the callback returns. To reserve image data so that it persists longer than that, see member function reserveCallbackBuffer() below.

Image data is queued per-callback. For each image callback the internal queue depth is 5 images, but see member functions getLargeBufferDetails() and setLargeBuffers().

Adding multiple callbacks subscribing to the same image data is allowed. The same instance of image data will be presented to each callback with no copying done.

Multiple image types may be subscribed to simultaneously in a single callback by using an imageSourceMask argument that is the bitwise or of the appropriate DataSource values.

Multiple callbacks of differing types may be added in order to isolate image processing by thread.

Parameters
callbackA user defined image::Callback to which image data will be sent.
imageSourceMaskThe specific image types to stream to the user defined callback. Multiple image sources may be combined using the bitwise OR operator.
userDataPA pointer to arbitrary user data. This typically is a pointer to the instance of the object where the callback is defined. See image::Header for a example of this usage
Returns
A crl::multisense::Status indicating if the callback registration succeeded or failed

Implements crl::multisense::Channel.

Definition at line 141 of file public.cc.

◆ addIsolatedCallback() [5/8]

virtual Status crl::multisense::details::impl::addIsolatedCallback ( imu::Callback  callback,
void *  userDataP 
)
virtual

Add a user defined callback attached to a lidar stream. Each callback will create a unique internal thread dedicated to servicing the callback.

The lidar data passed to the callback are valid only until the callback returns. To reserve image data so that it persists longer than that, see member function reserveCallbackBuffer() below.

Lidar data is queued per-callback. For each lidar callback the maximum queue depth is 20 lidar scans.

Adding multiple callbacks subscribing to the same lidar data is allowed. The same instance of lidar data will be presented to each callback with no copying done.

Parameters
callbackA user defined lidar::Callback to send lidar data to
userDataPA pointer to arbitrary user data.
Returns
A crl::multisense::Status indicating if the callback registration succeeded or failed

Implements crl::multisense::Channel.

◆ addIsolatedCallback() [6/8]

Status crl::multisense::details::impl::addIsolatedCallback ( lidar::Callback  callback,
void *  userDataP 
)
virtual

Add a user defined callback attached to a lidar stream. Each callback will create a unique internal thread dedicated to servicing the callback.

The lidar data passed to the callback are valid only until the callback returns. To reserve image data so that it persists longer than that, see member function reserveCallbackBuffer() below.

Lidar data is queued per-callback. For each lidar callback the maximum queue depth is 20 lidar scans.

Adding multiple callbacks subscribing to the same lidar data is allowed. The same instance of lidar data will be presented to each callback with no copying done.

Parameters
callbackA user defined lidar::Callback to send lidar data to
userDataPA pointer to arbitrary user data.
Returns
A crl::multisense::Status indicating if the callback registration succeeded or failed

Implements crl::multisense::Channel.

Definition at line 163 of file public.cc.

◆ addIsolatedCallback() [7/8]

virtual Status crl::multisense::details::impl::addIsolatedCallback ( pps::Callback  callback,
void *  userDataP 
)
virtual

Add a user defined callback attached to a lidar stream. Each callback will create a unique internal thread dedicated to servicing the callback.

The lidar data passed to the callback are valid only until the callback returns. To reserve image data so that it persists longer than that, see member function reserveCallbackBuffer() below.

Lidar data is queued per-callback. For each lidar callback the maximum queue depth is 20 lidar scans.

Adding multiple callbacks subscribing to the same lidar data is allowed. The same instance of lidar data will be presented to each callback with no copying done.

Parameters
callbackA user defined lidar::Callback to send lidar data to
userDataPA pointer to arbitrary user data.
Returns
A crl::multisense::Status indicating if the callback registration succeeded or failed

Implements crl::multisense::Channel.

◆ addIsolatedCallback() [8/8]

virtual Status crl::multisense::details::impl::addIsolatedCallback ( secondary_app::Callback  callback,
void *  userDataP 
)
virtual

Add a user defined callback attached to a lidar stream. Each callback will create a unique internal thread dedicated to servicing the callback.

The lidar data passed to the callback are valid only until the callback returns. To reserve image data so that it persists longer than that, see member function reserveCallbackBuffer() below.

Lidar data is queued per-callback. For each lidar callback the maximum queue depth is 20 lidar scans.

Adding multiple callbacks subscribing to the same lidar data is allowed. The same instance of lidar data will be presented to each callback with no copying done.

Parameters
callbackA user defined lidar::Callback to send lidar data to
userDataPA pointer to arbitrary user data.
Returns
A crl::multisense::Status indicating if the callback registration succeeded or failed

Implements crl::multisense::Channel.

◆ applySensorTimeOffset()

void crl::multisense::details::impl::applySensorTimeOffset ( const utility::TimeStamp offset)
private

Definition at line 633 of file Legacy/details/channel.cc.

◆ bind()

void crl::multisense::details::impl::bind ( const std::string &  ifName)
private

Definition at line 311 of file Legacy/details/channel.cc.

◆ cleanup()

void crl::multisense::details::impl::cleanup ( )
private

Definition at line 233 of file Legacy/details/channel.cc.

◆ DEFAULT_ACK_TIMEOUT()

static double crl::multisense::details::impl::DEFAULT_ACK_TIMEOUT ( )
inlinestaticprivate

◆ dispatch()

void crl::multisense::details::impl::dispatch ( utility::BufferStreamWriter buffer)
private

Definition at line 270 of file dispatch.cc.

◆ dispatchAprilTagDetections()

void crl::multisense::details::impl::dispatchAprilTagDetections ( apriltag::Header header)
private

Definition at line 232 of file dispatch.cc.

◆ dispatchCompressedImage()

void crl::multisense::details::impl::dispatchCompressedImage ( utility::BufferStream buffer,
compressed_image::Header header 
)
private

Definition at line 195 of file dispatch.cc.

◆ dispatchGroundSurfaceSpline()

void crl::multisense::details::impl::dispatchGroundSurfaceSpline ( ground_surface::Header header)
private

Definition at line 214 of file dispatch.cc.

◆ dispatchImage()

void crl::multisense::details::impl::dispatchImage ( utility::BufferStream buffer,
image::Header header 
)
private

Definition at line 122 of file dispatch.cc.

◆ dispatchImu()

void crl::multisense::details::impl::dispatchImu ( imu::Header header)
private

Definition at line 177 of file dispatch.cc.

◆ dispatchLidar()

void crl::multisense::details::impl::dispatchLidar ( utility::BufferStream buffer,
lidar::Header header 
)
private

Definition at line 141 of file dispatch.cc.

◆ dispatchPps()

void crl::multisense::details::impl::dispatchPps ( pps::Header header)
private

Definition at line 159 of file dispatch.cc.

◆ dispatchSecondaryApplication()

void crl::multisense::details::impl::dispatchSecondaryApplication ( utility::BufferStream buffer,
secondary_app::Header header 
)
private

Definition at line 250 of file dispatch.cc.

◆ findFreeBuffer()

utility::BufferStreamWriter & crl::multisense::details::impl::findFreeBuffer ( uint32_t  messageLength)
private

Definition at line 770 of file dispatch.cc.

◆ getApiVersion()

Status crl::multisense::details::impl::getApiVersion ( VersionType version)
virtual

Get the API version of LibMultiSense.

Parameters
versionThe API version of LibMultiSense, returned by reference
Returns
A crl::multisense::Status indicating if the LibMultiSense API version query succeeded

Implements crl::multisense::Channel.

Definition at line 833 of file public.cc.

◆ getAuxImageConfig()

Status crl::multisense::details::impl::getAuxImageConfig ( image::AuxConfig c)
virtual

Query the aux image configuration.

See image::AuxConfig for a usage example

Parameters
cThe aux image configuration returned by reference from the query
Returns
A crl::multisense::Status indicating if the image configuration query succeeded

Implements crl::multisense::Channel.

Definition at line 928 of file public.cc.

◆ getDeviceInfo()

Status crl::multisense::details::impl::getDeviceInfo ( system::DeviceInfo info)
virtual

Query the current sensor's device information.

See system::DeviceInfo for a usage example

Parameters
infoA DeviceInfo returned by reference containing the device information for the current sensor
Returns
A crl::multisense::Status indicating if the device information query was successful

Implements crl::multisense::Channel.

Definition at line 1594 of file public.cc.

◆ getDeviceModes()

Status crl::multisense::details::impl::getDeviceModes ( std::vector< system::DeviceMode > &  m)
virtual

Query the available sensor device modes.

See system::DeviceMode for a usage example

Parameters
mA vector of possible device modes returned by reference from the sensor
Returns
A crl::multisense::Status indicating if the device mode query was successful

Implements crl::multisense::Channel.

Definition at line 1442 of file public.cc.

◆ getDeviceStatus()

Status crl::multisense::details::impl::getDeviceStatus ( system::StatusMessage status)
virtual

Get the current status of the device. Status is updated at 1Hz and should not be queried at a higher frequency.

Parameters
statusThe status of the attached device returned by reference
Returns
A crl::multisense::Status indicating if the status was successfully queried

Implements crl::multisense::Channel.

Definition at line 1638 of file public.cc.

◆ getEnabledStreams()

Status crl::multisense::details::impl::getEnabledStreams ( DataSource mask)
virtual

Get the current data streams which are enabled on the sensor.

Parameters
maskThe current data streams which are enabled. These are returned by reference in mask
Returns
A crl::multisense::Status indicating if the getEnabledStreams query succeeded.

Implements crl::multisense::Channel.

Definition at line 697 of file public.cc.

◆ getExternalCalibration()

Status crl::multisense::details::impl::getExternalCalibration ( system::ExternalCalibration calibration)
virtual

Get the external calibration associated with the MultiSense device

Parameters
calibrationThe external calibration object to query from non-volatile flash
Returns
A crl::multisense::Status indicating if the calibration was successfully queried

Implements crl::multisense::Channel.

Definition at line 1675 of file public.cc.

◆ getImageCalibration()

Status crl::multisense::details::impl::getImageCalibration ( image::Calibration c)
virtual

Query the current camera calibration.

See image::Calibration for a usage example

Parameters
cA image calibration returned by reference from getImageCalibration()
Returns
A crl::multisense::Status indicating if the image calibration was successfully queried

Implements crl::multisense::Channel.

Definition at line 1304 of file public.cc.

◆ getImageConfig()

Status crl::multisense::details::impl::getImageConfig ( image::Config c)
virtual

Query the image configuration.

See image::Config for a usage example

Parameters
cThe image configuration returned by reference from the query
Returns
A crl::multisense::Status indicating if the image configuration query succeeded

Implements crl::multisense::Channel.

Definition at line 863 of file public.cc.

◆ getImageHistogram()

Status crl::multisense::details::impl::getImageHistogram ( int64_t  frameId,
image::Histogram histogram 
)
virtual

Get the image histogram for the image corresponding to a specified frameId.

See image::Histogram for a usage example

Parameters
frameIdThe frameId of the corresponding left image to query a histogram for. Histograms can only be queried for images with frameIds fewer than 20 frameIds from the most recent image's frameId.
histogramA histogram returned by reference
Returns
A crl::multisense::Status indicating if the histogram query was successful

Implements crl::multisense::Channel.

Definition at line 584 of file public.cc.

◆ getImageTime()

template<class WireT >
void crl::multisense::details::impl::getImageTime ( const WireT *  wire,
uint32_t &  seconds,
uint32_t &  microSeconds 
)
inlineprivate

◆ getImuConfig()

Status crl::multisense::details::impl::getImuConfig ( uint32_t &  samplesPerMessage,
std::vector< imu::Config > &  c 
)
virtual

Query the current IMU configuration.

See imu::Config for a usage example

Parameters
samplesPerMessageThe number of samples (aggregate from all IMU types) that the sensor will queue internally before putting on the wire. Note that low settings combined with high IMU sensor rates may interfere with the acquisition and transmission of image and lidar data.
cThe current imu configuration returned by reference
Returns
A crl::multisense::Status indicating if the IMU configuration was successfully queried

Implements crl::multisense::Channel.

Definition at line 1926 of file public.cc.

◆ getImuInfo()

Status crl::multisense::details::impl::getImuInfo ( uint32_t &  maxSamplesPerMessage,
std::vector< imu::Info > &  info 
)
virtual

Query detailed information about the current sensor's IMU.

See imu::Info for a usage example

Parameters
maxSamplesPerMessageThe maximum number of IMU samples which can be aggregated in a single IMU message
infoA vector of imu::Info returned by reference. This contains all the possible configurations for each IMU sensor
Returns
A crl::multisense::Status indicating if the IMU info was successfully queried

Implements crl::multisense::Channel.

Definition at line 1886 of file public.cc.

◆ getLargeBufferDetails()

Status crl::multisense::details::impl::getLargeBufferDetails ( uint32_t &  bufferCount,
uint32_t &  bufferSize 
)
virtual

Query the suggested number and size of the image buffers.

NOTe: Other number/size can be used but it is not recommended

The channel maintains and recycles a set of large buffers used for image storage and dispatching.

Parameters
bufferCountThe number of buffers returned by reference
bufferSizeThe size of a single buffer returned by reference
Returns
A crl::multisense::Status indicating if the buffer details were successfully queried

Implements crl::multisense::Channel.

Definition at line 1978 of file public.cc.

◆ getLidarCalibration()

Status crl::multisense::details::impl::getLidarCalibration ( lidar::Calibration c)
virtual

Query the current laser calibration.

See lidar::Calibration for a usage example

Parameters
cA laser calibration returned by reference from getLidarCalibration()
Returns
A crl::multisense::Status indicating if the laser calibration was successfully queried

Implements crl::multisense::Channel.

Definition at line 1412 of file public.cc.

◆ getLightingConfig()

Status crl::multisense::details::impl::getLightingConfig ( lighting::Config c)
virtual

Query the on-board lighting configuration.

See lighting::Config for a usage example

Parameters
cA lighting configuration returned by reference
Returns
A crl::multisense::Status indicating if the lighting configuration query succeeded

Implements crl::multisense::Channel.

Definition at line 753 of file public.cc.

◆ getLightingSensorStatus()

Status crl::multisense::details::impl::getLightingSensorStatus ( lighting::SensorStatus status)
virtual

Get the status of the sensors attached to the external lighting platform

Parameters
statusThe status of the external lighting sensors returned by reference

Implements crl::multisense::Channel.

Definition at line 807 of file public.cc.

◆ getLocalUdpPort()

Status crl::multisense::details::impl::getLocalUdpPort ( uint16_t &  port)
virtual

Query the system-assigned local UDP port.

Parameters
portThe local system UDP port returned by reference
Returns
A crl::multisense::Status indicating if the local UDP port was successfully queried

Implements crl::multisense::Channel.

Definition at line 2032 of file public.cc.

◆ getMotorPos()

Status crl::multisense::details::impl::getMotorPos ( int32_t &  mtu)
virtual

Query the maxon or SLB motor for its current encoder position in microradians.

Parameters
mtuAn int32_t returned by reference containing the current motor encoder position in microradians
Returns
A crl::multisense::Status indicating success if a motor was found and could report its encoder position, or fail if no motor is present.

Implements crl::multisense::Channel.

Definition at line 1551 of file public.cc.

◆ getMtu()

Status crl::multisense::details::impl::getMtu ( int32_t &  mtu)
virtual

Query the current sensor's MTU configuration. The MTU setting controls the maximum size of the UDP packets that will be transmitted from the sensor via Ethernet. In general, larger MTU settings are preferred, but the MTU value must not exceed the MTU setting of the network interface to which the MultiSense unit is sending data.

Parameters
mtuAn int32_t returned by reference containing the current MTU setting
Returns
A crl::multisense::Status indicating if the mtu query was successful

Implements crl::multisense::Channel.

Definition at line 1495 of file public.cc.

◆ getNetworkConfig()

Status crl::multisense::details::impl::getNetworkConfig ( system::NetworkConfig c)
virtual

Query the current sensor's network configuration.

See system::NetworkConfig for a usage example

Parameters
cA NetworkConfig returned by reference containing the current sensor's network configuration
Returns
A crl::multisense::Status indicating if the network configuration query was successful

Implements crl::multisense::Channel.

Definition at line 1577 of file public.cc.

◆ getPacketDelay()

Status crl::multisense::details::impl::getPacketDelay ( image::PacketDelay c)
virtual

Query the current device udp packet delay.

Parameters
cThe udp packet delay instance which will be returned by reference
Returns
A crl::multisense::Status indicating if the udp packet delay was successfully queried

Implements crl::multisense::Channel.

Definition at line 1385 of file public.cc.

◆ getPtpStatus()

Status crl::multisense::details::impl::getPtpStatus ( system::PtpStatus ptpStatus)
virtual

Get PTP status information (updates at 1Hz)

Parameters
ptpStatusA ptpStatus obj returned by reference from the sensor
Returns
A crl::multisense::Status indicating if the PTP status query was successful

Implements crl::multisense::Channel.

Definition at line 621 of file public.cc.

◆ getRegisteredApps()

Status crl::multisense::details::impl::getRegisteredApps ( system::SecondaryAppRegisteredApps c)
virtual

Query the secondary application(s) registered with the MultiSense device

Parameters
paramsThe secondary application(s) supported by this firmware version
Returns
A crl::multisense::Status indicating if the params were successfully queried

Implements crl::multisense::Channel.

Definition at line 1804 of file public.cc.

◆ getRemoteHeadConfig()

Status crl::multisense::details::impl::getRemoteHeadConfig ( image::RemoteHeadConfig c)
virtual

Set the current Remote Head Config

Parameters
cA remoteHeadConfig returned by reference from getRemoteHeadConfig()
Returns
A crl::multisense::Status indicating if the Remote Head Config was successfully queried

Implements crl::multisense::Channel.

Definition at line 1226 of file public.cc.

◆ getSecondaryAppConfig()

Status crl::multisense::details::impl::getSecondaryAppConfig ( system::SecondaryAppConfig c)
virtual

Get the secondary application config parameters associated with the MultiSense device

Parameters
paramsThe secondary application parameters to send to the secondary application
Returns
A crl::multisense::Status indicating if the params were successfully queried

Implements crl::multisense::Channel.

Definition at line 1750 of file public.cc.

◆ getSensorVersion()

Status crl::multisense::details::impl::getSensorVersion ( VersionType version)
virtual

Get the API version of the sensor firmware.

Parameters
versionThe API version of the sensor firmware, returned by reference
Returns
A crl::multisense::Status indicating if the sensor API version query succeeded

Implements crl::multisense::Channel.

Definition at line 824 of file public.cc.

◆ getStats()

system::ChannelStatistics crl::multisense::details::impl::getStats ( )
virtual

Query the statistics of the channel object.

Returns
A crl::multisense::system::ChannelStatistics object that contains various metrics of this channel object

Implements crl::multisense::Channel.

Definition at line 2038 of file public.cc.

◆ getTransmitDelay()

Status crl::multisense::details::impl::getTransmitDelay ( image::TransmitDelay c)
virtual

Query the current device network delay.

Parameters
cThe network delay instance which will be returned by reference
Returns
A crl::multisense::Status indicating if the network delay was successfully queried

Implements crl::multisense::Channel.

Definition at line 1358 of file public.cc.

◆ getUdpAssembler()

impl::UdpAssembler crl::multisense::details::impl::getUdpAssembler ( const uint8_t *  udpDatagramP,
uint32_t  length 
)
private

Definition at line 744 of file dispatch.cc.

◆ getVersionInfo()

Status crl::multisense::details::impl::getVersionInfo ( system::VersionInfo v)
virtual

Get the version info for the sensor and LibMultiSense.

See system::VersionInfo for a usage example.

Parameters
vThe version information returned by reference
Returns
A crl::multisense::Status indicating if the version information query succeeded

Implements crl::multisense::Channel.

Definition at line 842 of file public.cc.

◆ handle()

void crl::multisense::details::impl::handle ( )
private

Definition at line 840 of file dispatch.cc.

◆ hardwareApiToWire()

uint32_t crl::multisense::details::impl::hardwareApiToWire ( uint32_t  h)
staticprivate

Definition at line 543 of file Legacy/details/channel.cc.

◆ hardwareWireToApi()

uint32_t crl::multisense::details::impl::hardwareWireToApi ( uint32_t  h)
staticprivate

Definition at line 570 of file Legacy/details/channel.cc.

◆ imagerApiToWire()

uint32_t crl::multisense::details::impl::imagerApiToWire ( uint32_t  h)
staticprivate

Definition at line 597 of file Legacy/details/channel.cc.

◆ imagerWireToApi()

uint32_t crl::multisense::details::impl::imagerWireToApi ( uint32_t  h)
staticprivate

Definition at line 613 of file Legacy/details/channel.cc.

◆ networkTimeSynchronization()

Status crl::multisense::details::impl::networkTimeSynchronization ( bool  enabled)
virtual

Enable or disable local network-based time synchronization.

Each Channel will keep a continuously updating and filtered offset between the sensor's internal clock and the local system clock.

If enabled, all sensor timestamps will be reported in the local system clock frame, after the offset has been applied.

If disabled, all sensor timestamps will be reported in the frame of the sensor's clock, which is free-running from 0 seconds on power up.

The network-based time synchronization is enabled by default.

Parameters
enabledA boolean flag which enables or disables network time synchronization
Returns
A crl::multisense::Status indicating if the network-based time synchronization was successfully enabled or disabled

Implements crl::multisense::Channel.

Definition at line 642 of file public.cc.

◆ ptpTimeSynchronization()

Status crl::multisense::details::impl::ptpTimeSynchronization ( bool  enabled)
virtual

Enable or disable PTP synchronization to an external PTP master. This subsumes the networkTimeSynchronization

Each Channel will keep a continuously updating and filtered offset between the sensor's internal clock and the local system clock.

If enabled, all sensor timestamps will be reported with the synchronized PTP time

If disabled, all sensor timestamps will be reported in the timebase determined by the current networkTimeSynchronization setting

The PTP-based time synchronization is disabled by default

Parameters
enabledA boolean flag which enables or disables PTP time synchronization
Returns
A crl::multisense::Status indicating if the PTP time synchronization was successfully enabled or disabled

Implements crl::multisense::Channel.

Definition at line 651 of file public.cc.

◆ publish() [1/2]

template<class T >
void crl::multisense::details::impl::publish ( const T &  message)
private

Definition at line 50 of file query.hh.

◆ publish() [2/2]

void crl::multisense::details::impl::publish ( const utility::BufferStreamWriter stream)
private

Definition at line 408 of file Legacy/details/channel.cc.

◆ releaseCallbackBuffer()

Status crl::multisense::details::impl::releaseCallbackBuffer ( void *  referenceP)
virtual

Release image or lidar data reserved within a isolated callback.

releaseCallbackBuffer() may be called from any thread context.

Parameters
referencePA pointer to the reserved data returned by reserveCallbackBuffer()
Returns
A crl::multisense::Status indicating if the callback data buffer was successfully released

Implements crl::multisense::Channel.

Definition at line 558 of file public.cc.

◆ removeIsolatedCallback() [1/8]

virtual Status crl::multisense::details::impl::removeIsolatedCallback ( apriltag::Callback  callback)
virtual

Unregister a user defined image::Callback. This stops the callback from receiving image data.

Parameters
callbackThe user defined image::Callback to unregister
Returns
A crl::multisense::Status indicating if the callback deregistration succeeded or failed

Implements crl::multisense::Channel.

◆ removeIsolatedCallback() [2/8]

virtual Status crl::multisense::details::impl::removeIsolatedCallback ( compressed_image::Callback  callback)
virtual

Unregister a user defined image::Callback. This stops the callback from receiving image data.

Parameters
callbackThe user defined image::Callback to unregister
Returns
A crl::multisense::Status indicating if the callback deregistration succeeded or failed

Implements crl::multisense::Channel.

◆ removeIsolatedCallback() [3/8]

virtual Status crl::multisense::details::impl::removeIsolatedCallback ( ground_surface::Callback  callback)
virtual

Unregister a user defined image::Callback. This stops the callback from receiving image data.

Parameters
callbackThe user defined image::Callback to unregister
Returns
A crl::multisense::Status indicating if the callback deregistration succeeded or failed

Implements crl::multisense::Channel.

◆ removeIsolatedCallback() [4/8]

Status crl::multisense::details::impl::removeIsolatedCallback ( image::Callback  callback)
virtual

Unregister a user defined image::Callback. This stops the callback from receiving image data.

Parameters
callbackThe user defined image::Callback to unregister
Returns
A crl::multisense::Status indicating if the callback deregistration succeeded or failed

Implements crl::multisense::Channel.

Definition at line 290 of file public.cc.

◆ removeIsolatedCallback() [5/8]

virtual Status crl::multisense::details::impl::removeIsolatedCallback ( imu::Callback  callback)
virtual

Unregister a user defined image::Callback. This stops the callback from receiving image data.

Parameters
callbackThe user defined image::Callback to unregister
Returns
A crl::multisense::Status indicating if the callback deregistration succeeded or failed

Implements crl::multisense::Channel.

◆ removeIsolatedCallback() [6/8]

virtual Status crl::multisense::details::impl::removeIsolatedCallback ( lidar::Callback  callback)
virtual

Unregister a user defined image::Callback. This stops the callback from receiving image data.

Parameters
callbackThe user defined image::Callback to unregister
Returns
A crl::multisense::Status indicating if the callback deregistration succeeded or failed

Implements crl::multisense::Channel.

◆ removeIsolatedCallback() [7/8]

virtual Status crl::multisense::details::impl::removeIsolatedCallback ( pps::Callback  callback)
virtual

Unregister a user defined image::Callback. This stops the callback from receiving image data.

Parameters
callbackThe user defined image::Callback to unregister
Returns
A crl::multisense::Status indicating if the callback deregistration succeeded or failed

Implements crl::multisense::Channel.

◆ removeIsolatedCallback() [8/8]

virtual Status crl::multisense::details::impl::removeIsolatedCallback ( secondary_app::Callback  callback)
virtual

Unregister a user defined image::Callback. This stops the callback from receiving image data.

Parameters
callbackThe user defined image::Callback to unregister
Returns
A crl::multisense::Status indicating if the callback deregistration succeeded or failed

Implements crl::multisense::Channel.

◆ reserveCallbackBuffer()

void * crl::multisense::details::impl::reserveCallbackBuffer ( )
virtual

Reserve image or lidar data within a isolated callback so it is available after the callback returns.

The memory buffer behind an image or lidar datum within an isolated callback may be reserved by the user. This is useful for performing data processing outside of the channel callback, without having to perform a memory copy of the sensor data.

The channel is guaranteed not to reuse the memory buffer until the user releases it back. Note that there are a limited amount of memory buffers, and care should be taken not to reserve them for too long.

Returns
A valid (non NULL) reference only when called within the context of an image or lidar callback.

Implements crl::multisense::Channel.

Definition at line 534 of file public.cc.

◆ rxThread()

void * crl::multisense::details::impl::rxThread ( void *  userDataP)
staticprivate

Definition at line 981 of file dispatch.cc.

◆ secondaryAppActivate()

Status crl::multisense::details::impl::secondaryAppActivate ( const std::string &  name)
virtual

Activate the secondary application for use with the MultiSense device

Parameters
namethe name of the secondary application to activate
Returns
A crl::multisense::Status indicating if the params were successfully set

Implements crl::multisense::Channel.

Definition at line 1829 of file public.cc.

◆ secondaryAppDeactivate()

Status crl::multisense::details::impl::secondaryAppDeactivate ( const std::string &  s)
virtual

Deactivate the secondary application for use with the MultiSense device

Parameters
namethe name of the secondary application to deactivate
Returns
A crl::multisense::Status indicating if the params were successfully set

Implements crl::multisense::Channel.

Definition at line 1836 of file public.cc.

◆ sensorToLocalTime() [1/2]

utility::TimeStamp crl::multisense::details::impl::sensorToLocalTime ( const utility::TimeStamp sensorTime)
private

Definition at line 667 of file Legacy/details/channel.cc.

◆ sensorToLocalTime() [2/2]

void crl::multisense::details::impl::sensorToLocalTime ( const utility::TimeStamp sensorTime,
uint32_t &  seconds,
uint32_t &  microseconds 
)
private

Definition at line 676 of file Legacy/details/channel.cc.

◆ setApriltagParams()

Status crl::multisense::details::impl::setApriltagParams ( const system::ApriltagParams params)
virtual

Set the apriltag parameters associated with the MultiSense device

Parameters
paramsThe apriltag parameters to send to the on-camera apriltag application
Returns
A crl::multisense::Status indicating if the params were successfully set

Implements crl::multisense::Channel.

Definition at line 1731 of file public.cc.

◆ setAuxImageConfig()

Status crl::multisense::details::impl::setAuxImageConfig ( const image::AuxConfig c)
virtual

Set the aux image configuration.

See image::AuxConfig for a usage example

Parameters
cThe new aux image configuration to send to the sensor
Returns
A crl::multisense::Status indicating if the image configuration was successfully received by the sensor

Implements crl::multisense::Channel.

Definition at line 1121 of file public.cc.

◆ setBestMtu()

Status crl::multisense::details::impl::setBestMtu ( )
virtual

Binary search for best path MTU (within ~118B).

Returns
A crl::multisense::Status indicating if the mtu configuration was successfully received

Implements crl::multisense::Channel.

Definition at line 1506 of file public.cc.

◆ setDeviceInfo()

Status crl::multisense::details::impl::setDeviceInfo ( const std::string &  key,
const system::DeviceInfo i 
)
virtual

Set the current sensor's device information.

NOTE: This function is intended for use at the factory, and is not publicly supported.

Parameters
keyThe secret key required to write new device information
iThe new DeviceInfo to write to the sensor
Returns
A crl::multisense::Status indicating if the device information was successfully received

Implements crl::multisense::Channel.

Definition at line 1846 of file public.cc.

◆ setExternalCalibration()

Status crl::multisense::details::impl::setExternalCalibration ( const system::ExternalCalibration calibration)
virtual

Set the external calibration associated with the MultiSense device

Parameters
calibrationThe external calibration object to write to non-volatile flash
Returns
A crl::multisense::Status indicating if the calibration was successfully set

Implements crl::multisense::Channel.

Definition at line 1693 of file public.cc.

◆ setGroundSurfaceParams()

Status crl::multisense::details::impl::setGroundSurfaceParams ( const system::GroundSurfaceParams params)
virtual

Set the ground surface parameters associated with the MultiSense device

Parameters
paramsThe ground surface parameters to send to the on-camera ground surface application
Returns
A crl::multisense::Status indicating if the params were successfully set

Implements crl::multisense::Channel.

Definition at line 1707 of file public.cc.

◆ setImageCalibration()

Status crl::multisense::details::impl::setImageCalibration ( const image::Calibration c)
virtual

Set the current camera calibration.

See image::Calibration for a usage example

Parameters
cA new image calibration to send to the sensor
Returns
A crl::multisense::Status indicating if the image calibration was successfully received by the sensor

Implements crl::multisense::Channel.

Definition at line 1333 of file public.cc.

◆ setImageConfig()

Status crl::multisense::details::impl::setImageConfig ( const image::Config c)
virtual

Set the image configuration.

See image::Config for a usage example

Parameters
cThe new image configuration to send to the sensor
Returns
A crl::multisense::Status indicating if the image configuration was successfully received by the sensor

Implements crl::multisense::Channel.

Definition at line 1066 of file public.cc.

◆ setImuConfig()

Status crl::multisense::details::impl::setImuConfig ( bool  storeSettingsInFlash,
uint32_t  samplesPerMessage,
const std::vector< imu::Config > &  c 
)
virtual

Set a new IMU configuration.

See imu::Config for a usage example

IMU streams must be restarted for any configuration changes to be reflected.

Parameters
storeSettingsInFlashA boolean flag which indicated if the configuration saved in non-volatile flash on the sensor head
samplesPerMessageThe new number of IMU samples to aggregate before sending a new IMU message. If the value is zero the sensor will keep its current samplesPerMessage setting
cThe imu configuration that will be sent to the sensor.
Returns
A crl::multisense::Status indicating if the IMU configuration was successfully received

Implements crl::multisense::Channel.

Definition at line 1953 of file public.cc.

◆ setLargeBuffers()

Status crl::multisense::details::impl::setLargeBuffers ( const std::vector< uint8_t * > &  buffers,
uint32_t  bufferSize 
)
virtual

Set user allocated large buffer.

This tells the channel to use the supplied buffers in lieu of its automatically allocated internal buffers. The channel's internal buffers will be freed.

All supplied buffers must be of the same size.

Responsibility for freeing the supplied buffers after channel closure is left to the user

Parameters
buffersA vector of new buffers to use for image storage. All buffers in the vector must be of the same size
bufferSizeThe size of one buffer in the buffers vector
Returns
A crl::multisense::Status indicating if the new buffers were successfully received

Implements crl::multisense::Channel.

Definition at line 1990 of file public.cc.

◆ setLidarCalibration()

Status crl::multisense::details::impl::setLidarCalibration ( const lidar::Calibration c)
virtual

Set the current laser calibration.

See lidar::Calibration for a usage example

Parameters
cA new laser calibration to send to the sensor
Returns
A crl::multisense::Status indicating if the laser calibration was successfully received by the sensor

Implements crl::multisense::Channel.

Definition at line 1429 of file public.cc.

◆ setLightingConfig()

Status crl::multisense::details::impl::setLightingConfig ( const lighting::Config c)
virtual

Set the on-board lighting configuration.

See lighting::Config for a usage example

Parameters
cA lighting configuration to send to the sensor
Returns
A crl::multisense::Status indicating if the lighting reconfiguration succeeded

Implements crl::multisense::Channel.

Definition at line 782 of file public.cc.

◆ setMotorSpeed()

Status crl::multisense::details::impl::setMotorSpeed ( float  rpm)
virtual

Set the laser spindle rotation speed. A positive value rotates the laser in the counter-clockwise direction. A negative value rotates the laser in the clockwise direction.

NOTE: Only positive rotations are recommended. Full life-cycle testing has only been done using a positive rotation.

Parameters
rpmThe number of rotations per minute [-50.0, 50.0]
Returns
A crl::multisense::Status indicating if the motor speed change succeeded

Implements crl::multisense::Channel.

Definition at line 745 of file public.cc.

◆ setMtu()

Status crl::multisense::details::impl::setMtu ( int32_t  mtu)
virtual

Set the current sensor's MTU.

Parameters
mtuThe new MTU to configure the sensor with
Returns
A crl::multisense::Status indicating if the mtu configuration was successfully received

Implements crl::multisense::Channel.

Definition at line 1471 of file public.cc.

◆ setNetworkConfig()

Status crl::multisense::details::impl::setNetworkConfig ( const system::NetworkConfig c)
virtual

Set the current sensor's network configuration.

See system::NetworkConfig for a usage example

Parameters
cA new network configuration to send to the sensor
Returns
A crl::multisense::Status indicating if the network configuration was successfully received

Implements crl::multisense::Channel.

Definition at line 1565 of file public.cc.

◆ setPacketDelay()

Status crl::multisense::details::impl::setPacketDelay ( const image::PacketDelay c)
virtual

Enable the camera udp packet delay. Enables a small delay approx 65us between udp packets for a large stream object. Recommended for clients with poor network bandwidth. If in doubt set to false (disable)

Parameters
cThe packet delay enable field which will be returned by reference
Returns
A crl::multisense::Status indicating if the packet delay was successfully received by the sensor

Implements crl::multisense::Channel.

Definition at line 1400 of file public.cc.

◆ setRemoteHeadConfig()

Status crl::multisense::details::impl::setRemoteHeadConfig ( const image::RemoteHeadConfig c)
virtual

Set the current Remote Head Config

Parameters
cThe new image remote head config to send to the sensor
Returns
A crl::multisense::Status indicating if the remote head configuration was successfully received by the sensor

Implements crl::multisense::Channel.

Definition at line 1264 of file public.cc.

◆ setSecondaryAppConfig()

Status crl::multisense::details::impl::setSecondaryAppConfig ( system::SecondaryAppConfig c)
virtual

Set the secondary application config associated with the MultiSense device

Parameters
paramsThe secondary application parameters to send to the on camera secondary application
Returns
A crl::multisense::Status indicating if the params were successfully set

Implements crl::multisense::Channel.

Definition at line 1783 of file public.cc.

◆ setTransmitDelay()

Status crl::multisense::details::impl::setTransmitDelay ( const image::TransmitDelay c)
virtual

Set the devices network delay (in ms). Default 0ms delay Delay scales down based on a max delay setting driven by the current FPS dynamically

Parameters
cThe desired network delay in ms which will be returned by reference
Returns
A crl::multisense::Status indicating if the transmit delay was successfully received by the sensor

Implements crl::multisense::Channel.

Definition at line 1373 of file public.cc.

◆ setTriggerSource()

Status crl::multisense::details::impl::setTriggerSource ( TriggerSource  s)
virtual

Set a new image trigger source. This is used to specify which source is used to trigger a image capture.

By default Trigger_Internal is used

Parameters
sThe new desired trigger source
Returns
A crl::multisense::Status indicating if the trigger source change succeeded

Implements crl::multisense::Channel.

Definition at line 709 of file public.cc.

◆ sourceApiToWire()

wire::SourceType crl::multisense::details::impl::sourceApiToWire ( DataSource  mask)
staticprivate

Definition at line 453 of file Legacy/details/channel.cc.

◆ sourceWireToApi()

DataSource crl::multisense::details::impl::sourceWireToApi ( wire::SourceType  mask)
staticprivate

Definition at line 498 of file Legacy/details/channel.cc.

◆ startStreams()

Status crl::multisense::details::impl::startStreams ( DataSource  mask)
virtual

Start streaming various DataSources from the sensor.

This is the primary means of stream control. All streams will come to the requestor (i.e., the machine making the request with this API. The server peeks the source address and port from the request UDP packet.)

Multiple streams may be started at once by setting the individual source bits in the mask. Different streams may be started at differing times by calling startStreams() multiple times.

Parameters
maskThe DataSources to start streaming. Multiple streams can be started by performing a bitwise OR operation with various crl::multisense::DataSource definitions
Returns
A crl::multisense::Status indicating if the specified streams were successfully started

Implements crl::multisense::Channel.

Definition at line 669 of file public.cc.

◆ statusThread()

void * crl::multisense::details::impl::statusThread ( void *  userDataP)
staticprivate

Definition at line 691 of file Legacy/details/channel.cc.

◆ stopStreams()

Status crl::multisense::details::impl::stopStreams ( DataSource  mask)
virtual

Stop specific data streams from the sensor.

Stop streams may be called to selectively disable streams at any time. (use stopStreams(crl::multisense::Source_All) to disable all streaming.

Parameters
maskThe DataSources to stop streaming. Multiple streams can be stopped by performing a bitwise OR operation with various crl::multisense::DataSource definitions
Returns
A crl::multisense::Status indicating if the specified streams were successfully stopped

Implements crl::multisense::Channel.

Definition at line 683 of file public.cc.

◆ toHeaderTime()

template<typename T >
void crl::multisense::details::impl::toHeaderTime ( nanoSeconds,
uint32_t &  seconds,
uint32_t &  microSeconds 
) const
inlineprivate

◆ unwrapSequenceId()

const int64_t & crl::multisense::details::impl::unwrapSequenceId ( uint16_t  id)
private

Definition at line 796 of file dispatch.cc.

◆ waitAck()

template<class T >
Status crl::multisense::details::impl::waitAck ( const T &  msg,
wire::IdType  id = MSG_ID(T::ID),
const double &  timeout = DEFAULT_ACK_TIMEOUT(),
int32_t  attempts = DEFAULT_ACK_ATTEMPTS 
)
private

Definition at line 89 of file query.hh.

◆ waitData()

template<class T , class U >
Status crl::multisense::details::impl::waitData ( const T &  command,
U &  data,
const double &  timeout = DEFAULT_ACK_TIMEOUT(),
int32_t  attempts = DEFAULT_ACK_ATTEMPTS 
)
private

Definition at line 120 of file query.hh.

Member Data Documentation

◆ API_VERSION

CRL_CONSTEXPR VersionType crl::multisense::details::impl::API_VERSION = 0x0701
staticprivate

◆ DEFAULT_ACK_ATTEMPTS

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::DEFAULT_ACK_ATTEMPTS = 5
staticprivate

◆ DEFAULT_SENSOR_TX_PORT

CRL_CONSTEXPR uint16_t crl::multisense::details::impl::DEFAULT_SENSOR_TX_PORT = 9001
staticprivate

◆ IMAGE_META_CACHE_DEPTH

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::IMAGE_META_CACHE_DEPTH = 4
staticprivate

◆ m_aprilTagDetectionListeners

std::list<AprilTagDetectionListener*> crl::multisense::details::impl::m_aprilTagDetectionListeners
private

◆ m_channelStatistics

system::ChannelStatistics crl::multisense::details::impl::m_channelStatistics
private

◆ m_compressedImageListeners

std::list<CompressedImageListener*> crl::multisense::details::impl::m_compressedImageListeners
private

◆ m_dispatchLock

utility::Mutex crl::multisense::details::impl::m_dispatchLock
private

◆ m_getPtpStatusReturnStatus

Status crl::multisense::details::impl::m_getPtpStatusReturnStatus
private

◆ m_getStatusReturnStatus

Status crl::multisense::details::impl::m_getStatusReturnStatus
private

◆ m_groundSurfaceSplineListeners

std::list<GroundSurfaceSplineListener*> crl::multisense::details::impl::m_groundSurfaceSplineListeners
private

◆ m_imageListeners

std::list<ImageListener*> crl::multisense::details::impl::m_imageListeners
private

◆ m_imageMetaCache

DepthCache<int64_t, wire::ImageMeta> crl::multisense::details::impl::m_imageMetaCache
private

◆ m_imuListeners

std::list<ImuListener*> crl::multisense::details::impl::m_imuListeners
private

◆ m_incomingBuffer

std::vector<uint8_t> crl::multisense::details::impl::m_incomingBuffer
private

◆ m_lastRxSeqId

int32_t crl::multisense::details::impl::m_lastRxSeqId
private

◆ m_lastUnexpectedSequenceId

int64_t crl::multisense::details::impl::m_lastUnexpectedSequenceId
private

◆ m_lidarListeners

std::list<LidarListener*> crl::multisense::details::impl::m_lidarListeners
private

◆ m_messages

MessageMap crl::multisense::details::impl::m_messages
private

◆ m_networkTimeSyncEnabled

bool crl::multisense::details::impl::m_networkTimeSyncEnabled
private

◆ m_ppsListeners

std::list<PpsListener*> crl::multisense::details::impl::m_ppsListeners
private

◆ m_ptpStatusResponseMessage

wire::PtpStatusResponse crl::multisense::details::impl::m_ptpStatusResponseMessage
private

◆ m_ptpTimeSyncEnabled

bool crl::multisense::details::impl::m_ptpTimeSyncEnabled
private

◆ m_rxLargeBufferPool

BufferPool crl::multisense::details::impl::m_rxLargeBufferPool
private

◆ m_rxLock

utility::Mutex crl::multisense::details::impl::m_rxLock
private

◆ m_rxSmallBufferPool

BufferPool crl::multisense::details::impl::m_rxSmallBufferPool
private

◆ m_rxThreadP

utility::Thread* crl::multisense::details::impl::m_rxThreadP
private

◆ m_secondaryAppListeners

std::list<SecondaryAppListener*> crl::multisense::details::impl::m_secondaryAppListeners
private

◆ m_secondaryAppMetaCache

DepthCache<int64_t, wire::SecondaryAppMetadata> crl::multisense::details::impl::m_secondaryAppMetaCache
private

◆ m_sensorAddress

struct sockaddr_in crl::multisense::details::impl::m_sensorAddress
private

◆ m_sensorMtu

int32_t crl::multisense::details::impl::m_sensorMtu
private

◆ m_sensorVersion

wire::VersionResponse crl::multisense::details::impl::m_sensorVersion
private

◆ m_serverSocket

socket_t crl::multisense::details::impl::m_serverSocket
private

◆ m_serverSocketPort

uint16_t crl::multisense::details::impl::m_serverSocketPort
private

◆ m_statisticsLock

utility::Mutex crl::multisense::details::impl::m_statisticsLock
private

◆ m_statusResponseMessage

wire::StatusResponse crl::multisense::details::impl::m_statusResponseMessage
private

◆ m_statusThreadP

utility::Thread* crl::multisense::details::impl::m_statusThreadP
private

◆ m_streamLock

utility::Mutex crl::multisense::details::impl::m_streamLock
private

◆ m_streamsEnabled

DataSource crl::multisense::details::impl::m_streamsEnabled
private

◆ m_threadsRunning

bool crl::multisense::details::impl::m_threadsRunning
private

◆ m_timeLock

utility::Mutex crl::multisense::details::impl::m_timeLock
private

◆ m_timeOffset

utility::TimeStamp crl::multisense::details::impl::m_timeOffset
private

◆ m_timeOffsetInit

bool crl::multisense::details::impl::m_timeOffsetInit
private

◆ m_txSeqId

uint16_t crl::multisense::details::impl::m_txSeqId
private

◆ m_udpAssemblerMap

UdpAssemblerMap crl::multisense::details::impl::m_udpAssemblerMap
private

◆ m_udpTrackerCache

DepthCache<int64_t, UdpTracker> crl::multisense::details::impl::m_udpTrackerCache
private

◆ m_unWrappedRxSeqId

int64_t crl::multisense::details::impl::m_unWrappedRxSeqId
private

◆ m_watch

MessageWatch crl::multisense::details::impl::m_watch
private

◆ MAX_BUFFER_ALLOCATION_RETRIES

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::MAX_BUFFER_ALLOCATION_RETRIES = 5
staticprivate

◆ MAX_DIRECTED_STREAMS

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::MAX_DIRECTED_STREAMS = 8
staticprivate

◆ MAX_MTU_SIZE

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::MAX_MTU_SIZE = 9000
staticprivate

◆ MAX_USER_APRILTAG_QUEUE_SIZE

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::MAX_USER_APRILTAG_QUEUE_SIZE = 8
staticprivate

◆ MAX_USER_COMPRESSED_IMAGE_QUEUE_SIZE

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::MAX_USER_COMPRESSED_IMAGE_QUEUE_SIZE = 8
staticprivate

◆ MAX_USER_GROUND_SURFACE_QUEUE_SIZE

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::MAX_USER_GROUND_SURFACE_QUEUE_SIZE = 8
staticprivate

◆ MAX_USER_IMAGE_QUEUE_SIZE

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::MAX_USER_IMAGE_QUEUE_SIZE = 8
staticprivate

◆ MAX_USER_IMU_QUEUE_SIZE

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::MAX_USER_IMU_QUEUE_SIZE = 64
staticprivate

◆ MAX_USER_LASER_QUEUE_SIZE

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::MAX_USER_LASER_QUEUE_SIZE = 8
staticprivate

◆ MAX_USER_PPS_QUEUE_SIZE

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::MAX_USER_PPS_QUEUE_SIZE = 2
staticprivate

◆ MAX_USER_SECONDARY_APP_QUEUE_SIZE

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::MAX_USER_SECONDARY_APP_QUEUE_SIZE = 8
staticprivate

◆ MIN_MTU_SIZE

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::MIN_MTU_SIZE = 1500
staticprivate

◆ RX_POOL_LARGE_BUFFER_COUNT

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::RX_POOL_LARGE_BUFFER_COUNT = 16
staticprivate

◆ RX_POOL_LARGE_BUFFER_SIZE

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::RX_POOL_LARGE_BUFFER_SIZE = (10 * (1024 * 1024))
staticprivate

◆ RX_POOL_SMALL_BUFFER_COUNT

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::RX_POOL_SMALL_BUFFER_COUNT = 256
staticprivate

◆ RX_POOL_SMALL_BUFFER_SIZE

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::RX_POOL_SMALL_BUFFER_SIZE = (8 * (1024))
staticprivate

◆ SECONDARY_APP_META_CACHE_DEPTH

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::SECONDARY_APP_META_CACHE_DEPTH = 4
staticprivate

◆ TIME_SYNC_OFFSET_DECAY

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::TIME_SYNC_OFFSET_DECAY = 8
staticprivate

◆ UDP_TRACKER_CACHE_DEPTH

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::UDP_TRACKER_CACHE_DEPTH = 4
staticprivate

The documentation for this class was generated from the following files:


multisense_lib
Author(s):
autogenerated on Thu Apr 17 2025 02:49:09