openni2_device_manager.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2013, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  *      Author: Julius Kammerl (jkammerl@willowgarage.com)
00030  */
00031 
00032 #include "openni2_camera/openni2_device_manager.h"
00033 #include "openni2_camera/openni2_convert.h"
00034 #include "openni2_camera/openni2_device.h"
00035 #include "openni2_camera/openni2_exception.h"
00036 
00037 #include <boost/make_shared.hpp>
00038 
00039 #include <ros/ros.h>
00040 
00041 #include <set>
00042 #include <string>
00043 
00044 #include "OpenNI.h"
00045 
00046 namespace openni2_wrapper
00047 {
00048 
00049 class OpenNI2DeviceInfoComparator
00050 {
00051 public:
00052   bool operator()(const OpenNI2DeviceInfo& di1, const OpenNI2DeviceInfo& di2)
00053   {
00054     return (di1.uri_.compare(di2.uri_) < 0);
00055   }
00056 };
00057 
00058 typedef std::set<OpenNI2DeviceInfo, OpenNI2DeviceInfoComparator> DeviceSet;
00059 
00060 class OpenNI2DeviceListener : public openni::OpenNI::DeviceConnectedListener,
00061                              public openni::OpenNI::DeviceDisconnectedListener,
00062                              public openni::OpenNI::DeviceStateChangedListener
00063 {
00064 public:
00065   OpenNI2DeviceListener() :
00066       openni::OpenNI::DeviceConnectedListener(),
00067       openni::OpenNI::DeviceDisconnectedListener(),
00068       openni::OpenNI::DeviceStateChangedListener()
00069   {
00070     openni::OpenNI::addDeviceConnectedListener(this);
00071     openni::OpenNI::addDeviceDisconnectedListener(this);
00072     openni::OpenNI::addDeviceStateChangedListener(this);
00073 
00074     // get list of currently connected devices
00075     openni::Array<openni::DeviceInfo> device_info_list;
00076     openni::OpenNI::enumerateDevices(&device_info_list);
00077 
00078     for (int i = 0; i < device_info_list.getSize(); ++i)
00079     {
00080       onDeviceConnected(&device_info_list[i]);
00081     }
00082   }
00083 
00084   ~OpenNI2DeviceListener()
00085   {
00086     openni::OpenNI::removeDeviceConnectedListener(this);
00087     openni::OpenNI::removeDeviceDisconnectedListener(this);
00088     openni::OpenNI::removeDeviceStateChangedListener(this);
00089   }
00090 
00091   virtual void onDeviceStateChanged(const openni::DeviceInfo* pInfo, openni::DeviceState state)
00092   {
00093     ROS_INFO("Device \"%s\" error state changed to %d\n", pInfo->getUri(), state);
00094 
00095     switch (state)
00096     {
00097       case openni::DEVICE_STATE_OK:
00098         onDeviceConnected(pInfo);
00099         break;
00100       case openni::DEVICE_STATE_ERROR:
00101       case openni::DEVICE_STATE_NOT_READY:
00102       case openni::DEVICE_STATE_EOF:
00103       default:
00104         onDeviceDisconnected(pInfo);
00105         break;
00106     }
00107   }
00108 
00109   virtual void onDeviceConnected(const openni::DeviceInfo* pInfo)
00110   {
00111     boost::mutex::scoped_lock l(device_mutex_);
00112 
00113     ROS_INFO("Device \"%s\" connected\n", pInfo->getUri());
00114 
00115     const OpenNI2DeviceInfo device_info_wrapped = openni2_convert(pInfo);
00116 
00117     // make sure it does not exist in set before inserting
00118     device_set_.erase(device_info_wrapped);
00119     device_set_.insert(device_info_wrapped);
00120   }
00121 
00122   virtual void onDeviceDisconnected(const openni::DeviceInfo* pInfo)
00123   {
00124     boost::mutex::scoped_lock l(device_mutex_);
00125 
00126     ROS_WARN("Device \"%s\" disconnected\n", pInfo->getUri());
00127 
00128     const OpenNI2DeviceInfo device_info_wrapped = openni2_convert(pInfo);
00129     device_set_.erase(device_info_wrapped);
00130   }
00131 
00132   boost::shared_ptr<std::vector<std::string> > getConnectedDeviceURIs()
00133   {
00134     boost::mutex::scoped_lock l(device_mutex_);
00135 
00136     boost::shared_ptr<std::vector<std::string> > result = boost::make_shared<std::vector<std::string> >();
00137 
00138     result->reserve(device_set_.size());
00139 
00140     std::set<OpenNI2DeviceInfo, OpenNI2DeviceInfoComparator>::const_iterator it;
00141     std::set<OpenNI2DeviceInfo, OpenNI2DeviceInfoComparator>::const_iterator it_end = device_set_.end();
00142 
00143     for (it = device_set_.begin(); it != it_end; ++it)
00144       result->push_back(it->uri_);
00145 
00146     return result;
00147   }
00148 
00149   boost::shared_ptr<std::vector<OpenNI2DeviceInfo> > getConnectedDeviceInfos()
00150   {
00151     boost::mutex::scoped_lock l(device_mutex_);
00152 
00153     boost::shared_ptr<std::vector<OpenNI2DeviceInfo> > result = boost::make_shared<std::vector<OpenNI2DeviceInfo> >();
00154 
00155     result->reserve(device_set_.size());
00156 
00157     DeviceSet::const_iterator it;
00158     DeviceSet::const_iterator it_end = device_set_.end();
00159 
00160     for (it = device_set_.begin(); it != it_end; ++it)
00161       result->push_back(*it);
00162 
00163     return result;
00164   }
00165 
00166   std::size_t getNumOfConnectedDevices()
00167   {
00168     boost::mutex::scoped_lock l(device_mutex_);
00169 
00170     return device_set_.size();
00171   }
00172 
00173   boost::mutex device_mutex_;
00174   DeviceSet device_set_;
00175 };
00176 
00178 
00179 boost::shared_ptr<OpenNI2DeviceManager> OpenNI2DeviceManager::singelton_;
00180 
00181 OpenNI2DeviceManager::OpenNI2DeviceManager()
00182 {
00183   openni::Status rc = openni::OpenNI::initialize();
00184   if (rc != openni::STATUS_OK)
00185       THROW_OPENNI_EXCEPTION("Initialize failed\n%s\n", openni::OpenNI::getExtendedError());
00186 
00187   device_listener_ = boost::make_shared<OpenNI2DeviceListener>();
00188 }
00189 
00190 OpenNI2DeviceManager::~OpenNI2DeviceManager()
00191 {
00192 }
00193 
00194 boost::shared_ptr<OpenNI2DeviceManager> OpenNI2DeviceManager::getSingelton()
00195 {
00196   if (singelton_.get()==0)
00197     singelton_ = boost::make_shared<OpenNI2DeviceManager>();
00198 
00199   return singelton_;
00200 }
00201 
00202 boost::shared_ptr<std::vector<OpenNI2DeviceInfo> > OpenNI2DeviceManager::getConnectedDeviceInfos() const
00203 {
00204 return device_listener_->getConnectedDeviceInfos();
00205 }
00206 
00207 boost::shared_ptr<std::vector<std::string> > OpenNI2DeviceManager::getConnectedDeviceURIs() const
00208 {
00209   return device_listener_->getConnectedDeviceURIs();
00210 }
00211 
00212 std::size_t OpenNI2DeviceManager::getNumOfConnectedDevices() const
00213 {
00214   return device_listener_->getNumOfConnectedDevices();
00215 }
00216 
00217 boost::shared_ptr<OpenNI2Device> OpenNI2DeviceManager::getAnyDevice()
00218 {
00219   return boost::make_shared<OpenNI2Device>("");
00220 }
00221 boost::shared_ptr<OpenNI2Device> OpenNI2DeviceManager::getDevice(const std::string& device_URI)
00222 {
00223   return boost::make_shared<OpenNI2Device>(device_URI);
00224 }
00225 
00226 
00227 std::ostream& operator << (std::ostream& stream, const OpenNI2DeviceManager& device_manager) {
00228 
00229   boost::shared_ptr<std::vector<OpenNI2DeviceInfo> > device_info = device_manager.getConnectedDeviceInfos();
00230 
00231   std::vector<OpenNI2DeviceInfo>::const_iterator it;
00232   std::vector<OpenNI2DeviceInfo>::const_iterator it_end = device_info->end();
00233 
00234   for (it = device_info->begin(); it != it_end; ++it)
00235   {
00236     stream << "Uri: " << it->uri_ << " (Vendor: " << it->vendor_ <<
00237                                      ", Name: " << it->name_ <<
00238                                      ", Vendor ID: " << it->vendor_id_ <<
00239                                      ", Product ID: " << it->product_id_ <<
00240                                       ")" << std::endl;
00241   }
00242 }
00243 
00244 
00245 } //namespace openni2_wrapper


openni2_camera
Author(s): Julius Kammerl
autogenerated on Mon Oct 6 2014 03:05:32