Class OpenNI2DeviceManager
Defined in File openni2_device_manager.h
Class Documentation
-
class OpenNI2DeviceManager
Public Functions
-
OpenNI2DeviceManager()
-
virtual ~OpenNI2DeviceManager()
-
std::shared_ptr<std::vector<OpenNI2DeviceInfo>> getConnectedDeviceInfos() const
-
std::shared_ptr<std::vector<std::string>> getConnectedDeviceURIs() const
-
std::size_t getNumOfConnectedDevices() const
-
std::shared_ptr<OpenNI2Device> getAnyDevice(rclcpp::Node *node)
-
std::shared_ptr<OpenNI2Device> getDevice(const std::string &device_URI, rclcpp::Node *node)
-
std::string getSerial(const std::string &device_URI) const
Public Static Functions
-
static std::shared_ptr<OpenNI2DeviceManager> getSingelton()
Protected Attributes
-
std::shared_ptr<OpenNI2DeviceListener> device_listener_
Protected Static Attributes
-
static std::shared_ptr<OpenNI2DeviceManager> singelton_
-
OpenNI2DeviceManager()