109 namespace multisense {
139 }
catch (
const std::exception& e) {
160 }
catch (
const std::exception& e) {
181 }
catch (
const std::exception& e) {
202 }
catch (
const std::exception& e) {
224 }
catch (
const std::exception& e) {
245 }
catch (
const std::exception& e) {
266 }
catch (
const std::exception& e) {
281 std::list<ImageListener*>::iterator it;
286 if ((*it)->callback() == callback) {
293 }
catch (
const std::exception& e) {
309 std::list<LidarListener*>::iterator it;
314 if ((*it)->callback() == callback) {
321 }
catch (
const std::exception& e) {
337 std::list<PpsListener*>::iterator it;
342 if ((*it)->callback() == callback) {
349 }
catch (
const std::exception& e) {
365 std::list<ImuListener*>::iterator it;
370 if ((*it)->callback() == callback) {
377 }
catch (
const std::exception& e) {
393 std::list<CompressedImageListener*>::iterator it;
398 if ((*it)->callback() == callback) {
405 }
catch (
const std::exception& e) {
421 std::list<GroundSurfaceSplineListener*>::iterator it;
426 if ((*it)->callback() == callback) {
433 }
catch (
const std::exception& e) {
449 std::list<AprilTagDetectionListener*>::iterator it;
454 if ((*it)->callback() == callback) {
461 }
catch (
const std::exception& e) {
474 if (dispatchBufferReferenceTP) {
480 }
catch (
const std::exception& e) {
504 }
catch (
const std::exception& e) {
531 CRL_DEBUG(
"no meta cached for frameId %ld",
532 static_cast<long int>(frameId));
539 const int entries = histogram.
channels * histogram.
bins;
540 const int sizeBytes = entries *
sizeof(uint32_t);
542 histogram.
data.resize(entries);
543 memcpy(&(histogram.
data[0]), metaP->histogramP, sizeBytes);
548 catch (
const std::exception& e) {
568 CRL_DEBUG(
"no meta cached for frameId %ld",
569 static_cast<long int>(frameId));
578 catch (
const std::exception& e) {
606 cmd.
enable = enabled ? 1 : 0;
715 duty = (data.
intensity[i] * 100.0f) / 255;
764 return requestStatus;
820 void setCal(
float fx,
float fy,
float cx,
float cy,
821 float tx,
float ty,
float tz,
822 float r,
float p,
float w) {
823 m_fx = fx; m_fy = fy; m_cx = cx; m_cy = cy;
824 m_tx = tx; m_ty = ty; m_tz = tz;
825 m_roll = r; m_pitch = p; m_yaw = w;
830 ConfigAccess& a = *((ConfigAccess *) &config);
865 a.setCameraProfile(static_cast<CameraProfile>(d.
cameraProfile));
880 void setCal(
float fx,
float fy,
float cx,
float cy) {
881 m_fx = fx; m_fy = fy; m_cx = cx; m_cy = cy;
886 ConfigAccess& a = *((ConfigAccess *) &config);
914 a.setCameraProfile(static_cast<CameraProfile>(d.
cameraProfile));
1166 modes.resize(d.
modes.size());
1167 for(uint32_t i=0; i<d.
modes.size(); i++) {
1280 info.
pcbs.push_back(pcb);
1496 std::vector<imu::Info>& info)
1508 info.resize(w.
details.size());
1509 for(uint32_t i=0; i<w.
details.size(); i++) {
1513 info[i].name = d.
name;
1514 info[i].device = d.
device;
1515 info[i].units = d.
units;
1517 info[i].rates.resize(d.
rates.size());
1518 for(uint32_t j=0; j<d.
rates.size(); j++) {
1519 info[i].rates[j].sampleRate = d.
rates[j].sampleRate;
1520 info[i].rates[j].bandwidthCutoff = d.
rates[j].bandwidthCutoff;
1522 info[i].ranges.resize(d.
ranges.size());
1523 for(uint32_t j=0; j<d.
ranges.size(); j++) {
1524 info[i].ranges[j].range = d.
ranges[j].range;
1525 info[i].ranges[j].resolution = d.
ranges[j].resolution;
1536 std::vector<imu::Config>& c)
1549 for(uint32_t i=0; i<w.
configs.size(); i++) {
1550 c[i].name = w.
configs[i].name;
1552 c[i].rateTableIndex = w.
configs[i].rateTableIndex;
1553 c[i].rangeTableIndex = w.
configs[i].rangeTableIndex;
1563 uint32_t samplesPerMessage,
1564 const std::vector<imu::Config>& c)
1574 for(uint32_t i=0; i<c.size(); i++) {
1575 w.
configs[i].name = c[i].name;
1577 w.
configs[i].rateTableIndex = c[i].rateTableIndex;
1578 w.
configs[i].rangeTableIndex = c[i].rangeTableIndex;
1588 uint32_t& bufferSize)
1600 uint32_t bufferSize)
1603 CRL_DEBUG(
"WARNING: supplying less than recommended number of large buffers: %ld/%ld\n",
1604 static_cast<long int>(buffers.size()),
1607 CRL_DEBUG(
"WARNING: supplying smaller than recommended large buffers: %ld/%ld bytes\n",
1608 static_cast<long int>(bufferSize),
1619 BufferPool::const_iterator it;
1627 for(uint32_t i=0; i<buffers.size(); i++)
1630 }
catch (
const std::exception& e) {
float whiteBalanceBlue() const
std::list< ImageListener * > m_imageListeners
float autoWhiteBalanceThresh() const
RemoteHeadChannel controller
static uint32_t imagerWireToApi(uint32_t h)
virtual Status setNetworkConfig(const system::NetworkConfig &c)
static CRL_CONSTEXPR uint32_t OP_PROGRAM
float sharpeningPercentage() const
Listener< image::Header, image::Callback > ImageListener
static uint32_t hardwareWireToApi(uint32_t h)
#define CRL_DEBUG_RAW(fmt)
std::vector< PcbInfo > pcbs
uint16_t autoExposureRoiY() const
int ground_surface_max_fitting_iterations
virtual Status getPtpStatus(int64_t frameId, system::PtpStatus &ptpStatus)
BufferPool m_rxLargeBufferPool
virtual Status getMtu(int32_t &mtu)
std::string firmwareBuildDate
virtual Status verifyBitstream(const std::string &file)
virtual Status getLocalUdpPort(uint16_t &port)
static CRL_CONSTEXPR uint32_t SOURCE_EXTERNAL
virtual Status setImuConfig(bool storeSettingsInFlash, uint32_t samplesPerMessage, const std::vector< imu::Config > &c)
uint16_t autoExposureRoiX
float ground_surface_pointcloud_grid_size
CRL_THREAD_LOCAL utility::BufferStream * dispatchBufferReferenceTP
float ambientLightPercentage
virtual Status verifyFirmware(const std::string &file)
float ground_surface_pointcloud_max_range_m
virtual Status setTriggerSource(TriggerSource s)
virtual Status getMotorPos(int32_t &mtu)
Listener< pps::Header, pps::Callback > PpsListener
float stereoPostFilterStrength
RemoteHeadChannel responder
virtual Status getExternalCalibration(system::ExternalCalibration &calibration)
static CRL_CONSTEXPR TriggerSource Trigger_Internal
virtual Status getLightingSensorStatus(lighting::SensorStatus &status)
Listener< apriltag::Header, apriltag::Callback > AprilTagDetectionListener
static CRL_CONSTEXPR TriggerSource Trigger_PTP
float whiteBalanceRed() const
float ground_surface_obstacle_height_thresh_m
virtual Status networkTimeSynchronization(bool enabled)
uint8_t intensity[lighting::MAX_LIGHTS]
virtual Status removeIsolatedCallback(image::Callback callback)
virtual Status setRemoteHeadConfig(const image::RemoteHeadConfig &c)
uint32_t autoExposureDecay() const
uint8_t rolling_shutter_led
bool autoExposure() const
void(* Callback)(const Header &header, void *userDataP)
uint32_t autoExposureMax() const
uint64_t sensorHardwareMagic
uint8_t storeSettingsInFlash
int ground_surface_pointcloud_decimation
virtual Status ptpTimeSynchronization(bool enabled)
uint64_t min_border_width
virtual Status setExternalCalibration(const system::ExternalCalibration &calibration)
int ground_surface_number_of_levels_x
virtual Status getLightingConfig(lighting::Config &c)
virtual Status getImageConfig(image::Config &c)
RemoteHeadSyncPair syncPair2
static CRL_CONSTEXPR uint32_t SOURCE_EXTERNAL_INVERTED
VersionType firmwareVersion
float cameraToSpindleFixed[4][4]
uint32_t samplesPerMessage
static CRL_CONSTEXPR TriggerSource Trigger_External
int64_t getNanoSeconds() const
float ground_surface_adjacent_cell_search_size_m
wire::StatusResponse m_statusResponseMessage
static CRL_CONSTEXPR uint32_t SOURCE_PTP
virtual Status setLidarCalibration(const lidar::Calibration &c)
static wire::SourceType sourceApiToWire(DataSource mask)
static CRL_CONSTEXPR uint32_t STATUS_LASER_OK
virtual Status setGroundSurfaceParams(const system::GroundSurfaceParams ¶ms)
uint32_t autoWhiteBalanceDecay
void enableSharpening(const bool &s)
std::list< PpsListener * > m_ppsListeners
virtual Status getLargeBufferDetails(uint32_t &bufferCount, uint32_t &bufferSize)
float ground_surface_obstacle_height_thresh_m
double quad_detection_decimate
bool autoExposure() const
uint16_t autoExposureRoiWidth
uint32_t getStartupTime() const
uint16_t autoExposureRoiX() const
virtual Status setMotorSpeed(float rpm)
std::list< AprilTagDetectionListener * > m_aprilTagDetectionListeners
DepthCache< int64_t, wire::ImageMeta > m_imageMetaCache
std::string sensorFirmwareBuildDate
static CRL_CONSTEXPR Status Status_Failed
float autoWhiteBalanceThresh
bool setDutyCycle(float percent)
float autoWhiteBalanceThresh
void(* Callback)(const Header &header, void *userDataP)
uint16_t autoExposureRoiWidth() const
virtual Status getAuxImageConfig(image::AuxConfig &c)
RemoteHeadSyncPair syncPair1
virtual Status setMtu(int32_t mtu)
int ground_surface_number_of_levels_z
std::vector< imu::Config > configs
virtual Status getDeviceStatus(system::StatusMessage &status)
float ground_surface_pointcloud_min_range_m
void(* Callback)(const Header &header, void *userDataP)
uint32_t supportedDataSources
float ground_surface_pointcloud_max_width_m
float powerSupplyTemperature
virtual Status stopStreams(DataSource mask)
virtual Status getNetworkConfig(system::NetworkConfig &c)
bool m_ptpTimeSyncEnabled
static CRL_CONSTEXPR uint32_t MAX_USER_APRILTAG_QUEUE_SIZE
float stereoPostFilterStrength
uint32_t autoWhiteBalanceDecay
Listener< ground_surface::Header, ground_surface::Callback > GroundSurfaceSplineListener
uint16_t autoExposureRoiX
void enable(SourceType mask)
float ground_surface_pointcloud_max_height_m
bool getInvertPulse() const
double quad_detection_blur_sigma
uint32_t maxSamplesPerMessage
float laserToSpindle[4][4]
std::vector< uint32_t > data
uint8_t sharpeningLimit() const
void(* Callback)(const Header &header, void *userDataP)
#define CPY_ARRAY_1(d_, s_, n_)
int ground_surface_min_points_per_grid
uint16_t autoExposureRoiY
RemoteHeadChannel syncPair1Responder() const
static CRL_CONSTEXPR uint32_t RGN_FIRMWARE
float autoExposureThresh() const
static CRL_CONSTEXPR uint32_t MAX_USER_GROUND_SURFACE_QUEUE_SIZE
virtual Status addIsolatedCallback(image::Callback callback, DataSource imageSourceMask, void *userDataP)
float stereoPostFilterStrength() const
bool setInvertPulse(const bool invert)
uint32_t autoExposureMax() const
static CRL_CONSTEXPR uint32_t MAX_USER_COMPRESSED_IMAGE_QUEUE_SIZE
static CRL_CONSTEXPR uint32_t STATUS_CAMERAS_OK
float autoExposureTargetIntensity
float ground_surface_pointcloud_max_width_m
float autoWhiteBalanceThresh
utility::Mutex m_dispatchLock
static CRL_CONSTEXPR uint32_t MAX_USER_PPS_QUEUE_SIZE
float autoExposureTargetIntensity() const
float leftImagerTemperature
virtual Status getVersionInfo(system::VersionInfo &v)
#define CPY_ARRAY_2(d_, s_, n_, m_)
virtual Status setApriltagParams(const system::ApriltagParams ¶ms)
virtual Status getSensorVersion(VersionType &version)
static CRL_CONSTEXPR uint32_t OP_VERIFY
uint32_t autoExposureDecay() const
static CRL_CONSTEXPR VersionType API_VERSION
bool getRollingShutterLedSynchronizationStatus(void) const
float autoExposureTargetIntensity
uint16_t autoExposureRoiY
void setFlash(bool onOff)
std::vector< DeviceMode > modes
float autoExposureTargetIntensity
uint16_t autoExposureRoiY() const
virtual Status getImuConfig(uint32_t &samplesPerMessage, std::vector< imu::Config > &c)
uint32_t hardwareRevision
static CRL_CONSTEXPR uint32_t FLAGS_ENABLED
Type boundValue(Type const &value, Type const &minimum, Type const &maximum)
uint16_t m_serverSocketPort
uint16_t autoExposureRoiHeight
static CRL_CONSTEXPR uint32_t RX_POOL_LARGE_BUFFER_COUNT
static CRL_CONSTEXPR Status Status_Ok
float ground_surface_pointcloud_max_height_m
RemoteHeadChannel syncPair2Responder() const
bool processingPipelineOk
uint16_t autoExposureRoiHeight
virtual Status getEnabledStreams(DataSource &mask)
uint16_t autoExposureRoiX
wire::VersionResponse m_sensorVersion
uint32_t getNumberOfPulses() const
static CRL_CONSTEXPR uint32_t MAX_USER_IMU_QUEUE_SIZE
uint32_t autoWhiteBalanceDecay
bool autoWhiteBalance() const
std::list< CompressedImageListener * > m_compressedImageListeners
float ground_surface_obstacle_percentage_thresh
RemoteHeadChannel responder
bool m_networkTimeSyncEnabled
uint16_t autoExposureRoiX
float ground_surface_adjacent_cell_search_size_m
virtual Status getImageHistogram(int64_t frameId, image::Histogram &histogram)
static CRL_CONSTEXPR TriggerSource Trigger_External_Inverted
static CRL_CONSTEXPR uint32_t SOURCE_INTERNAL
uint16_t autoExposureRoiHeight() const
float autoExposureTargetIntensity
float ground_surface_pointcloud_min_width_m
uint32_t autoExposureDecay
static CRL_CONSTEXPR uint32_t STATUS_EXTERNAL_LED_OK
uint16_t autoExposureRoiX() const
std::list< GroundSurfaceSplineListener * > m_groundSurfaceSplineListeners
static uint32_t imagerApiToWire(uint32_t h)
utility::Mutex m_streamLock
uint16_t autoExposureRoiWidth
utility::TimeStamp uptime
float ground_surface_pointcloud_grid_size
float laserToSpindle[4][4]
RemoteHeadSyncPair syncPair2
int ground_surface_min_points_per_grid
Listener< compressed_image::Header, compressed_image::Callback > CompressedImageListener
float sharpeningPercentage
int ground_surface_number_of_levels_x
CameraProfile cameraProfile() const
int ground_surface_base_model
virtual Status startStreams(DataSource mask)
Listener< lidar::Header, lidar::Callback > LidarListener
VersionType sensorFirmwareVersion
int ground_surface_base_model
float whiteBalanceBlue() const
virtual Status setDeviceInfo(const std::string &key, const system::DeviceInfo &i)
RemoteHeadChannel controller
float sharpeningPercentage
virtual void * reserveCallbackBuffer()
float ground_surface_pointcloud_max_range_m
virtual Status getApiVersion(VersionType &version)
virtual Status setImageCalibration(const image::Calibration &c)
float ground_surface_obstacle_percentage_thresh
static CRL_CONSTEXPR uint32_t MAX_USER_LASER_QUEUE_SIZE
uint32_t autoWhiteBalanceDecay() const
std::vector< RangeType > ranges
static CRL_CONSTEXPR uint32_t STATUS_LASER_MOTOR_OK
float ground_surface_pointcloud_min_range_m
float autoExposureThresh() const
Status waitAck(const T &msg, wire::IdType id=MSG_ID(T::ID), const double &timeout=DEFAULT_ACK_TIMEOUT(), int32_t attempts=DEFAULT_ACK_ATTEMPTS)
float ground_surface_pointcloud_min_height_m
bool enableRollingShutterLedSynchronization(const bool enabled)
float cameraToSpindleFixed[4][4]
#define CRL_DEBUG(fmt,...)
static CRL_CONSTEXPR uint32_t STATUS_PIPELINE_OK
float whiteBalanceRed() const
uint32_t autoExposureDecay
uint32_t disparities() const
uint16_t autoExposureRoiHeight
float nominalRelativeAperture
virtual Status getImageCalibration(image::Calibration &c)
bool setStartupTime(uint32_t ledTransientResponse_us)
static CRL_CONSTEXPR uint32_t RX_POOL_LARGE_BUFFER_SIZE
std::list< LidarListener * > m_lidarListeners
virtual Status getImuInfo(uint32_t &maxSamplesPerMessage, std::vector< imu::Info > &info)
uint32_t exposure() const
float ground_surface_pointcloud_min_width_m
uint32_t autoWhiteBalanceDecay
uint8_t rolling_shutter_led
static CRL_CONSTEXPR uint32_t MAX_LIGHTS
Listener< imu::Header, imu::Callback > ImuListener
virtual Status getDeviceModes(std::vector< system::DeviceMode > &modes)
virtual Status getRemoteHeadConfig(image::RemoteHeadConfig &c)
static uint32_t hardwareApiToWire(uint32_t h)
bool setNumberOfPulses(const uint32_t numPulses)
uint16_t autoExposureRoiY
void(* Callback)(const Header &header, void *userDataP)
bool autoWhiteBalance() const
CameraProfile cameraProfile() const
uint16_t autoExposureRoiHeight
float autoExposureTargetIntensity() const
uint32_t hardwareRevision
float rightImagerTemperature
float autoWhiteBalanceThresh
uint32_t exposure() const
virtual Status flashBitstream(const std::string &file)
Status m_getStatusReturnStatus
double quad_detection_blur_sigma
int ground_surface_number_of_levels_z
uint16_t autoExposureRoiWidth
void(* Callback)(const Header &header, void *userDataP)
double quad_detection_decimate
virtual Status setLargeBuffers(const std::vector< uint8_t *> &buffers, uint32_t bufferSize)
virtual Status setTransmitDelay(const image::TransmitDelay &c)
std::list< ImuListener * > m_imuListeners
static CRL_CONSTEXPR Status Status_Exception
int ground_surface_max_fitting_iterations
uint16_t autoExposureRoiY
RemoteHeadChannel syncPair2Controller() const
virtual Status getLidarCalibration(lidar::Calibration &c)
virtual Status getTransmitDelay(image::TransmitDelay &c)
static CRL_CONSTEXPR uint32_t MAX_USER_IMAGE_QUEUE_SIZE
Status waitData(const T &command, U &data, const double &timeout=DEFAULT_ACK_TIMEOUT(), int32_t attempts=DEFAULT_ACK_ATTEMPTS)
uint32_t autoWhiteBalanceDecay() const
uint16_t autoExposureRoiWidth() const
uint32_t number_of_pulses
uint32_t autoExposureDecay
virtual Status flashFirmware(const std::string &file)
DataSource m_streamsEnabled
static CRL_CONSTEXPR Status Status_Error
uint64_t sensorHardwareVersion
void disable(SourceType mask)
std::vector< RateType > rates
uint8_t intensity[lighting::MAX_LIGHTS]
static CRL_CONSTEXPR uint32_t RGN_BITSTREAM
virtual Status setLightingConfig(const lighting::Config &c)
uint32_t number_of_pulses
std::vector< imu::Details > details
float ambientLightPercentage
float ground_surface_pointcloud_min_height_m
RemoteHeadChannel syncPair1Controller() const
RemoteHeadSyncPair syncPair1
static CRL_CONSTEXPR uint32_t STATUS_GENERAL_OK
DataSource supportedDataSources
uint16_t autoExposureRoiHeight() const
int ground_surface_pointcloud_decimation
uint16_t autoExposureRoiWidth
virtual Status setAuxImageConfig(const image::AuxConfig &c)
virtual Status setImageConfig(const image::Config &c)
float getDutyCycle(uint32_t i) const
static DataSource sourceWireToApi(wire::SourceType mask)
Status doFlashOp(const std::string &filename, uint32_t operation, uint32_t region)
float autoWhiteBalanceThresh() const
virtual Status getDeviceInfo(system::DeviceInfo &info)
static CRL_CONSTEXPR uint32_t STATUS_IMU_OK
void(* Callback)(const Header &header, void *userDataP)
uint32_t autoExposureDecay
virtual Status releaseCallbackBuffer(void *referenceP)
float nominalRelativeAperture