PublisheR.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 PublisheR {
00007 public:
00008         PublisheR(ros::NodeHandle* handle, const char* cTopic, const char* cMsgType, const char* cMsgDefinition, const char* cMsgMD5){
00009 
00010                 m_rosPublisher = new ros::Publisher();
00011 
00012                 topic_tools::ShapeShifter *ss = new topic_tools::ShapeShifter();
00013                 ss->morph(cMsgMD5, cMsgType, cMsgDefinition, "");
00014                 *m_rosPublisher = ss->advertise(*handle, cTopic, 1);
00015 
00016                 m_strMsgType            = cMsgType;
00017                 m_strMsgDefinition      = cMsgDefinition;
00018                 m_strMsgMD5                     = cMsgMD5;
00019 
00020                 m_uiBufferSize = 10000000;
00021 
00022                 m_ui8Buffer = new boost::shared_array<uint8_t> (new uint8_t[m_uiBufferSize]);
00023                 m_osStream  = new ros::serialization::OStream(m_ui8Buffer->get(), m_uiBufferSize);
00024         };
00025         ~PublisheR() {
00026                 delete m_rosPublisher;
00027                 delete m_osStream;
00028         };
00029 
00030         const char* getMessageType() {
00031                 return m_strMsgType.c_str();    };
00032         const char* getMessageDefinition() {
00033                 return m_strMsgDefinition.c_str(); };
00034         const char* getMessageMD5() {
00035                 return m_strMsgMD5.c_str(); };
00036         const char* getTopic() {
00037                 return m_rosPublisher->getTopic().c_str(); };
00038 
00039         void publish(){
00040                 topic_tools::ShapeShifter *ss = new topic_tools::ShapeShifter();
00041                 ss->morph(m_strMsgMD5, m_strMsgType, m_strMsgDefinition, "");
00042 
00043                 if(m_osStream->getLength() != m_uiBufferSize){
00044                         m_osStream->advance(-(m_uiBufferSize-m_osStream->getLength()));
00045                 }
00046                 ss->read(*m_osStream);
00047 
00048                 m_rosPublisher->publish(*ss);
00049                 delete ss;
00050         }
00051 
00052         ros::serialization::OStream* getMessageStream(){
00053 
00054                 if(m_osStream->getLength() != m_uiBufferSize){
00055                         m_osStream->advance(-(m_uiBufferSize-m_osStream->getLength()));
00056                 }
00057 
00058                 return m_osStream;
00059         }
00060 
00061 private:
00062 
00063         ros::Publisher* m_rosPublisher;
00064         std::string m_strMsgType;
00065         std::string m_strMsgDefinition;
00066         std::string m_strMsgMD5;
00067 
00068         boost::shared_array<uint8_t> *m_ui8Buffer;
00069         unsigned int m_uiBufferSize;
00070         ros::serialization::OStream *m_osStream;
00071 };
00072 
00073 
00074 PublisheR* rrosPublisher(       ros::NodeHandle* handle,
00075                                                         const char* topic,
00076                                                         const char* type,
00077                                                         const char* msg_def,
00078                                                         const char* msg_md5);
00079 
00080 const char* rrosPublisherGetTopic(PublisheR* publisher);
00081 const char* rrosPublisherGetMessageType(PublisheR* publisher);
00082 const char* rrosPublisherGetMessageMD5(PublisheR* publisher);
00083 const char* rrosPublisherGetMessageDefinition(PublisheR* publisher);
00084 
00085 void rrosPublish(PublisheR* publisher);
00086 
00087 ros::serialization::OStream* rrosPublisherGetMessageStream(PublisheR *publisher);
00088 
00089 void rros_stream_write_bool(ros::serialization::OStream *s, bool val);
00090 void rros_stream_write_int8(ros::serialization::OStream *s, signed char val);
00091 void rros_stream_write_uint8(ros::serialization::OStream *s, unsigned char val);
00092 void rros_stream_write_int16(ros::serialization::OStream *s, signed short val);
00093 void rros_stream_write_uint16(ros::serialization::OStream *s, unsigned short val);
00094 void rros_stream_write_int32(ros::serialization::OStream *s, signed int val);
00095 void rros_stream_write_uint32(ros::serialization::OStream *s, unsigned int val);
00096 void rros_stream_write_int64(ros::serialization::OStream *s, signed long long val);
00097 void rros_stream_write_uint64(ros::serialization::OStream *s, unsigned long long val);
00098 void rros_stream_write_float32(ros::serialization::OStream *s, float val);
00099 void rros_stream_write_float64(ros::serialization::OStream *s, double val);
00100 void rros_stream_write_string(ros::serialization::OStream *s, char *val);
00101 
00102 void rros_stream_write_int8_array(ros::serialization::OStream *s, std::vector<signed char>* vec);
00103 void rros_stream_write_uint8_array(ros::serialization::OStream *s, std::vector<unsigned char>* vec);
00104 void rros_stream_write_int16_array(ros::serialization::OStream *s, std::vector<signed short>* vec);
00105 void rros_stream_write_uint16_array(ros::serialization::OStream *s, std::vector<unsigned short>* vec);
00106 void rros_stream_write_int32_array(ros::serialization::OStream *s, std::vector<signed int>* vec);
00107 void rros_stream_write_uint32_array(ros::serialization::OStream *s, std::vector<unsigned int>* vec);
00108 void rros_stream_write_int64_array(ros::serialization::OStream *s, std::vector<signed long long>* vec);
00109 void rros_stream_write_uint64_array(ros::serialization::OStream *s, std::vector<unsigned long long>* vec);
00110 void rros_stream_write_float32_array(ros::serialization::OStream *s, std::vector<float>* vec);
00111 void rros_stream_write_float64_array(ros::serialization::OStream *s, std::vector<double>* vec);
00112 void rros_stream_write_string_array(ros::serialization::OStream *s,  std::vector<std::string>* vec);


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