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


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