astra_device.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Willow Garage, Inc.
3  * Copyright (c) 2016, Orbbec Ltd.
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * * Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  * * Neither the name of the Willow Garage, Inc. nor the names of its
15  * contributors may be used to endorse or promote products derived from
16  * this software without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  * POSSIBILITY OF SUCH DAMAGE.
29  *
30  * Author: Tim Liu (liuhua@orbbec.com)
31  */
32 
33 #ifndef ASTRA_DEVICE_H
34 #define ASTRA_DEVICE_H
35 
37 
40 
41 #include <openni2/OpenNI.h>
42 
43 #include <boost/shared_ptr.hpp>
44 #include <boost/cstdint.hpp>
45 #include <boost/bind.hpp>
46 #include <boost/function.hpp>
47 
48 #include <sensor_msgs/Image.h>
49 
50 #include <string>
51 #include <vector>
52 
53 namespace openni
54 {
55 class Device;
56 class DeviceInfo;
57 class VideoStream;
58 class SensorInfo;
59 }
60 
61 namespace astra_wrapper
62 {
63 
64 typedef boost::function<void(sensor_msgs::ImagePtr image)> FrameCallbackFunction;
65 
66 class AstraFrameListener;
67 
69 {
70 public:
71  AstraDevice(const std::string& device_URI);
72  virtual ~AstraDevice();
73 
74  const std::string getUri() const;
75  const std::string getVendor() const;
76  const std::string getName() const;
77  uint16_t getUsbVendorId() const;
78  uint16_t getUsbProductId() const;
79 
80  const std::string getStringID() const;
81 
82  bool isValid() const;
83 
84  bool hasIRSensor() const;
85  bool hasColorSensor() const;
86  bool hasDepthSensor() const;
87 
88  void startIRStream();
89  void startColorStream();
90  void startDepthStream();
91 
92  void stopAllStreams();
93 
94  void stopIRStream();
95  void stopColorStream();
96  void stopDepthStream();
97 
98  bool isIRStreamStarted();
99  bool isColorStreamStarted();
100  bool isDepthStreamStarted();
101 
102  bool isImageRegistrationModeSupported() const;
103  void setImageRegistrationMode(bool enabled);
104  void setDepthColorSync(bool enabled);
105 
106  const AstraVideoMode getIRVideoMode();
107  const AstraVideoMode getColorVideoMode();
108  const AstraVideoMode getDepthVideoMode();
109 
110  const std::vector<AstraVideoMode>& getSupportedIRVideoModes() const;
111  const std::vector<AstraVideoMode>& getSupportedColorVideoModes() const;
112  const std::vector<AstraVideoMode>& getSupportedDepthVideoModes() const;
113 
114  bool isIRVideoModeSupported(const AstraVideoMode& video_mode) const;
115  bool isColorVideoModeSupported(const AstraVideoMode& video_mode) const;
116  bool isDepthVideoModeSupported(const AstraVideoMode& video_mode) const;
117 
118  void setIRVideoMode(const AstraVideoMode& video_mode);
119  void setColorVideoMode(const AstraVideoMode& video_mode);
120  void setDepthVideoMode(const AstraVideoMode& video_mode);
121 
122  void setIRFrameCallback(FrameCallbackFunction callback);
123  void setColorFrameCallback(FrameCallbackFunction callback);
124  void setDepthFrameCallback(FrameCallbackFunction callback);
125 
126  float getIRFocalLength (int output_y_resolution) const;
127  float getColorFocalLength (int output_y_resolution) const;
128  float getDepthFocalLength (int output_y_resolution) const;
129  float getBaseline () const;
130  OBCameraParams getCameraParams() const;
131  bool isCameraParamsValid();
132  char* getSerialNumber();
133  char* getDeviceType();
134  OB_DEVICE_NO getDeviceTypeNo();
135  int getIRGain() const;
136  int getIRExposure() const;
137 
138  void setCameraParams(OBCameraParams param);
139  void setIRGain(int gain);
140  void setIRExposure(int exposure);
141  void setLaser(bool enable);
142  void setIRFlood(bool enable);
143  void setLDP(bool enable);
144 
145  void switchIRCamera(int cam);
146 
147  void setAutoExposure(bool enable);
148  void setAutoWhiteBalance(bool enable);
149 
150  bool getAutoExposure() const;
151  bool getAutoWhiteBalance() const;
152 
153  void setUseDeviceTimer(bool enable);
154 
155 protected:
156  void shutdown();
157 
158  boost::shared_ptr<openni::VideoStream> getIRVideoStream() const;
159  boost::shared_ptr<openni::VideoStream> getColorVideoStream() const;
160  boost::shared_ptr<openni::VideoStream> getDepthVideoStream() const;
161 
164 
168 
172 
173  mutable std::vector<AstraVideoMode> ir_video_modes_;
174  mutable std::vector<AstraVideoMode> color_video_modes_;
175  mutable std::vector<AstraVideoMode> depth_video_modes_;
176 
180 
182 
184 
187  char serial_number[12];
188  char device_type[32];
190 };
191 
192 std::ostream& operator << (std::ostream& stream, const AstraDevice& device);
193 
194 }
195 
196 #endif /* OPENNI_DEVICE_H */
bool param(const std::string &param_name, T &param_val, const T &default_val)
boost::shared_ptr< AstraFrameListener > ir_frame_listener
Definition: astra_device.h:165
boost::shared_ptr< AstraFrameListener > depth_frame_listener
Definition: astra_device.h:167
boost::shared_ptr< openni::VideoStream > depth_video_stream_
Definition: astra_device.h:171
unsigned short uint16_t
boost::shared_ptr< AstraFrameListener > color_frame_listener
Definition: astra_device.h:166
std::string getName(void *handle)
std::vector< AstraVideoMode > ir_video_modes_
Definition: astra_device.h:173
OBCameraParams m_CamParams
Definition: astra_device.h:185
std::vector< AstraVideoMode > color_video_modes_
Definition: astra_device.h:174
void callback(const sensor_msgs::ImageConstPtr &msg)
boost::shared_ptr< openni::VideoStream > color_video_stream_
Definition: astra_device.h:170
boost::function< void(sensor_msgs::ImagePtr image)> FrameCallbackFunction
Definition: astra_device.h:64
boost::shared_ptr< openni::VideoStream > ir_video_stream_
Definition: astra_device.h:169
OB_DEVICE_NO
std::ostream & operator<<(std::ostream &stream, const AstraDevice &device)
std::vector< AstraVideoMode > depth_video_modes_
Definition: astra_device.h:175
boost::shared_ptr< openni::Device > openni_device_
Definition: astra_device.h:162
boost::shared_ptr< openni::DeviceInfo > device_info_
Definition: astra_device.h:163


astra_camera
Author(s): Tim Liu
autogenerated on Wed Dec 16 2020 03:54:34