Public Member Functions | Private Member Functions | Private Attributes | List of all members
multisense::legacy::LegacyChannel Class Reference

#include <channel.hh>

Inheritance diagram for multisense::legacy::LegacyChannel:
Inheritance graph
[legend]

Public Member Functions

void add_image_frame_callback (std::function< void(const ImageFrame &)> callback) final override
 Add a image frame callback to get serviced inline with the receipt of a new frame. Only a single image frame callback can be added to the channel NOTE: Perform minimal work in this callback, and ideally copy the lightweight ImageFrame object out to another processing thread. More...
 
void add_imu_frame_callback (std::function< void(const ImuFrame &)> callback) final override
 Add a imu frame callback to get serviced inline with the receipt of a new frame. Only a single imu frame callback can be added to the channel NOTE: Perform minimal work in this callback, and ideally copy the lightweight ImuFrame object out to another processing thread. More...
 
Status connect (const Config &config) final override
 Initialize the connection to the camera. More...
 
void disconnect () final override
 Disconnect from the camera. More...
 
StereoCalibration get_calibration () final override
 Get the current stereo calibration. The output calibration will correspond to the full-resolution operating mode of the camera. More...
 
MultiSenseConfig get_config () final override
 Get the current MultiSense configuration. More...
 
MultiSenseInfo get_info () final override
 Get the device info associated with the camera. More...
 
std::optional< ImageFrameget_next_image_frame () final override
 A blocking call that waits for one image frame from the camera. More...
 
std::optional< ImuFrameget_next_imu_frame () final override
 A blocking call that waits for one imu frame from the camera. More...
 
std::optional< MultiSenseStatusget_system_status () final override
 Query the current MultiSense status. More...
 
 LegacyChannel (const Config &config)
 
Status set_calibration (const StereoCalibration &calibration) final override
 Set the current stereo calibration. The calibration is expected to be or the full-resolution operating mode of the camera. More...
 
Status set_config (const MultiSenseConfig &config) final override
 Get set the current MultiSense configuration. More...
 
Status set_device_info (const MultiSenseInfo::DeviceInfo &device_info, const std::string &key) final override
 Set the camera's device info. This setting is protected via a key since invalid values in the device info can result in internal camera failures. More...
 
Status set_network_config (const MultiSenseInfo::NetworkInfo &config, const std::optional< std::string > &broadcast_interface) final override
 Update the network configuration of the MultiSense. This will require a hardware reboot of the MultiSense after it's been successfully applied. More...
 
Status start_streams (const std::vector< DataSource > &sources) final override
 Start a collection of image streams. Repeated calls to this function will not implicitly stop the previously started streams. For example if a user started a left_raw stream in one call and a disparity stream in a second call, both streams would be active until stop_streams is called for either. More...
 
Status stop_streams (const std::vector< DataSource > &sources) final override
 Stop a collection of streams. More...
 
virtual ~LegacyChannel ()
 
- Public Member Functions inherited from multisense::Channel
 Channel ()=default
 
 Channel (Channel &&) noexcept=default
 
 Channel (const Channel &)=delete
 
Channeloperator= (Channel &&) noexcept=default
 
Channeloperator= (const Channel &)=delete
 
virtual ~Channel ()=default
 

Private Member Functions

void disparity_callback (std::shared_ptr< const std::vector< uint8_t >> data)
 Disparity callback used to internally receive images sent from the MultiSense. More...
 
void handle_and_dispatch (Image image, int64_t frame_id, const StereoCalibration &calibration, const TimeT &capture_time, const TimeT &ptp_capture_time)
 Handle internal process, and potentially dispatch a image. More...
 
void image_callback (std::shared_ptr< const std::vector< uint8_t >> data)
 Image callback used to internally receive images sent from the MultiSense. More...
 
void image_meta_callback (std::shared_ptr< const std::vector< uint8_t >> data)
 Image meta callback used to internally receive images sent from the MultiSense. More...
 
void imu_callback (std::shared_ptr< const std::vector< uint8_t >> data)
 Disparity callback used to internally receive images sent from the MultiSense. More...
 
std::optional< StereoCalibrationquery_calibration ()
 Query the calibration from the camera. More...
 
std::optional< MultiSenseConfigquery_configuration (bool has_aux_camera, bool has_imu, bool ptp_enabled)
 Query the full configuration. More...
 
std::optional< MultiSenseInfo::DeviceInfoquery_device_info ()
 Query the device_info from the camera. More...
 
std::optional< MultiSenseInfoquery_info ()
 Query the MultiSense Info. More...
 
