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

#include <channel.hh>

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

List of all members.

Classes

class  UdpTracker

Public Member Functions

virtual Status addIsolatedCallback (image::Callback callback, DataSource imageSourceMask, void *userDataP)
virtual Status addIsolatedCallback (lidar::Callback callback, void *userDataP)
virtual Status addIsolatedCallback (pps::Callback callback, void *userDataP)
virtual Status addIsolatedCallback (imu::Callback callback, void *userDataP)
virtual Status flashBitstream (const std::string &file)
virtual Status flashFirmware (const std::string &file)
virtual Status getApiVersion (VersionType &version)
virtual Status getDeviceInfo (system::DeviceInfo &info)
virtual Status getDeviceModes (std::vector< system::DeviceMode > &modes)
virtual Status getDeviceStatus (system::StatusMessage &status)
virtual Status getDirectedStreams (std::vector< DirectedStream > &streams)
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 getMtu (int32_t &mtu)
virtual Status getNetworkConfig (system::NetworkConfig &c)
virtual Status getSensorCalibration (image::SensorCalibration &c)
virtual Status getSensorVersion (VersionType &version)
virtual Status getTransmitDelay (image::TransmitDelay &c)
virtual Status getVersionInfo (system::VersionInfo &v)
 impl (const std::string &address)
virtual Status maxDirectedStreams (uint32_t &maximum)
virtual Status networkTimeSynchronization (bool enabled)
virtual Status releaseCallbackBuffer (void *referenceP)
virtual Status removeIsolatedCallback (image::Callback callback)
virtual Status removeIsolatedCallback (lidar::Callback callback)
virtual Status removeIsolatedCallback (pps::Callback callback)
virtual Status removeIsolatedCallback (imu::Callback callback)
virtual void * reserveCallbackBuffer ()
virtual Status setDeviceInfo (const std::string &key, const system::DeviceInfo &i)
virtual Status setExternalCalibration (const system::ExternalCalibration &calibration)
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 setSensorCalibration (const image::SensorCalibration &c)
virtual Status setTransmitDelay (const image::TransmitDelay &c)
virtual Status setTriggerSource (TriggerSource s)
virtual Status startDirectedStream (const DirectedStream &stream)
virtual Status startDirectedStreams (const std::vector< DirectedStream > &streams)
virtual Status startStreams (DataSource mask)
virtual Status stopDirectedStream (const DirectedStream &stream)
virtual Status stopStreams (DataSource mask)
virtual Status verifyBitstream (const std::string &file)
virtual Status verifyFirmware (const std::string &file)
 ~impl ()

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,
UdpAssembler
UdpAssemblerMap

Private Member Functions

void applySensorTimeOffset (const double &offset)
void bind ()
void cleanup ()
void dispatch (utility::BufferStreamWriter &buffer)
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)
Status doFlashOp (const std::string &filename, uint32_t operation, uint32_t region)
void eraseFlashRegion (uint32_t region)
utility::BufferStreamWriterfindFreeBuffer (uint32_t messageLength)
UdpAssembler getUdpAssembler (const uint8_t *udpDatagramP, uint32_t length)
void handle ()
void programOrVerifyFlashRegion (std::ifstream &file, uint32_t operation, uint32_t region)
template<class T >
void publish (const T &message)
void publish (const utility::BufferStreamWriter &stream)
double sensorToLocalTime (const double &sensorTime)
void sensorToLocalTime (const double &sensorTime, uint32_t &seconds, uint32_t &microseconds)
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 CRL_CONSTEXPR 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

utility::Mutex m_dispatchLock
std::list< ImageListener * > m_imageListeners
DepthCache< int64_t,
wire::ImageMeta
m_imageMetaCache
std::list< ImuListener * > m_imuListeners
std::vector< uint8_t > m_incomingBuffer
int32_t m_lastRxSeqId
std::list< LidarListener * > m_lidarListeners
MessageMap m_messages
bool m_networkTimeSyncEnabled
std::list< PpsListener * > m_ppsListeners
BufferPool m_rxLargeBufferPool
utility::Mutex m_rxLock
BufferPool m_rxSmallBufferPool
utility::Threadm_rxThreadP
struct sockaddr_in m_sensorAddress
int32_t m_sensorMtu
wire::VersionResponse m_sensorVersion
int32_t m_serverSocket
uint16_t m_serverSocketPort
wire::StatusResponse m_statusResponseMessage
utility::Threadm_statusThreadP
utility::Mutex m_streamLock
DataSource m_streamsEnabled
bool m_threadsRunning
utility::Mutex m_timeLock
double 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 = 0x0308
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 = 20
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_IMAGE_QUEUE_SIZE = 5
static CRL_CONSTEXPR uint32_t MAX_USER_IMU_QUEUE_SIZE = 50
static CRL_CONSTEXPR uint32_t MAX_USER_LASER_QUEUE_SIZE = 20
static CRL_CONSTEXPR uint32_t MAX_USER_PPS_QUEUE_SIZE = 2
static CRL_CONSTEXPR uint32_t RX_POOL_LARGE_BUFFER_COUNT = 50
static CRL_CONSTEXPR uint32_t RX_POOL_LARGE_BUFFER_SIZE = (10 * (1024 * 1024))
static CRL_CONSTEXPR uint32_t RX_POOL_SMALL_BUFFER_COUNT = 100
static CRL_CONSTEXPR uint32_t RX_POOL_SMALL_BUFFER_SIZE = (10 * (1024))
static CRL_CONSTEXPR uint32_t TIME_SYNC_OFFSET_DECAY = 8
static CRL_CONSTEXPR uint32_t UDP_TRACKER_CACHE_DEPTH = 10

