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;
376  virtual Status addIsolatedCallback(secondary_app::Callback callback,
377  void *userDataP=NULL) = 0;
378 
389  virtual Status removeIsolatedCallback(image::Callback callback) = 0;
390 
401  virtual Status removeIsolatedCallback(lidar::Callback callback) = 0;
402 
413  virtual Status removeIsolatedCallback(pps::Callback callback) = 0;
414 
425  virtual Status removeIsolatedCallback(imu::Callback callback) = 0;
426 
437  virtual Status removeIsolatedCallback(compressed_image::Callback callback) = 0;
438 
449  virtual Status removeIsolatedCallback(ground_surface::Callback callback) = 0;
450 
461  virtual Status removeIsolatedCallback(apriltag::Callback callback) = 0;
462 
472  virtual Status removeIsolatedCallback(secondary_app::Callback callback) = 0;
473 
492  virtual void *reserveCallbackBuffer() = 0;
493 
506  virtual Status releaseCallbackBuffer(void *referenceP) = 0;
507 
529  virtual Status networkTimeSynchronization(bool enabled) = 0;
530 
551  virtual Status ptpTimeSynchronization(bool enabled) = 0;
552 
572  virtual Status startStreams (DataSource mask) = 0;
573 
588  virtual Status stopStreams (DataSource mask) = 0;
589 
600  virtual Status getEnabledStreams(DataSource& mask) = 0;
601 
602 
615  virtual Status setTriggerSource (TriggerSource s) = 0;
616 
631  virtual Status setMotorSpeed (float rpm) = 0;
632 
644  virtual Status getLightingConfig (lighting::Config& c) = 0;
645 
657  virtual Status setLightingConfig (const lighting::Config& c) = 0;
658 
665  virtual Status getLightingSensorStatus (lighting::SensorStatus& status) = 0;
666 
676  virtual Status getSensorVersion (VersionType& version) = 0;
677 
687  virtual Status getApiVersion (VersionType& version) = 0;
688 
700  virtual Status getVersionInfo (system::VersionInfo& v) = 0;
701 
713  virtual Status getImageConfig (image::Config& c) = 0;
714 
726  virtual Status setImageConfig (const image::Config& c) = 0;
727 
737  virtual Status setRemoteHeadConfig (const image::RemoteHeadConfig& c) = 0;
738 
749  virtual Status getRemoteHeadConfig (image::RemoteHeadConfig& c) = 0;
750 
762  virtual Status getAuxImageConfig (image::AuxConfig& c) = 0;
763 
775  virtual Status setAuxImageConfig (const image::AuxConfig& c) = 0;
776 
789  virtual Status getImageCalibration (image::Calibration& c) = 0;
790 
802  virtual Status setImageCalibration (const image::Calibration& c) = 0;
803 
813  virtual Status getTransmitDelay (image::TransmitDelay& c) = 0;
814 
825  virtual Status setTransmitDelay (const image::TransmitDelay& c) = 0;
826 
836  virtual Status getPacketDelay (image::PacketDelay& c) = 0;
837 
849  virtual Status setPacketDelay (const image::PacketDelay& c) = 0;
850 
863  virtual Status getLidarCalibration (lidar::Calibration& c) = 0;
864 
876  virtual Status setLidarCalibration (const lidar::Calibration& c) = 0;
877 
894  virtual Status getImageHistogram (int64_t frameId, // from last 20 images, left only
895  image::Histogram& histogram) = 0;
896 
905  virtual Status getPtpStatus(system::PtpStatus &ptpStatus) = 0;
906 
907 
920  virtual Status getDeviceModes (std::vector<system::DeviceMode>& m) = 0;
921 
937  virtual Status getMtu (int32_t& mtu) = 0;
938 
951  virtual Status getMotorPos (int32_t& mtu) = 0;
952 
962  virtual Status setMtu (int32_t mtu) = 0;
963 
972  virtual Status setBestMtu () = 0;
973 
986  virtual Status getNetworkConfig (system::NetworkConfig& c) = 0;
987 
998  virtual Status setNetworkConfig (const system::NetworkConfig& c) = 0;
999 
1012  virtual Status getDeviceInfo (system::DeviceInfo& info) = 0;
1013 
1028  virtual Status setDeviceInfo (const std::string& key,
1029  const system::DeviceInfo& i) = 0;
1030 
1040  virtual Status getDeviceStatus (system::StatusMessage& status) = 0;
1041 
1050  virtual Status getExternalCalibration (system::ExternalCalibration& calibration) = 0;
1051 
1060  virtual Status setExternalCalibration (const system::ExternalCalibration& calibration) = 0;
1061 
1070  virtual Status setGroundSurfaceParams (const system::GroundSurfaceParams& params) = 0;
1071 
1080  virtual Status setApriltagParams (const system::ApriltagParams& params) = 0;
1081 
1089  virtual Status getSecondaryAppConfig (system::SecondaryAppConfig & c) = 0;
1090 
1099  virtual Status setSecondaryAppConfig (system::SecondaryAppConfig & c) = 0;
1100 
1108  virtual Status getRegisteredApps (system::SecondaryAppRegisteredApps & c) = 0;
1109 
1117  virtual Status secondaryAppActivate (const std::string & name) = 0;
1118 
1126  virtual Status secondaryAppDeactivate(const std::string & s) = 0;
1127 
1128  //
1129  // IMU configuration.
1130  //
1131  // Detailed info may be queried, and configuration may be queried or set.
1132  //
1133  // See imu::Details and imu::Config classes for more information.
1134  //
1135  // 'samplesPerMessage' is the number of samples (aggregate from all IMU types)
1136  // that the sensor will queue internally before putting on the wire.
1137  // Note that low settings combined with high IMU sensor rates may interfere
1138  // with the acquisition and transmission of image and lidar data.
1139  //
1140  // For setImuConfig():
1141  //
1142  // Set 'storeSettingsInFlash' to true to have the configuration saved in
1143  // non-volatile flash on the sensor head.
1144  //
1145  // Set 'samplesPerMessage' to zero for the sensor to keep its current
1146  // samplesPerMessage setting.
1147  //
1148  // IMU streams must be restarted for any configuration changes to be
1149  // reflected.
1150 
1166  virtual Status getImuInfo (uint32_t& maxSamplesPerMesage,
1167  std::vector<imu::Info>& info) = 0;
1168 
1185  virtual Status getImuConfig (uint32_t& samplesPerMessage,
1186  std::vector<imu::Config>& c) = 0;
1187 
1208  virtual Status setImuConfig (bool storeSettingsInFlash,
1209  uint32_t samplesPerMessage,
1210  const std::vector<imu::Config>& c) = 0;
1211 
1229  virtual Status getLargeBufferDetails(uint32_t& bufferCount,
1230  uint32_t& bufferSize) = 0;
1251  virtual Status setLargeBuffers (const std::vector<uint8_t*>& buffers,
1252  uint32_t bufferSize) = 0;
1253 
1263  virtual Status getLocalUdpPort(uint16_t& port) = 0;
1264 
1271  virtual system::ChannelStatistics getStats() = 0;
1272 };
1273 
1274 
1275 } // namespace multisense
1276 } // namespace crl
1277 
1278 #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:3940
crl::multisense::secondary_app::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks for apriltag data.
Definition: MultiSenseTypes.hh:3060
crl::multisense::image::Calibration
Class used For querying/setting camera calibration.
Definition: MultiSenseTypes.hh:1910
crl::multisense::image::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks of image data.
Definition: MultiSenseTypes.hh:513
crl::multisense::VersionType
uint32_t VersionType
Sensor version typedef used to store a given version number.
Definition: MultiSenseTypes.hh:88
crl::multisense::lidar::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks of lidar data.
Definition: MultiSenseTypes.hh:2112
crl::multisense::image::PacketDelay
Definition: MultiSenseTypes.hh:1946
crl::multisense::system::ChannelStatistics
A struct for storing statistics for a channel object.
Definition: MultiSenseTypes.hh:3972
MultiSenseTypes.hh
crl::multisense::system::DeviceInfo
Class used to store device information specific to a sensor.
Definition: MultiSenseTypes.hh:3245
crl::multisense::image::Histogram
Class which stores a image histogram from a camera image.
Definition: MultiSenseTypes.hh:1992
crl::multisense::image::RemoteHeadConfig
Definition: MultiSenseTypes.hh:2011
crl::multisense::lidar::Calibration
Class used to store a laser calibration.
Definition: MultiSenseTypes.hh:2195
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:2662
crl::multisense::system::StatusMessage
Class containing status information for a particular device.
Definition: MultiSenseTypes.hh:3496
crl::multisense::DataSource
uint64_t DataSource
Data sources typedef representing the various data sources available from sensors in the MultiSense-S...
Definition: MultiSenseTypes.hh:115
crl::multisense::system::SecondaryAppConfig
Definition: MultiSenseTypes.hh:4040
crl::multisense::image::AuxConfig
Definition: MultiSenseTypes.hh:1373
crl::multisense::lighting::Config
Class used to store a specific lighting configuration.
Definition: MultiSenseTypes.hh:2300
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:2960
crl::multisense::system::GroundSurfaceParams
Class containing parameters for the ground surface modeling and obstacle detection application which ...
Definition: MultiSenseTypes.hh:3742
crl::multisense::system::ExternalCalibration
A external calibration associated with the MultiSense.
Definition: MultiSenseTypes.hh:3659
crl::multisense::TriggerSource
uint32_t TriggerSource
Definition: MultiSenseTypes.hh:272
crl::multisense::compressed_image::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks for compressed image data.
Definition: MultiSenseTypes.hh:2909
crl::multisense::Status
int32_t Status
General status typdef used as a return value for get/set crl::multisense::Channel methods.
Definition: MultiSenseTypes.hh:94
MULTISENSE_API
#define MULTISENSE_API
Definition: MultiSenseTypes.hh:66
crl::multisense::pps::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks for PPS events.
Definition: MultiSenseTypes.hh:2575
multisense
Definition: MultiSenseChannel.hh:44
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:3425
crl::multisense::image::TransmitDelay
Definition: MultiSenseTypes.hh:1938
crl::multisense::system::VersionInfo
Class containing version info for a specific sensor.
Definition: MultiSenseTypes.hh:3159
crl::multisense::system::SecondaryAppRegisteredApps
Definition: MultiSenseTypes.hh:4093
crl::multisense::system::ApriltagParams
Class containing parameters for the apriltag fiduciual detection algorithm application which may be r...
Definition: MultiSenseTypes.hh:3880
crl::multisense::lighting::SensorStatus
A external sensor status.
Definition: MultiSenseTypes.hh:2534
crl::multisense::image::Config
Class used to store a specific camera configuration.
Definition: MultiSenseTypes.hh:797
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:210
crl::multisense::apriltag::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks for apriltag data.
Definition: MultiSenseTypes.hh:3016