Go to the documentation of this file.00001 #include "PublisheR.h"
00002
00003 PublisheR* rrosPublisher( ros::NodeHandle* handle,
00004 const char* topic,
00005 const char* type,
00006 const char* msg_def,
00007 const char* msg_md5) {
00008
00009 PublisheR *pub = new PublisheR(handle, topic, type, msg_def, msg_md5);
00010
00011 return pub;
00012 }
00013
00014
00015 const char* rrosPublisherGetTopic(PublisheR* publisher){
00016 return publisher->getTopic(); }
00017 const char* rrosPublisherGetMessageType(PublisheR* publisher){
00018 return publisher->getMessageType(); }
00019 const char* rrosPublisherGetMessageMD5(PublisheR* publisher){
00020 return publisher->getMessageMD5(); }
00021 const char* rrosPublisherGetMessageDefinition(PublisheR* publisher){
00022 return publisher->getMessageDefinition(); }
00023
00024 ros::serialization::OStream* rrosPublisherGetMessageStream(PublisheR *publisher){
00025 return publisher->getMessageStream();
00026 }
00027
00028 void rrosPublish(PublisheR* publisher){
00029 publisher->publish();
00030 }
00031
00032 void rros_stream_write_bool( ros::serialization::OStream *s, bool val){ s->next(val); }
00033 void rros_stream_write_int8( ros::serialization::OStream *s, signed char val){ s->next(val); }
00034 void rros_stream_write_uint8( ros::serialization::OStream *s, unsigned char val){ s->next(val); }
00035 void rros_stream_write_int16( ros::serialization::OStream *s, signed short val){ s->next(val); }
00036 void rros_stream_write_uint16( ros::serialization::OStream *s, unsigned short val){ s->next(val); }
00037 void rros_stream_write_int32( ros::serialization::OStream *s, signed int val){ s->next(val); }
00038 void rros_stream_write_uint32( ros::serialization::OStream *s, unsigned int val){ s->next(val); }
00039 void rros_stream_write_int64( ros::serialization::OStream *s, signed long long val){ s->next(val); }
00040 void rros_stream_write_uint64( ros::serialization::OStream *s, unsigned long long val){ s->next(val); }
00041 void rros_stream_write_float32( ros::serialization::OStream *s, float val){ s->next(val); }
00042 void rros_stream_write_float64( ros::serialization::OStream *s, double val){ s->next(val); }
00043 void rros_stream_write_string( ros::serialization::OStream *s, char* val){
00044 std::string str = val;
00045 s->next(str); }
00046
00047 void rros_stream_write_int8_array(ros::serialization::OStream *s, std::vector<signed char>* vec) { s->next(*vec); }
00048 void rros_stream_write_uint8_array(ros::serialization::OStream *s, std::vector<unsigned char>* vec) { s->next(*vec); }
00049 void rros_stream_write_int16_array(ros::serialization::OStream *s, std::vector<signed short>* vec) { s->next(*vec); }
00050 void rros_stream_write_uint16_array(ros::serialization::OStream *s, std::vector<unsigned short>* vec) { s->next(*vec); }
00051 void rros_stream_write_int32_array(ros::serialization::OStream *s, std::vector<signed int>* vec) { s->next(*vec); }
00052 void rros_stream_write_uint32_array(ros::serialization::OStream *s, std::vector<unsigned int>* vec) { s->next(*vec); }
00053 void rros_stream_write_int64_array(ros::serialization::OStream *s, std::vector<signed long long>* vec) { s->next(*vec); }
00054 void rros_stream_write_uint64_array(ros::serialization::OStream *s, std::vector<unsigned long long>* vec) { s->next(*vec); }
00055 void rros_stream_write_float32_array(ros::serialization::OStream *s, std::vector<float>* vec) { s->next(*vec); }
00056 void rros_stream_write_float64_array(ros::serialization::OStream *s, std::vector<double>* vec) { s->next(*vec); }
00057 void rros_stream_write_string_array(ros::serialization::OStream *s, std::vector<std::string>* vec) { s->next(*vec); }
00058