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


astra_camera
Author(s): Tim Liu
autogenerated on Wed Jul 10 2019 03:18:54