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 00007 #ifndef ROSR_H 00008 #define ROSR_H 00009 00011 class NodeR { 00012 public: 00013 NodeR() { handle = new ros::NodeHandle; }; 00014 ros::NodeHandle* getHandle() { return handle; }; 00015 public: 00016 ros::NodeHandle *handle; 00017 }; 00018 00020 struct StreamR 00021 { 00022 inline uint8_t* getData() { return data_; } 00023 00024 uint8_t* advance(int32_t len){ 00025 uint8_t* old_data = data_; 00026 data_ += len; 00027 return old_data; 00028 } 00029 inline int32_t getLength() { return (int32_t)(end_ - data_); } 00030 protected: 00031 StreamR(uint8_t* _data, uint32_t _count) : data_(_data) , end_(_data + _count) 00032 {} 00033 private: 00034 uint8_t* data_; 00035 uint8_t* end_; 00036 }; 00037 00039 NodeR* rrosInitNode(char *name); 00040 00041 void rrosSpinOnce(); 00042 void rrosSpin(); 00043 bool rrosOK(); 00044 double rrosTimeNow(); 00045 00046 void rrosLog(char *message, unsigned char type); 00047 00048 #endif //ROSR_H