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 #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
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
00110
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
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
00192
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 }