Detailed Description

Definition at line 72 of file channel.hh.


Member Typedef Documentation

Definition at line 317 of file channel.hh.

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

Definition at line 186 of file channel.hh.

Definition at line 330 of file channel.hh.


Constructor & Destructor Documentation

crl::multisense::details::impl::impl ( const std::string &  address)

Definition at line 63 of file channel.cc.

Definition at line 235 of file channel.cc.


Member Function Documentation

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 116 of file public.cc.

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 138 of file public.cc.

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.

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.

void crl::multisense::details::impl::applySensorTimeOffset ( const double &  offset) [private]

Definition at line 463 of file channel.cc.

Definition at line 244 of file channel.cc.

Definition at line 184 of file channel.cc.

static CRL_CONSTEXPR double crl::multisense::details::impl::DEFAULT_ACK_TIMEOUT ( ) [inline, static, private]

Definition at line 206 of file channel.hh.

Definition at line 163 of file dispatch.cc.

Definition at line 102 of file dispatch.cc.

Definition at line 148 of file dispatch.cc.

Definition at line 118 of file dispatch.cc.

Definition at line 133 of file dispatch.cc.

Status crl::multisense::details::impl::doFlashOp ( const std::string &  filename,
uint32_t  operation,
uint32_t  region 
) [private]

Definition at line 184 of file flash.cc.

void crl::multisense::details::impl::eraseFlashRegion ( uint32_t  region) [private]

Definition at line 51 of file flash.cc.

Definition at line 517 of file dispatch.cc.

Status crl::multisense::details::impl::flashBitstream ( const std::string &  file) [virtual]

Flash a new FPGA bitstream file to the sensor.

WARNING: This member should not be used directly. Inproper usage can result in the sensor being inoperable. Use the MultiSenseUpdater script to update the sensor's firmware/bitstream

Parameters:
fileThe path to the file containing the new sensor bitstream
Returns:
A crl::multisense::Status indicating if the new bitstream was successfully flashed

Implements crl::multisense::Channel.

Definition at line 1111 of file public.cc.

Status crl::multisense::details::impl::flashFirmware ( const std::string &  file) [virtual]

Flash a new firmware file to the sensor.

WARNING: This member should not be used directly. Inproper usage can result in the sensor being inoperable. Use the MultiSenseUpdater script to update the sensor's firmware/bitstream

Parameters:
fileThe path to the file containing the new sensor firmware
Returns:
A crl::multisense::Status indicating if the new firmware was successfully flashed

Implements crl::multisense::Channel.

Definition at line 1121 of file public.cc.

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 612 of file public.cc.

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 957 of file public.cc.

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 865 of file public.cc.

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 1001 of file public.cc.

Get the current list of active streams.

NOTE: Directed streams are currently only supported by CRL's Monocular IP Camera. MultiSense S* hardware variations are not supported (the following functions will return the 'Status_Unknown' error code.)

Parameters:
streamsA vector of DirectedStreams which is populated by getDirectedStreams()
Returns:
A crl::multisense::Status indicating if the DirectedStream query succeeded

Implements crl::multisense::Channel.

Definition at line 485 of file public.cc.

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 436 of file public.cc.

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 1034 of file public.cc.

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 735 of file public.cc.

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 637 of file public.cc.

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 363 of file public.cc.

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 1191 of file public.cc.

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

Query detailed information about the current sensor's IMU.

See imu::Info for a usage example

Parameters:
maxSamplesPerMesageThe 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 1151 of file public.cc.

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 1243 of file public.cc.

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 835 of file public.cc.

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 548 of file public.cc.

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 586 of file public.cc.

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 1297 of file public.cc.

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 919 of file public.cc.

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 940 of file public.cc.

