#include <channel.hh>
Definition at line 71 of file channel.hh.
typedef std::vector<utility::BufferStreamWriter*> crl::multisense::details::impl::BufferPool [private] |
Definition at line 303 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 172 of file channel.hh.
typedef std::map<wire::IdType, UdpAssembler> crl::multisense::details::impl::UdpAssemblerMap [private] |
Definition at line 316 of file channel.hh.
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.
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.
callback | A user defined image::Callback to which image data will be sent. |
imageSourceMask | The specific image types to stream to the user defined callback. Multiple image sources may be combined using the bitwise OR operator. |
userDataP | A 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 |
Implements crl::multisense::Channel.
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.
callback | A user defined lidar::Callback to send lidar data to |
userDataP | A pointer to arbitrary user data. |
Implements crl::multisense::Channel.
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.
callback | A user defined lidar::Callback to send lidar data to |
userDataP | A pointer to arbitrary user data. |
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.
callback | A user defined lidar::Callback to send lidar data to |
userDataP | A pointer to arbitrary user data. |
Implements crl::multisense::Channel.
void crl::multisense::details::impl::applySensorTimeOffset | ( | const double & | offset | ) | [private] |
Definition at line 461 of file channel.cc.
void crl::multisense::details::impl::bind | ( | ) | [private] |
Definition at line 244 of file channel.cc.
void crl::multisense::details::impl::cleanup | ( | ) | [private] |
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 192 of file channel.hh.
void crl::multisense::details::impl::dispatch | ( | utility::BufferStreamWriter & | buffer | ) | [private] |
Definition at line 159 of file dispatch.cc.
void crl::multisense::details::impl::dispatchImage | ( | utility::BufferStream & | buffer, |
image::Header & | header | ||
) | [private] |
Definition at line 97 of file dispatch.cc.
void crl::multisense::details::impl::dispatchImu | ( | imu::Header & | header | ) | [private] |
Definition at line 144 of file dispatch.cc.
void crl::multisense::details::impl::dispatchLidar | ( | utility::BufferStream & | buffer, |
lidar::Header & | header | ||
) | [private] |
Definition at line 113 of file dispatch.cc.
void crl::multisense::details::impl::dispatchPps | ( | pps::Header & | header | ) | [private] |
Definition at line 129 of file dispatch.cc.
Status crl::multisense::details::impl::doFlashOp | ( | const std::string & | filename, |
uint32_t | operation, | ||
uint32_t | region | ||
) | [private] |
void crl::multisense::details::impl::eraseFlashRegion | ( | uint32_t | region | ) | [private] |
utility::BufferStreamWriter & crl::multisense::details::impl::findFreeBuffer | ( | uint32_t | messageLength | ) | [private] |
Definition at line 500 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
file | The path to the file containing the new sensor bitstream |
Implements crl::multisense::Channel.
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
file | The path to the file containing the new sensor firmware |
Implements crl::multisense::Channel.
Status crl::multisense::details::impl::getApiVersion | ( | VersionType & | version | ) | [virtual] |
Get the API version of LibMultiSense.
version | The API version of LibMultiSense, returned by reference |
Implements crl::multisense::Channel.
Status crl::multisense::details::impl::getDeviceInfo | ( | system::DeviceInfo & | info | ) | [virtual] |
Query the current sensor's device information.
See system::DeviceInfo for a usage example
info | A DeviceInfo returned by reference containing the device information for the current sensor |
Implements crl::multisense::Channel.
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
m | A vector of possible device modes returned by reference from the sensor |
Implements crl::multisense::Channel.
Status crl::multisense::details::impl::getDirectedStreams | ( | std::vector< DirectedStream > & | streams | ) | [virtual] |
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.)
streams | A vector of DirectedStreams which is populated by getDirectedStreams() |
Implements crl::multisense::Channel.
Status crl::multisense::details::impl::getEnabledStreams | ( | DataSource & | mask | ) | [virtual] |
Get the current data streams which are enabled on the sensor.
mask | The current data streams which are enabled. These are returned by reference in mask |
Implements crl::multisense::Channel.
Status crl::multisense::details::impl::getImageCalibration | ( | image::Calibration & | c | ) | [virtual] |
Query the current camera calibration.
See image::Calibration for a usage example
c | A image calibration returned by reference from getImageCalibration() |
Implements crl::multisense::Channel.
Status crl::multisense::details::impl::getImageConfig | ( | image::Config & | c | ) | [virtual] |
Query the image configuration.
See image::Config for a usage example
c | The image configuration returned by reference from the query |
Implements crl::multisense::Channel.
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
frameId | The 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. |
histogram | A histogram returned by reference |
Implements crl::multisense::Channel.
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
samplesPerMessage | The 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. |
c | The current imu configuration returned by reference |
Implements crl::multisense::Channel.
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
maxSamplesPerMesage | The maximum number of IMU samples which can be aggregated in a single IMU message |
info | A vector of imu::Info returned by reference. This contains all the possible configurations for each IMU sensor |
Implements crl::multisense::Channel.
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.
bufferCount | The number of buffers returned by reference |
bufferSize | The size of a single buffer returned by reference |
Implements crl::multisense::Channel.
Status crl::multisense::details::impl::getLidarCalibration | ( | lidar::Calibration & | c | ) | [virtual] |
Query the current laser calibration.
See lidar::Calibration for a usage example
c | A laser calibration returned by reference from getLidarCalibration() |
Implements crl::multisense::Channel.
Status crl::multisense::details::impl::getLightingConfig | ( | lighting::Config & | c | ) | [virtual] |
Query the on-board lighting configuration.
See lighting::Config for a usage example
c | A lighting configuration returned by reference |
Implements crl::multisense::Channel.
Status crl::multisense::details::impl::getLocalUdpPort | ( | uint16_t & | port | ) | [virtual] |
Query the system-assigned local UDP port.
port | The local system UDP port returned by reference |
Implements crl::multisense::Channel.
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.
mtu | An int32_t returned by reference containing the current MTU setting |
Implements crl::multisense::Channel.
Status crl::multisense::details::impl::getNetworkConfig | ( | system::NetworkConfig & | c | ) | [virtual] |
Query the current sensor's network configuration.
See system::NetworkConfig for a usage example
c | A NetworkConfig returned by reference containing the current sensor's network configuration |
Implements crl::multisense::Channel.
Status crl::multisense::details::impl::getSensorVersion | ( | VersionType & | version | ) | [virtual] |
Get the API version of the sensor firmware.
version | The API version of the sensor firmware, returned by reference |
Implements crl::multisense::Channel.
impl::UdpAssembler crl::multisense::details::impl::getUdpAssembler | ( | const uint8_t * | udpDatagramP, |
uint32_t | length | ||
) | [private] |
Definition at line 474 of file dispatch.cc.
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.
v | The version information returned by reference |
Implements crl::multisense::Channel.
void crl::multisense::details::impl::handle | ( | ) | [private] |
Definition at line 568 of file dispatch.cc.
uint32_t crl::multisense::details::impl::hardwareApiToWire | ( | uint32_t | h | ) | [static, private] |
Definition at line 401 of file channel.cc.
uint32_t crl::multisense::details::impl::hardwareWireToApi | ( | uint32_t | h | ) | [static, private] |
Definition at line 416 of file channel.cc.
uint32_t crl::multisense::details::impl::imagerApiToWire | ( | uint32_t | h | ) | [static, private] |
Definition at line 431 of file channel.cc.
uint32_t crl::multisense::details::impl::imagerWireToApi | ( | uint32_t | h | ) | [static, private] |
Definition at line 444 of file channel.cc.
Status crl::multisense::details::impl::maxDirectedStreams | ( | uint32_t & | maximum | ) | [virtual] |
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.
maximum | The maximum number of DirectedStreams returned by reference |
Implements crl::multisense::Channel.
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.
enabled | A boolean flag which enables or disables network time synchronization |
Implements crl::multisense::Channel.
void crl::multisense::details::impl::programOrVerifyFlashRegion | ( | std::ifstream & | file, |
uint32_t | operation, | ||
uint32_t | region | ||
) | [private] |
void crl::multisense::details::impl::publish | ( | const T & | message | ) | [private] |
void crl::multisense::details::impl::publish | ( | const utility::BufferStreamWriter & | stream | ) | [private] |
Definition at line 318 of file channel.cc.
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.
referenceP | A pointer to the reserved data returned by reserveCallbackBuffer() |
Implements crl::multisense::Channel.
Status crl::multisense::details::impl::removeIsolatedCallback | ( | image::Callback | callback | ) | [virtual] |
Unregister a user defined image::Callback. This stops the callback from receiving image data.
callback | The user defined imu::Callback to unregister |
Implements crl::multisense::Channel.
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.
callback | The user defined imu::Callback to unregister |
Implements crl::multisense::Channel.
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.
callback | The user defined imu::Callback to unregister |
Implements crl::multisense::Channel.
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.
callback | The user defined imu::Callback to unregister |
Implements crl::multisense::Channel.
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.
Implements crl::multisense::Channel.
void * crl::multisense::details::impl::rxThread | ( | void * | userDataP | ) | [static, private] |
Definition at line 681 of file dispatch.cc.
double crl::multisense::details::impl::sensorToLocalTime | ( | const double & | sensorTime | ) | [private] |
Definition at line 479 of file channel.cc.
void crl::multisense::details::impl::sensorToLocalTime | ( | const double & | sensorTime, |
uint32_t & | seconds, | ||
uint32_t & | microseconds | ||
) | [private] |
Definition at line 488 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.
key | The secret key required to write new device information |
i | The new DeviceInfo to write to the sensor |
Implements crl::multisense::Channel.
Status crl::multisense::details::impl::setImageCalibration | ( | const image::Calibration & | c | ) | [virtual] |
Set the current camera calibration.
See image::Calibration for a usage example
c | A new image calibration to send to the sensor |
Implements crl::multisense::Channel.
Status crl::multisense::details::impl::setImageConfig | ( | const image::Config & | c | ) | [virtual] |
Set the image configuration.
See image::Config for a usage example
c | The new image configuration to send to the sensor |
Implements crl::multisense::Channel.
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.
storeSettingsInFlash | A boolean flag which indicated if the configuration saved in non-volatile flash on the sensor head |
samplesPerMessage | The 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 |
c | The imu configuration that will be sent to the sensor. |
Implements crl::multisense::Channel.
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
buffers | A vector of new buffers to use for image storage. All buffers in the vector must be of the same size |
bufferSize | The size of one buffer in the buffers vector |
Implements crl::multisense::Channel.
Status crl::multisense::details::impl::setLidarCalibration | ( | const lidar::Calibration & | c | ) | [virtual] |
Set the current laser calibration.
See lidar::Calibration for a usage example
c | A new laser calibration to send to the sensor |
Implements crl::multisense::Channel.
Status crl::multisense::details::impl::setLightingConfig | ( | const lighting::Config & | c | ) | [virtual] |
Set the on-board lighting configuration.
See lighting::Config for a usage example
c | A lighting configuration to send to the sensor |
Implements crl::multisense::Channel.
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.
rpm | The number of rotations per minute [-50.0, 50.0] |
Implements crl::multisense::Channel.
Status crl::multisense::details::impl::setMtu | ( | int32_t | mtu | ) | [virtual] |
Set the current sensor's MTU.
mtu | The new MTU to configure the sensor with |
Implements crl::multisense::Channel.
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
c | A new network configuration to send to the sensor |
Implements crl::multisense::Channel.
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
s | The new desired trigger source |
Implements crl::multisense::Channel.
wire::SourceType crl::multisense::details::impl::sourceApiToWire | ( | DataSource | mask | ) | [static, private] |
Definition at line 355 of file channel.cc.
DataSource crl::multisense::details::impl::sourceWireToApi | ( | wire::SourceType | mask | ) | [static, private] |
Definition at line 378 of file channel.cc.
Status crl::multisense::details::impl::startDirectedStream | ( | const DirectedStream & | stream | ) | [virtual] |
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.
stream | A DrirectedStream to either add or update setting of |
Implements crl::multisense::Channel.
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.
streams | A vector of DrirectedStream to either add or update setting of |
Implements crl::multisense::Channel.
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.
mask | The DataSources to start streaming. Multiple streams can be started by performing a bitwise OR operation with various crl::multisense::DataSource definitions |
Implements crl::multisense::Channel.
void * crl::multisense::details::impl::statusThread | ( | void * | userDataP | ) | [static, private] |
Definition at line 503 of file channel.cc.
Status crl::multisense::details::impl::stopDirectedStream | ( | const DirectedStream & | stream | ) | [virtual] |
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.)
stream | A DirectedStream to stop |
Implements crl::multisense::Channel.
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.
mask | The DataSources to stop streaming. Multiple streams can be stopped by performing a bitwise OR operation with various crl::multisense::DataSource definitions |
Implements crl::multisense::Channel.
const int64_t & crl::multisense::details::impl::unwrapSequenceId | ( | uint16_t | id | ) | [private] |
Definition at line 526 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
file | The path to the file containing the bitstream to check |
Implements crl::multisense::Channel.
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
file | The path to the file containing the firmware to check |
Implements crl::multisense::Channel.
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] |
Status crl::multisense::details::impl::waitData | ( | const T & | command, |
U & | data, | ||
const double & | timeout = DEFAULT_ACK_TIMEOUT() , |
||
int32_t | attempts = DEFAULT_ACK_ATTEMPTS |
||
) | [private] |
CRL_CONSTEXPR VersionType crl::multisense::details::impl::API_VERSION = 0x0305 [static, private] |
Definition at line 180 of file channel.hh.
CRL_CONSTEXPR uint32_t crl::multisense::details::impl::DEFAULT_ACK_ATTEMPTS = 5 [static, private] |
Definition at line 193 of file channel.hh.
CRL_CONSTEXPR uint16_t crl::multisense::details::impl::DEFAULT_SENSOR_TX_PORT = 9001 [static, private] |
Definition at line 186 of file channel.hh.
CRL_CONSTEXPR uint32_t crl::multisense::details::impl::IMAGE_META_CACHE_DEPTH = 20 [static, private] |
Definition at line 194 of file channel.hh.
Definition at line 323 of file channel.hh.
std::list<ImageListener*> crl::multisense::details::impl::m_imageListeners [private] |
Definition at line 349 of file channel.hh.
DepthCache<int64_t, wire::ImageMeta> crl::multisense::details::impl::m_imageMetaCache [private] |
Definition at line 311 of file channel.hh.
std::list<ImuListener*> crl::multisense::details::impl::m_imuListeners [private] |
Definition at line 352 of file channel.hh.
std::vector<uint8_t> crl::multisense::details::impl::m_incomingBuffer [private] |
Definition at line 286 of file channel.hh.
int32_t crl::multisense::details::impl::m_lastRxSeqId [private] |
Definition at line 292 of file channel.hh.
std::list<LidarListener*> crl::multisense::details::impl::m_lidarListeners [private] |
Definition at line 350 of file channel.hh.
Definition at line 362 of file channel.hh.
bool crl::multisense::details::impl::m_networkTimeSyncEnabled [private] |
Definition at line 375 of file channel.hh.
std::list<PpsListener*> crl::multisense::details::impl::m_ppsListeners [private] |
Definition at line 351 of file channel.hh.
Definition at line 305 of file channel.hh.
Definition at line 339 of file channel.hh.
Definition at line 306 of file channel.hh.
Definition at line 338 of file channel.hh.
struct sockaddr_in crl::multisense::details::impl::m_sensorAddress [private] |
Definition at line 276 of file channel.hh.
int32_t crl::multisense::details::impl::m_sensorMtu [private] |
Definition at line 281 of file channel.hh.
Definition at line 380 of file channel.hh.
int32_t crl::multisense::details::impl::m_serverSocket [private] |
Definition at line 270 of file channel.hh.
uint16_t crl::multisense::details::impl::m_serverSocketPort [private] |
Definition at line 271 of file channel.hh.
Definition at line 344 of file channel.hh.
Definition at line 328 of file channel.hh.
Definition at line 367 of file channel.hh.
bool crl::multisense::details::impl::m_threadsRunning [private] |
Definition at line 333 of file channel.hh.
Definition at line 372 of file channel.hh.
double crl::multisense::details::impl::m_timeOffset [private] |
Definition at line 374 of file channel.hh.
bool crl::multisense::details::impl::m_timeOffsetInit [private] |
Definition at line 373 of file channel.hh.
uint16_t crl::multisense::details::impl::m_txSeqId [private] |
Definition at line 291 of file channel.hh.
Definition at line 318 of file channel.hh.
DepthCache<int64_t, UdpTracker> crl::multisense::details::impl::m_udpTrackerCache [private] |
Definition at line 298 of file channel.hh.
int64_t crl::multisense::details::impl::m_unWrappedRxSeqId [private] |
Definition at line 293 of file channel.hh.
Definition at line 357 of file channel.hh.
CRL_CONSTEXPR uint32_t crl::multisense::details::impl::MAX_DIRECTED_STREAMS = 8 [static, private] |
Definition at line 218 of file channel.hh.
CRL_CONSTEXPR uint32_t crl::multisense::details::impl::MAX_MTU_SIZE = 9000 [static, private] |
Definition at line 185 of file channel.hh.
CRL_CONSTEXPR uint32_t crl::multisense::details::impl::MAX_USER_IMAGE_QUEUE_SIZE = 5 [static, private] |
Definition at line 205 of file channel.hh.
CRL_CONSTEXPR uint32_t crl::multisense::details::impl::MAX_USER_IMU_QUEUE_SIZE = 50 [static, private] |
Definition at line 213 of file channel.hh.
CRL_CONSTEXPR uint32_t crl::multisense::details::impl::MAX_USER_LASER_QUEUE_SIZE = 20 [static, private] |
Definition at line 206 of file channel.hh.
CRL_CONSTEXPR uint32_t crl::multisense::details::impl::MAX_USER_PPS_QUEUE_SIZE = 2 [static, private] |
Definition at line 212 of file channel.hh.
CRL_CONSTEXPR uint32_t crl::multisense::details::impl::RX_POOL_LARGE_BUFFER_COUNT = 50 [static, private] |
Definition at line 188 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 187 of file channel.hh.
CRL_CONSTEXPR uint32_t crl::multisense::details::impl::RX_POOL_SMALL_BUFFER_COUNT = 100 [static, private] |
Definition at line 190 of file channel.hh.
CRL_CONSTEXPR uint32_t crl::multisense::details::impl::RX_POOL_SMALL_BUFFER_SIZE = (10 * (1024)) [static, private] |
Definition at line 189 of file channel.hh.
CRL_CONSTEXPR uint32_t crl::multisense::details::impl::TIME_SYNC_OFFSET_DECAY = 8 [static, private] |
Definition at line 196 of file channel.hh.
CRL_CONSTEXPR uint32_t crl::multisense::details::impl::UDP_TRACKER_CACHE_DEPTH = 10 [static, private] |
Definition at line 195 of file channel.hh.