Go to the documentation of this file.
   41 #include "MultiSense/MultiSenseChannel.hh" 
   73         std::lock_guard<std::mutex> lock(
m_mutex);
 
   81     template <
class Rep, 
class Period>
 
   82     std::optional<T> 
wait(
const std::optional<std::chrono::duration<Rep, Period>>& timeout)
 
   84         std::unique_lock<std::mutex> lock(
m_mutex);
 
   86         std::optional<T> output_frame = std::nullopt;
 
   89             if (std::cv_status::no_timeout == 
m_cv.wait_for(lock, timeout.value()))
 
   91                 output_frame = std::move(
m_frame);
 
   97             output_frame = std::move(
m_frame);
 
  110         const std::optional<std::chrono::milliseconds> timeout = std::nullopt;
 
  111         return wait(timeout);
 
  231                               const std::optional<std::string> &broadcast_interface) 
final override;
 
  248     std::optional<MultiSenseConfig> 
query_configuration(
bool has_aux_camera, 
bool has_imu, 
bool ptp_enabled);
 
  273     void image_callback(std::shared_ptr<
const std::vector<uint8_t>> data);
 
  283     void imu_callback(std::shared_ptr<
const std::vector<uint8_t>> data);
 
  291                             const TimeT &capture_time,
 
  292                             const TimeT &ptp_capture_time);
 
  377     std::map<int64_t, crl::multisense::details::wire::ImageMeta> 
m_meta_cache{};
 
  
ImuFrame m_current_imu_frame
A cache of IMU samples which will be internally filled until it reaches the sample threshold for disp...
std::atomic_bool m_connected
Atomic flag to determine if we are connected to an active camera.
std::optional< T > m_frame
std::optional< MultiSenseConfig > query_configuration(bool has_aux_camera, bool has_imu, bool ptp_enabled)
Query the full configuration.
The network configuration for the MultiSense.
Complete configuration object for configuring the MultiSense. Can be updated during camera operation.
std::mutex m_image_callback_mutex
Internal mutex used to handle user callbacks for image data.
void disparity_callback(std::shared_ptr< const std::vector< uint8_t >> data)
Disparity callback used to internally receive images sent from the MultiSense.
Process incoming network data, and try the data into valid MultiSense Wire messages.
FrameNotifier< ImuFrame > m_imu_frame_notifier
Notifier used to service the get_next_imu_frame member function.
StereoCalibration get_calibration() final override
Get the current stereo calibration. The output calibration will correspond to the full-resolution ope...
std::condition_variable m_cv
ImuSampleScalars m_imu_scalars
Scalars to convert imu samples from wire units to standard LibMultiSense units.
std::atomic_uint32_t m_max_batched_imu_messages
The max number of IMU messages which can be batched over the wire.
A frame containing multiple images (indexed by DataSource).
Config m_config
Channel config.
MultiSenseInfo get_info() final override
Get the device info associated with the camera.
std::unique_ptr< UdpReceiver > m_udp_receiver
Helper object to receive UDP traffic. Internally manages a receive thread.
Status set_mtu(uint16_t mtu)
Try and set the MTU.
void image_callback(std::shared_ptr< const std::vector< uint8_t >> data)
Image callback used to internally receive images sent from the MultiSense.
std::chrono::time_point< std::chrono::system_clock, std::chrono::nanoseconds > TimeT
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 pre...
std::optional< T > wait()
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....
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 MultiS...
std::optional< MultiSenseInfo::DeviceInfo > query_device_info()
Query the device_info from the camera.
std::optional< MultiSenseStatus > get_system_status() final override
Query the current MultiSense status.
Status stop_streams(const std::vector< DataSource > &sources) final override
Stop a collection of streams.
void disconnect() final override
Disconnect from the camera.
A collection of IMU samples from the camera.
std::optional< ImageFrame > get_next_image_frame() final override
A blocking call that waits for one image frame from the camera.
std::map< int64_t, crl::multisense::details::wire::ImageMeta > m_meta_cache
A cache of image metadata associated with a specific frame id.
std::function< void(const ImuFrame &)> m_user_imu_frame_callback
The currently active imu frame user callback.
std::atomic_uint16_t m_current_mtu
The current MTU the camera is operating with.
void imu_callback(std::shared_ptr< const std::vector< uint8_t >> data)
Disparity callback used to internally receive images sent from the MultiSense.
MultiSenseInfo m_info
The current cached device info stored here for convenience.
std::set< DataSource > m_active_streams
The current set of active data streams the MultiSense is transmitting.
std::optional< MultiSenseInfo > query_info()
Query the MultiSense Info.
Convenience network socket object which contains the data corresponding to our connection.
std::map< int64_t, ImageFrame > m_frame_buffer
A cache of image frames associated with a specific frame id.
MessageAssembler m_message_assembler
Helper object to assemble raw UDP packets into complete MultiSense wire messages.
StereoCalibration m_calibration
The current cached calibration stored here for convenience.
The Device information associated with the MultiSense. The DeviceInfo is used to determine what featu...
std::optional< T > wait(const std::optional< std::chrono::duration< Rep, Period >> &timeout)
Wait for the notifier to be valid. If the timeout is invalid, will wait forever.
void set_and_notify(const T &in_frame)
Copy a frame into the local storage, and notify all waiters that the frame is valid.
std::mutex m_mutex
Internal mutex used to handle updates from users.
Status set_calibration(const StereoCalibration &calibration) final override
Set the current stereo calibration. The calibration is expected to be or the full-resolution operatin...
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.
MultiSenseConfig get_config() final override
Get the current MultiSense configuration.
Values to scale IMU samples from the MultiSense camera into standard units LibMultiSense expects.
MultiSenseConfig m_multisense_config
The current cached MultiSense configuration stored for convenience.
std::optional< ImuFrame > get_next_imu_frame() final override
A blocking call that waits for one imu frame from the camera.
std::shared_ptr< BufferPool > m_buffer_pool
A collection of buffers to avoid dynamic allocation for incoming messages.
Static status info for the MultiSense. Will not change during camera operation.
std::function< void(const ImageFrame &)> m_user_image_frame_callback
The currently active image frame user callback.
Status connect(const Config &config) final override
Initialize the connection to the camera.
Status set_config(const MultiSenseConfig &config) final override
Get set the current MultiSense configuration.
Represents a single image plus metadata.
std::optional< StereoCalibration > query_calibration()
Query the calibration from the camera.
NetworkSocket m_socket
Active network socket for receiving and transmitting data.
LegacyChannel(const Config &config)
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 ...
std::atomic_uint16_t m_transmit_id
Monotonically increasing internal id used to uniquely identify requests sent to the camera.
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 fr...
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.
std::mutex m_imu_callback_mutex
Internal mutex used to handle user callbacks imu data.
FrameNotifier< ImageFrame > m_image_frame_notifier
Notifier used to service the get_next_image_frame member function.