Query the current device imager calibration. This is the DC imager gain and black level offset used to match the left and right imagers to improve stereo matching performance.

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

Implements crl::multisense::Channel.

Definition at line 779 of file public.cc.

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 603 of file public.cc.

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 808 of file public.cc.

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

Definition at line 491 of file dispatch.cc.

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 621 of file public.cc.

Definition at line 585 of file dispatch.cc.

uint32_t crl::multisense::details::impl::hardwareApiToWire ( uint32_t  h) [static, private]

Definition at line 403 of file channel.cc.

uint32_t crl::multisense::details::impl::hardwareWireToApi ( uint32_t  h) [static, private]

Definition at line 418 of file channel.cc.

uint32_t crl::multisense::details::impl::imagerApiToWire ( uint32_t  h) [static, private]

Definition at line 433 of file channel.cc.

uint32_t crl::multisense::details::impl::imagerWireToApi ( uint32_t  h) [static, private]

Definition at line 446 of file channel.cc.

Query the number of simultaneous parties which can be supported.

NOTE: Directed streams are currently only supported by CRL's Monocular IP Camera. MultiSense S* hardware variations are not supported (the following functions will return the 'Status_Unknown' error code.)

If the number of maximum directed streams has already been achieved, startDirectedStream() will return an error code.

Parameters:
maximumThe maximum number of DirectedStreams returned by reference
Returns:
A crl::multisense::Status indicating if the query succeeded

Implements crl::multisense::Channel.

Definition at line 505 of file public.cc.

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 399 of file public.cc.

void crl::multisense::details::impl::programOrVerifyFlashRegion ( std::ifstream &  file,
uint32_t  operation,
uint32_t  region 
) [private]

Definition at line 115 of file flash.cc.

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

Definition at line 50 of file query.hh.

Definition at line 318 of file channel.cc.

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 337 of file public.cc.

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

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

Implements crl::multisense::Channel.

Definition at line 201 of file public.cc.

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

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

Implements crl::multisense::Channel.

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

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

Implements crl::multisense::Channel.

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

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

Implements crl::multisense::Channel.

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 313 of file public.cc.

void * crl::multisense::details::impl::rxThread ( void *  userDataP) [static, private]

Definition at line 698 of file dispatch.cc.

double crl::multisense::details::impl::sensorToLocalTime ( const double &  sensorTime) [private]

Definition at line 481 of file channel.cc.

void crl::multisense::details::impl::sensorToLocalTime ( const double &  sensorTime,
uint32_t &  seconds,
uint32_t &  microseconds 
) [private]

Definition at line 490 of file channel.cc.

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 1071 of file public.cc.

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 1052 of file public.cc.

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 759 of file public.cc.

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 698 of file public.cc.

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 1218 of file public.cc.

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 1255 of file public.cc.

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 852 of file public.cc.

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 569 of file public.cc.

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 540 of file public.cc.

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 894 of file public.cc.

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 933 of file public.cc.

Set the devices imager calibration. This is used to adjust the DC imager gains and the black level offsets so that both imagers match one another. This calibration is stored in flash and only needs to be set once

Parameters:
cThe sensor calibration instance to write to flash memory
Returns:
A crl::multisense::Status indicating if the imager calibration was successfully received by the sensor

Implements crl::multisense::Channel.

Definition at line 795 of file public.cc.

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 823 of file public.cc.

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 514 of file public.cc.

Definition at line 355 of file channel.cc.

Definition at line 379 of file channel.cc.

Start a directed stream used to stream data to multiple 3rd parties.

NOTE: Directed streams are currently only supported by CRL's Monocular IP Camera. MultiSense S* hardware variations are not supported (the following functions will return the 'Status_Unknown' error code.)

Secondary stream control. In addition to the primary stream control above, a set of streams may be directed to a 3rd party (or multiple 3rd parties), where a 3rd party is uniquely defined as an IP address / UDP port pair.

The number of simulataneous parties supported can be queried via maxDirectedStreams(). If the number of maximum directed streams has already been achieved, startDirectedStream() will return an error code.

If the stream address/port combination already exists as a streaming destination, then startDirectedStream() will update the data source mask and FPS decimation.

Parameters:
streamA DrirectedStream to either add or update setting of
Returns:
A crl::multisense::Status indicating if the DirectedStream was successfully started

Implements crl::multisense::Channel.

Definition at line 448 of file public.cc.

Status crl::multisense::details::impl::startDirectedStreams ( const std::vector< DirectedStream > &  streams) [virtual]

Start several directed streams used to stream data to multiple 3rd parties.

