Personal fork

Dependencies:   MODSERIAL

Dependents:   rosserial_mbed

Fork of rosserial_mbed_lib by nucho

Committer:
garyservin
Date:
Thu May 01 06:01:31 2014 +0000
Revision:
5:19c5437ed9fe
Parent:
3:1cf99502f396
Updated to hydro

Who changed what in which revision?

UserRevisionLine numberNew contents of line
nucho 3:1cf99502f396 1 #ifndef _ROS_SERVICE_RequestParam_h
nucho 3:1cf99502f396 2 #define _ROS_SERVICE_RequestParam_h
nucho 0:77afd7560544 3 #include <stdint.h>
nucho 0:77afd7560544 4 #include <string.h>
nucho 0:77afd7560544 5 #include <stdlib.h>
nucho 3:1cf99502f396 6 #include "ros/msg.h"
nucho 0:77afd7560544 7
nucho 0:77afd7560544 8 namespace rosserial_msgs
nucho 0:77afd7560544 9 {
nucho 0:77afd7560544 10
nucho 0:77afd7560544 11 static const char REQUESTPARAM[] = "rosserial_msgs/RequestParam";
nucho 0:77afd7560544 12
nucho 0:77afd7560544 13 class RequestParamRequest : public ros::Msg
nucho 0:77afd7560544 14 {
nucho 0:77afd7560544 15 public:
nucho 0:77afd7560544 16 char * name;
nucho 0:77afd7560544 17
nucho 3:1cf99502f396 18 virtual int serialize(unsigned char *outbuffer) const
nucho 0:77afd7560544 19 {
nucho 0:77afd7560544 20 int offset = 0;
nucho 3:1cf99502f396 21 uint32_t * length_name = (uint32_t *)(outbuffer + offset);
nucho 0:77afd7560544 22 *length_name = strlen( (const char*) this->name);
nucho 0:77afd7560544 23 offset += 4;
nucho 0:77afd7560544 24 memcpy(outbuffer + offset, this->name, *length_name);
nucho 0:77afd7560544 25 offset += *length_name;
nucho 0:77afd7560544 26 return offset;
nucho 0:77afd7560544 27 }
nucho 0:77afd7560544 28
nucho 0:77afd7560544 29 virtual int deserialize(unsigned char *inbuffer)
nucho 0:77afd7560544 30 {
nucho 0:77afd7560544 31 int offset = 0;
nucho 0:77afd7560544 32 uint32_t length_name = *(uint32_t *)(inbuffer + offset);
nucho 0:77afd7560544 33 offset += 4;
nucho 0:77afd7560544 34 for(unsigned int k= offset; k< offset+length_name; ++k){
nucho 0:77afd7560544 35 inbuffer[k-1]=inbuffer[k];
nucho 3:1cf99502f396 36 }
nucho 0:77afd7560544 37 inbuffer[offset+length_name-1]=0;
nucho 0:77afd7560544 38 this->name = (char *)(inbuffer + offset-1);
nucho 0:77afd7560544 39 offset += length_name;
nucho 0:77afd7560544 40 return offset;
nucho 0:77afd7560544 41 }
nucho 0:77afd7560544 42
nucho 0:77afd7560544 43 virtual const char * getType(){ return REQUESTPARAM; };
nucho 3:1cf99502f396 44 virtual const char * getMD5(){ return "c1f3d28f1b044c871e6eff2e9fc3c667"; };
nucho 0:77afd7560544 45
nucho 0:77afd7560544 46 };
nucho 0:77afd7560544 47
nucho 0:77afd7560544 48 class RequestParamResponse : public ros::Msg
nucho 0:77afd7560544 49 {
nucho 0:77afd7560544 50 public:
nucho 3:1cf99502f396 51 uint8_t ints_length;
nucho 3:1cf99502f396 52 int32_t st_ints;
nucho 3:1cf99502f396 53 int32_t * ints;
nucho 3:1cf99502f396 54 uint8_t floats_length;
nucho 0:77afd7560544 55 float st_floats;
nucho 0:77afd7560544 56 float * floats;
nucho 3:1cf99502f396 57 uint8_t strings_length;
nucho 0:77afd7560544 58 char* st_strings;
nucho 0:77afd7560544 59 char* * strings;
nucho 0:77afd7560544 60
nucho 3:1cf99502f396 61 virtual int serialize(unsigned char *outbuffer) const
nucho 0:77afd7560544 62 {
nucho 0:77afd7560544 63 int offset = 0;
nucho 0:77afd7560544 64 *(outbuffer + offset++) = ints_length;
nucho 0:77afd7560544 65 *(outbuffer + offset++) = 0;
nucho 0:77afd7560544 66 *(outbuffer + offset++) = 0;
nucho 0:77afd7560544 67 *(outbuffer + offset++) = 0;
nucho 3:1cf99502f396 68 for( uint8_t i = 0; i < ints_length; i++){
nucho 0:77afd7560544 69 union {
nucho 3:1cf99502f396 70 int32_t real;
nucho 3:1cf99502f396 71 uint32_t base;
nucho 0:77afd7560544 72 } u_intsi;
nucho 0:77afd7560544 73 u_intsi.real = this->ints[i];
nucho 0:77afd7560544 74 *(outbuffer + offset + 0) = (u_intsi.base >> (8 * 0)) & 0xFF;
nucho 0:77afd7560544 75 *(outbuffer + offset + 1) = (u_intsi.base >> (8 * 1)) & 0xFF;
nucho 0:77afd7560544 76 *(outbuffer + offset + 2) = (u_intsi.base >> (8 * 2)) & 0xFF;
nucho 0:77afd7560544 77 *(outbuffer + offset + 3) = (u_intsi.base >> (8 * 3)) & 0xFF;
nucho 0:77afd7560544 78 offset += sizeof(this->ints[i]);
nucho 0:77afd7560544 79 }
nucho 0:77afd7560544 80 *(outbuffer + offset++) = floats_length;
nucho 0:77afd7560544 81 *(outbuffer + offset++) = 0;
nucho 0:77afd7560544 82 *(outbuffer + offset++) = 0;
nucho 0:77afd7560544 83 *(outbuffer + offset++) = 0;
nucho 3:1cf99502f396 84 for( uint8_t i = 0; i < floats_length; i++){
nucho 0:77afd7560544 85 union {
nucho 0:77afd7560544 86 float real;
nucho 3:1cf99502f396 87 uint32_t base;
nucho 0:77afd7560544 88 } u_floatsi;
nucho 0:77afd7560544 89 u_floatsi.real = this->floats[i];
nucho 0:77afd7560544 90 *(outbuffer + offset + 0) = (u_floatsi.base >> (8 * 0)) & 0xFF;
nucho 0:77afd7560544 91 *(outbuffer + offset + 1) = (u_floatsi.base >> (8 * 1)) & 0xFF;
nucho 0:77afd7560544 92 *(outbuffer + offset + 2) = (u_floatsi.base >> (8 * 2)) & 0xFF;
nucho 0:77afd7560544 93 *(outbuffer + offset + 3) = (u_floatsi.base >> (8 * 3)) & 0xFF;
nucho 0:77afd7560544 94 offset += sizeof(this->floats[i]);
nucho 0:77afd7560544 95 }
nucho 0:77afd7560544 96 *(outbuffer + offset++) = strings_length;
nucho 0:77afd7560544 97 *(outbuffer + offset++) = 0;
nucho 0:77afd7560544 98 *(outbuffer + offset++) = 0;
nucho 0:77afd7560544 99 *(outbuffer + offset++) = 0;
nucho 3:1cf99502f396 100 for( uint8_t i = 0; i < strings_length; i++){
nucho 3:1cf99502f396 101 uint32_t * length_stringsi = (uint32_t *)(outbuffer + offset);
nucho 0:77afd7560544 102 *length_stringsi = strlen( (const char*) this->strings[i]);
nucho 0:77afd7560544 103 offset += 4;
nucho 0:77afd7560544 104 memcpy(outbuffer + offset, this->strings[i], *length_stringsi);
nucho 0:77afd7560544 105 offset += *length_stringsi;
nucho 0:77afd7560544 106 }
nucho 0:77afd7560544 107 return offset;
nucho 0:77afd7560544 108 }
nucho 0:77afd7560544 109
nucho 0:77afd7560544 110 virtual int deserialize(unsigned char *inbuffer)
nucho 0:77afd7560544 111 {
nucho 0:77afd7560544 112 int offset = 0;
nucho 3:1cf99502f396 113 uint8_t ints_lengthT = *(inbuffer + offset++);
nucho 0:77afd7560544 114 if(ints_lengthT > ints_length)
nucho 3:1cf99502f396 115 this->ints = (int32_t*)realloc(this->ints, ints_lengthT * sizeof(int32_t));
nucho 0:77afd7560544 116 offset += 3;
nucho 0:77afd7560544 117 ints_length = ints_lengthT;
nucho 3:1cf99502f396 118 for( uint8_t i = 0; i < ints_length; i++){
nucho 0:77afd7560544 119 union {
nucho 3:1cf99502f396 120 int32_t real;
nucho 3:1cf99502f396 121 uint32_t base;
nucho 0:77afd7560544 122 } u_st_ints;
nucho 0:77afd7560544 123 u_st_ints.base = 0;
nucho 3:1cf99502f396 124 u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
nucho 3:1cf99502f396 125 u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
nucho 3:1cf99502f396 126 u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
nucho 3:1cf99502f396 127 u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
nucho 0:77afd7560544 128 this->st_ints = u_st_ints.real;
nucho 0:77afd7560544 129 offset += sizeof(this->st_ints);
nucho 3:1cf99502f396 130 memcpy( &(this->ints[i]), &(this->st_ints), sizeof(int32_t));
nucho 0:77afd7560544 131 }
nucho 3:1cf99502f396 132 uint8_t floats_lengthT = *(inbuffer + offset++);
nucho 0:77afd7560544 133 if(floats_lengthT > floats_length)
nucho 0:77afd7560544 134 this->floats = (float*)realloc(this->floats, floats_lengthT * sizeof(float));
nucho 0:77afd7560544 135 offset += 3;
nucho 0:77afd7560544 136 floats_length = floats_lengthT;
nucho 3:1cf99502f396 137 for( uint8_t i = 0; i < floats_length; i++){
nucho 0:77afd7560544 138 union {
nucho 0:77afd7560544 139 float real;
nucho 3:1cf99502f396 140 uint32_t base;
nucho 0:77afd7560544 141 } u_st_floats;
nucho 0:77afd7560544 142 u_st_floats.base = 0;
nucho 3:1cf99502f396 143 u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
nucho 3:1cf99502f396 144 u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
nucho 3:1cf99502f396 145 u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
nucho 3:1cf99502f396 146 u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
nucho 0:77afd7560544 147 this->st_floats = u_st_floats.real;
nucho 0:77afd7560544 148 offset += sizeof(this->st_floats);
nucho 0:77afd7560544 149 memcpy( &(this->floats[i]), &(this->st_floats), sizeof(float));
nucho 0:77afd7560544 150 }
nucho 3:1cf99502f396 151 uint8_t strings_lengthT = *(inbuffer + offset++);
nucho 0:77afd7560544 152 if(strings_lengthT > strings_length)
nucho 0:77afd7560544 153 this->strings = (char**)realloc(this->strings, strings_lengthT * sizeof(char*));
nucho 0:77afd7560544 154 offset += 3;
nucho 0:77afd7560544 155 strings_length = strings_lengthT;
nucho 3:1cf99502f396 156 for( uint8_t i = 0; i < strings_length; i++){
nucho 0:77afd7560544 157 uint32_t length_st_strings = *(uint32_t *)(inbuffer + offset);
nucho 0:77afd7560544 158 offset += 4;
nucho 0:77afd7560544 159 for(unsigned int k= offset; k< offset+length_st_strings; ++k){
nucho 0:77afd7560544 160 inbuffer[k-1]=inbuffer[k];
nucho 3:1cf99502f396 161 }
nucho 0:77afd7560544 162 inbuffer[offset+length_st_strings-1]=0;
nucho 0:77afd7560544 163 this->st_strings = (char *)(inbuffer + offset-1);
nucho 0:77afd7560544 164 offset += length_st_strings;
nucho 0:77afd7560544 165 memcpy( &(this->strings[i]), &(this->st_strings), sizeof(char*));
nucho 0:77afd7560544 166 }
nucho 0:77afd7560544 167 return offset;
nucho 0:77afd7560544 168 }
nucho 0:77afd7560544 169
nucho 3:1cf99502f396 170 virtual const char * getType(){ return REQUESTPARAM; };
nucho 3:1cf99502f396 171 virtual const char * getMD5(){ return "9f0e98bda65981986ddf53afa7a40e49"; };
nucho 3:1cf99502f396 172
nucho 3:1cf99502f396 173 };
nucho 0:77afd7560544 174
nucho 3:1cf99502f396 175 class RequestParam {
nucho 3:1cf99502f396 176 public:
nucho 3:1cf99502f396 177 typedef RequestParamRequest Request;
nucho 3:1cf99502f396 178 typedef RequestParamResponse Response;
nucho 0:77afd7560544 179 };
nucho 0:77afd7560544 180
nucho 0:77afd7560544 181 }
nucho 0:77afd7560544 182 #endif