#include <MultiSenseChannel.hh>
Static Public Member Functions | |
static Channel * | Create (const std::string &sensorAddress) |
static void | Destroy (Channel *instanceP) |
static const char * | statusString (Status status) |
Class which manages all communications with a MultiSense device.
Example code to instantiate and destroy a Channel
Definition at line 69 of file MultiSenseChannel.hh.
|
inlinevirtual |
Destructor.
Definition at line 98 of file MultiSenseChannel.hh.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure 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. |
Implemented in crl::multisense::details::impl, crl::multisense::details::impl, and crl::multisense::details::impl.
|
pure virtual |
Add a user defined callback attached to a pulse per-second (PPS) stream. This PPS stream corresponds to the pulse on the OPTO-TX line.
Each callback will create a unique internal thread dedicated to servicing the callback.
PPS data is queued per-callback. For each PPS callback the maximum queue depth is 2 pps events.
Adding multiple callbacks subscribing to the same PPS data is allowed.
PPS data is stored on the heap and released after returning from the callback
callback | A user defined pps::Callback to send PPS data to |
userDataP | A pointer to arbitrary user data. |
Implemented in crl::multisense::details::impl, crl::multisense::details::impl, and crl::multisense::details::impl.
|
pure virtual |
Add a user defined callback attached to the IMU stream.
Each callback will create a unique internal thread dedicated to servicing the callback.
IMU data is queued per-callback. For each IMU callback the maximum queue depth is 50 IMU messages.
Adding multiple callbacks subscribing to the same IMU data is allowed.
IMU data is stored on the heap and released after returning from the callback
Each imu::Header contains multiple IMU samples to reduce the number of UDP packets sent from the sensor.
callback | A user defined imu::Callback to send PPS data to |
userDataP | A pointer to arbitrary user data. |
Implemented in crl::multisense::details::impl, crl::multisense::details::impl, and crl::multisense::details::impl.
|
static |
Create a Channel instance, used to manage all communications with a sensor. The resulting pointer must be explicitly destroyed using the static member function Channel::Destroy().
sensorAddress | The device IPv4 address which can be a dotted-quad, or any hostname resolvable by gethostbyname(). |
return A pointer to a new Channel instance
Definition at line 583 of file channel.cc.
|
static |
Destroy a channel instance that was created using the static member function Channel::Create(). This operation should be done before exiting
instanceP | A pointer to a Channel instance to be destroyed |
Definition at line 596 of file channel.cc.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure virtual |
Get the API version of LibMultiSense.
version | The API version of LibMultiSense, returned by reference |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure virtual |
Get the current status of the device. Status is updated at 1Hz and should not be queried at a higher frequency.
status | The status of the attached device returned by reference |
Implemented in crl::multisense::details::impl.
|
pure 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() |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure virtual |
Get the external calibration associated with the MultiSense device
calibration | The external calibration object to query from non-volatile flash |
Implemented in crl::multisense::details::impl.
|
pure virtual |
Query the current camera calibration.
See image::Calibration for a usage example
c | A image calibration returned by reference from getImageCalibration() |
Implemented in crl::multisense::details::impl.
|
pure virtual |
Query the image configuration.
See image::Config for a usage example
c | The image configuration returned by reference from the query |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure virtual |
Query the current laser calibration.
See lidar::Calibration for a usage example
c | A laser calibration returned by reference from getLidarCalibration() |
Implemented in crl::multisense::details::impl.
|
pure virtual |
Query the on-board lighting configuration.
See lighting::Config for a usage example
c | A lighting configuration returned by reference |
Implemented in crl::multisense::details::impl.
|
pure virtual |
Get the status of the sensors attached to the external lighting platform
status | The status of the external lighting sensors returned by reference |
Implemented in crl::multisense::details::impl.
|
pure virtual |
Query the system-assigned local UDP port.
port | The local system UDP port returned by reference |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure virtual |
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.
c | The sensor calibration instance which will be returned by reference |
Implemented in crl::multisense::details::impl.
|
pure virtual |
Get the API version of the sensor firmware.
version | The API version of the sensor firmware, returned by reference |
Implemented in crl::multisense::details::impl.
|
pure virtual |
Query the current device network delay.
c | The network delay instance which will be returned by reference |
Implemented in crl::multisense::details::impl.
|
pure virtual |
Get the version info for the sensor and LibMultiSense.
See system::VersionInfo for a usage example.
v | The version information returned by reference |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure 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() |
Implemented in crl::multisense::details::impl.
|
pure virtual |
Unregister a user defined image::Callback. This stops the callback from receiving image data.
callback | The user defined imu::Callback to unregister |
Implemented in crl::multisense::details::impl, crl::multisense::details::impl, crl::multisense::details::impl, and crl::multisense::details::impl.
|
pure virtual |
Unregister a user defined lidar::Callback. This stops the callback from receiving lidar data
callback | The user defined image::Callback to unregister |
Implemented in crl::multisense::details::impl, crl::multisense::details::impl, crl::multisense::details::impl, and crl::multisense::details::impl.
|
pure virtual |
Unregister a user defined pps::Callback. This stops the callback from receiving pps data
callback | The user defined lidar::Callback to unregister |
Implemented in crl::multisense::details::impl, crl::multisense::details::impl, crl::multisense::details::impl, and crl::multisense::details::impl.
|
pure virtual |
Unregister a user defined imu::Callback. This stops the callback from receiving imu data
callback | The user defined pps::Callback to unregister |
Implemented in crl::multisense::details::impl, crl::multisense::details::impl, crl::multisense::details::impl, and crl::multisense::details::impl.
|
pure 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.
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure virtual |
Set the external calibration associated with the MultiSense device
calibration | The external calibration object to write to non-volatile flash |
Implemented in crl::multisense::details::impl.
|
pure virtual |
Set the current camera calibration.
See image::Calibration for a usage example
c | A new image calibration to send to the sensor |
Implemented in crl::multisense::details::impl.
|
pure virtual |
Set the image configuration.
See image::Config for a usage example
c | The new image configuration to send to the sensor |
Implemented in crl::multisense::details::impl.
|
pure 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. |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure virtual |
Set the current laser calibration.
See lidar::Calibration for a usage example
c | A new laser calibration to send to the sensor |
Implemented in crl::multisense::details::impl.
|
pure virtual |
Set the on-board lighting configuration.
See lighting::Config for a usage example
c | A lighting configuration to send to the sensor |
Implemented in crl::multisense::details::impl.
|
pure 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] |
Implemented in crl::multisense::details::impl.
|
pure virtual |
Set the current sensor's MTU.
mtu | The new MTU to configure the sensor with |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure virtual |
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
c | The sensor calibration instance to write to flash memory |
Implemented in crl::multisense::details::impl.
|
pure 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
c | The desired network delay in ms which will be returned by reference |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
static |
Helper method used to get a string describing a specific status code
status | A status code to convert to a string |
return A char* corresponding to the input status code
Definition at line 609 of file channel.cc.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.
|
pure 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 |
Implemented in crl::multisense::details::impl.