rosserial for Hydro
Fork of rosserial_mbed_lib by
Revision 6:e5254bf7e322, committed 2014-05-08
- Comitter:
- isad
- Date:
- Thu May 08 06:34:37 2014 +0000
- Parent:
- 5:c30c76e8c3f1
- Commit message:
- 0.1
Changed in this revision
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/roscpp/Empty.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,62 @@ +#ifndef _ROS_SERVICE_Empty_h +#define _ROS_SERVICE_Empty_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace roscpp +{ + +static const char EMPTY[] = "roscpp/Empty"; + + class EmptyRequest : public ros::Msg + { + public: + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return EMPTY; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class EmptyResponse : public ros::Msg + { + public: + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return EMPTY; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class Empty { + public: + typedef EmptyRequest Request; + typedef EmptyResponse Response; + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/roscpp/GetLoggers.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,82 @@ +#ifndef _ROS_SERVICE_GetLoggers_h +#define _ROS_SERVICE_GetLoggers_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "roscpp/Logger.h" + +namespace roscpp +{ + +static const char GETLOGGERS[] = "roscpp/GetLoggers"; + + class GetLoggersRequest : public ros::Msg + { + public: + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return GETLOGGERS; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class GetLoggersResponse : public ros::Msg + { + public: + uint8_t loggers_length; + roscpp::Logger st_loggers; + roscpp::Logger * loggers; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = loggers_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < loggers_length; i++){ + offset += this->loggers[i].serialize(outbuffer + offset); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t loggers_lengthT = *(inbuffer + offset++); + if(loggers_lengthT > loggers_length) + this->loggers = (roscpp::Logger*)realloc(this->loggers, loggers_lengthT * sizeof(roscpp::Logger)); + offset += 3; + loggers_length = loggers_lengthT; + for( uint8_t i = 0; i < loggers_length; i++){ + offset += this->st_loggers.deserialize(inbuffer + offset); + memcpy( &(this->loggers[i]), &(this->st_loggers), sizeof(roscpp::Logger)); + } + return offset; + } + + const char * getType(){ return GETLOGGERS; }; + const char * getMD5(){ return "32e97e85527d4678a8f9279894bb64b0"; }; + + }; + + class GetLoggers { + public: + typedef GetLoggersRequest Request; + typedef GetLoggersResponse Response; + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/roscpp/Logger.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,64 @@ +#ifndef _ROS_roscpp_Logger_h +#define _ROS_roscpp_Logger_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace roscpp +{ + + class Logger : public ros::Msg + { + public: + char * name; + char * level; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen( (const char*) this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + uint32_t length_level = strlen( (const char*) this->level); + memcpy(outbuffer + offset, &length_level, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->level, length_level); + offset += length_level; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + uint32_t length_level; + memcpy(&length_level, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_level; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_level-1]=0; + this->level = (char *)(inbuffer + offset-1); + offset += length_level; + return offset; + } + + const char * getType(){ return "roscpp/Logger"; }; + const char * getMD5(){ return "a6069a2ff40db7bd32143dd66e1f408e"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/roscpp/SetLoggerLevel.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,92 @@ +#ifndef _ROS_SERVICE_SetLoggerLevel_h +#define _ROS_SERVICE_SetLoggerLevel_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace roscpp +{ + +static const char SETLOGGERLEVEL[] = "roscpp/SetLoggerLevel"; + + class SetLoggerLevelRequest : public ros::Msg + { + public: + char * logger; + char * level; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_logger = strlen( (const char*) this->logger); + memcpy(outbuffer + offset, &length_logger, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->logger, length_logger); + offset += length_logger; + uint32_t length_level = strlen( (const char*) this->level); + memcpy(outbuffer + offset, &length_level, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->level, length_level); + offset += length_level; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_logger; + memcpy(&length_logger, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_logger; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_logger-1]=0; + this->logger = (char *)(inbuffer + offset-1); + offset += length_logger; + uint32_t length_level; + memcpy(&length_level, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_level; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_level-1]=0; + this->level = (char *)(inbuffer + offset-1); + offset += length_level; + return offset; + } + + const char * getType(){ return SETLOGGERLEVEL; }; + const char * getMD5(){ return "51da076440d78ca1684d36c868df61ea"; }; + + }; + + class SetLoggerLevelResponse : public ros::Msg + { + public: + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return SETLOGGERLEVEL; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + + class SetLoggerLevel { + public: + typedef SetLoggerLevelRequest Request; + typedef SetLoggerLevelResponse Response; + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rosserial_msgs/Log.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,59 @@ +#ifndef _ROS_rosserial_msgs_Log_h +#define _ROS_rosserial_msgs_Log_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace rosserial_msgs +{ + + class Log : public ros::Msg + { + public: + uint8_t level; + char * msg; + enum { ROSDEBUG = 0 }; + enum { INFO = 1 }; + enum { WARN = 2 }; + enum { ERROR = 3 }; + enum { FATAL = 4 }; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->level >> (8 * 0)) & 0xFF; + offset += sizeof(this->level); + uint32_t length_msg = strlen( (const char*) this->msg); + memcpy(outbuffer + offset, &length_msg, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->msg, length_msg); + offset += length_msg; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->level = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->level); + uint32_t length_msg; + memcpy(&length_msg, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_msg; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_msg-1]=0; + this->msg = (char *)(inbuffer + offset-1); + offset += length_msg; + return offset; + } + + const char * getType(){ return "rosserial_msgs/Log"; }; + const char * getMD5(){ return "11abd731c25933261cd6183bd12d6295"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rosserial_msgs/RequestParam.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,184 @@ +#ifndef _ROS_SERVICE_RequestParam_h +#define _ROS_SERVICE_RequestParam_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace rosserial_msgs +{ + +static const char REQUESTPARAM[] = "rosserial_msgs/RequestParam"; + + class RequestParamRequest : public ros::Msg + { + public: + char * name; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen( (const char*) this->name); + memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + return offset; + } + + const char * getType(){ return REQUESTPARAM; }; + const char * getMD5(){ return "c1f3d28f1b044c871e6eff2e9fc3c667"; }; + + }; + + class RequestParamResponse : public ros::Msg + { + public: + uint8_t ints_length; + int32_t st_ints; + int32_t * ints; + uint8_t floats_length; + float st_floats; + float * floats; + uint8_t strings_length; + char* st_strings; + char* * strings; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset++) = ints_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < ints_length; i++){ + union { + int32_t real; + uint32_t base; + } u_intsi; + u_intsi.real = this->ints[i]; + *(outbuffer + offset + 0) = (u_intsi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_intsi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_intsi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_intsi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->ints[i]); + } + *(outbuffer + offset++) = floats_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < floats_length; i++){ + union { + float real; + uint32_t base; + } u_floatsi; + u_floatsi.real = this->floats[i]; + *(outbuffer + offset + 0) = (u_floatsi.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_floatsi.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_floatsi.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_floatsi.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->floats[i]); + } + *(outbuffer + offset++) = strings_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < strings_length; i++){ + uint32_t length_stringsi = strlen( (const char*) this->strings[i]); + memcpy(outbuffer + offset, &length_stringsi, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->strings[i], length_stringsi); + offset += length_stringsi; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint8_t ints_lengthT = *(inbuffer + offset++); + if(ints_lengthT > ints_length) + this->ints = (int32_t*)realloc(this->ints, ints_lengthT * sizeof(int32_t)); + offset += 3; + ints_length = ints_lengthT; + for( uint8_t i = 0; i < ints_length; i++){ + union { + int32_t real; + uint32_t base; + } u_st_ints; + u_st_ints.base = 0; + u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_ints = u_st_ints.real; + offset += sizeof(this->st_ints); + memcpy( &(this->ints[i]), &(this->st_ints), sizeof(int32_t)); + } + uint8_t floats_lengthT = *(inbuffer + offset++); + if(floats_lengthT > floats_length) + this->floats = (float*)realloc(this->floats, floats_lengthT * sizeof(float)); + offset += 3; + floats_length = floats_lengthT; + for( uint8_t i = 0; i < floats_length; i++){ + union { + float real; + uint32_t base; + } u_st_floats; + u_st_floats.base = 0; + u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_floats = u_st_floats.real; + offset += sizeof(this->st_floats); + memcpy( &(this->floats[i]), &(this->st_floats), sizeof(float)); + } + uint8_t strings_lengthT = *(inbuffer + offset++); + if(strings_lengthT > strings_length) + this->strings = (char**)realloc(this->strings, strings_lengthT * sizeof(char*)); + offset += 3; + strings_length = strings_lengthT; + for( uint8_t i = 0; i < strings_length; i++){ + uint32_t length_st_strings; + memcpy(&length_st_strings, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_st_strings; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_st_strings-1]=0; + this->st_strings = (char *)(inbuffer + offset-1); + offset += length_st_strings; + memcpy( &(this->strings[i]), &(this->st_strings), sizeof(char*)); + } + return offset; + } + + const char * getType(){ return REQUESTPARAM; }; + const char * getMD5(){ return "9f0e98bda65981986ddf53afa7a40e49"; }; + + }; + + class RequestParam { + public: + typedef RequestParamRequest Request; + typedef RequestParamResponse Response; + }; + +} +#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/rosserial_msgs/TopicInfo.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,115 @@ +#ifndef _ROS_rosserial_msgs_TopicInfo_h +#define _ROS_rosserial_msgs_TopicInfo_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace rosserial_msgs +{ + + class TopicInfo : public ros::Msg + { + public: + uint16_t topic_id; + char * topic_name; + char * message_type; + char * md5sum; + int32_t buffer_size; + enum { ID_PUBLISHER = 0 }; + enum { ID_SUBSCRIBER = 1 }; + enum { ID_SERVICE_SERVER = 2 }; + enum { ID_SERVICE_CLIENT = 4 }; + enum { ID_PARAMETER_REQUEST = 6 }; + enum { ID_LOG = 7 }; + enum { ID_TIME = 10 }; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->topic_id >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->topic_id >> (8 * 1)) & 0xFF; + offset += sizeof(this->topic_id); + uint32_t length_topic_name = strlen( (const char*) this->topic_name); + memcpy(outbuffer + offset, &length_topic_name, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->topic_name, length_topic_name); + offset += length_topic_name; + uint32_t length_message_type = strlen( (const char*) this->message_type); + memcpy(outbuffer + offset, &length_message_type, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->message_type, length_message_type); + offset += length_message_type; + uint32_t length_md5sum = strlen( (const char*) this->md5sum); + memcpy(outbuffer + offset, &length_md5sum, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->md5sum, length_md5sum); + offset += length_md5sum; + union { + int32_t real; + uint32_t base; + } u_buffer_size; + u_buffer_size.real = this->buffer_size; + *(outbuffer + offset + 0) = (u_buffer_size.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_buffer_size.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_buffer_size.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_buffer_size.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->buffer_size); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->topic_id = ((uint16_t) (*(inbuffer + offset))); + this->topic_id |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + offset += sizeof(this->topic_id); + uint32_t length_topic_name; + memcpy(&length_topic_name, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_topic_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_topic_name-1]=0; + this->topic_name = (char *)(inbuffer + offset-1); + offset += length_topic_name; + uint32_t length_message_type; + memcpy(&length_message_type, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_message_type; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_message_type-1]=0; + this->message_type = (char *)(inbuffer + offset-1); + offset += length_message_type; + uint32_t length_md5sum; + memcpy(&length_md5sum, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_md5sum; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_md5sum-1]=0; + this->md5sum = (char *)(inbuffer + offset-1); + offset += length_md5sum; + union { + int32_t real; + uint32_t base; + } u_buffer_size; + u_buffer_size.base = 0; + u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->buffer_size = u_buffer_size.real; + offset += sizeof(this->buffer_size); + return offset; + } + + const char * getType(){ return "rosserial_msgs/TopicInfo"; }; + const char * getMD5(){ return "63aa5e8f1bdd6f35c69fe1a1b9d28e9f"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Bool.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,50 @@ +#ifndef _ROS_std_msgs_Bool_h +#define _ROS_std_msgs_Bool_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Bool : public ros::Msg + { + public: + bool data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Bool"; }; + const char * getMD5(){ return "8b94c1b53db61fb6aed406028ad6332a"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Byte.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,50 @@ +#ifndef _ROS_std_msgs_Byte_h +#define _ROS_std_msgs_Byte_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Byte : public ros::Msg + { + public: + int8_t data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Byte"; }; + const char * getMD5(){ return "ad736a2e8818154c487bb80fe42ce43b"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/ByteMultiArray.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,70 @@ +#ifndef _ROS_std_msgs_ByteMultiArray_h +#define _ROS_std_msgs_ByteMultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class ByteMultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + int8_t st_data; + int8_t * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/ByteMultiArray"; }; + const char * getMD5(){ return "70ea476cbcfd65ac2f68f3cda1e891fe"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Char.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,39 @@ +#ifndef _ROS_std_msgs_Char_h +#define _ROS_std_msgs_Char_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Char : public ros::Msg + { + public: + uint8_t data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->data = ((uint8_t) (*(inbuffer + offset))); + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Char"; }; + const char * getMD5(){ return "1bf77f25acecdedba0e224b162199717"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/ColorRGBA.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,122 @@ +#ifndef _ROS_std_msgs_ColorRGBA_h +#define _ROS_std_msgs_ColorRGBA_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class ColorRGBA : public ros::Msg + { + public: + float r; + float g; + float b; + float a; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + float real; + uint32_t base; + } u_r; + u_r.real = this->r; + *(outbuffer + offset + 0) = (u_r.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_r.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_r.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_r.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->r); + union { + float real; + uint32_t base; + } u_g; + u_g.real = this->g; + *(outbuffer + offset + 0) = (u_g.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_g.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_g.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_g.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->g); + union { + float real; + uint32_t base; + } u_b; + u_b.real = this->b; + *(outbuffer + offset + 0) = (u_b.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_b.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_b.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_b.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->b); + union { + float real; + uint32_t base; + } u_a; + u_a.real = this->a; + *(outbuffer + offset + 0) = (u_a.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_a.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_a.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_a.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->a); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + float real; + uint32_t base; + } u_r; + u_r.base = 0; + u_r.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_r.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_r.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_r.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->r = u_r.real; + offset += sizeof(this->r); + union { + float real; + uint32_t base; + } u_g; + u_g.base = 0; + u_g.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_g.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_g.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_g.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->g = u_g.real; + offset += sizeof(this->g); + union { + float real; + uint32_t base; + } u_b; + u_b.base = 0; + u_b.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_b.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_b.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_b.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->b = u_b.real; + offset += sizeof(this->b); + union { + float real; + uint32_t base; + } u_a; + u_a.base = 0; + u_a.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_a.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_a.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_a.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->a = u_a.real; + offset += sizeof(this->a); + return offset; + } + + const char * getType(){ return "std_msgs/ColorRGBA"; }; + const char * getMD5(){ return "a29a96539573343b1310c73607334b00"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Duration.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,56 @@ +#ifndef _ROS_std_msgs_Duration_h +#define _ROS_std_msgs_Duration_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/duration.h" + +namespace std_msgs +{ + + class Duration : public ros::Msg + { + public: + ros::Duration data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->data.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->data.sec); + *(outbuffer + offset + 0) = (this->data.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->data.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->data.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->data.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->data.nsec); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->data.sec = ((uint32_t) (*(inbuffer + offset))); + this->data.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->data.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data.sec); + this->data.nsec = ((uint32_t) (*(inbuffer + offset))); + this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->data.nsec); + return offset; + } + + const char * getType(){ return "std_msgs/Duration"; }; + const char * getMD5(){ return "3e286caf4241d664e55f3ad380e2ae46"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Empty.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,34 @@ +#ifndef _ROS_std_msgs_Empty_h +#define _ROS_std_msgs_Empty_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Empty : public ros::Msg + { + public: + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + return offset; + } + + const char * getType(){ return "std_msgs/Empty"; }; + const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Float32.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,56 @@ +#ifndef _ROS_std_msgs_Float32_h +#define _ROS_std_msgs_Float32_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Float32 : public ros::Msg + { + public: + float data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + float real; + uint32_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + float real; + uint32_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Float32"; }; + const char * getMD5(){ return "73fcbf46b49191e672908e50842a83d4"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Float32MultiArray.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,76 @@ +#ifndef _ROS_std_msgs_Float32MultiArray_h +#define _ROS_std_msgs_Float32MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Float32MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + float st_data; + float * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + float real; + uint32_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (float*)realloc(this->data, data_lengthT * sizeof(float)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + float real; + uint32_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Float32MultiArray"; }; + const char * getMD5(){ return "6a40e0ffa6a17a503ac3f8616991b1f6"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Float64.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,60 @@ +#ifndef _ROS_std_msgs_Float64_h +#define _ROS_std_msgs_Float64_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Float64 : public ros::Msg + { + public: + float data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + int32_t * val_data = (int32_t *) &(this->data); + int32_t exp_data = (((*val_data)>>23)&255); + if(exp_data != 0) + exp_data += 1023-127; + int32_t sig_data = *val_data; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_data<<5) & 0xff; + *(outbuffer + offset++) = (sig_data>>3) & 0xff; + *(outbuffer + offset++) = (sig_data>>11) & 0xff; + *(outbuffer + offset++) = ((exp_data<<4) & 0xF0) | ((sig_data>>19)&0x0F); + *(outbuffer + offset++) = (exp_data>>4) & 0x7F; + if(this->data < 0) *(outbuffer + offset -1) |= 0x80; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t * val_data = (uint32_t*) &(this->data); + offset += 3; + *val_data = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_data |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_data |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_data |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_data = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_data |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_data !=0) + *val_data |= ((exp_data)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->data = -this->data; + return offset; + } + + const char * getType(){ return "std_msgs/Float64"; }; + const char * getMD5(){ return "fdb28210bfa9d7c91146260178d9a584"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Float64MultiArray.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,80 @@ +#ifndef _ROS_std_msgs_Float64MultiArray_h +#define _ROS_std_msgs_Float64MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Float64MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + float st_data; + float * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + int32_t * val_datai = (int32_t *) &(this->data[i]); + int32_t exp_datai = (((*val_datai)>>23)&255); + if(exp_datai != 0) + exp_datai += 1023-127; + int32_t sig_datai = *val_datai; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = (sig_datai<<5) & 0xff; + *(outbuffer + offset++) = (sig_datai>>3) & 0xff; + *(outbuffer + offset++) = (sig_datai>>11) & 0xff; + *(outbuffer + offset++) = ((exp_datai<<4) & 0xF0) | ((sig_datai>>19)&0x0F); + *(outbuffer + offset++) = (exp_datai>>4) & 0x7F; + if(this->data[i] < 0) *(outbuffer + offset -1) |= 0x80; + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (float*)realloc(this->data, data_lengthT * sizeof(float)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + uint32_t * val_st_data = (uint32_t*) &(this->st_data); + offset += 3; + *val_st_data = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); + *val_st_data |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; + *val_st_data |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; + *val_st_data |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; + uint32_t exp_st_data = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; + exp_st_data |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; + if(exp_st_data !=0) + *val_st_data |= ((exp_st_data)-1023+127)<<23; + if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_data = -this->st_data; + memcpy( &(this->data[i]), &(this->st_data), sizeof(float)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Float64MultiArray"; }; + const char * getMD5(){ return "4b7d974086d4060e7db4613a7e6c3ba4"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Header.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,82 @@ +#ifndef _ROS_std_msgs_Header_h +#define _ROS_std_msgs_Header_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "ros/time.h" + +namespace std_msgs +{ + + class Header : public ros::Msg + { + public: + uint32_t seq; + ros::Time stamp; + char * frame_id; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + *(outbuffer + offset + 0) = (this->seq >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->seq >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->seq >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->seq >> (8 * 3)) & 0xFF; + offset += sizeof(this->seq); + *(outbuffer + offset + 0) = (this->stamp.sec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->stamp.sec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->stamp.sec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->stamp.sec >> (8 * 3)) & 0xFF; + offset += sizeof(this->stamp.sec); + *(outbuffer + offset + 0) = (this->stamp.nsec >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (this->stamp.nsec >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (this->stamp.nsec >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (this->stamp.nsec >> (8 * 3)) & 0xFF; + offset += sizeof(this->stamp.nsec); + uint32_t length_frame_id = strlen( (const char*) this->frame_id); + memcpy(outbuffer + offset, &length_frame_id, sizeof(uint32_t)); + offset += 4; + memcpy(outbuffer + offset, this->frame_id, length_frame_id); + offset += length_frame_id; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + this->seq = ((uint32_t) (*(inbuffer + offset))); + this->seq |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->seq |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->seq |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->seq); + this->stamp.sec = ((uint32_t) (*(inbuffer + offset))); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->stamp.sec); + this->stamp.nsec = ((uint32_t) (*(inbuffer + offset))); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + offset += sizeof(this->stamp.nsec); + uint32_t length_frame_id; + memcpy(&length_frame_id, (inbuffer + offset), sizeof(uint32_t)); + offset += 4; + for(unsigned int k= offset; k< offset+length_frame_id; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_frame_id-1]=0; + this->frame_id = (char *)(inbuffer + offset-1); + offset += length_frame_id; + return offset; + } + + const char * getType(){ return "std_msgs/Header"; }; + const char * getMD5(){ return "2176decaecbce78abc3b96ef049fabed"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int16.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,52 @@ +#ifndef _ROS_std_msgs_Int16_h +#define _ROS_std_msgs_Int16_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Int16 : public ros::Msg + { + public: + int16_t data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int16_t real; + uint16_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int16_t real; + uint16_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Int16"; }; + const char * getMD5(){ return "8524586e34fbd7cb1c08c5f5f1ca0e57"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int16MultiArray.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,72 @@ +#ifndef _ROS_std_msgs_Int16MultiArray_h +#define _ROS_std_msgs_Int16MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Int16MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + int16_t st_data; + int16_t * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + int16_t real; + uint16_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (int16_t*)realloc(this->data, data_lengthT * sizeof(int16_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + int16_t real; + uint16_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int16_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Int16MultiArray"; }; + const char * getMD5(){ return "d9338d7f523fcb692fae9d0a0e9f067c"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int32.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,56 @@ +#ifndef _ROS_std_msgs_Int32_h +#define _ROS_std_msgs_Int32_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Int32 : public ros::Msg + { + public: + int32_t data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int32_t real; + uint32_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Int32"; }; + const char * getMD5(){ return "da5909fbe378aeaf85e547e830cc1bb7"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int32MultiArray.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,76 @@ +#ifndef _ROS_std_msgs_Int32MultiArray_h +#define _ROS_std_msgs_Int32MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Int32MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + int32_t st_data; + int32_t * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + int32_t real; + uint32_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (int32_t*)realloc(this->data, data_lengthT * sizeof(int32_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + int32_t real; + uint32_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int32_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Int32MultiArray"; }; + const char * getMD5(){ return "1d99f79f8b325b44fee908053e9c945b"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int64.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,64 @@ +#ifndef _ROS_std_msgs_Int64_h +#define _ROS_std_msgs_Int64_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Int64 : public ros::Msg + { + public: + int64_t data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_data.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_data.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_data.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_data.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int64_t real; + uint64_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_data.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Int64"; }; + const char * getMD5(){ return "34add168574510e6e17f5d23ecc077ef"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int64MultiArray.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,84 @@ +#ifndef _ROS_std_msgs_Int64MultiArray_h +#define _ROS_std_msgs_Int64MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Int64MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + int64_t st_data; + int64_t * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + int64_t real; + uint64_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; + *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF; + *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF; + *(outbuffer + offset + 4) = (u_datai.base >> (8 * 4)) & 0xFF; + *(outbuffer + offset + 5) = (u_datai.base >> (8 * 5)) & 0xFF; + *(outbuffer + offset + 6) = (u_datai.base >> (8 * 6)) & 0xFF; + *(outbuffer + offset + 7) = (u_datai.base >> (8 * 7)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (int64_t*)realloc(this->data, data_lengthT * sizeof(int64_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + int64_t real; + uint64_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); + u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int64_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Int64MultiArray"; }; + const char * getMD5(){ return "54865aa6c65be0448113a2afc6a49270"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int8.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,50 @@ +#ifndef _ROS_std_msgs_Int8_h +#define _ROS_std_msgs_Int8_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_msgs +{ + + class Int8 : public ros::Msg + { + public: + int8_t data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + int8_t real; + uint8_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return "std_msgs/Int8"; }; + const char * getMD5(){ return "27ffa0c9c4b8fb8492252bcad9e5c57b"; }; + + }; + +} +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_msgs/Int8MultiArray.h Thu May 08 06:34:37 2014 +0000 @@ -0,0 +1,70 @@ +#ifndef _ROS_std_msgs_Int8MultiArray_h +#define _ROS_std_msgs_Int8MultiArray_h + +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "std_msgs/MultiArrayLayout.h" + +namespace std_msgs +{ + + class Int8MultiArray : public ros::Msg + { + public: + std_msgs::MultiArrayLayout layout; + uint8_t data_length; + int8_t st_data; + int8_t * data; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->layout.serialize(outbuffer + offset); + *(outbuffer + offset++) = data_length; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + *(outbuffer + offset++) = 0; + for( uint8_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_datai; + u_datai.real = this->data[i]; + *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data[i]); + } + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->layout.deserialize(inbuffer + offset); + uint8_t data_lengthT = *(inbuffer + offset++); + if(data_lengthT > data_length) + this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t)); + offset += 3; + data_length = data_lengthT; + for( uint8_t i = 0; i < data_length; i++){ + union { + int8_t real; + uint8_t base; + } u_st_data; + u_st_data.base = 0; + u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->st_data = u_st_data.real; + offset += sizeof(this->st_data); + memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t)); + } + return offset; + } + + const char * getType(){ return "std_msgs/Int8MultiArray"; }; + const char * getMD5(){ return "d7c1af35a1b4781bbe79e03dd94b7c13"; }; + + }; + +} +#endif \ No newline at end of file