astra_device_manager.cpp
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 
37 
38 #include <boost/make_shared.hpp>
39 
40 #include <ros/ros.h>
41 
42 #include <set>
43 #include <string>
44 
45 #include "openni2/OpenNI.h"
46 
47 namespace astra_wrapper
48 {
49 
51 {
52 public:
53  bool operator()(const AstraDeviceInfo& di1, const AstraDeviceInfo& di2)
54  {
55  return (di1.uri_.compare(di2.uri_) < 0);
56  }
57 };
58 
59 typedef std::set<AstraDeviceInfo, AstraDeviceInfoComparator> DeviceSet;
60 
64 {
65 public:
70  {
74 
75  // get list of currently connected devices
76  openni::Array<openni::DeviceInfo> device_info_list;
77  openni::OpenNI::enumerateDevices(&device_info_list);
78 
79  for (int i = 0; i < device_info_list.getSize(); ++i)
80  {
81  onDeviceConnected(&device_info_list[i]);
82  }
83  }
84 
86  {
90  }
91 
93  {
94  ROS_INFO("Device \"%s\" error state changed to %d\n", pInfo->getUri(), state);
95 
96  switch (state)
97  {
99  onDeviceConnected(pInfo);
100  break;
104  default:
105  onDeviceDisconnected(pInfo);
106  break;
107  }
108  }
109 
110  virtual void onDeviceConnected(const openni::DeviceInfo* pInfo)
111  {
112  boost::mutex::scoped_lock l(device_mutex_);
113 
114  const AstraDeviceInfo device_info_wrapped = astra_convert(pInfo);
115 
116  ROS_INFO("Device \"%s\" found.", pInfo->getUri());
117 
118  // make sure it does not exist in set before inserting
119  device_set_.erase(device_info_wrapped);
120  device_set_.insert(device_info_wrapped);
121  }
122 
123 
124  virtual void onDeviceDisconnected(const openni::DeviceInfo* pInfo)
125  {
126  boost::mutex::scoped_lock l(device_mutex_);
127 
128  ROS_WARN("Device \"%s\" disconnected\n", pInfo->getUri());
129 
130  const AstraDeviceInfo device_info_wrapped = astra_convert(pInfo);
131  device_set_.erase(device_info_wrapped);
132  }
133 
135  {
136  boost::mutex::scoped_lock l(device_mutex_);
137 
138  boost::shared_ptr<std::vector<std::string> > result = boost::make_shared<std::vector<std::string> >();
139 
140  result->reserve(device_set_.size());
141 
142  std::set<AstraDeviceInfo, AstraDeviceInfoComparator>::const_iterator it;
143  std::set<AstraDeviceInfo, AstraDeviceInfoComparator>::const_iterator it_end = device_set_.end();
144 
145  for (it = device_set_.begin(); it != it_end; ++it)
146  result->push_back(it->uri_);
147 
148  return result;
149  }
150 
152  {
153  boost::mutex::scoped_lock l(device_mutex_);
154 
155  boost::shared_ptr<std::vector<AstraDeviceInfo> > result = boost::make_shared<std::vector<AstraDeviceInfo> >();
156 
157  result->reserve(device_set_.size());
158 
159  DeviceSet::const_iterator it;
160  DeviceSet::const_iterator it_end = device_set_.end();
161 
162  for (it = device_set_.begin(); it != it_end; ++it)
163  result->push_back(*it);
164 
165  return result;
166  }
167 
169  {
170  boost::mutex::scoped_lock l(device_mutex_);
171 
172  return device_set_.size();
173  }
174 
175  boost::mutex device_mutex_;
177 };
178 
180 
182 
184 {
186  if (rc != openni::STATUS_OK)
187  THROW_OPENNI_EXCEPTION("Initialize failed\n%s\n", openni::OpenNI::getExtendedError());
188 
189  device_listener_ = boost::make_shared<AstraDeviceListener>();
190 }
191 
193 {
194 }
195 
197 {
198  if (singelton_.get()==0)
199  singelton_ = boost::make_shared<AstraDeviceManager>();
200 
201  return singelton_;
202 }
203 
205 {
206 return device_listener_->getConnectedDeviceInfos();
207 }
208 
210 {
211  return device_listener_->getConnectedDeviceURIs();
212 }
213 
215 {
216  return device_listener_->getNumOfConnectedDevices();
217 }
218 
219 std::string AstraDeviceManager::getSerial(const std::string& Uri) const
220 {
221  openni::Device openni_device;
222  std::string ret;
223 
224  // we need to open the device to query the serial number
225  if (Uri.length() > 0 && openni_device.open(Uri.c_str()) == openni::STATUS_OK)
226  {
227  int serial_len = 100;
228  char serial[serial_len];
229 
230  openni::Status rc = openni_device.getProperty(openni::DEVICE_PROPERTY_SERIAL_NUMBER, serial, &serial_len);
231  if (rc == openni::STATUS_OK)
232  ret = serial;
233  else
234  {
235  THROW_OPENNI_EXCEPTION("Serial number query failed: %s", openni::OpenNI::getExtendedError());
236  }
237  // close the device again
238  openni_device.close();
239  }
240  else
241  {
242  //THROW_OPENNI_EXCEPTION("Device open failed: %s", openni::OpenNI::getExtendedError());
243  }
244  return ret;
245 }
246 
248 {
249  return boost::make_shared<AstraDevice>("");
250 }
252 {
253  return boost::make_shared<AstraDevice>(device_URI);
254 }
255 
256 
257 std::ostream& operator << (std::ostream& stream, const AstraDeviceManager& device_manager) {
258 
260 
261  std::vector<AstraDeviceInfo>::const_iterator it;
262  std::vector<AstraDeviceInfo>::const_iterator it_end = device_info->end();
263 
264  for (it = device_info->begin(); it != it_end; ++it)
265  {
266  stream << "Uri: " << it->uri_ << " (Vendor: " << it->vendor_ <<
267  ", Name: " << it->name_ <<
268  ", Vendor ID: " << it->vendor_id_ <<
269  ", Product ID: " << it->product_id_ <<
270  ")" << std::endl;
271  }
272 
273  return stream;
274 }
275 
276 
277 } //namespace openni2_wrapper
openni::OpenNI::DeviceConnectedListener::OpenNI
friend class OpenNI
Definition: OpenNI.h:2055
openni::OpenNI::DeviceConnectedListener
Definition: OpenNI.h:2021
openni::STATUS_OK
@ STATUS_OK
Definition: OniEnums.h:68
astra_wrapper::AstraDeviceListener::getConnectedDeviceURIs
boost::shared_ptr< std::vector< std::string > > getConnectedDeviceURIs()
Definition: astra_device_manager.cpp:134
openni::OpenNI::DeviceConnectedListener::DeviceConnectedListener
DeviceConnectedListener()
Definition: OpenNI.h:2024
THROW_OPENNI_EXCEPTION
#define THROW_OPENNI_EXCEPTION(format,...)
Definition: astra_exception.h:49
openni::OpenNI::addDeviceStateChangedListener
static Status addDeviceStateChangedListener(DeviceStateChangedListener *pListener)
Definition: OpenNI.h:2289
openni::OpenNI::initialize
static Status initialize()
Definition: OpenNI.h:2163
astra_wrapper::operator<<
std::ostream & operator<<(std::ostream &stream, const AstraDevice &device)
Definition: astra_device.cpp:822
openni::OpenNI::DeviceDisconnectedListener::DeviceDisconnectedListener
DeviceDisconnectedListener()
Definition: OpenNI.h:2079
boost::shared_ptr
astra_wrapper::astra_convert
const AstraDeviceInfo astra_convert(const openni::DeviceInfo *pInfo)
Definition: astra_convert.cpp:43
astra_wrapper::AstraDeviceManager::getAnyDevice
boost::shared_ptr< AstraDevice > getAnyDevice()
Definition: astra_device_manager.cpp:247
openni::OpenNI::DeviceDisconnectedListener
Definition: OpenNI.h:2076
openni::Device::open
Status open(const char *uri)
Definition: OpenNI.h:2732
openni::OpenNI::DeviceStateChangedListener
Definition: OpenNI.h:2124
ros.h
openni::OpenNI::removeDeviceStateChangedListener
static void removeDeviceStateChangedListener(DeviceStateChangedListener *pListener)
Definition: OpenNI.h:2328
openni::Status
Status
Definition: OniEnums.h:47
astra_wrapper::AstraDeviceListener::~AstraDeviceListener
~AstraDeviceListener()
Definition: astra_device_manager.cpp:85
astra_convert.h
openni::DEVICE_STATE_OK
@ DEVICE_STATE_OK
Definition: OniEnums.h:88
astra_wrapper::AstraDeviceListener::onDeviceConnected
virtual void onDeviceConnected(const openni::DeviceInfo *pInfo)
Definition: astra_device_manager.cpp:110
astra_wrapper::AstraDeviceListener::device_mutex_
boost::mutex device_mutex_
Definition: astra_device_manager.cpp:175
astra_wrapper::AstraDeviceInfo
Definition: astra_device_info.h:43
openni::DeviceInfo::getUri
const char * getUri() const
Definition: OpenNI.h:416
astra_wrapper::DeviceSet
std::set< AstraDeviceInfo, AstraDeviceInfoComparator > DeviceSet
Definition: astra_device_manager.cpp:59
astra_wrapper::AstraDeviceManager::getDevice
boost::shared_ptr< AstraDevice > getDevice(const std::string &device_URI)
Definition: astra_device_manager.cpp:251
astra_wrapper::AstraDeviceListener::onDeviceStateChanged
virtual void onDeviceStateChanged(const openni::DeviceInfo *pInfo, openni::DeviceState state)
Definition: astra_device_manager.cpp:92
astra_wrapper::AstraDeviceManager::getNumOfConnectedDevices
std::size_t getNumOfConnectedDevices() const
Definition: astra_device_manager.cpp:214
astra_wrapper::AstraDeviceListener
Definition: astra_device_manager.cpp:61
astra_wrapper::AstraDeviceListener::getConnectedDeviceInfos
boost::shared_ptr< std::vector< AstraDeviceInfo > > getConnectedDeviceInfos()
Definition: astra_device_manager.cpp:151
ROS_WARN
#define ROS_WARN(...)
openni::OpenNI::addDeviceConnectedListener
static Status addDeviceConnectedListener(DeviceConnectedListener *pListener)
Definition: OpenNI.h:2259
openni::Array::getSize
int getSize() const
Definition: OpenNI.h:166
astra_wrapper::AstraDeviceInfo::uri_
std::string uri_
Definition: astra_device_info.h:45
astra_wrapper::AstraDeviceManager::singelton_
static boost::shared_ptr< AstraDeviceManager > singelton_
Definition: astra_device_manager.h:70
astra_wrapper::AstraDeviceListener::onDeviceDisconnected
virtual void onDeviceDisconnected(const openni::DeviceInfo *pInfo)
Definition: astra_device_manager.cpp:124
astra_wrapper::AstraDeviceListener::AstraDeviceListener
AstraDeviceListener()
Definition: astra_device_manager.cpp:66
openni::DEVICE_STATE_ERROR
@ DEVICE_STATE_ERROR
Definition: OniEnums.h:89
openni
Definition: astra_device.h:53
astra_device_manager.h
astra_wrapper
Definition: astra_convert.h:44
astra_wrapper::AstraDeviceManager::device_listener_
boost::shared_ptr< AstraDeviceListener > device_listener_
Definition: astra_device_manager.h:68
openni::Device::getProperty
Status getProperty(int propertyId, void *data, int *dataSize) const
Definition: OpenNI.h:1478
astra_device.h
astra_wrapper::AstraDeviceManager::getConnectedDeviceURIs
boost::shared_ptr< std::vector< std::string > > getConnectedDeviceURIs() const
Definition: astra_device_manager.cpp:209
openni::OpenNI::DeviceStateChangedListener::DeviceStateChangedListener
DeviceStateChangedListener()
Definition: OpenNI.h:2127
astra_wrapper::AstraDeviceManager::getSingelton
static boost::shared_ptr< AstraDeviceManager > getSingelton()
Definition: astra_device_manager.cpp:196
astra_wrapper::AstraDeviceManager
Definition: astra_device_manager.h:50
astra_wrapper::AstraDeviceManager::~AstraDeviceManager
virtual ~AstraDeviceManager()
Definition: astra_device_manager.cpp:192
openni::OpenNI::addDeviceDisconnectedListener
static Status addDeviceDisconnectedListener(DeviceDisconnectedListener *pListener)
Definition: OpenNI.h:2274
openni::OpenNI::getExtendedError
static const char * getExtendedError()
Definition: OpenNI.h:2198
openni::OpenNI::removeDeviceDisconnectedListener
static void removeDeviceDisconnectedListener(DeviceDisconnectedListener *pListener)
Definition: OpenNI.h:2316
astra_wrapper::AstraDeviceInfoComparator::operator()
bool operator()(const AstraDeviceInfo &di1, const AstraDeviceInfo &di2)
Definition: astra_device_manager.cpp:53
astra_wrapper::AstraDeviceManager::getSerial
std::string getSerial(const std::string &device_URI) const
Definition: astra_device_manager.cpp:219
openni::DEVICE_STATE_NOT_READY
@ DEVICE_STATE_NOT_READY
Definition: OniEnums.h:90
OpenNI.h
openni::DEVICE_STATE_EOF
@ DEVICE_STATE_EOF
Definition: OniEnums.h:91
openni::Array
Definition: OpenNI.h:137
ROS_INFO
#define ROS_INFO(...)
astra_wrapper::AstraDeviceListener::device_set_
DeviceSet device_set_
Definition: astra_device_manager.cpp:176
openni::DeviceState
DeviceState
Definition: OniEnums.h:86
openni::DEVICE_PROPERTY_SERIAL_NUMBER
@ DEVICE_PROPERTY_SERIAL_NUMBER
Definition: OniProperties.h:71
openni::DeviceInfo
Definition: OpenNI.h:409
openni::OpenNI::enumerateDevices
static void enumerateDevices(Array< DeviceInfo > *deviceInfoList)
Definition: OpenNI.h:2207
astra_wrapper::AstraDeviceListener::getNumOfConnectedDevices
std::size_t getNumOfConnectedDevices()
Definition: astra_device_manager.cpp:168
astra_wrapper::AstraDeviceInfoComparator
Definition: astra_device_manager.cpp:50
astra_wrapper::AstraDeviceManager::getConnectedDeviceInfos
boost::shared_ptr< std::vector< AstraDeviceInfo > > getConnectedDeviceInfos() const
Definition: astra_device_manager.cpp:204
openni::Device::close
void close()
Definition: OpenNI.h:2802
openni::Device
Definition: OpenNI.h:1298
astra_wrapper::AstraDeviceManager::AstraDeviceManager
AstraDeviceManager()
Definition: astra_device_manager.cpp:183
openni::OpenNI::removeDeviceConnectedListener
static void removeDeviceConnectedListener(DeviceConnectedListener *pListener)
Definition: OpenNI.h:2304
astra_exception.h


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