Status set_mtu (const std::optional< uint16_t > &mtu)
 Set the MTU. If the MTU is invalid, try and find the best MTU via a basic search. More...
 
Status set_mtu (uint16_t mtu)
 Try and set the MTU. More...
 

Private Attributes

std::set< DataSourcem_active_streams {}
 The current set of active data streams the MultiSense is transmitting. More...
 
std::shared_ptr< BufferPoolm_buffer_pool = nullptr
 A collection of buffers to avoid dynamic allocation for incoming messages. More...
 
StereoCalibration m_calibration {}
 The current cached calibration stored here for convenience. More...
 
Config m_config {}
 Channel config. More...
 
std::atomic_bool m_connected = false
 Atomic flag to determine if we are connected to an active camera. More...
 
ImuFrame m_current_imu_frame {}
 A cache of IMU samples which will be internally filled until it reaches the sample threshold for dispatch. More...
 
std::atomic_uint16_t m_current_mtu = 1500
 The current MTU the camera is operating with. More...
 
std::map< int64_t, ImageFramem_frame_buffer {}
 A cache of image frames associated with a specific frame id. More...
 
std::mutex m_image_callback_mutex {}
 Internal mutex used to handle user callbacks for image data. More...
 
FrameNotifier< ImageFramem_image_frame_notifier {}
 Notifier used to service the get_next_image_frame member function. More...
 
std::mutex m_imu_callback_mutex {}
 Internal mutex used to handle user callbacks imu data. More...
 
FrameNotifier< ImuFramem_imu_frame_notifier {}
 Notifier used to service the get_next_imu_frame member function. More...
 
ImuSampleScalars m_imu_scalars {}
 Scalars to convert imu samples from wire units to standard LibMultiSense units. More...
 
MultiSenseInfo m_info {}
 The current cached device info stored here for convenience. More...
 
std::atomic_uint32_t m_max_batched_imu_messages = 0
 The max number of IMU messages which can be batched over the wire. More...
 
MessageAssembler m_message_assembler
 Helper object to assemble raw UDP packets into complete MultiSense wire messages. More...
 
std::map< int64_t, crl::multisense::details::wire::ImageMetam_meta_cache {}
 A cache of image metadata associated with a specific frame id. More...
 
MultiSenseConfig m_multisense_config {}
 The current cached MultiSense configuration stored for convenience. More...
 
std::mutex m_mutex {}
 Internal mutex used to handle updates from users. More...
 
NetworkSocket m_socket {}
 Active network socket for receiving and transmitting data. More...
 
std::atomic_uint16_t m_transmit_id = 0
 Monotonically increasing internal id used to uniquely identify requests sent to the camera. More...
 
std::unique_ptr< UdpReceiverm_udp_receiver = nullptr
 Helper object to receive UDP traffic. Internally manages a receive thread. More...
 
std::function< void(const ImageFrame &)> m_user_image_frame_callback {}
 The currently active image frame user callback. More...
 
std::function< void(const ImuFrame &)> m_user_imu_frame_callback {}
 The currently active imu frame user callback. More...
 

Additional Inherited Members

- Public Types inherited from multisense::Channel
enum  ChannelImplementation { ChannelImplementation::LEGACY }
 Identifiers for the different Channel implementations. Used for selecting a implementation at runtime. More...
 
- Static Public Member Functions inherited from multisense::Channel
static std::unique_ptr< Channelcreate (const Config &config, const ChannelImplementation &impl=ChannelImplementation::LEGACY)
 Factory create function which allows for switching between different channel implementations. More...
 

Detailed Description

Definition at line 122 of file LibMultiSense/include/details/legacy/channel.hh.

Constructor & Destructor Documentation

◆ LegacyChannel()

multisense::legacy::LegacyChannel::LegacyChannel ( const Config config)
explicit

Definition at line 120 of file LibMultiSense/details/legacy/channel.cc.

◆ ~LegacyChannel()

multisense::legacy::LegacyChannel::~LegacyChannel ( )
virtual

Definition at line 134 of file LibMultiSense/details/legacy/channel.cc.

Member Function Documentation

◆ add_image_frame_callback()

void multisense::legacy::LegacyChannel::add_image_frame_callback ( std::function< void(const ImageFrame &)>  callback)
finaloverridevirtual

Add a image frame callback to get serviced inline with the receipt of a new frame. Only a single image frame callback can be added to the channel NOTE: Perform minimal work in this callback, and ideally copy the lightweight ImageFrame object out to another processing thread.

Implements multisense::Channel.

