SubscribeR.cpp
Go to the documentation of this file.
00001 #include "SubscribeR.h"
00002 
00003 SubscribeR* rrosSubscriber(     NodeR* handle,
00004                                 const char* topic,
00005                                 const char* type,
00006                                 const char* msg_def,
00007                                 const char* msg_md5) {
00008         return new SubscribeR(handle, topic, type, msg_def, msg_md5);
00009 }
00010 
00011 bool rrosSubscriberHasNewMsg(SubscribeR* subscriber){
00012         return subscriber->hasNewMessage(); }
00013 bool rrosSubscriberHasAnyMsg(SubscribeR* subscriber){
00014         return subscriber->hasAnyMessage(); }
00015 
00016 const char* rrosSubscriberGetPublisher(SubscribeR* subscriber){
00017         return subscriber->getPublisher(); }
00018 const char* rrosSubscriberGetMessageType(SubscribeR* subscriber){
00019         return subscriber->getMessageType(); }
00020 const char* rrosSubscriberGetMessageMD5(SubscribeR* subscriber){
00021         return subscriber->getMessageMD5(); }
00022 const char* rrosSubscriberGetMessageDefinition(SubscribeR* subscriber){
00023         return subscriber->getMessageDefinition(); }
00024 
00025 
00026 /***************************************************************/
00027 IStreamR* rrosSubscriberGetMessageStream(SubscribeR* subscriber){
00028         return subscriber->getMessageStream();
00029 }
00030 bool rros_stream_read_bool(IStreamR *s){
00031         unsigned char val;
00032         s->next(val);
00033         return val; }
00034 signed char rros_stream_read_int8(IStreamR *s){
00035         signed char val;
00036         s->next(val);
00037         return val; }
00038 unsigned char rros_stream_read_uint8(IStreamR *s){
00039         unsigned char val;
00040         s->next(val);
00041         return val; }
00042 signed short rros_stream_read_int16(IStreamR *s){
00043         signed short val;
00044         s->next(val);
00045         return val; }
00046 unsigned short rros_stream_read_uint16(IStreamR *s){
00047         unsigned short val;
00048         s->next(val);
00049         return val; }
00050 signed int rros_stream_read_int32(IStreamR *s){
00051         signed int val;
00052         s->next(val);
00053         return val; }
00054 unsigned int rros_stream_read_uint32(IStreamR *s){
00055         unsigned int val;
00056         s->next(val);
00057         return val; }
00058 signed long rros_stream_read_int64(IStreamR *s){
00059         signed long val;
00060         s->next(val);
00061         return val; }
00062 unsigned long rros_stream_read_uint64(IStreamR *s){
00063         unsigned long val;
00064         s->next(val);
00065         return val; }
00066 float rros_stream_read_float32(IStreamR *s){
00067         float val;
00068         s->next(val);
00069         return val; }
00070 double rros_stream_read_float64(IStreamR *s){
00071         double val;
00072         s->next(val);
00073         return val; }
00074 char* rros_stream_read_string(IStreamR *s){
00075         std::string val;
00076         s->next(val);
00077         return const_cast<char*>(val.c_str()); }
00078 
00079 /*--------------------------------------------------------------------*/
00080 std::vector<signed char>* rros_stream_read_int8_array(IStreamR *s, unsigned int size){
00081         std::vector<signed char> *val = new std::vector<signed char>(size);
00082         s->next(*val);
00083         return val; }
00084 std::vector<unsigned char>* rros_stream_read_uint8_array(IStreamR *s, unsigned int size) {
00085         std::vector<unsigned char> *val = new std::vector<unsigned char>(size);
00086         s->next(*val);
00087         return val; }
00088 std::vector<signed short>* rros_stream_read_int16_array(IStreamR *s, unsigned int size){
00089         std::vector<signed short> *val = new std::vector<signed short>(size);
00090         s->next(*val);
00091         return val; }
00092 std::vector<unsigned short>* rros_stream_read_uint16_array(IStreamR *s, unsigned int size){
00093         std::vector<unsigned short> *val = new std::vector<unsigned short>(size);
00094         s->next(*val);
00095         return val; }
00096 std::vector<signed int>* rros_stream_read_int32_array(IStreamR *s, unsigned int size){
00097         std::vector<signed int> *val = new std::vector<signed int>(size);
00098         s->next(*val);
00099         return val; }
00100 std::vector<unsigned int>* rros_stream_read_uint32_array(IStreamR *s, unsigned int size){
00101         std::vector<unsigned int> *val = new std::vector<unsigned int>(size);
00102         s->next(*val);
00103         return val; }
00104 std::vector<signed long>* rros_stream_read_int64_array(IStreamR *s, unsigned int size){
00105         std::vector<signed long> *val = new std::vector<signed long>(size);
00106         s->next(*val);
00107         return val; }
00108 std::vector<unsigned long>* rros_stream_read_uint64_array(IStreamR *s, unsigned int size){
00109         std::vector<unsigned long> *val = new std::vector<unsigned long>(size);
00110         s->next(*val);
00111         return val; }
00112 std::vector<float>* rros_stream_read_float32_array(IStreamR *s, unsigned int size){
00113         std::vector<float> *val = new std::vector<float>(size);
00114         s->next(*val);
00115         return val; }
00116 std::vector<double>* rros_stream_read_float64_array(IStreamR *s, unsigned int size){
00117         std::vector<double> *val = new std::vector<double>(size);
00118         s->next(*val);
00119         return val; }
00120 std::vector<std::string>* rros_stream_read_string_array(IStreamR *s, unsigned int size=0){
00121         std::vector<std::string> *val = new std::vector<std::string>(size);
00122         s->next(*val);
00123         return val; }
00124 


rosR
Author(s): André Dietrich, Sebastian Zug
autogenerated on Fri Aug 28 2015 12:43:50