LibMultiSense
LibMultiSense Documentation
|
Class which manages all communications with a MultiSense device. More...
#include <MultiSenseChannel.hh>
Public Member Functions | |
virtual | ~Channel () |
Destructor. More... | |
virtual Status | addIsolatedCallback (image::Callback callback, DataSource imageSourceMask, void *userDataP=NULL)=0 |
Add a user defined callback attached to the image streams specified by imageSourceMask. More... | |
virtual Status | addIsolatedCallback (lidar::Callback callback, void *userDataP=NULL)=0 |
Add a user defined callback attached to a lidar stream. More... | |
virtual Status | addIsolatedCallback (pps::Callback callback, void *userDataP=NULL)=0 |
Add a user defined callback attached to a pulse per-second (PPS) stream. More... | |
virtual Status | addIsolatedCallback (imu::Callback callback, void *userDataP=NULL)=0 |
Add a user defined callback attached to the IMU stream. More... | |
virtual Status | addIsolatedCallback (compressed_image::Callback callback, DataSource imageSourceMask, void *userDataP=NULL)=0 |
Add a user defined callback attached to compressed image streams. More... | |
virtual Status | addIsolatedCallback (ground_surface::Callback callback, void *userDataP=NULL)=0 |
Add a user defined callback attached to the Ground Surface result stream. More... | |
virtual Status | addIsolatedCallback (apriltag::Callback callback, void *userDataP=NULL)=0 |
Add a user defined callback attached to the AprilTag result stream. More... | |
virtual Status | addIsolatedCallback (feature_detector::Callback callback, void *userDataP=NULL)=0 |
Add a user defined callback attached to the feature detector stream. More... | |
virtual Status | removeIsolatedCallback (image::Callback callback)=0 |
Unregister a user defined image::Callback. More... | |
virtual Status | removeIsolatedCallback (lidar::Callback callback)=0 |
Unregister a user defined lidar::Callback. More... | |
virtual Status | removeIsolatedCallback (pps::Callback callback)=0 |
Unregister a user defined pps::Callback. More... | |
virtual Status | removeIsolatedCallback (imu::Callback callback)=0 |
Unregister a user defined imu::Callback. More... | |
virtual Status | removeIsolatedCallback (compressed_image::Callback callback)=0 |
Unregister a user defined compressed_image::Callback. More... | |
virtual Status | removeIsolatedCallback (ground_surface::Callback callback)=0 |
Unregister a user defined ground_surface::Callback. More... | |
virtual Status | removeIsolatedCallback (apriltag::Callback callback)=0 |
Unregister a user defined apriltag::Callback. More... | |
virtual Status | removeIsolatedCallback (feature_detector::Callback callback)=0 |
Unregister a user defined feature_detector::Callback. More... | |
virtual void * | reserveCallbackBuffer ()=0 |
Reserve image or lidar data within a isolated callback so it is available after the callback returns. More... | |
virtual Status | releaseCallbackBuffer (void *referenceP)=0 |
Release image or lidar data reserved within a isolated callback. More... | |
virtual Status | networkTimeSynchronization (bool enabled)=0 |
Enable or disable local network-based time synchronization. More... | |
virtual Status | ptpTimeSynchronization (bool enabled)=0 |
Enable or disable PTP synchronization to an external PTP master. More... | |
virtual Status | startStreams (DataSource mask)=0 |
Start streaming various DataSources from the sensor. More... | |
virtual Status | stopStreams (DataSource mask)=0 |
Stop specific data streams from the sensor. More... | |
virtual Status | getEnabledStreams (DataSource &mask)=0 |
Get the current data streams which are enabled on the sensor. More... | |
virtual Status | setTriggerSource (TriggerSource s)=0 |
Set a new image trigger source. More... | |
virtual Status | setMotorSpeed (float rpm)=0 |
Set the laser spindle rotation speed. More... | |
virtual Status | getLightingConfig (lighting::Config &c)=0 |
Query the on-board lighting configuration. More... | |
virtual Status | setLightingConfig (const lighting::Config &c)=0 |
Set the on-board lighting configuration. More... | |
virtual Status | getLightingSensorStatus (lighting::SensorStatus &status)=0 |
Get the status of the sensors attached to the external lighting platform. More... | |
virtual Status | getSensorVersion (VersionType &version)=0 |
Get the API version of the sensor firmware. More... | |
virtual Status | getApiVersion (VersionType &version)=0 |
Get the API version of LibMultiSense. More... | |
virtual Status | getVersionInfo (system::VersionInfo &v)=0 |
Get the version info for the sensor and LibMultiSense. More... | |
virtual Status | getImageConfig (image::Config &c)=0 |
Query the image configuration. More... | |
virtual Status | setImageConfig (const image::Config &c)=0 |
Set the image configuration. More... | |
virtual Status | setRemoteHeadConfig (const image::RemoteHeadConfig &c)=0 |
Set the current Remote Head Config. More... | |
virtual Status | getRemoteHeadConfig (image::RemoteHeadConfig &c)=0 |
Set the current Remote Head Config. More... | |
virtual Status | getAuxImageConfig (image::AuxConfig &c)=0 |
Query the aux image configuration. More... | |
virtual Status | setAuxImageConfig (const image::AuxConfig &c)=0 |
Set the aux image configuration. More... | |
virtual Status | getImageCalibration (image::Calibration &c)=0 |
Query the current camera calibration. More... | |
virtual Status | setImageCalibration (const image::Calibration &c)=0 |
Set the current camera calibration. More... | |
virtual Status | getTransmitDelay (image::TransmitDelay &c)=0 |
Query the current device network delay. More... | |
virtual Status | setTransmitDelay (const image::TransmitDelay &c)=0 |
Set the devices network delay (in ms). More... | |
virtual Status | getPacketDelay (image::PacketDelay &c)=0 |
Query the current device udp packet delay. More... | |
virtual Status | setPacketDelay (const image::PacketDelay &c)=0 |
Enable the camera udp packet delay. More... | |
virtual Status | getLidarCalibration (lidar::Calibration &c)=0 |
Query the current laser calibration. More... | |
virtual Status | setLidarCalibration (const lidar::Calibration &c)=0 |
Set the current laser calibration. More... | |
virtual Status | getImageHistogram (int64_t frameId, image::Histogram &histogram)=0 |
Get the image histogram for the image corresponding to a specified frameId. More... | |
virtual Status | getPtpStatus (system::PtpStatus &ptpStatus)=0 |
Get PTP status information (updates at 1Hz) More... | |
virtual Status | getDeviceModes (std::vector< system::DeviceMode > &m)=0 |
Query the available sensor device modes. More... | |
virtual Status | getMtu (int32_t &mtu)=0 |
Query the current sensor's MTU configuration. More... | |
virtual Status | getMotorPos (int32_t &mtu)=0 |
Query the maxon or SLB motor for its current encoder position in microradians. More... | |
virtual Status | setMtu (int32_t mtu)=0 |
Set the current sensor's MTU. More... | |
virtual Status | getNetworkConfig (system::NetworkConfig &c)=0 |
Query the current sensor's network configuration. More... | |
virtual Status | setNetworkConfig (const system::NetworkConfig &c)=0 |
Set the current sensor's network configuration. More... | |
virtual Status | getDeviceInfo (system::DeviceInfo &info)=0 |
Query the current sensor's device information. More... | |
virtual Status | setDeviceInfo (const std::string &key, const system::DeviceInfo &i)=0 |
Set the current sensor's device information. More... | |
virtual Status | getDeviceStatus (system::StatusMessage &status)=0 |
Get the current status of the device. More... | |
virtual Status | getExternalCalibration (system::ExternalCalibration &calibration)=0 |
Get the external calibration associated with the MultiSense device. More... | |
virtual Status | setExternalCalibration (const system::ExternalCalibration &calibration)=0 |
Set the external calibration associated with the MultiSense device. More... | |
virtual Status | setGroundSurfaceParams (const system::GroundSurfaceParams ¶ms)=0 |
Set the ground surface parameters associated with the MultiSense device. More... | |
virtual Status | setApriltagParams (const system::ApriltagParams ¶ms)=0 |
Set the apriltag parameters associated with the MultiSense device. More... | |
virtual Status | setFeatureDetectorConfig (const system::FeatureDetectorConfig ¶ms)=0 |
Set the feature detector config associated with the MultiSense device. More... | |
virtual Status | getFeatureDetectorConfig (system::FeatureDetectorConfig ¶ms)=0 |
Get the feature detector parameters associated with the MultiSense device. More... | |
virtual Status | flashBitstream (const std::string &file)=0 |
Flash a new FPGA bitstream file to the sensor. More... | |
virtual Status | flashFirmware (const std::string &file)=0 |
Flash a new firmware file to the sensor. More... | |
virtual Status | verifyBitstream (const std::string &file)=0 |
Verify that the current bitstream in the sensor's flash is the same as the bitstream specified by file. More... | |
virtual Status | verifyFirmware (const std::string &file)=0 |
Verify the current firmware in the sensor's flash is the same as the firmware specified by file. More... | |
virtual Status | getImuInfo (uint32_t &maxSamplesPerMesage, std::vector< imu::Info > &info)=0 |
Query detailed information about the current sensor's IMU. More... | |
virtual Status | getImuConfig (uint32_t &samplesPerMessage, std::vector< imu::Config > &c)=0 |
Query the current IMU configuration. More... | |
virtual Status | setImuConfig (bool storeSettingsInFlash, uint32_t samplesPerMessage, const std::vector< imu::Config > &c)=0 |
Set a new IMU configuration. More... | |
virtual Status | getLargeBufferDetails (uint32_t &bufferCount, uint32_t &bufferSize)=0 |
Query the suggested number and size of the image buffers. More... | |
virtual Status | setLargeBuffers (const std::vector< uint8_t * > &buffers, uint32_t bufferSize)=0 |
Set user allocated large buffer. More... | |
virtual Status | getLocalUdpPort (uint16_t &port)=0 |
Query the system-assigned local UDP port. More... | |
virtual system::ChannelStatistics | getStats ()=0 |
Query the statistics of the channel object. More... | |
Static Public Member Functions | |
static Channel * | Create (const std::string &sensorAddress) |
Create a Channel instance, used to manage all communications with a sensor. More... | |
static Channel * | Create (const std::string &sensorAddress, const RemoteHeadChannel &cameraId) |
Create a Channel instance, used to manage all communications with a sensor. More... | |
static Channel * | Create (const std::string &sensorAddress, const std::string &interfaceName) |
static Channel * | Create (const std::string &sensorAddress, const RemoteHeadChannel &cameraId, const std::string &interfaceName) |
static void | Destroy (Channel *instanceP) |
Destroy a channel instance that was created using the static member function Channel::Create(). More... | |
static const char * | statusString (Status status) |
Helper method used to get a string describing a specific status code. More... | |
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 143 of file MultiSenseChannel.hh.
|
pure virtual |
Add a user defined callback attached to the AprilTag result stream.
Each callback will create a unique internal thread dedicated to servicing the callback.
AprilTag data is queued per-callback. For each AprilTag callback the maximum queue depth is 5 AprilTag messages.
Adding multiple callbacks subscribing to the same AprilTag data is allowed.
AprilTag data is stored on the heap and released after returning from the callback
callback | A user defined apriltag::Callback to send Ground Surface data to |
userDataP | A pointer to arbitrary user data. |
|
pure virtual |
Add a user defined callback attached to compressed image streams.
Each callback will create a unique internal thread dedicated to servicing the callback.
Adding multiple callbacks subscribing to the same compressed image data is allowed.
Compressed image data is queued per-callback. For each compressed image callback the maximum queue depth is 6 images.
callback | A user defined compressed_image::Callback to send compressed image data to |
userDataP | A pointer to arbitrary user data. |
|
pure virtual |
Add a user defined callback attached to the feature detector stream.
Each callback will create a unique internal thread dedicated to servicing the callback.
callback | A user defined feature_detector::Callback to send Ground Surface data to |
userDataP | A pointer to arbitrary user data. |
|
pure virtual |
Add a user defined callback attached to the Ground Surface result stream.
Each callback will create a unique internal thread dedicated to servicing the callback.
Ground Surface data is queued per-callback. For each Ground Surface callback the maximum queue depth is 5 Ground Surface messages.
Adding multiple callbacks subscribing to the same Ground Surface data is allowed.
Ground Surface data is stored on the heap and released after returning from the callback
callback | A user defined ground_surface::Callback to send Ground Surface data to |
userDataP | A pointer to arbitrary user data. |
|
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 |
|
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 IMU data to |
userDataP | A pointer to arbitrary user data. |
|
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. |
|
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. |
|
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
|
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(). |
cameraId | The ID of the remote camera to connect to. This is used for newer remote head based systems which have multiple stereo cameras connected to a single FPGA for stereo processing |
return A pointer to a new Channel instance
|
static |
sensorAddress | The device IPv4 address which can be a dotted-quad, or any hostname resolvable by gethostbyname(). |
cameraId | The ID of the remote camera to connect to. This is used for newer remote head based systems which have multiple stereo cameras connected to a single FPGA for stereo processing |
interfaceName | The name of the network interface to bind to use for this connection. Set using the socket option SO_BINDTODEVICE |
|
static |
sensorAddress | The device IPv4 address which can be a dotted-quad, or any hostname resolvable by gethostbyname(). |
interfaceName | The name of the network interface to bind to using the SO_BINDTODEVICE option |
|
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 |
|
pure virtual |
Flash a new FPGA bitstream file to the sensor.
WARNING: This member should not be used directly. Improper 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 |
|
pure virtual |
Flash a new firmware file to the sensor.
WARNING: This member should not be used directly. Improper 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 |
|
pure virtual |
Get the API version of LibMultiSense.
version | The API version of LibMultiSense, returned by reference |
|
pure virtual |
Query the aux image configuration.
See image::AuxConfig for a usage example
c | The aux image configuration returned by reference from the query |
|
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 |
|
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 |
|
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 |
|
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 |
|
pure virtual |
Get the external calibration associated with the MultiSense device.
calibration | The external calibration object to query from non-volatile flash |
|
pure virtual |
Get the feature detector parameters associated with the MultiSense device.
params | The feature detector parameters to send to the on-camera feature detector application |
|
pure virtual |
Query the current camera calibration.
See image::Calibration for a usage example
c | A image calibration returned by reference from getImageCalibration() |
|
pure virtual |
Query the image configuration.
See image::Config for a usage example
c | The image configuration returned by reference from the query |
|
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 |
|
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 |
|
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 |
|
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 |
|
pure virtual |
Query the current laser calibration.
See lidar::Calibration for a usage example
c | A laser calibration returned by reference from getLidarCalibration() |
|
pure virtual |
Query the on-board lighting configuration.
See lighting::Config for a usage example
c | A lighting configuration returned by reference |
|
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 |
|
pure virtual |
Query the system-assigned local UDP port.
port | The local system UDP port returned by reference |
|
pure virtual |
Query the maxon or SLB motor for its current encoder position in microradians.
mtu | An int32_t returned by reference containing the current motor encoder position in microradians |
|
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 |
|
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 |
|
pure virtual |
Query the current device udp packet delay.
c | The udp packet delay instance which will be returned by reference |
|
pure virtual |
Get PTP status information (updates at 1Hz)
ptpStatus | A ptpStatus obj returned by reference from the sensor |
|
pure virtual |
Set the current Remote Head Config.
c | A remoteHeadConfig returned by reference from getRemoteHeadConfig() |
|
pure virtual |
Get the API version of the sensor firmware.
version | The API version of the sensor firmware, returned by reference |
|
pure virtual |
Query the statistics of the channel object.
|
pure virtual |
Query the current device network delay.
c | The network delay instance which will be returned by reference |
|
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 |
|
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 |
|
pure virtual |
Enable or disable PTP synchronization to an external PTP master.
This subsumes the networkTimeSynchronization
Each Channel will keep a continuously updating and filtered offset between the sensor's internal clock and the local system clock.
If enabled, all sensor timestamps will be reported with the synchronized PTP time
If disabled, all sensor timestamps will be reported in the timebase determined by the current networkTimeSynchronization setting
The PTP-based time synchronization is disabled by default
enabled | A boolean flag which enables or disables PTP time synchronization |
|
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() |
|
pure virtual |
Unregister a user defined apriltag::Callback.
This stops the callback from receiving ground surface data
callback | The user defined apriltag::Callback to unregister |
|
pure virtual |
Unregister a user defined compressed_image::Callback.
This stops the callback from receiving imu data
callback | The user defined compressed_image::Callback to unregister |
|
pure virtual |
Unregister a user defined feature_detector::Callback.
This stops the callback from receiving feature data
callback | The user defined feature_detector::Callback to unregister |
|
pure virtual |
Unregister a user defined ground_surface::Callback.
This stops the callback from receiving ground surface data
callback | The user defined ground_surface::Callback to unregister |
|
pure virtual |
Unregister a user defined image::Callback.
This stops the callback from receiving image data.
callback | The user defined image::Callback to unregister |
|
pure virtual |
Unregister a user defined imu::Callback.
This stops the callback from receiving imu data
callback | The user defined imu::Callback to unregister |
|
pure virtual |
Unregister a user defined lidar::Callback.
This stops the callback from receiving lidar data
callback | The user defined lidar::Callback to unregister |
|
pure virtual |
Unregister a user defined pps::Callback.
This stops the callback from receiving pps data
callback | The user defined pps::Callback to unregister |
|
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.
|
pure virtual |
Set the apriltag parameters associated with the MultiSense device.
params | The apriltag parameters to send to the on-camera apriltag application |
|
pure virtual |
Set the aux image configuration.
See image::AuxConfig for a usage example
c | The new aux image configuration to send to the sensor |
|
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 |
|
pure virtual |
Set the external calibration associated with the MultiSense device.
calibration | The external calibration object to write to non-volatile flash |
|
pure virtual |
Set the feature detector config associated with the MultiSense device.
params | The feature detector parameters to send to the on-camera feature detector application |
|
pure virtual |
Set the ground surface parameters associated with the MultiSense device.
params | The ground surface parameters to send to the on-camera ground surface application |
|
pure virtual |
Set the current camera calibration.
See image::Calibration for a usage example
c | A new image calibration to send to the sensor |
|
pure virtual |
Set the image configuration.
See image::Config for a usage example
c | The new image configuration to send to the sensor |
|
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. |
|
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 |
|
pure virtual |
Set the current laser calibration.
See lidar::Calibration for a usage example
c | A new laser calibration to send to the sensor |
|
pure virtual |
Set the on-board lighting configuration.
See lighting::Config for a usage example
c | A lighting configuration to send to the sensor |
|
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] |
|
pure virtual |
Set the current sensor's MTU.
mtu | The new MTU to configure the sensor with |
|
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 |
|
pure virtual |
Enable the camera udp packet delay.
Enables a small delay approx 65us between udp packets for a large stream object. Recommended for clients with poor network bandwidth. If in doubt set to false (disable)
c | The packet delay enable field which will be returned by reference |
|
pure virtual |
Set the current Remote Head Config.
c | The new image remote head config to send to the sensor |
|
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 |
|
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 |
|
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 |
|
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
|
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 |
|
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 |
|
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 |