client_context.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2010, 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 
00030 #include <rve_render_client/client_context.h>
00031 #include <rve_render_client/registry.h>
00032 #include <rve_render_client/context_object.h>
00033 
00034 #include <rve_rpc/client.h>
00035 
00036 #include <ros/node_handle.h>
00037 
00038 #include <boost/unordered_map.hpp>
00039 
00040 #include <set>
00041 
00042 namespace rve_render_client
00043 {
00044 
00045 struct ClientContext::Impl
00046 {
00047   Impl(ClientContext* parent, const std::string& name, const ros::NodeHandle& nh);
00048   ~Impl();
00049 
00050   InterfaceHandle lookupInterface(const std::string& name) const;
00051   rve_interface_gen::Interface* getInterface(InterfaceHandle handle) const;
00052   rve_rpc::Client& getRPCClient() { return client_; }
00053 
00054   void addObject(ContextObject* obj);
00055   void removeObject(ContextObject* obj);
00056   bool hasObject(ContextObject* obj);
00057 
00058   void close();
00059   void reopen();
00060   bool isConnected()
00061   {
00062     return client_.isConnected();
00063   }
00064 
00065   ros::NodeHandle& getNodeHandle() { return nh_; }
00066 
00067   struct InterfaceInfo
00068   {
00069     rve_interface_gen::InterfacePtr interface;
00070     std::string name;
00071   };
00072 
00073   ClientContext* parent_;
00074 
00075   typedef boost::unordered_map<InterfaceHandle, InterfaceInfo> M_Interface;
00076   M_Interface interfaces_;
00077   uint32_t id_counter_;
00078   rve_rpc::Client client_;
00079 
00080   typedef std::vector<ContextObject*> V_ContextObject;
00081   V_ContextObject objects_;
00082 
00083   ros::NodeHandle nh_;
00084 };
00085 
00086 ClientContext::Impl::Impl(ClientContext* parent, const std::string& name, const ros::NodeHandle& nh)
00087 : parent_(parent)
00088 , id_counter_(0)
00089 , client_(name, nh)
00090 , nh_(nh)
00091 {
00092   // grab all the currently available interfaces and create them
00093   V_string names;
00094   getProxyNames(names);
00095   V_string::iterator it = names.begin();
00096   V_string::iterator end = names.end();
00097   for (; it != end; ++it)
00098   {
00099     const std::string& name = *it;
00100     InterfaceInfo info;
00101     info.interface.reset(createProxy(name, client_), boost::bind(destroyProxy, name, _1));
00102     info.name = name;
00103 
00104     while (interfaces_.count(++id_counter_) > 0);
00105 
00106     interfaces_.insert(std::make_pair(id_counter_, info));
00107   }
00108 
00109   // TODO: do this async
00110   //client_.connectAsync();
00111   client_.connect();
00112 }
00113 
00114 ClientContext::Impl::~Impl()
00115 {
00116   if (isConnected())
00117   {
00118     close();
00119   }
00120 }
00121 
00122 InterfaceHandle ClientContext::Impl::lookupInterface(const std::string& name) const
00123 {
00124   M_Interface::const_iterator it = interfaces_.begin();
00125   M_Interface::const_iterator end = interfaces_.end();
00126   for (; it != end; ++it)
00127   {
00128     const InterfaceInfo& info = it->second;
00129     if (info.name == name)
00130     {
00131       return it->first;
00132     }
00133   }
00134 
00135   return NullHandle;
00136 }
00137 
00138 rve_interface_gen::Interface* ClientContext::Impl::getInterface(InterfaceHandle handle) const
00139 {
00140   M_Interface::const_iterator it = interfaces_.find(handle);
00141   if (it == interfaces_.end())
00142   {
00143     return 0;
00144   }
00145 
00146   return it->second.interface.get();
00147 }
00148 
00149 void ClientContext::Impl::addObject(ContextObject* obj)
00150 {
00151   objects_.push_back(obj);
00152   obj->create(parent_);
00153 }
00154 
00155 void ClientContext::Impl::removeObject(ContextObject* obj)
00156 {
00157   obj->destroy(parent_);
00158   V_ContextObject::iterator it = std::find(objects_.begin(), objects_.end(), obj);
00159   ROS_ASSERT(it != objects_.end());
00160   objects_.erase(it);
00161 }
00162 
00163 bool ClientContext::Impl::hasObject(ContextObject* obj)
00164 {
00165   V_ContextObject::iterator it = std::find(objects_.begin(), objects_.end(), obj);
00166   return it != objects_.end();
00167 }
00168 
00169 void ClientContext::Impl::close()
00170 {
00171   // for each object call obj->destroy(this)
00172   std::for_each(objects_.begin(), objects_.end(), boost::bind(&ContextObject::destroy, _1, parent_));
00173 
00174   client_.flush();
00175   client_.disconnect();
00176 }
00177 
00178 void ClientContext::Impl::reopen()
00179 {
00180   client_.connect();
00181 
00182   std::set<rve_common::UUID> left;
00183   V_ContextObject::iterator it = objects_.begin();
00184   V_ContextObject::iterator end = objects_.end();
00185   for (; it != end; ++it)
00186   {
00187     ContextObject* obj = *it;
00188     left.insert(obj->getID());
00189   }
00190 
00191   // horribly inefficient, but easy.  Wait for all dependencies of an object
00192   // to be created before creating said object.
00193   std::vector<rve_common::UUID> deps;
00194   while (!left.empty())
00195   {
00196     deps.clear();
00197     it = objects_.begin();
00198     for (; it != end; ++it)
00199     {
00200       ContextObject* obj = *it;
00201       bool ready = true;
00202       obj->getDependencies(deps);
00203       for (size_t i = 0; i < deps.size(); ++i)
00204       {
00205         if (left.count(deps[i]) > 0)
00206         {
00207           ready = false;
00208           break;
00209         }
00210       }
00211 
00212       if (ready)
00213       {
00214         obj->create(parent_);
00215         left.erase(obj->getID());
00216       }
00217     }
00218   }
00219 }
00220 
00224 
00225 ClientContext::ClientContext(const std::string& name, const ros::NodeHandle& nh)
00226 : impl_(new Impl(this, name, nh))
00227 {
00228 }
00229 
00230 ClientContext::~ClientContext()
00231 {
00232 }
00233 
00234 InterfaceHandle ClientContext::lookupInterface(const std::string& name) const
00235 {
00236   return impl_->lookupInterface(name);
00237 }
00238 
00239 rve_interface_gen::Interface* ClientContext::getInterface(InterfaceHandle handle) const
00240 {
00241   return impl_->getInterface(handle);
00242 }
00243 
00244 rve_rpc::Client& ClientContext::getRPCClient()
00245 {
00246   return impl_->getRPCClient();
00247 }
00248 
00249 void ClientContext::addObject(ContextObject* obj)
00250 {
00251   impl_->addObject(obj);
00252 }
00253 
00254 void ClientContext::removeObject(ContextObject* obj)
00255 {
00256   impl_->removeObject(obj);
00257 }
00258 
00259 void ClientContext::close()
00260 {
00261   impl_->close();
00262 }
00263 
00264 void ClientContext::reopen()
00265 {
00266   impl_->reopen();
00267 }
00268 
00269 bool ClientContext::isConnected()
00270 {
00271   return impl_->isConnected();
00272 }
00273 
00274 bool ClientContext::hasObject(ContextObject* obj)
00275 {
00276   return impl_->hasObject(obj);
00277 }
00278 
00279 ros::NodeHandle& ClientContext::getNodeHandle()
00280 {
00281   return impl_->getNodeHandle();
00282 }
00283 
00284 }


rve_render_client
Author(s): Josh Faust
autogenerated on Wed Dec 11 2013 14:31:32