#include <utility/Exception.hh>
#include <wire/Protocol.hh>
#include <utility/BufferStream.hh>
#include <wire/AckMessage.hh>
#include <wire/ImuDataMessage.hh>
#include <wire/ImuInfoMessage.hh>
#include "details/legacy/message.hh"
#include "details/legacy/udp.hh"
#include "MultiSense/MultiSenseTypes.hh"
Go to the source code of this file.
Classes | |
struct | multisense::legacy::ImuSampleScalars |
Values to scale IMU samples from the MultiSense camera into standard units LibMultiSense expects. More... | |
struct | multisense::legacy::TimedResponse< T > |
Namespaces | |
multisense | |
multisense::legacy | |
Functions | |
ImuSample | multisense::legacy::add_wire_sample (ImuSample sample, const crl::multisense::details::wire::ImuSample &wire, const ImuSampleScalars &scalars) |
Add a wire sample to a ImuSample. More... | |
std::vector< DataSource > | multisense::legacy::convert_sources (const crl::multisense::details::wire::SourceType &source) |
Convert wire sources to a vector of DataSources. More... | |
crl::multisense::details::wire::SourceType | multisense::legacy::convert_sources (const std::vector< DataSource > &sources) |
Convert a vector of DataSources to a wire source. More... | |
std::vector< DataSource > | multisense::legacy::expand_source (const DataSource &source) |
Expand sources since some sources may represent multiple sources on the wire. More... | |
double | multisense::legacy::get_acceleration_scale (const std::string &units) |
Get a scale for the acceleration value based on a units string. More... | |
MultiSenseConfig::MaxDisparities | multisense::legacy::get_disparities (size_t disparity) |
Convert a disparity integer to a fixed disparity setting. More... | |
double | multisense::legacy::get_gyroscope_scale (const std::string &units) |
Get a scale for the gyroscope value based on a units string. More... | |
ImuSampleScalars | multisense::legacy::get_imu_scalars (const crl::multisense::details::wire::ImuInfo &info) |
Get IMU scalars from the cameras's reported IMU info. More... | |
double | multisense::legacy::get_magnetometer_scale (const std::string &units) |
Get a scale for the magnetometer value based on a units string. More... | |
uint32_t | multisense::legacy::get_range_index (const std::vector< ImuRange > &ranges, const ImuRange &range) |
Get the index of the range in a vector of ranges. More... | |
uint32_t | multisense::legacy::get_rate_index (const std::vector< ImuRate > &rates, const ImuRate &rate) |
Get the index of the rate in a vector of rates. More... | |
Status | multisense::legacy::get_status (const crl::multisense::details::wire::Ack::AckStatus &status) |
MultiSenseInfo::Version | multisense::legacy::get_version (const crl::multisense::details::wire::VersionType &version) |
Convert a wire version to a API Version. More... | |
bool | multisense::legacy::is_image_source (const DataSource &source) |
Determine if a datasource is a image source. More... | |
template<typename QueryMessage , class Rep , class Period > | |
std::optional< crl::multisense::details::wire::Ack > | multisense::legacy::wait_for_ack (MessageAssembler &assembler, const NetworkSocket &socket, const QueryMessage &query, uint16_t sequence_id, uint16_t mtu, const std::optional< std::chrono::duration< Rep, Period >> &wait_time, size_t attempts=1) |
Helper to wait for ack from the camera from a given query command. Once a query command is sent to the MultiSense, it Ack's the command before sending the response. More... | |
template<typename OutputMessage , typename QueryMessage , class Rep , class Period > | |
std::optional< OutputMessage > | multisense::legacy::wait_for_data (MessageAssembler &assembler, const NetworkSocket &socket, const QueryMessage &query, uint16_t sequence_id, uint16_t mtu, const std::optional< std::chrono::duration< Rep, Period >> &wait_time, size_t attempts=1) |
Helper to wait for data from the camera from a given query command. Once a query command is sent to the MultiSense, it Ack's the command before sending the response. More... | |
template<typename OutputMessage , typename QueryMessage , class Rep , class Period > | |
std::optional< TimedResponse< OutputMessage > > | multisense::legacy::wait_for_data_timed (MessageAssembler &assembler, const NetworkSocket &socket, const QueryMessage &query, uint16_t sequence_id, uint16_t mtu, const std::optional< std::chrono::duration< Rep, Period >> &wait_time, size_t attempts=1) |
Helper to wait for data from the camera from a given query command. Once a query command is sent to the MultiSense, it Ack's the command before sending the response. More... | |
Variables | |
constexpr crl::multisense::details::wire::SourceType | multisense::legacy::all_sources |
All the supported wire source types created for convenience. More... | |
Copyright 2013-2025 Carnegie Robotics, LLC 4501 Hatfield Street, Pittsburgh, PA 15201 http://www.carnegierobotics.com
All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL CARNEGIE ROBOTICS, LLC BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
Significant history (date, user, job code, action): 2025-01-13, malva, IRAD, Created file. rado @carn egie robot ics. com
Definition in file utilities.hh.