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_SUBSCRIBER_H_
00038 #define ROSMPI_SUBSCRIBER_H_
00039 
00040 #include "rosmpi/forwards.h"
00041 
00042 #include <ros/message.h>
00043 #include <ros/message_deserializer.h>
00044 #include <ros/serialized_message.h>
00045 #include <ros/serialization.h>
00046 #include <ros/subscription_callback_helper.h>
00047 
00048 namespace rosmpi
00049 {
00051   class Subscriber
00052   {
00053     public:
00054       Subscriber () {}
00055       
00056       ~Subscriber ()
00057       {
00058         helper_.reset ();
00059       }
00060 
00061     public:
00062 
00063       template <typename M> void 
00064         call ()
00065       {
00066         MPI::Status status;
00067         
00068         MPI::COMM_WORLD.Probe (MPI_ANY_SOURCE, MPI_ANY_TAG, status);      
00069 
00070         
00071         int count = status.Get_count (MPI_BYTE);
00072 
00073         uint8_t *buf_raw = (uint8_t*)malloc (count * sizeof (uint8_t));
00074         
00075         MPI::COMM_WORLD.Recv (buf_raw, count, MPI_BYTE, MPI_ANY_SOURCE, MPI_ANY_TAG);
00076         count -= 4;
00077 
00078         boost::shared_array<uint8_t> buf (new uint8_t[count]);
00079         memcpy (buf.get (), &buf_raw[4], count);
00080         free (buf_raw);
00081 
00082         ros::SerializedMessage m (buf, count);
00083         
00084         boost::shared_ptr<ros::M_string> connection_header;     
00085         ros::MessageDeserializer deserializer (helper_, m, connection_header);
00086         ros::VoidConstPtr msg = deserializer.deserialize ();
00087 
00088         ros::SubscriptionCallbackHelperCallParams params;
00089         
00090         
00091         params.event = ros::MessageEvent<void const> (msg, connection_header, ros::Time::now (), true, ros::MessageEvent<void const>::CreateFunction ());
00092         helper_->call (params);
00093       }
00094 
00095     private:
00096       Subscriber (const ros::SubscriptionCallbackHelperPtr &helper) : helper_ (helper)
00097       { 
00098       }
00099 
00100       ros::SubscriptionCallbackHelperPtr helper_;
00101 
00102       friend class NodeHandle;
00103   };
00104 }
00105 
00106 #endif  //#ifndef ROSMPI_SUBSCRIBER_H_