00001 /* 00002 * Copyright (c) 2013, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 * 00029 * Author: Julius Kammerl (jkammerl@willowgarage.com) 00030 */ 00031 00032 #ifndef OPENNI2_DEVICE_H 00033 #define OPENNI2_DEVICE_H 00034 00035 #include "openni2_camera/openni2_video_mode.h" 00036 00037 #include "openni2_camera/openni2_exception.h" 00038 00039 #include <boost/shared_ptr.hpp> 00040 #include <boost/cstdint.hpp> 00041 #include <boost/bind.hpp> 00042 #include <boost/function.hpp> 00043 00044 #include <sensor_msgs/Image.h> 00045 00046 #include <string> 00047 #include <vector> 00048 00049 namespace openni 00050 { 00051 class Device; 00052 class DeviceInfo; 00053 class VideoStream; 00054 class SensorInfo; 00055 } 00056 00057 namespace openni2_wrapper 00058 { 00059 00060 typedef boost::function<void(sensor_msgs::ImagePtr image)> FrameCallbackFunction; 00061 00062 class OpenNI2FrameListener; 00063 00064 class OpenNI2Device 00065 { 00066 public: 00067 OpenNI2Device(const std::string& device_URI) throw (OpenNI2Exception); 00068 virtual ~OpenNI2Device(); 00069 00070 const std::string getUri() const; 00071 const std::string getVendor() const; 00072 const std::string getName() const; 00073 uint16_t getUsbVendorId() const; 00074 uint16_t getUsbProductId() const; 00075 00076 const std::string getStringID() const; 00077 00078 bool isValid() const; 00079 00080 bool hasIRSensor() const; 00081 bool hasColorSensor() const; 00082 bool hasDepthSensor() const; 00083 00084 void startIRStream(); 00085 void startColorStream(); 00086 void startDepthStream(); 00087 00088 void stopAllStreams(); 00089 00090 void stopIRStream(); 00091 void stopColorStream(); 00092 void stopDepthStream(); 00093 00094 bool isIRStreamStarted(); 00095 bool isColorStreamStarted(); 00096 bool isDepthStreamStarted(); 00097 00098 bool isImageRegistrationModeSupported() const; 00099 void setImageRegistrationMode(bool enabled) throw (OpenNI2Exception); 00100 void setDepthColorSync(bool enabled) throw (OpenNI2Exception); 00101 00102 const OpenNI2VideoMode getIRVideoMode() throw (OpenNI2Exception); 00103 const OpenNI2VideoMode getColorVideoMode() throw (OpenNI2Exception); 00104 const OpenNI2VideoMode getDepthVideoMode() throw (OpenNI2Exception); 00105 00106 const std::vector<OpenNI2VideoMode>& getSupportedIRVideoModes() const; 00107 const std::vector<OpenNI2VideoMode>& getSupportedColorVideoModes() const; 00108 const std::vector<OpenNI2VideoMode>& getSupportedDepthVideoModes() const; 00109 00110 bool isIRVideoModeSupported(const OpenNI2VideoMode& video_mode) const; 00111 bool isColorVideoModeSupported(const OpenNI2VideoMode& video_mode) const; 00112 bool isDepthVideoModeSupported(const OpenNI2VideoMode& video_mode) const; 00113 00114 void setIRVideoMode(const OpenNI2VideoMode& video_mode) throw (OpenNI2Exception); 00115 void setColorVideoMode(const OpenNI2VideoMode& video_mode) throw (OpenNI2Exception); 00116 void setDepthVideoMode(const OpenNI2VideoMode& video_mode) throw (OpenNI2Exception); 00117 00118 void setIRFrameCallback(FrameCallbackFunction callback); 00119 void setColorFrameCallback(FrameCallbackFunction callback); 00120 void setDepthFrameCallback(FrameCallbackFunction callback); 00121 00122 float getIRFocalLength (int output_y_resolution) const; 00123 float getColorFocalLength (int output_y_resolution) const; 00124 float getDepthFocalLength (int output_y_resolution) const; 00125 00126 void setAutoExposure(bool enable) throw (OpenNI2Exception); 00127 void setAutoWhiteBalance(bool enable) throw (OpenNI2Exception); 00128 00129 bool getAutoExposure() const; 00130 bool getAutoWhiteBalance() const; 00131 00132 void setUseDeviceTimer(bool enable); 00133 00134 protected: 00135 void shutdown(); 00136 00137 boost::shared_ptr<openni::VideoStream> getIRVideoStream() const throw (OpenNI2Exception); 00138 boost::shared_ptr<openni::VideoStream> getColorVideoStream() const throw (OpenNI2Exception); 00139 boost::shared_ptr<openni::VideoStream> getDepthVideoStream() const throw (OpenNI2Exception); 00140 00141 boost::shared_ptr<openni::Device> openni_device_; 00142 boost::shared_ptr<openni::DeviceInfo> device_info_; 00143 00144 boost::shared_ptr<OpenNI2FrameListener> ir_frame_listener; 00145 boost::shared_ptr<OpenNI2FrameListener> color_frame_listener; 00146 boost::shared_ptr<OpenNI2FrameListener> depth_frame_listener; 00147 00148 mutable boost::shared_ptr<openni::VideoStream> ir_video_stream_; 00149 mutable boost::shared_ptr<openni::VideoStream> color_video_stream_; 00150 mutable boost::shared_ptr<openni::VideoStream> depth_video_stream_; 00151 00152 mutable std::vector<OpenNI2VideoMode> ir_video_modes_; 00153 mutable std::vector<OpenNI2VideoMode> color_video_modes_; 00154 mutable std::vector<OpenNI2VideoMode> depth_video_modes_; 00155 00156 bool ir_video_started_; 00157 bool color_video_started_; 00158 bool depth_video_started_; 00159 00160 bool image_registration_activated_; 00161 00162 bool use_device_time_; 00163 00164 }; 00165 00166 std::ostream& operator << (std::ostream& stream, const OpenNI2Device& device); 00167 00168 } 00169 00170 #endif /* OPENNI_DEVICE_H */