Definition at line 217 of file LibMultiSense/details/legacy/channel.cc.

◆ add_imu_frame_callback()

void multisense::legacy::LegacyChannel::add_imu_frame_callback ( std::function< void(const ImuFrame &)>  callback)
finaloverridevirtual

Add a imu frame callback to get serviced inline with the receipt of a new frame. Only a single imu frame callback can be added to the channel NOTE: Perform minimal work in this callback, and ideally copy the lightweight ImuFrame object out to another processing thread.

Implements multisense::Channel.

Definition at line 224 of file LibMultiSense/details/legacy/channel.cc.

◆ connect()

Status multisense::legacy::LegacyChannel::connect ( const Config config)
finaloverridevirtual

Initialize the connection to the camera.

Implements multisense::Channel.

Definition at line 231 of file LibMultiSense/details/legacy/channel.cc.

◆ disconnect()

void multisense::legacy::LegacyChannel::disconnect ( )
finaloverridevirtual

Disconnect from the camera.

Implements multisense::Channel.

Definition at line 339 of file LibMultiSense/details/legacy/channel.cc.

◆ disparity_callback()

void multisense::legacy::LegacyChannel::disparity_callback ( std::shared_ptr< const std::vector< uint8_t >>  data)
private

Disparity callback used to internally receive images sent from the MultiSense.

Definition at line 1086 of file LibMultiSense/details/legacy/channel.cc.

◆ get_calibration()

StereoCalibration multisense::legacy::LegacyChannel::get_calibration ( )
finaloverridevirtual

Get the current stereo calibration. The output calibration will correspond to the full-resolution operating mode of the camera.

Implements multisense::Channel.

Definition at line 587 of file LibMultiSense/details/legacy/channel.cc.

◆ get_config()

MultiSenseConfig multisense::legacy::LegacyChannel::get_config ( )
finaloverridevirtual

Get the current MultiSense configuration.

Implements multisense::Channel.

Definition at line 386 of file LibMultiSense/details/legacy/channel.cc.

◆ get_info()

MultiSenseInfo multisense::legacy::LegacyChannel::get_info ( )
finaloverridevirtual

Get the device info associated with the camera.

Implements multisense::Channel.

Definition at line 635 of file LibMultiSense/details/legacy/channel.cc.

◆ get_next_image_frame()

std::optional< ImageFrame > multisense::legacy::LegacyChannel::get_next_image_frame ( )
finaloverridevirtual

A blocking call that waits for one image frame from the camera.

If you’ve set a receive timeout (via Config), it will block until that timeout expires; otherwise, it blocks indefinitely until data arrives.

Returns
The newly received ImageFrame, or std::nullopt if timed out (and you used a timeout).

Implements multisense::Channel.

Definition at line 366 of file LibMultiSense/details/legacy/channel.cc.

◆ get_next_imu_frame()

std::optional< ImuFrame > multisense::legacy::LegacyChannel::get_next_imu_frame ( )
finaloverridevirtual

A blocking call that waits for one imu frame from the camera.

If you’ve set a receive timeout (via Config), it will block until that timeout expires; otherwise, it blocks indefinitely until data arrives.

Returns
The newly received ImuFrame, or std::nullopt if timed out (and you used a timeout).

Implements multisense::Channel.

Definition at line 376 of file LibMultiSense/details/legacy/channel.cc.

◆ get_system_status()

std::optional< MultiSenseStatus > multisense::legacy::LegacyChannel::get_system_status ( )
finaloverridevirtual

Query the current MultiSense status.

Implements multisense::Channel.

Definition at line 678 of file LibMultiSense/details/legacy/channel.cc.

◆ handle_and_dispatch()

void multisense::legacy::LegacyChannel::handle_and_dispatch ( Image  image,
int64_t  frame_id,
const StereoCalibration calibration,
const TimeT capture_time,
const TimeT ptp_capture_time 
)
private

Handle internal process, and potentially dispatch a image.

Definition at line 1205 of file LibMultiSense/details/legacy/channel.cc.

◆ image_callback()

void multisense::legacy::LegacyChannel::image_callback ( std::shared_ptr< const std::vector< uint8_t >>  data)
private

Image callback used to internally receive images sent from the MultiSense.

Definition at line 1018 of file LibMultiSense/details/legacy/channel.cc.

◆ image_meta_callback()

void multisense::legacy::LegacyChannel::image_meta_callback ( std::shared_ptr< const std::vector< uint8_t >>  data)
private

Image meta callback used to internally receive images sent from the MultiSense.

