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;
71 const std::string getVendor()
const;
72 const std::string
getName()
const;
73 uint16_t getUsbVendorId()
const;
74 uint16_t getUsbProductId()
const;
76 const std::string getStringID()
const;
80 bool hasIRSensor()
const;
81 bool hasColorSensor()
const;
82 bool hasDepthSensor()
const;
85 void startColorStream();
86 void startDepthStream();
88 void stopAllStreams();
91 void stopColorStream();
92 void stopDepthStream();
94 bool isIRStreamStarted();
95 bool isColorStreamStarted();
96 bool isDepthStreamStarted();
98 bool isImageRegistrationModeSupported()
const;
106 const std::vector<OpenNI2VideoMode>& getSupportedIRVideoModes()
const;
107 const std::vector<OpenNI2VideoMode>& getSupportedColorVideoModes()
const;
108 const std::vector<OpenNI2VideoMode>& getSupportedDepthVideoModes()
const;
118 void setIRFrameCallback(FrameCallbackFunction callback);
119 void setColorFrameCallback(FrameCallbackFunction callback);
120 void setDepthFrameCallback(FrameCallbackFunction callback);
122 float getIRFocalLength (
int output_y_resolution)
const;
123 float getColorFocalLength (
int output_y_resolution)
const;
124 float getDepthFocalLength (
int output_y_resolution)
const;
125 float getBaseline ()
const;
131 bool getAutoExposure()
const;
132 bool getAutoWhiteBalance()
const;
133 int getExposure()
const;
135 void setUseDeviceTimer(
bool enable);
std::ostream & operator<<(std::ostream &stream, const OpenNI2Device &device)
boost::function< void(sensor_msgs::ImagePtr image)> FrameCallbackFunction
boost::shared_ptr< openni::VideoStream > depth_video_stream_
boost::shared_ptr< openni::VideoStream > color_video_stream_
bool depth_video_started_
std::vector< OpenNI2VideoMode > ir_video_modes_
std::string getName(void *handle)
bool color_video_started_
std::vector< OpenNI2VideoMode > color_video_modes_
bool image_registration_activated_
boost::shared_ptr< OpenNI2FrameListener > ir_frame_listener
boost::shared_ptr< OpenNI2FrameListener > color_frame_listener
boost::shared_ptr< OpenNI2FrameListener > depth_frame_listener
boost::shared_ptr< openni::Device > openni_device_
boost::shared_ptr< openni::VideoStream > ir_video_stream_
boost::shared_ptr< openni::DeviceInfo > device_info_
std::vector< OpenNI2VideoMode > depth_video_modes_