Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 #include "astra_camera/astra_device_manager.h"
00034 #include "astra_camera/astra_convert.h"
00035 #include "astra_camera/astra_device.h"
00036 #include "astra_camera/astra_exception.h"
00037
00038 #include <boost/make_shared.hpp>
00039
00040 #include <ros/ros.h>
00041
00042 #include <set>
00043 #include <string>
00044
00045 #include "openni2/OpenNI.h"
00046
00047 namespace astra_wrapper
00048 {
00049
00050 class AstraDeviceInfoComparator
00051 {
00052 public:
00053 bool operator()(const AstraDeviceInfo& di1, const AstraDeviceInfo& di2)
00054 {
00055 return (di1.uri_.compare(di2.uri_) < 0);
00056 }
00057 };
00058
00059 typedef std::set<AstraDeviceInfo, AstraDeviceInfoComparator> DeviceSet;
00060
00061 class AstraDeviceListener : public openni::OpenNI::DeviceConnectedListener,
00062 public openni::OpenNI::DeviceDisconnectedListener,
00063 public openni::OpenNI::DeviceStateChangedListener
00064 {
00065 public:
00066 AstraDeviceListener() :
00067 openni::OpenNI::DeviceConnectedListener(),
00068 openni::OpenNI::DeviceDisconnectedListener(),
00069 openni::OpenNI::DeviceStateChangedListener()
00070 {
00071 openni::OpenNI::addDeviceConnectedListener(this);
00072 openni::OpenNI::addDeviceDisconnectedListener(this);
00073 openni::OpenNI::addDeviceStateChangedListener(this);
00074
00075
00076 openni::Array<openni::DeviceInfo> device_info_list;
00077 openni::OpenNI::enumerateDevices(&device_info_list);
00078
00079 for (int i = 0; i < device_info_list.getSize(); ++i)
00080 {
00081 onDeviceConnected(&device_info_list[i]);
00082 }
00083 }
00084
00085 ~AstraDeviceListener()
00086 {
00087 openni::OpenNI::removeDeviceConnectedListener(this);
00088 openni::OpenNI::removeDeviceDisconnectedListener(this);
00089 openni::OpenNI::removeDeviceStateChangedListener(this);
00090 }
00091
00092 virtual void onDeviceStateChanged(const openni::DeviceInfo* pInfo, openni::DeviceState state)
00093 {
00094 ROS_INFO("Device \"%s\" error state changed to %d\n", pInfo->getUri(), state);
00095
00096 switch (state)
00097 {
00098 case openni::DEVICE_STATE_OK:
00099 onDeviceConnected(pInfo);
00100 break;
00101 case openni::DEVICE_STATE_ERROR:
00102 case openni::DEVICE_STATE_NOT_READY:
00103 case openni::DEVICE_STATE_EOF:
00104 default:
00105 onDeviceDisconnected(pInfo);
00106 break;
00107 }
00108 }
00109
00110 virtual void onDeviceConnected(const openni::DeviceInfo* pInfo)
00111 {
00112 boost::mutex::scoped_lock l(device_mutex_);
00113
00114 const AstraDeviceInfo device_info_wrapped = astra_convert(pInfo);
00115
00116 ROS_INFO("Device \"%s\" found.", pInfo->getUri());
00117
00118
00119 device_set_.erase(device_info_wrapped);
00120 device_set_.insert(device_info_wrapped);
00121 }
00122
00123
00124 virtual void onDeviceDisconnected(const openni::DeviceInfo* pInfo)
00125 {
00126 boost::mutex::scoped_lock l(device_mutex_);
00127
00128 ROS_WARN("Device \"%s\" disconnected\n", pInfo->getUri());
00129
00130 const AstraDeviceInfo device_info_wrapped = astra_convert(pInfo);
00131 device_set_.erase(device_info_wrapped);
00132 }
00133
00134 boost::shared_ptr<std::vector<std::string> > getConnectedDeviceURIs()
00135 {
00136 boost::mutex::scoped_lock l(device_mutex_);
00137
00138 boost::shared_ptr<std::vector<std::string> > result = boost::make_shared<std::vector<std::string> >();
00139
00140 result->reserve(device_set_.size());
00141
00142 std::set<AstraDeviceInfo, AstraDeviceInfoComparator>::const_iterator it;
00143 std::set<AstraDeviceInfo, AstraDeviceInfoComparator>::const_iterator it_end = device_set_.end();
00144
00145 for (it = device_set_.begin(); it != it_end; ++it)
00146 result->push_back(it->uri_);
00147
00148 return result;
00149 }
00150
00151 boost::shared_ptr<std::vector<AstraDeviceInfo> > getConnectedDeviceInfos()
00152 {
00153 boost::mutex::scoped_lock l(device_mutex_);
00154
00155 boost::shared_ptr<std::vector<AstraDeviceInfo> > result = boost::make_shared<std::vector<AstraDeviceInfo> >();
00156
00157 result->reserve(device_set_.size());
00158
00159 DeviceSet::const_iterator it;
00160 DeviceSet::const_iterator it_end = device_set_.end();
00161
00162 for (it = device_set_.begin(); it != it_end; ++it)
00163 result->push_back(*it);
00164
00165 return result;
00166 }
00167
00168 std::size_t getNumOfConnectedDevices()
00169 {
00170 boost::mutex::scoped_lock l(device_mutex_);
00171
00172 return device_set_.size();
00173 }
00174
00175 boost::mutex device_mutex_;
00176 DeviceSet device_set_;
00177 };
00178
00180
00181 boost::shared_ptr<AstraDeviceManager> AstraDeviceManager::singelton_;
00182
00183 AstraDeviceManager::AstraDeviceManager()
00184 {
00185 openni::Status rc = openni::OpenNI::initialize();
00186 if (rc != openni::STATUS_OK)
00187 THROW_OPENNI_EXCEPTION("Initialize failed\n%s\n", openni::OpenNI::getExtendedError());
00188
00189 device_listener_ = boost::make_shared<AstraDeviceListener>();
00190 }
00191
00192 AstraDeviceManager::~AstraDeviceManager()
00193 {
00194 }
00195
00196 boost::shared_ptr<AstraDeviceManager> AstraDeviceManager::getSingelton()
00197 {
00198 if (singelton_.get()==0)
00199 singelton_ = boost::make_shared<AstraDeviceManager>();
00200
00201 return singelton_;
00202 }
00203
00204 boost::shared_ptr<std::vector<AstraDeviceInfo> > AstraDeviceManager::getConnectedDeviceInfos() const
00205 {
00206 return device_listener_->getConnectedDeviceInfos();
00207 }
00208
00209 boost::shared_ptr<std::vector<std::string> > AstraDeviceManager::getConnectedDeviceURIs() const
00210 {
00211 return device_listener_->getConnectedDeviceURIs();
00212 }
00213
00214 std::size_t AstraDeviceManager::getNumOfConnectedDevices() const
00215 {
00216 return device_listener_->getNumOfConnectedDevices();
00217 }
00218
00219 std::string AstraDeviceManager::getSerial(const std::string& Uri) const
00220 {
00221 openni::Device openni_device;
00222 std::string ret;
00223
00224
00225 if (Uri.length() > 0 && openni_device.open(Uri.c_str()) == openni::STATUS_OK)
00226 {
00227 int serial_len = 100;
00228 char serial[serial_len];
00229
00230 openni::Status rc = openni_device.getProperty(openni::DEVICE_PROPERTY_SERIAL_NUMBER, serial, &serial_len);
00231 if (rc == openni::STATUS_OK)
00232 ret = serial;
00233 else
00234 {
00235 THROW_OPENNI_EXCEPTION("Serial number query failed: %s", openni::OpenNI::getExtendedError());
00236 }
00237
00238 openni_device.close();
00239 }
00240 else
00241 {
00242
00243 }
00244 return ret;
00245 }
00246
00247 boost::shared_ptr<AstraDevice> AstraDeviceManager::getAnyDevice()
00248 {
00249 return boost::make_shared<AstraDevice>("");
00250 }
00251 boost::shared_ptr<AstraDevice> AstraDeviceManager::getDevice(const std::string& device_URI)
00252 {
00253 return boost::make_shared<AstraDevice>(device_URI);
00254 }
00255
00256
00257 std::ostream& operator << (std::ostream& stream, const AstraDeviceManager& device_manager) {
00258
00259 boost::shared_ptr<std::vector<AstraDeviceInfo> > device_info = device_manager.getConnectedDeviceInfos();
00260
00261 std::vector<AstraDeviceInfo>::const_iterator it;
00262 std::vector<AstraDeviceInfo>::const_iterator it_end = device_info->end();
00263
00264 for (it = device_info->begin(); it != it_end; ++it)
00265 {
00266 stream << "Uri: " << it->uri_ << " (Vendor: " << it->vendor_ <<
00267 ", Name: " << it->name_ <<
00268 ", Vendor ID: " << it->vendor_id_ <<
00269 ", Product ID: " << it->product_id_ <<
00270 ")" << std::endl;
00271 }
00272
00273 return stream;
00274 }
00275
00276
00277 }