|
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 | getMotorPos (int32_t &mtu) |
|
virtual Status | getMtu (int32_t &mtu) |
|
virtual Status | getNetworkConfig (system::NetworkConfig &c) |
|
virtual Status | getPtpStatus (int64_t frameId, system::PtpStatus &ptpStatus) |
|
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 | ptpTimeSynchronization (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 () |
|
virtual | ~Channel () |
|
|
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::BufferStreamWriter & | findFreeBuffer (uint32_t messageLength) |
|
template<class WireT > |
void | getImageTime (const WireT *wire, uint32_t &seconds, uint32_t µSeconds) |
|
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 µseconds) |
|
template<typename T > |
void | toHeaderTime (T nanoSeconds, uint32_t &seconds, uint32_t µSeconds) const |
|
const int64_t & | unwrapSequenceId (uint16_t id) |
|
template<class T > |
Status | waitAck (const T &msg, wire::IdType id=MSG_ID(T::ID), const double &timeout=DEFAULT_ACK_TIMEOUT(), int32_t attempts=DEFAULT_ACK_ATTEMPTS) |
|
template<class T , class U > |
Status | waitData (const T &command, U &data, const double &timeout=DEFAULT_ACK_TIMEOUT(), int32_t attempts=DEFAULT_ACK_ATTEMPTS) |
|
Definition at line 84 of file channel.hh.
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
-
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 |
- Returns
- A crl::multisense::Status indicating if the callback registration succeeded or failed
Implements crl::multisense::Channel.
Definition at line 120 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
-
callback | A user defined lidar::Callback to send lidar data to |
userDataP | A 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 142 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
-
callback | A user defined lidar::Callback to send lidar data to |
userDataP | A 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
-
callback | A user defined lidar::Callback to send lidar data to |
userDataP | A pointer to arbitrary user data. |
- Returns
- A crl::multisense::Status indicating if the callback registration succeeded or failed
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.
- Parameters
-
bufferCount | The number of buffers returned by reference |
bufferSize | The 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 1343 of file public.cc.
Status crl::multisense::details::impl::networkTimeSynchronization |
( |
bool |
enabled | ) |
|
|
virtual |
Enable or disable local network-based time synchronization.
Each Channel will keep a continuously updating and filtered offset between the sensor's internal clock and the local system clock.
If enabled, all sensor timestamps will be reported in the local system clock frame, after the offset has been applied.
If disabled, all sensor timestamps will be reported in the frame of the sensor's clock, which is free-running from 0 seconds on power up.
The network-based time synchronization is enabled by default.
- Parameters
-
enabled | A 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 437 of file public.cc.
Status crl::multisense::details::impl::ptpTimeSynchronization |
( |
bool |
enabled | ) |
|
|
virtual |
Enable or disable PTP synchronization to an external PTP master. This subsumes the networkTimeSynchronization
Each Channel will keep a continuously updating and filtered offset between the sensor's internal clock and the local system clock.
If enabled, all sensor timestamps will be reported with the synchronized PTP time
If disabled, all sensor timestamps will be reported in the timebase determined by the current networkTimeSynchronization setting
The PTP-based time synchronization is disabled by default
- Parameters
-
enabled | A boolean flag which enables or disables PTP time synchronization |
- Returns
- A crl::multisense::Status indicating if the PTP time synchronization was successfully enabled or disabled
Implements crl::multisense::Channel.
Definition at line 446 of file public.cc.
void * crl::multisense::details::impl::reserveCallbackBuffer |
( |
| ) |
|
|
virtual |
Reserve image or lidar data within a isolated callback so it is available after the callback returns.
The memory buffer behind an image or lidar datum within an isolated callback may be reserved by the user. This is useful for performing data processing outside of the channel callback, without having to perform a memory copy of the sensor data.
The channel is guaranteed not to reuse the memory buffer until the user releases it back. Note that there are a limited amount of memory buffers, and care should be taken not to reserve them for too long.
- Returns
- A valid (non NULL) reference only when called within the context of an image or lidar callback.
Implements crl::multisense::Channel.
Definition at line 317 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
-
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 |
- Returns
- A crl::multisense::Status indicating if the new buffers were successfully received
Implements crl::multisense::Channel.
Definition at line 1355 of file public.cc.
Start a directed stream used to stream data to multiple 3rd parties.
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
-
stream | A 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 504 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.
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
-
streams | A 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 515 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
-
mask | The 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 464 of file public.cc.