Definition at line 1009 of file LibMultiSense/details/legacy/channel.cc.

◆ imu_callback()

void multisense::legacy::LegacyChannel::imu_callback ( std::shared_ptr< const std::vector< uint8_t >>  data)
private

Disparity callback used to internally receive images sent from the MultiSense.

We have enough valid samples to notify the listener and call our user callback

Definition at line 1155 of file LibMultiSense/details/legacy/channel.cc.

◆ query_calibration()

std::optional< StereoCalibration > multisense::legacy::LegacyChannel::query_calibration ( )
private

Query the calibration from the camera.

Definition at line 905 of file LibMultiSense/details/legacy/channel.cc.

◆ query_configuration()

std::optional< MultiSenseConfig > multisense::legacy::LegacyChannel::query_configuration ( bool  has_aux_camera,
bool  has_imu,
bool  ptp_enabled 
)
private

Query the full configuration.

Definition at line 846 of file LibMultiSense/details/legacy/channel.cc.

◆ query_device_info()

std::optional< MultiSenseInfo::DeviceInfo > multisense::legacy::LegacyChannel::query_device_info ( )
private

Query the device_info from the camera.

Definition at line 992 of file LibMultiSense/details/legacy/channel.cc.

◆ query_info()

std::optional< MultiSenseInfo > multisense::legacy::LegacyChannel::query_info ( )
private

Query the MultiSense Info.

Definition at line 922 of file LibMultiSense/details/legacy/channel.cc.

◆ set_calibration()

Status multisense::legacy::LegacyChannel::set_calibration ( const StereoCalibration calibration)
finaloverridevirtual

Set the current stereo calibration. The calibration is expected to be or the full-resolution operating mode of the camera.

Implements multisense::Channel.

Definition at line 599 of file LibMultiSense/details/legacy/channel.cc.

◆ set_config()

Status multisense::legacy::LegacyChannel::set_config ( const MultiSenseConfig config)
finaloverridevirtual

Get set the current MultiSense configuration.

Implements multisense::Channel.

Definition at line 398 of file LibMultiSense/details/legacy/channel.cc.

◆ set_device_info()

Status multisense::legacy::LegacyChannel::set_device_info ( const MultiSenseInfo::DeviceInfo device_info,
const std::string &  key 
)
finaloverridevirtual

Set the camera's device info. This setting is protected via a key since invalid values in the device info can result in internal camera failures.

Implements multisense::Channel.

Definition at line 647 of file LibMultiSense/details/legacy/channel.cc.

◆ set_mtu() [1/2]

Status multisense::legacy::LegacyChannel::set_mtu ( const std::optional< uint16_t > &  mtu)
private

Set the MTU. If the MTU is invalid, try and find the best MTU via a basic search.

Definition at line 821 of file LibMultiSense/details/legacy/channel.cc.

◆ set_mtu() [2/2]

Status multisense::legacy::LegacyChannel::set_mtu ( uint16_t  mtu)
private

Try and set the MTU.

Definition at line 786 of file LibMultiSense/details/legacy/channel.cc.

◆ set_network_config()

Status multisense::legacy::LegacyChannel::set_network_config ( const MultiSenseInfo::NetworkInfo config,
const std::optional< std::string > &  broadcast_interface 
)
finaloverridevirtual

Update the network configuration of the MultiSense. This will require a hardware reboot of the MultiSense after it's been successfully applied.

Implements multisense::Channel.

Definition at line 741 of file LibMultiSense/details/legacy/channel.cc.

◆ start_streams()

Status multisense::legacy::LegacyChannel::start_streams ( const std::vector< DataSource > &  sources)
finaloverridevirtual

Start a collection of image streams. Repeated calls to this function will not implicitly stop the previously started streams. For example if a user started a left_raw stream in one call and a disparity stream in a second call, both streams would be active until stop_streams is called for either.

Implements multisense::Channel.

Definition at line 140 of file LibMultiSense/details/legacy/channel.cc.

◆ stop_streams()

Status multisense::legacy::LegacyChannel::stop_streams ( const std::vector< DataSource > &  sources)
finaloverridevirtual

Stop a collection of streams.

Implements multisense::Channel.

Definition at line 179 of file LibMultiSense/details/legacy/channel.cc.

Member Data Documentation

◆ m_active_streams

std::set<DataSource> multisense::legacy::LegacyChannel::m_active_streams {}
private

The current set of active data streams the MultiSense is transmitting.

Definition at line 352 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_buffer_pool

std::shared_ptr<BufferPool> multisense::legacy::LegacyChannel::m_buffer_pool = nullptr
private

