Class OpenNI2Device

Class Documentation

class OpenNI2Device

Public Functions

OpenNI2Device(const std::string &device_URI, rclcpp::Node *node)
virtual ~OpenNI2Device()
const std::string getUri() const
const std::string getVendor() const
const std::string getName() const
uint16_t getUsbVendorId() const
uint16_t getUsbProductId() const
const std::string getStringID() const
bool isValid() const
bool hasIRSensor() const
bool hasColorSensor() const
bool hasDepthSensor() const
void startIRStream()
void startColorStream()
void startDepthStream()
void stopAllStreams()
void stopIRStream()
void stopColorStream()
void stopDepthStream()
bool isIRStreamStarted()
bool isColorStreamStarted()
bool isDepthStreamStarted()
bool isImageRegistrationModeSupported() const
void setImageRegistrationMode(bool enabled)
void setDepthColorSync(bool enabled)
const OpenNI2VideoMode getIRVideoMode()
const OpenNI2VideoMode getColorVideoMode()
const OpenNI2VideoMode getDepthVideoMode()
const std::vector<OpenNI2VideoMode> &getSupportedIRVideoModes() const
const std::vector<OpenNI2VideoMode> &getSupportedColorVideoModes() const
const std::vector<OpenNI2VideoMode> &getSupportedDepthVideoModes() const
bool isIRVideoModeSupported(const OpenNI2VideoMode &video_mode) const
bool isColorVideoModeSupported(const OpenNI2VideoMode &video_mode) const
bool isDepthVideoModeSupported(const OpenNI2VideoMode &video_mode) const
void setIRVideoMode(const OpenNI2VideoMode &video_mode)
void setColorVideoMode(const OpenNI2VideoMode &video_mode)
void setDepthVideoMode(const OpenNI2VideoMode &video_mode)
void setIRFrameCallback(FrameCallbackFunction callback)
void setColorFrameCallback(FrameCallbackFunction callback)
void setDepthFrameCallback(FrameCallbackFunction callback)
float getIRFocalLength(int output_y_resolution) const
float getColorFocalLength(int output_y_resolution) const
float getDepthFocalLength(int output_y_resolution) const
float getBaseline() const
void setAutoExposure(bool enable)
void setAutoWhiteBalance(bool enable)
void setExposure(int exposure)
bool getAutoExposure() const
bool getAutoWhiteBalance() const
int getExposure() const
void setUseDeviceTimer(bool enable)

Protected Functions

void shutdown()
std::shared_ptr<openni::VideoStream> getIRVideoStream() const
std::shared_ptr<openni::VideoStream> getColorVideoStream() const
std::shared_ptr<openni::VideoStream> getDepthVideoStream() const

Protected Attributes

std::shared_ptr<openni::Device> openni_device_
std::shared_ptr<openni::DeviceInfo> device_info_
std::shared_ptr<OpenNI2FrameListener> ir_frame_listener
std::shared_ptr<OpenNI2FrameListener> color_frame_listener
std::shared_ptr<OpenNI2FrameListener> depth_frame_listener
mutable std::shared_ptr<openni::VideoStream> ir_video_stream_
mutable std::shared_ptr<openni::VideoStream> color_video_stream_
mutable std::shared_ptr<openni::VideoStream> depth_video_stream_
mutable std::vector<OpenNI2VideoMode> ir_video_modes_
mutable std::vector<OpenNI2VideoMode> color_video_modes_
mutable std::vector<OpenNI2VideoMode> depth_video_modes_
bool ir_video_started_
bool color_video_started_
bool depth_video_started_
bool image_registration_activated_