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
00034
00035
00036
00037 #ifndef ROSMPI_NODE_HANDLE_H_
00038 #define ROSMPI_NODE_HANDLE_H_
00039
00040 #include <ros/subscription_callback_helper.h>
00041 #include "rosmpi/forwards.h"
00042 #include "rosmpi/subscriber.h"
00043
00044 namespace rosmpi
00045 {
00046 class NodeHandle
00047 {
00048 public:
00049 NodeHandle () {}
00050
00051 ~NodeHandle () {}
00052
00053 template <typename M> ros::SubscriptionCallbackHelperPtr init (const boost::function<void (const boost::shared_ptr<M const>&)>& _callback)
00054 {
00055 typedef typename ros::ParameterAdapter<M>::Message MessageType;
00056 ros::SubscriptionCallbackHelperPtr helper = ros::SubscriptionCallbackHelperPtr (new ros::SubscriptionCallbackHelperT<const boost::shared_ptr<MessageType const>&>(_callback));
00057 return (helper);
00058 }
00059
00060 template <typename M, class T> Subscriber subscribe (void(T::*fp)(const boost::shared_ptr<M const>&), T* obj)
00061 {
00062 ros::SubscriptionCallbackHelperPtr helper = init<M> (boost::bind (fp, obj, _1));
00063 Subscriber s (helper);
00064 s.call<M> ();
00065 return (s);
00066 }
00067
00068 template <typename M> Subscriber subscribe (void(*fp)(const boost::shared_ptr<M const>&))
00069 {
00070 ros::SubscriptionCallbackHelperPtr helper = init<M> (fp);
00071 Subscriber s (helper);
00072 s.call<M> ();
00073 return (s);
00074 }
00075 };
00076 }
00077
00078 #endif //#ifndef ROSMPI_NODE_HANDLE_H_