NOTE: Directed streams are currently only supported by CRL's Monocular IP Camera. MultiSense S* hardware variations are not supported (the following functions will return the 'Status_Unknown' error code.)

Secondary stream control. In addition to the primary stream control above, a set of streams may be directed to a 3rd party (or multiple 3rd parties), where a 3rd party is uniquely defined as an IP address / UDP port pair.

The number of simulataneous parties supported can be queried via maxDirectedStreams(). If the number of maximum directed streams has already been achieved, startDirectedStream() will return an error code.

If the stream address/port combination already exists as a streaming destination, then startDirectedStream() will update the data source mask and FPS decimation.

Parameters:
streamsA vector of DrirectedStream to either add or update setting of
Returns:
A crl::multisense::Status indicating if the DirectedStream was successfully started

Implements crl::multisense::Channel.

Definition at line 459 of file public.cc.

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 408 of file public.cc.

void * crl::multisense::details::impl::statusThread ( void *  userDataP) [static, private]

Definition at line 505 of file channel.cc.

Stop a specific directed stream.

NOTE: Directed streams are currently only supported by CRL's Monocular IP Camera. MultiSense S* hardware variations are not supported (the following functions will return the 'Status_Unknown' error code.)

Parameters:
streamA DirectedStream to stop
Returns:
A crl::multisense::Status indicating if the DirectedStream was successfully stopped

Implements crl::multisense::Channel.

Definition at line 474 of file public.cc.

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 422 of file public.cc.

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

Definition at line 543 of file dispatch.cc.

Status crl::multisense::details::impl::verifyBitstream ( const std::string &  file) [virtual]

Verify that the current bitstream in the sensor's flash is the same as the bitstream specified by file

Parameters:
fileThe path to the file containing the bitstream to check
Returns:
A crl::multisense::Status indicating if the bitstream specified by file is loaded in the sensor's non-volatile flash memory

Implements crl::multisense::Channel.

Definition at line 1131 of file public.cc.

Status crl::multisense::details::impl::verifyFirmware ( const std::string &  file) [virtual]

Verify the current firmware in the sensor's flash is the same as the firmware specified by file

Parameters:
fileThe path to the file containing the firmware to check
Returns:
A crl::multisense::Status indicating if the firmware specified by file is loaded in the sensor's non-volatile flash memory

Implements crl::multisense::Channel.

Definition at line 1141 of file public.cc.

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.

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

Definition at line 194 of file channel.hh.

Definition at line 207 of file channel.hh.

Definition at line 200 of file channel.hh.

Definition at line 208 of file channel.hh.

Definition at line 337 of file channel.hh.

Definition at line 363 of file channel.hh.

Definition at line 325 of file channel.hh.

Definition at line 366 of file channel.hh.

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

Definition at line 300 of file channel.hh.

Definition at line 306 of file channel.hh.

Definition at line 364 of file channel.hh.

Definition at line 376 of file channel.hh.

Definition at line 389 of file channel.hh.

Definition at line 365 of file channel.hh.

Definition at line 319 of file channel.hh.

Definition at line 353 of file channel.hh.

Definition at line 320 of file channel.hh.

Definition at line 352 of file channel.hh.

Definition at line 290 of file channel.hh.

Definition at line 295 of file channel.hh.

Definition at line 394 of file channel.hh.

Definition at line 284 of file channel.hh.

Definition at line 285 of file channel.hh.

Definition at line 399 of file channel.hh.

Definition at line 358 of file channel.hh.

Definition at line 342 of file channel.hh.

Definition at line 381 of file channel.hh.

Definition at line 347 of file channel.hh.

Definition at line 386 of file channel.hh.

Definition at line 388 of file channel.hh.

Definition at line 387 of file channel.hh.

Definition at line 305 of file channel.hh.

Definition at line 332 of file channel.hh.

Definition at line 312 of file channel.hh.

Definition at line 307 of file channel.hh.

Definition at line 371 of file channel.hh.

Definition at line 232 of file channel.hh.

Definition at line 199 of file channel.hh.

Definition at line 219 of file channel.hh.

Definition at line 227 of file channel.hh.

Definition at line 220 of file channel.hh.

Definition at line 226 of file channel.hh.

Definition at line 202 of file channel.hh.

CRL_CONSTEXPR uint32_t crl::multisense::details::impl::RX_POOL_LARGE_BUFFER_SIZE = (10 * (1024 * 1024)) [static, private]

Definition at line 201 of file channel.hh.

Definition at line 204 of file channel.hh.

Definition at line 203 of file channel.hh.

Definition at line 210 of file channel.hh.

Definition at line 209 of file channel.hh.


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


multisense_lib
Author(s):
autogenerated on Mon Oct 9 2017 03:06:22