A collection of buffers to avoid dynamic allocation for incoming messages.

Definition at line 403 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_calibration

StereoCalibration multisense::legacy::LegacyChannel::m_calibration {}
private

The current cached calibration stored here for convenience.

Definition at line 337 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_config

Config multisense::legacy::LegacyChannel::m_config {}
private

Channel config.

Definition at line 322 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_connected

std::atomic_bool multisense::legacy::LegacyChannel::m_connected = false
private

Atomic flag to determine if we are connected to an active camera.

Definition at line 312 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_current_imu_frame

ImuFrame multisense::legacy::LegacyChannel::m_current_imu_frame {}
private

A cache of IMU samples which will be internally filled until it reaches the sample threshold for dispatch.

Definition at line 398 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_current_mtu

std::atomic_uint16_t multisense::legacy::LegacyChannel::m_current_mtu = 1500
private

The current MTU the camera is operating with.

Definition at line 317 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_frame_buffer

std::map<int64_t, ImageFrame> multisense::legacy::LegacyChannel::m_frame_buffer {}
private

A cache of image frames associated with a specific frame id.

Definition at line 382 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_image_callback_mutex

std::mutex multisense::legacy::LegacyChannel::m_image_callback_mutex {}
private

Internal mutex used to handle user callbacks for image data.

Definition at line 302 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_image_frame_notifier

FrameNotifier<ImageFrame> multisense::legacy::LegacyChannel::m_image_frame_notifier {}
private

Notifier used to service the get_next_image_frame member function.

Definition at line 367 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_imu_callback_mutex

std::mutex multisense::legacy::LegacyChannel::m_imu_callback_mutex {}
private

Internal mutex used to handle user callbacks imu data.

Definition at line 307 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_imu_frame_notifier

FrameNotifier<ImuFrame> multisense::legacy::LegacyChannel::m_imu_frame_notifier {}
private

Notifier used to service the get_next_imu_frame member function.

Definition at line 372 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_imu_scalars

ImuSampleScalars multisense::legacy::LegacyChannel::m_imu_scalars {}
private

Scalars to convert imu samples from wire units to standard LibMultiSense units.

Definition at line 392 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_info

MultiSenseInfo multisense::legacy::LegacyChannel::m_info {}
private

The current cached device info stored here for convenience.

Definition at line 342 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_max_batched_imu_messages

std::atomic_uint32_t multisense::legacy::LegacyChannel::m_max_batched_imu_messages = 0
private

The max number of IMU messages which can be batched over the wire.

Definition at line 387 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_message_assembler

MessageAssembler multisense::legacy::LegacyChannel::m_message_assembler
private

Helper object to assemble raw UDP packets into complete MultiSense wire messages.

Definition at line 413 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_meta_cache

std::map<int64_t, crl::multisense::details::wire::ImageMeta> multisense::legacy::LegacyChannel::m_meta_cache {}
private

A cache of image metadata associated with a specific frame id.

Definition at line 377 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_multisense_config

MultiSenseConfig multisense::legacy::LegacyChannel::m_multisense_config {}
private

The current cached MultiSense configuration stored for convenience.

Definition at line 347 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_mutex

std::mutex multisense::legacy::LegacyChannel::m_mutex {}
private

Internal mutex used to handle updates from users.

Definition at line 297 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_socket

NetworkSocket multisense::legacy::LegacyChannel::m_socket {}
private

Active network socket for receiving and transmitting data.

Definition at line 327 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_transmit_id

std::atomic_uint16_t multisense::legacy::LegacyChannel::m_transmit_id = 0
private

Monotonically increasing internal id used to uniquely identify requests sent to the camera.

Definition at line 332 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_udp_receiver

std::unique_ptr<UdpReceiver> multisense::legacy::LegacyChannel::m_udp_receiver = nullptr
private

Helper object to receive UDP traffic. Internally manages a receive thread.

Definition at line 408 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_user_image_frame_callback

std::function<void(const ImageFrame&)> multisense::legacy::LegacyChannel::m_user_image_frame_callback {}
private

The currently active image frame user callback.

Definition at line 357 of file LibMultiSense/include/details/legacy/channel.hh.

◆ m_user_imu_frame_callback

std::function<void(const ImuFrame&)> multisense::legacy::LegacyChannel::m_user_imu_frame_callback {}
private

The currently active imu frame user callback.

Definition at line 362 of file LibMultiSense/include/details/legacy/channel.hh.


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


multisense_lib
Author(s):
autogenerated on Thu Apr 17 2025 02:49:10