SubscribeR.h
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <ros/package.h>
00003 #include <std_msgs/String.h>
00004 #include <topic_tools/shape_shifter.h>
00005 
00006 class SubscribeR {
00007 public:
00008         SubscribeR(ros::NodeHandle* handle, const char* cTopic, const char* cMsgType, const char* cMsgDefinition, const char* cMsgMD5){
00009                 m_bNewMessage = false;
00010                 m_bAnyMessage = false;
00011                 m_rosSubscriber = handle->subscribe(cTopic, 1, &SubscribeR::callback, this);
00012 
00013                 m_strMsgType            = cMsgType;
00014                 m_strMsgDefinition      = cMsgDefinition;
00015                 m_strMsgMD5                     = cMsgMD5;
00016 
00017                 m_uiBufferSize = 10000000;
00018 
00019                 m_ui8Buffer = new boost::shared_array<uint8_t> (new uint8_t[m_uiBufferSize]);
00020                 m_isStream  = new ros::serialization::IStream(m_ui8Buffer->get(), m_uiBufferSize);
00021         };
00022         ~SubscribeR() {
00023                 delete m_isStream;
00024                 delete m_ui8Buffer;
00025         };
00026 
00027         void callback(const ros::MessageEvent<topic_tools::ShapeShifter const>& event) {
00028                 m_bNewMessage = true;
00029                 m_bAnyMessage = true;
00030 
00031                 m_Event = event;
00032 
00033                 // uninitialzed
00034                 if(m_strMsgType.size() == 0){
00035                         m_strMsgType = m_Event.getMessage()->getDataType();
00036                         m_strMsgMD5  = m_Event.getMessage()->getMD5Sum();
00037                         m_strMsgDefinition = m_Event.getMessage()->getMessageDefinition();
00038                 }
00039         };
00040 
00041         bool hasAnyMessage() { return m_bAnyMessage; };
00042         bool hasNewMessage() { return m_bNewMessage; };
00043 
00044         const char* getPublisher() {
00045                 return m_Event.getPublisherName().c_str();      };
00046         const char* getMessageType() {
00047                 return m_strMsgType.c_str();    };
00048         const char* getMessageDefinition() {
00049                 return m_strMsgDefinition.c_str(); };
00050         const char* getMessageMD5() {
00051                 return m_strMsgMD5.c_str(); };
00052 
00053         ros::serialization::IStream * getMessageStream(){
00054                 m_bNewMessage = false;
00055 
00056                 if(m_isStream->getLength() != m_uiBufferSize){
00057                         m_isStream->advance(-(m_uiBufferSize-m_isStream->getLength()));
00058                 }
00059 
00060                 m_Event.getMessage()->write(*m_isStream);
00061                 m_isStream->advance(-m_Event.getMessage()->size());
00062 
00063                 return m_isStream;
00064         };
00065 
00066 private:
00067         bool m_bNewMessage;
00068         bool m_bAnyMessage;
00069 
00070         ros::Subscriber m_rosSubscriber;
00071         std::string m_strMsgType;
00072         std::string m_strMsgDefinition;
00073         std::string m_strMsgMD5;
00074 
00075         ros::MessageEvent<topic_tools::ShapeShifter const> m_Event;
00076 
00077         boost::shared_array<uint8_t> *m_ui8Buffer;
00078         unsigned int m_uiBufferSize;
00079         ros::serialization::IStream *m_isStream;
00080 };
00081 
00082 SubscribeR* rrosSubscriber(ros::NodeHandle* handle,
00083                                                         const char* topic,
00084                                                         const char* type,
00085                                                         const char* msg_def,
00086                                                         const char* msg_md5);
00087 
00088 bool rrosSubscriberHasNewMsg(SubscribeR* subscriber);
00089 bool rrosSubscriberHasAnyMsg(SubscribeR* subscriber);
00090 
00091 ros::serialization::IStream* rrosSubscriberGetMessageStream(SubscribeR* subscriber);
00092 
00093 const char* rrosSubscriberGetPublisher(SubscribeR* subscriber);
00094 const char* rrosSubscriberGetMessageType(SubscribeR* subscriber);
00095 const char* rrosSubscriberGetMessageMD5(SubscribeR* subscriber);
00096 const char* rrosSubscriberGetMessageDefinition(SubscribeR* subscriber);
00097 
00098 bool rros_stream_read_bool(ros::serialization::IStream *s);
00099 signed char rros_stream_read_int8(ros::serialization::IStream *s);
00100 unsigned char rros_stream_read_uint8(ros::serialization::IStream *s);
00101 signed short rros_stream_read_int16(ros::serialization::IStream *s);
00102 unsigned short rros_stream_read_uint16(ros::serialization::IStream *s);
00103 signed int rros_stream_read_int32(ros::serialization::IStream *s);
00104 unsigned int rros_stream_read_uint32(ros::serialization::IStream *s);
00105 signed long long rros_stream_read_int64(ros::serialization::IStream *s);
00106 unsigned long long rros_stream_read_uint64(ros::serialization::IStream *s);
00107 float rros_stream_read_float32(ros::serialization::IStream *s);
00108 double rros_stream_read_float64(ros::serialization::IStream *s);
00109 char* rros_stream_read_string(ros::serialization::IStream *s);
00110 
00111 std::vector<signed char>* rros_stream_read_int8_array(ros::serialization::IStream *s, unsigned int size=0);
00112 std::vector<unsigned char>* rros_stream_read_uint8_array(ros::serialization::IStream *s, unsigned int size=0);
00113 std::vector<signed short>* rros_stream_read_int16_array(ros::serialization::IStream *s, unsigned int size=0);
00114 std::vector<unsigned short>* rros_stream_read_uint16_array(ros::serialization::IStream *s, unsigned int size=0);
00115 std::vector<signed int>* rros_stream_read_int32_array(ros::serialization::IStream *s, unsigned int size=0);
00116 std::vector<unsigned int>* rros_stream_read_uint32_array(ros::serialization::IStream *s, unsigned int size=0);
00117 std::vector<signed long long>* rros_stream_read_int64_array(ros::serialization::IStream *s, unsigned int size=0);
00118 std::vector<unsigned long long>* rros_stream_read_uint64_array(ros::serialization::IStream *s, unsigned int size=0);
00119 std::vector<float>* rros_stream_read_float32_array(ros::serialization::IStream *s, unsigned int size=0);
00120 std::vector<double>* rros_stream_read_float64_array(ros::serialization::IStream *s, unsigned int size=0);
00121 std::vector<std::string>* rros_stream_read_string_array(ros::serialization::IStream *s, unsigned int size=0);
00122 


rosR
Author(s): André Dietrich, Sebastian Zug
autogenerated on Sun Jan 5 2014 11:10:28