Go to the documentation of this file.
32 #ifndef OPENNI2_DEVICE_H
33 #define OPENNI2_DEVICE_H
39 #include <boost/shared_ptr.hpp>
40 #include <boost/cstdint.hpp>
41 #include <boost/bind.hpp>
42 #include <boost/function.hpp>
44 #include <sensor_msgs/Image.h>
70 const std::string
getUri()
const;
72 const std::string
getName()
const;
const OpenNI2VideoMode getIRVideoMode()
bool hasColorSensor() const
boost::shared_ptr< openni::VideoStream > ir_video_stream_
const OpenNI2VideoMode getDepthVideoMode()
bool image_registration_activated_
bool isImageRegistrationModeSupported() const
bool getAutoExposure() const
const std::vector< OpenNI2VideoMode > & getSupportedColorVideoModes() const
bool color_video_started_
std::vector< OpenNI2VideoMode > ir_video_modes_
const std::string getUri() const
void setDepthColorSync(bool enabled)
bool isDepthVideoModeSupported(const OpenNI2VideoMode &video_mode) const
const std::string getName() const
bool getAutoWhiteBalance() const
boost::shared_ptr< openni::VideoStream > depth_video_stream_
bool isIRVideoModeSupported(const OpenNI2VideoMode &video_mode) const
boost::shared_ptr< OpenNI2FrameListener > ir_frame_listener
float getIRFocalLength(int output_y_resolution) const
std::ostream & operator<<(std::ostream &stream, const OpenNI2Device &device)
const std::vector< OpenNI2VideoMode > & getSupportedIRVideoModes() const
void setColorVideoMode(const OpenNI2VideoMode &video_mode)
boost::shared_ptr< OpenNI2FrameListener > color_frame_listener
void setAutoWhiteBalance(bool enable)
OpenNI2Device(const std::string &device_URI)
void setDepthFrameCallback(FrameCallbackFunction callback)
void setUseDeviceTimer(bool enable)
bool isColorVideoModeSupported(const OpenNI2VideoMode &video_mode) const
float getDepthFocalLength(int output_y_resolution) const
void setExposure(int exposure)
boost::shared_ptr< openni::VideoStream > getDepthVideoStream() const
float getColorFocalLength(int output_y_resolution) const
bool hasDepthSensor() const
const std::string getVendor() const
bool isDepthStreamStarted()
boost::shared_ptr< openni::VideoStream > color_video_stream_
void setImageRegistrationMode(bool enabled)
std::vector< OpenNI2VideoMode > color_video_modes_
void setDepthVideoMode(const OpenNI2VideoMode &video_mode)
void setIRVideoMode(const OpenNI2VideoMode &video_mode)
uint16_t getUsbProductId() const
void setAutoExposure(bool enable)
boost::function< void(sensor_msgs::ImagePtr image)> FrameCallbackFunction
void setColorFrameCallback(FrameCallbackFunction callback)
const OpenNI2VideoMode getColorVideoMode()
boost::shared_ptr< openni::VideoStream > getColorVideoStream() const
boost::shared_ptr< openni::VideoStream > getIRVideoStream() const
uint16_t getUsbVendorId() const
float getBaseline() const
boost::shared_ptr< openni::Device > openni_device_
const std::string getStringID() const
void setIRFrameCallback(FrameCallbackFunction callback)
std::vector< OpenNI2VideoMode > depth_video_modes_
const std::vector< OpenNI2VideoMode > & getSupportedDepthVideoModes() const
bool depth_video_started_
boost::shared_ptr< OpenNI2FrameListener > depth_frame_listener
bool isColorStreamStarted()
boost::shared_ptr< openni::DeviceInfo > device_info_
openni2_camera
Author(s): Julius Kammerl
autogenerated on Thu Oct 26 2023 02:33:32