transformer.h
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 
00031 #ifndef RVE_TRANSFORMER_TRANSFORMER_H
00032 #define RVE_TRANSFORMER_TRANSFORMER_H
00033 
00034 #include <rve_common/forwards.h>
00035 #include <rve_properties/forwards.h>
00036 #include <rve_render_client/forwards.h>
00037 #include <message_filters/chain.h>
00038 #include <message_filters/subscriber.h>
00039 #include <ros/parameter_adapter.h>
00040 #include <ros/message_traits.h>
00041 #include <ros/advertise_options.h>
00042 #include <ros/publisher.h>
00043 
00044 #include <vector>
00045 #include <set>
00046 
00047 namespace ros
00048 {
00049 class CallbackQueue;
00050 }
00051 
00052 namespace rve_transformer
00053 {
00054 
00055 class TransformerManager;
00056 
00057 class Publisher
00058 {
00059 public:
00060   template<typename T>
00061   void publish(const T& t)
00062   {
00063     if (pub_)
00064     {
00065       pub_.publish(t);
00066     }
00067   }
00068 
00069 private:
00070   void setPublisher(const ros::Publisher& pub)
00071   {
00072     pub_ = pub;
00073   }
00074 
00075   ros::Publisher pub_;
00076 
00077   friend class Transformer;
00078 };
00079 typedef boost::shared_ptr<Publisher> PublisherPtr;
00080 
00081 class Transformer
00082 {
00083 public:
00084   Transformer();
00085   virtual ~Transformer();
00086 
00087   const rve_properties::PropertyNodePtr& getPropertyNode() { return property_node_; }
00088   ros::CallbackQueue* getCallbackQueue() { return callback_queue_; }
00089   TransformerManager* getManager() { return manager_; }
00090 
00091   // TODO: attachToScene should really be able to take care of automatically doing attachToContext and
00092   // not necessitate a call to attachToContext first
00093   void attachToScene(rve_render_client::Scene* scene);
00094   void detachFromScene(rve_render_client::Scene* scene);
00095 
00096   void attachToContext(rve_render_client::ClientContext* context);
00097   void detachFromContext(rve_render_client::ClientContext* context);
00098 
00099   void update();
00100 
00101   void setSubscription(const std::string& name, const std::string& topic);
00102 
00103   bool addToRegistry( rve_common::RegistryPtr registry, rve_common::RegistrantWPtr registrant );
00104   bool removeFromRegistry( rve_common::RegistryPtr registry, rve_common::RegistrantWPtr registrant );
00105 
00106 protected:
00107   virtual void onInit() = 0;
00108   virtual void onUpdate() = 0;
00109 
00110   template<typename P>
00111   void addSubscriber(const std::string& name, uint32_t queue_size, const boost::function<void(P)>& callback)
00112   {
00113     typedef ros::ParameterAdapter<P> PA;
00114     boost::shared_ptr<message_filters::Subscriber<typename PA::Message> > sub(new message_filters::Subscriber<typename PA::Message>);
00115     sub->registerCallback(callback);
00116     addSubscriber(name, queue_size, sub);
00117   }
00118 
00119   template<typename P>
00120   void addSubscriber(const std::string& name, uint32_t queue_size, void(*callback)(P))
00121   {
00122     typedef ros::ParameterAdapter<P> PA;
00123     boost::shared_ptr<message_filters::Subscriber<typename PA::Message> > sub(new message_filters::Subscriber<typename PA::Message>);
00124     sub->registerCallback(callback);
00125     addSubscriber(name, queue_size, sub);
00126   }
00127 
00128   template<typename T, typename P>
00129   void addSubscriber(const std::string& name, uint32_t queue_size, void(T::*callback)(P), T* t)
00130   {
00131     typedef ros::ParameterAdapter<P> PA;
00132     boost::shared_ptr<message_filters::Subscriber<typename PA::Message> > sub(new message_filters::Subscriber<typename PA::Message>);
00133     sub->registerCallback(callback, t);
00134     addSubscriber(name, queue_size, sub);
00135   }
00136 
00137   template<typename M>
00138   PublisherPtr addPublisher(const std::string& name, uint32_t queue_size)
00139   {
00140     PubPtr pub(new Pub);
00141     pub->ops.template init<M>("", queue_size);
00142     pub->name = name;
00143     pub->pub.reset(new Publisher);
00144     pubs_.push_back(pub);
00145 
00146     return pub->pub;
00147   }
00148 
00149   template<typename T>
00150   T addObject(const T& t)
00151   {
00152     addObjectImpl(t);
00153     return t;
00154   }
00155   void removeObject(const rve_render_client::SceneObjectPtr& obj);
00156   void removeObject(const rve_render_client::ContextObjectPtr& obj);
00157 
00158 private:
00159   Transformer(const Transformer&);
00160   void operator=(const Transformer&);
00161 
00162   void init(TransformerManager* manager, const rve_properties::PropertyNodePtr& property_node);
00163 
00164   void addObjectImpl(const rve_render_client::SceneObjectPtr& obj);
00165   void addObjectImpl(const rve_render_client::ContextObjectPtr& obj);
00166 
00167   template<typename M>
00168   void addSubscriber(const std::string& name, uint32_t queue_size, const boost::shared_ptr<message_filters::Subscriber<M> >& sub)
00169   {
00170     SubPtr my_sub(new Sub);
00171     message_filters::Chain<M>* chain = new message_filters::Chain<M>;
00172     chain->addFilter(sub);
00173     my_sub->name = name;
00174     my_sub->chain.reset(chain);
00175     my_sub->sub = sub;
00176     my_sub->queue_size = queue_size;
00177     my_sub->datatype = ros::message_traits::datatype<M>();
00178     subs_.push_back(my_sub);
00179   }
00180 
00181   rve_properties::PropertyNodePtr property_node_;
00182   ros::CallbackQueue* callback_queue_;
00183   TransformerManager* manager_;
00184 
00185   struct Sub
00186   {
00187     message_filters::ChainBasePtr chain;
00188     message_filters::SubscriberBasePtr sub;
00189     std::string datatype;
00190     std::string name;
00191     uint32_t queue_size;
00192   };
00193   typedef boost::shared_ptr<Sub> SubPtr;
00194   typedef std::vector<SubPtr> V_Sub;
00195   V_Sub subs_;
00196 
00197   struct Pub
00198   {
00199     ros::AdvertiseOptions ops;
00200     std::string name;
00201     PublisherPtr pub;
00202   };
00203   typedef boost::shared_ptr<Pub> PubPtr;
00204   typedef std::vector<PubPtr> V_Pub;
00205   V_Pub pubs_;
00206 
00207   rve_render_client::SceneObjectCollectionPtr scene_objects_;
00208   rve_render_client::ContextObjectCollectionPtr context_objects_;
00209 
00210   friend class TransformerManager;
00211 };
00212 
00213 } // namespace rve_transformer
00214 
00215 #endif // RVE_TRANSFORMER_TRANSFORMER_H


rve_transformer
Author(s): Josh Faust
autogenerated on Wed Dec 11 2013 14:31:51