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 
103  void setImageRegistrationMode(bool enabled);
104  void setDepthColorSync(bool enabled);
105 
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 
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;
131  bool isCameraParamsValid();
132  char* getSerialNumber();
133  char* getDeviceType();
135  int getIRGain() const;
136  int getIRExposure() const;
137 
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 
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 */
astra_wrapper::AstraDevice::setIRVideoMode
void setIRVideoMode(const AstraVideoMode &video_mode)
Definition: astra_device.cpp:644
astra_wrapper::AstraDevice::setLaser
void setLaser(bool enable)
Definition: astra_device.cpp:236
astra_wrapper::AstraDevice::getIRExposure
int getIRExposure() const
Definition: astra_device.cpp:210
astra_wrapper::AstraDevice::getStringID
const std::string getStringID() const
Definition: astra_device.cpp:161
astra_wrapper::AstraDevice::depth_frame_listener
boost::shared_ptr< AstraFrameListener > depth_frame_listener
Definition: astra_device.h:167
astra_wrapper::AstraDevice::hasDepthSensor
bool hasDepthSensor() const
Definition: astra_device.cpp:399
astra_wrapper::AstraDevice::getBaseline
float getBaseline() const
Definition: astra_device.cpp:329
astra_wrapper::operator<<
std::ostream & operator<<(std::ostream &stream, const AstraDevice &device)
Definition: astra_device.cpp:822
astra_wrapper::AstraDevice::setCameraParams
void setCameraParams(OBCameraParams param)
Definition: astra_device.cpp:218
boost::shared_ptr< openni::VideoStream >
astra_wrapper::AstraDevice::color_frame_listener
boost::shared_ptr< AstraFrameListener > color_frame_listener
Definition: astra_device.h:166
astra_wrapper::AstraDevice::ir_frame_listener
boost::shared_ptr< AstraFrameListener > ir_frame_listener
Definition: astra_device.h:165
astra_wrapper::AstraDevice::setAutoExposure
void setAutoExposure(bool enable)
Definition: astra_device.cpp:683
callback
void callback(const sensor_msgs::ImageConstPtr &msg)
astra_wrapper::AstraDevice::isIRVideoModeSupported
bool isIRVideoModeSupported(const AstraVideoMode &video_mode) const
Definition: astra_device.cpp:334
astra_wrapper::AstraDevice::getIRGain
int getIRGain() const
Definition: astra_device.cpp:202
astra_wrapper::AstraDevice::isDepthVideoModeSupported
bool isDepthVideoModeSupported(const AstraVideoMode &video_mode) const
Definition: astra_device.cpp:370
astra_wrapper::AstraDevice::isValid
bool isValid() const
Definition: astra_device.cpp:172
astra_wrapper::AstraDevice::getDepthVideoStream
boost::shared_ptr< openni::VideoStream > getDepthVideoStream() const
Definition: astra_device.cpp:806
astra_wrapper::AstraDevice::isDepthStreamStarted
bool isDepthStreamStarted()
Definition: astra_device.cpp:505
astra_wrapper::AstraDevice::getSupportedIRVideoModes
const std::vector< AstraVideoMode > & getSupportedIRVideoModes() const
Definition: astra_device.cpp:510
astra_wrapper::AstraDevice::setUseDeviceTimer
void setUseDeviceTimer(bool enable)
Definition: astra_device.cpp:747
astra_wrapper::AstraDevice::depth_video_stream_
boost::shared_ptr< openni::VideoStream > depth_video_stream_
Definition: astra_device.h:171
astra_wrapper::AstraFrameListener
Definition: astra_frame_listener.h:49
astra_wrapper::AstraDevice::startColorStream
void startColorStream()
Definition: astra_device.cpp:418
openni::SensorInfo
Definition: OpenNI.h:351
astra_wrapper::AstraDevice::getCameraParams
OBCameraParams getCameraParams() const
Definition: astra_device.cpp:177
astra_wrapper::AstraDevice::setIRGain
void setIRGain(int gain)
Definition: astra_device.cpp:224
astra_video_mode.h
astra_wrapper::AstraDevice::setIRFrameCallback
void setIRFrameCallback(FrameCallbackFunction callback)
Definition: astra_device.cpp:759
astra_wrapper::AstraDevice::serial_number
char serial_number[12]
Definition: astra_device.h:187
astra_wrapper::AstraDevice::getUsbProductId
uint16_t getUsbProductId() const
Definition: astra_device.cpp:156
astra_wrapper::AstraDevice::ir_video_modes_
std::vector< AstraVideoMode > ir_video_modes_
Definition: astra_device.h:173
astra_wrapper::AstraDevice::getUsbVendorId
uint16_t getUsbVendorId() const
Definition: astra_device.cpp:151
astra_wrapper::AstraDevice::getColorFocalLength
float getColorFocalLength(int output_y_resolution) const
Definition: astra_device.cpp:303
astra_wrapper::AstraDevice::switchIRCamera
void switchIRCamera(int cam)
Definition: astra_device.cpp:282
astra_wrapper::AstraDevice::stopDepthStream
void stopDepthStream()
Definition: astra_device.cpp:472
astra_wrapper::AstraDevice::m_CamParams
OBCameraParams m_CamParams
Definition: astra_device.h:185
astra_wrapper::FrameCallbackFunction
boost::function< void(sensor_msgs::ImagePtr image)> FrameCallbackFunction
Definition: astra_device.h:64
astra_wrapper::AstraDevice::m_ParamsValid
bool m_ParamsValid
Definition: astra_device.h:186
astra_wrapper::AstraDevice::getIRVideoMode
const AstraVideoMode getIRVideoMode()
Definition: astra_device.cpp:590
astra_wrapper::AstraDevice::setColorVideoMode
void setColorVideoMode(const AstraVideoMode &video_mode)
Definition: astra_device.cpp:657
astra_wrapper::AstraDevice::color_video_modes_
std::vector< AstraVideoMode > color_video_modes_
Definition: astra_device.h:174
astra_wrapper::AstraDevice::getUri
const std::string getUri() const
Definition: astra_device.cpp:136
astra_wrapper::AstraDevice::device_type
char device_type[32]
Definition: astra_device.h:188
astra_wrapper::AstraDevice::~AstraDevice
virtual ~AstraDevice()
Definition: astra_device.cpp:127
astra_wrapper::AstraVideoMode
Definition: astra_video_mode.h:59
astra_wrapper::AstraDevice::setColorFrameCallback
void setColorFrameCallback(FrameCallbackFunction callback)
Definition: astra_device.cpp:764
astra_wrapper::AstraDevice::isColorVideoModeSupported
bool isColorVideoModeSupported(const AstraVideoMode &video_mode) const
Definition: astra_device.cpp:352
astra_wrapper::AstraDevice::stopColorStream
void stopColorStream()
Definition: astra_device.cpp:461
astra_wrapper::AstraDevice::isCameraParamsValid
bool isCameraParamsValid()
Definition: astra_device.cpp:182
astra_wrapper::AstraDevice::getIRVideoStream
boost::shared_ptr< openni::VideoStream > getIRVideoStream() const
Definition: astra_device.cpp:774
astra_wrapper::AstraDevice::startDepthStream
void startDepthStream()
Definition: astra_device.cpp:430
astra_wrapper::AstraDevice::startIRStream
void startIRStream()
Definition: astra_device.cpp:404
astra_wrapper::AstraDevice::getColorVideoMode
const AstraVideoMode getColorVideoMode()
Definition: astra_device.cpp:608
astra_device_type.h
uint16_t
unsigned short uint16_t
Definition: OniPlatformWin32.h:66
astra_wrapper::AstraDevice::color_video_stream_
boost::shared_ptr< openni::VideoStream > color_video_stream_
Definition: astra_device.h:170
astra_wrapper::AstraDevice::AstraDevice
AstraDevice(const std::string &device_URI)
Definition: astra_device.cpp:55
astra_wrapper::AstraDevice::setLDP
void setLDP(bool enable)
Definition: astra_device.cpp:258
astra_wrapper::AstraDevice::use_device_time_
bool use_device_time_
Definition: astra_device.h:183
astra_wrapper::AstraDevice::getDepthFocalLength
float getDepthFocalLength(int output_y_resolution) const
Definition: astra_device.cpp:316
astra_wrapper::AstraDevice::getName
const std::string getName() const
Definition: astra_device.cpp:146
astra_wrapper::AstraDevice::getDepthVideoMode
const AstraVideoMode getDepthVideoMode()
Definition: astra_device.cpp:626
astra_wrapper::AstraDevice::getDeviceType
char * getDeviceType()
Definition: astra_device.cpp:192
astra_wrapper::AstraDevice::depth_video_modes_
std::vector< AstraVideoMode > depth_video_modes_
Definition: astra_device.h:175
astra_wrapper::AstraDevice::setImageRegistrationMode
void setImageRegistrationMode(bool enabled)
Definition: astra_device.cpp:563
astra_wrapper::AstraDevice::getSerialNumber
char * getSerialNumber()
Definition: astra_device.cpp:187
astra_wrapper::AstraDevice::ir_video_started_
bool ir_video_started_
Definition: astra_device.h:177
astra_wrapper::AstraDevice::getColorVideoStream
boost::shared_ptr< openni::VideoStream > getColorVideoStream() const
Definition: astra_device.cpp:790
astra_wrapper::AstraDevice::stopIRStream
void stopIRStream()
Definition: astra_device.cpp:450
astra_wrapper::AstraDevice::getAutoExposure
bool getAutoExposure() const
Definition: astra_device.cpp:716
astra_wrapper::AstraDevice::setIRFlood
void setIRFlood(bool enable)
Definition: astra_device.cpp:247
astra_wrapper::AstraDevice::ir_video_stream_
boost::shared_ptr< openni::VideoStream > ir_video_stream_
Definition: astra_device.h:169
astra_wrapper::AstraDevice::setIRExposure
void setIRExposure(int exposure)
Definition: astra_device.cpp:230
openni
Definition: astra_device.h:53
astra_wrapper::AstraDevice::getSupportedColorVideoModes
const std::vector< AstraVideoMode > & getSupportedColorVideoModes() const
Definition: astra_device.cpp:526
astra_wrapper::AstraDevice::getAutoWhiteBalance
bool getAutoWhiteBalance() const
Definition: astra_device.cpp:731
astra_wrapper
Definition: astra_convert.h:44
astra_wrapper::AstraDevice::device_type_no
OB_DEVICE_NO device_type_no
Definition: astra_device.h:189
astra_wrapper::AstraDevice::hasIRSensor
bool hasIRSensor() const
Definition: astra_device.cpp:389
astra_wrapper::AstraDevice::device_info_
boost::shared_ptr< openni::DeviceInfo > device_info_
Definition: astra_device.h:163
OB_DEVICE_NO
OB_DEVICE_NO
Definition: astra_device_type.h:9
astra_wrapper::AstraDevice::depth_video_started_
bool depth_video_started_
Definition: astra_device.h:179
openni::VideoStream
Definition: OpenNI.h:682
astra_wrapper::AstraDevice::image_registration_activated_
bool image_registration_activated_
Definition: astra_device.h:181
astra_wrapper::AstraDevice::openni_device_
boost::shared_ptr< openni::Device > openni_device_
Definition: astra_device.h:162
astra_wrapper::AstraDevice::isColorStreamStarted
bool isColorStreamStarted()
Definition: astra_device.cpp:501
param
T param(const std::string &param_name, const T &default_val)
astra_wrapper::AstraDevice::getIRFocalLength
float getIRFocalLength(int output_y_resolution) const
Definition: astra_device.cpp:290
astra_wrapper::AstraDevice::color_video_started_
bool color_video_started_
Definition: astra_device.h:178
oni::driver::void
typedef void(ONI_CALLBACK_TYPE *DeviceConnectedCallback)(const OniDeviceInfo *
astra_wrapper::AstraDevice::getDeviceTypeNo
OB_DEVICE_NO getDeviceTypeNo()
Definition: astra_device.cpp:197
astra_wrapper::AstraDevice
Definition: astra_device.h:68
OpenNI.h
astra_wrapper::AstraDevice::hasColorSensor
bool hasColorSensor() const
Definition: astra_device.cpp:394
astra_wrapper::AstraDevice::setDepthColorSync
void setDepthColorSync(bool enabled)
Definition: astra_device.cpp:583
astra_wrapper::AstraDevice::isImageRegistrationModeSupported
bool isImageRegistrationModeSupported() const
Definition: astra_device.cpp:558
astra_wrapper::AstraDevice::setAutoWhiteBalance
void setAutoWhiteBalance(bool enable)
Definition: astra_device.cpp:699
astra_wrapper::AstraDevice::stopAllStreams
void stopAllStreams()
Definition: astra_device.cpp:443
astra_wrapper::AstraDevice::getSupportedDepthVideoModes
const std::vector< AstraVideoMode > & getSupportedDepthVideoModes() const
Definition: astra_device.cpp:542
openni::DeviceInfo
Definition: OpenNI.h:409
astra_wrapper::AstraDevice::isIRStreamStarted
bool isIRStreamStarted()
Definition: astra_device.cpp:497
astra_wrapper::AstraDevice::setDepthFrameCallback
void setDepthFrameCallback(FrameCallbackFunction callback)
Definition: astra_device.cpp:769
openni::Device
Definition: OpenNI.h:1298
astra_wrapper::AstraDevice::getVendor
const std::string getVendor() const
Definition: astra_device.cpp:141
astra_wrapper::AstraDevice::setDepthVideoMode
void setDepthVideoMode(const AstraVideoMode &video_mode)
Definition: astra_device.cpp:670
OBCameraParams
Definition: OniCTypes.h:85
astra_wrapper::AstraDevice::shutdown
void shutdown()
Definition: astra_device.cpp:484
astra_exception.h


ros_astra_camera
Author(s): Tim Liu
autogenerated on Wed Mar 2 2022 00:52:57