LibMultiSense
LibMultiSense Documentation
MultiSenseChannel.hh
Go to the documentation of this file.
1 
37 #ifndef LibMultiSense_MultiSenseChannel_hh
38 #define LibMultiSense_MultiSenseChannel_hh
39 
40 #include <stdint.h>
41 #include <string>
42 #include <vector>
43 
44 #include "MultiSenseTypes.hh"
45 
46 namespace crl {
47 namespace multisense {
48 
70 public:
71 
83  static Channel* Create(const std::string& sensorAddress);
84 
99  static Channel* Create(const std::string& sensorAddress, const RemoteHeadChannel& cameraId);
111  static Channel* Create(const std::string& sensorAddress, const std::string& interfaceName);
112 
128  static Channel* Create(const std::string& sensorAddress, const RemoteHeadChannel& cameraId, const std::string& interfaceName);
129 
138  static void Destroy(Channel* instanceP);
139 
143  virtual ~Channel() {};
144 
153  static const char *statusString(Status status);
154 
155 
195  virtual Status addIsolatedCallback(image::Callback callback,
196  DataSource imageSourceMask,
197  void *userDataP=NULL) = 0;
198 
223  virtual Status addIsolatedCallback(lidar::Callback callback,
224  void *userDataP=NULL) = 0;
225 
249  virtual Status addIsolatedCallback(pps::Callback callback,
250  void *userDataP=NULL) = 0;
251 
276  virtual Status addIsolatedCallback(imu::Callback callback,
277  void *userDataP=NULL) = 0;
278 
279 
298  virtual Status addIsolatedCallback(compressed_image::Callback callback,
299  DataSource imageSourceMask,
300  void *userDataP=NULL) = 0;
301 
325  virtual Status addIsolatedCallback(ground_surface::Callback callback,
326  void *userDataP=NULL) = 0;
327 
351  virtual Status addIsolatedCallback(apriltag::Callback callback,
352  void *userDataP=NULL) = 0;
353 
368  virtual Status addIsolatedCallback(feature_detector::Callback callback,
369  void *userDataP=NULL) = 0;
370 
381  virtual Status removeIsolatedCallback(image::Callback callback) = 0;
382 
393  virtual Status removeIsolatedCallback(lidar::Callback callback) = 0;
394 
405  virtual Status removeIsolatedCallback(pps::Callback callback) = 0;
406 
417  virtual Status removeIsolatedCallback(imu::Callback callback) = 0;
418 
429  virtual Status removeIsolatedCallback(compressed_image::Callback callback) = 0;
430 
441  virtual Status removeIsolatedCallback(ground_surface::Callback callback) = 0;
442 
453  virtual Status removeIsolatedCallback(apriltag::Callback callback) = 0;
454 
465  virtual Status removeIsolatedCallback(feature_detector::Callback callback) = 0;
466 
485  virtual void *reserveCallbackBuffer() = 0;
486 
499  virtual Status releaseCallbackBuffer(void *referenceP) = 0;
500 
522  virtual Status networkTimeSynchronization(bool enabled) = 0;
523 
544  virtual Status ptpTimeSynchronization(bool enabled) = 0;
545 
565  virtual Status startStreams (DataSource mask) = 0;
566 
581  virtual Status stopStreams (DataSource mask) = 0;
582 
593  virtual Status getEnabledStreams(DataSource& mask) = 0;
594 
595 
608  virtual Status setTriggerSource (TriggerSource s) = 0;
609 
624  virtual Status setMotorSpeed (float rpm) = 0;
625 
637  virtual Status getLightingConfig (lighting::Config& c) = 0;
638 
650  virtual Status setLightingConfig (const lighting::Config& c) = 0;
651 
658  virtual Status getLightingSensorStatus (lighting::SensorStatus& status) = 0;
659 
669  virtual Status getSensorVersion (VersionType& version) = 0;
670 
680  virtual Status getApiVersion (VersionType& version) = 0;
681 
693  virtual Status getVersionInfo (system::VersionInfo& v) = 0;
694 
706  virtual Status getImageConfig (image::Config& c) = 0;
707 
719  virtual Status setImageConfig (const image::Config& c) = 0;
720 
730  virtual Status setRemoteHeadConfig (const image::RemoteHeadConfig& c) = 0;
731 
742  virtual Status getRemoteHeadConfig (image::RemoteHeadConfig& c) = 0;
743 
755  virtual Status getAuxImageConfig (image::AuxConfig& c) = 0;
756 
768  virtual Status setAuxImageConfig (const image::AuxConfig& c) = 0;
769 
782  virtual Status getImageCalibration (image::Calibration& c) = 0;
783 
795  virtual Status setImageCalibration (const image::Calibration& c) = 0;
796 
806  virtual Status getTransmitDelay (image::TransmitDelay& c) = 0;
807 
818  virtual Status setTransmitDelay (const image::TransmitDelay& c) = 0;
819 
829  virtual Status getPacketDelay (image::PacketDelay& c) = 0;
830 
842  virtual Status setPacketDelay (const image::PacketDelay& c) = 0;
843 
856  virtual Status getLidarCalibration (lidar::Calibration& c) = 0;
857 
869  virtual Status setLidarCalibration (const lidar::Calibration& c) = 0;
870 
887  virtual Status getImageHistogram (int64_t frameId, // from last 20 images, left only
888  image::Histogram& histogram) = 0;
889 
898  virtual Status getPtpStatus(system::PtpStatus &ptpStatus) = 0;
899 
900 
913  virtual Status getDeviceModes (std::vector<system::DeviceMode>& m) = 0;
914 
930  virtual Status getMtu (int32_t& mtu) = 0;
931 
944  virtual Status getMotorPos (int32_t& mtu) = 0;
945 
955  virtual Status setMtu (int32_t mtu) = 0;
956 
969  virtual Status getNetworkConfig (system::NetworkConfig& c) = 0;
970 
981  virtual Status setNetworkConfig (const system::NetworkConfig& c) = 0;
982 
995  virtual Status getDeviceInfo (system::DeviceInfo& info) = 0;
996 
1011  virtual Status setDeviceInfo (const std::string& key,
1012  const system::DeviceInfo& i) = 0;
1013 
1023  virtual Status getDeviceStatus (system::StatusMessage& status) = 0;
1024 
1033  virtual Status getExternalCalibration (system::ExternalCalibration& calibration) = 0;
1034 
1043  virtual Status setExternalCalibration (const system::ExternalCalibration& calibration) = 0;
1044 
1053  virtual Status setGroundSurfaceParams (const system::GroundSurfaceParams& params) = 0;
1054 
1063  virtual Status setApriltagParams (const system::ApriltagParams& params) = 0;
1064 
1073  virtual Status setFeatureDetectorConfig (const system::FeatureDetectorConfig& params) = 0;
1074 
1083  virtual Status getFeatureDetectorConfig (system::FeatureDetectorConfig& params) = 0;
1084 
1098  virtual Status flashBitstream (const std::string& file) = 0;
1099 
1113  virtual Status flashFirmware (const std::string& file) = 0;
1114 
1125  virtual Status verifyBitstream (const std::string& file) = 0;
1126 
1137  virtual Status verifyFirmware (const std::string& file) = 0;
1138 
1139  //
1140  // IMU configuration.
1141  //
1142  // Detailed info may be queried, and configuration may be queried or set.
1143  //
1144  // See imu::Details and imu::Config classes for more information.
1145  //
1146  // 'samplesPerMessage' is the number of samples (aggregate from all IMU types)
1147  // that the sensor will queue internally before putting on the wire.
1148  // Note that low settings combined with high IMU sensor rates may interfere
1149  // with the acquisition and transmission of image and lidar data.
1150  //
1151  // For setImuConfig():
1152  //
1153  // Set 'storeSettingsInFlash' to true to have the configuration saved in
1154  // non-volatile flash on the sensor head.
1155  //
1156  // Set 'samplesPerMessage' to zero for the sensor to keep its current
1157  // samplesPerMessage setting.
1158  //
1159  // IMU streams must be restarted for any configuration changes to be
1160  // reflected.
1161 
1177  virtual Status getImuInfo (uint32_t& maxSamplesPerMesage,
1178  std::vector<imu::Info>& info) = 0;
1179 
1196  virtual Status getImuConfig (uint32_t& samplesPerMessage,
1197  std::vector<imu::Config>& c) = 0;
1198 
1219  virtual Status setImuConfig (bool storeSettingsInFlash,
1220  uint32_t samplesPerMessage,
1221  const std::vector<imu::Config>& c) = 0;
1222 
1240  virtual Status getLargeBufferDetails(uint32_t& bufferCount,
1241  uint32_t& bufferSize) = 0;
1262  virtual Status setLargeBuffers (const std::vector<uint8_t*>& buffers,
1263  uint32_t bufferSize) = 0;
1264 
1274  virtual Status getLocalUdpPort(uint16_t& port) = 0;
1275 
1282  virtual system::ChannelStatistics getStats() = 0;
1283 };
1284 
1285 
1286 } // namespace multisense
1287 } // namespace crl
1288 
1289 #endif // LibMultiSense_MultiSenseChannel_hh
crl::multisense::Channel
Class which manages all communications with a MultiSense device.
Definition: MultiSenseChannel.hh:69
crl::multisense::system::PtpStatus
PTP status data associated with a specific stamped MultiSense message.
Definition: MultiSenseTypes.hh:4075
crl::multisense::image::Calibration
Class used For querying/setting camera calibration.
Definition: MultiSenseTypes.hh:1867
crl::multisense::image::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks of image data.
Definition: MultiSenseTypes.hh:506
crl::multisense::VersionType
uint32_t VersionType
Sensor version typedef used to store a given version number.
Definition: MultiSenseTypes.hh:87
MULTISENSE_API
#define MULTISENSE_API
Definition: MultiSenseTypes.hh:65
crl::multisense::feature_detector::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks for feature_detector data.
Definition: MultiSenseTypes.hh:3024
crl::multisense::lidar::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks of lidar data.
Definition: MultiSenseTypes.hh:2069
crl::multisense::image::PacketDelay
Definition: MultiSenseTypes.hh:1903
crl::multisense::system::ChannelStatistics
A struct for storing statistics for a channel object.
Definition: MultiSenseTypes.hh:4104
crl::multisense::system::FeatureDetectorConfig
Example code showing usage of the onboard feature detector.
Definition: MultiSenseTypes.hh:3959
crl::multisense::system::DeviceInfo
Class used to store device information specific to a sensor.
Definition: MultiSenseTypes.hh:3211
crl::multisense::image::Histogram
Class which stores a image histogram from a camera image.
Definition: MultiSenseTypes.hh:1949
crl::multisense::image::RemoteHeadConfig
Definition: MultiSenseTypes.hh:1968
MultiSenseTypes.hh
crl::multisense::lidar::Calibration
Class used to store a laser calibration.
Definition: MultiSenseTypes.hh:2152
crl
Definition: MultiSenseChannel.hh:46
crl::multisense::imu::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks for IMU data.
Definition: MultiSenseTypes.hh:2619
crl::multisense::system::StatusMessage
Class containing status information for a particular device.
Definition: MultiSenseTypes.hh:3460
crl::multisense::DataSource
uint64_t DataSource
Data sources typedef representing the various data sources available from sensors in the MultiSense-S...
Definition: MultiSenseTypes.hh:114
crl::multisense::image::AuxConfig
Definition: MultiSenseTypes.hh:1348
crl::multisense::lighting::Config
Class used to store a specific lighting configuration.
Definition: MultiSenseTypes.hh:2257
crl::multisense::ground_surface::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks for Ground Surface Spline data.
Definition: MultiSenseTypes.hh:2917
crl::multisense::system::GroundSurfaceParams
Class containing parameters for the ground surface modeling and obstacle detection application which ...
Definition: MultiSenseTypes.hh:3706
crl::multisense::system::ExternalCalibration
A external calibration associated with the MultiSense.
Definition: MultiSenseTypes.hh:3623
crl::multisense::TriggerSource
uint32_t TriggerSource
Definition: MultiSenseTypes.hh:265
crl::multisense::compressed_image::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks for compressed image data.
Definition: MultiSenseTypes.hh:2866
crl::multisense::Status
int32_t Status
General status typdef used as a return value for get/set crl::multisense::Channel methods.
Definition: MultiSenseTypes.hh:93
crl::multisense::pps::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks for PPS events.
Definition: MultiSenseTypes.hh:2532
crl::multisense::Channel::~Channel
virtual ~Channel()
Destructor.
Definition: MultiSenseChannel.hh:143
crl::multisense::system::NetworkConfig
Class containing the network configuration for a specific sensor.
Definition: MultiSenseTypes.hh:3389
crl::multisense::image::TransmitDelay
Definition: MultiSenseTypes.hh:1895
crl::multisense::system::VersionInfo
Class containing version info for a specific sensor.
Definition: MultiSenseTypes.hh:3125
crl::multisense::system::ApriltagParams
Class containing parameters for the apriltag fiduciual detection algorithm application which may be r...
Definition: MultiSenseTypes.hh:3844
crl::multisense::lighting::SensorStatus
A external sensor status.
Definition: MultiSenseTypes.hh:2491
crl::multisense::image::Config
Class used to store a specific camera configuration.
Definition: MultiSenseTypes.hh:790
crl::multisense::RemoteHeadChannel
int16_t RemoteHeadChannel
Remote head channel defines which channel is used to communicate to a specific component in the Remot...
Definition: MultiSenseTypes.hh:206
crl::multisense::apriltag::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks for apriltag data.
Definition: MultiSenseTypes.hh:2973