Personal fork
Fork of rosserial_mbed_lib by
rosserial_msgs/RequestParam.h@0:77afd7560544, 2011-08-19 (annotated)
- Committer:
- nucho
- Date:
- Fri Aug 19 09:06:30 2011 +0000
- Revision:
- 0:77afd7560544
- Child:
- 3:1cf99502f396
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
nucho | 0:77afd7560544 | 1 | #ifndef ros_SERVICE_RequestParam_h |
nucho | 0:77afd7560544 | 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 | 0:77afd7560544 | 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 | 0:77afd7560544 | 18 | virtual int serialize(unsigned char *outbuffer) |
nucho | 0:77afd7560544 | 19 | { |
nucho | 0:77afd7560544 | 20 | int offset = 0; |
nucho | 0:77afd7560544 | 21 | long * length_name = (long *)(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 | 0:77afd7560544 | 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 | 0:77afd7560544 | 44 | |
nucho | 0:77afd7560544 | 45 | }; |
nucho | 0:77afd7560544 | 46 | |
nucho | 0:77afd7560544 | 47 | class RequestParamResponse : public ros::Msg |
nucho | 0:77afd7560544 | 48 | { |
nucho | 0:77afd7560544 | 49 | public: |
nucho | 0:77afd7560544 | 50 | unsigned char ints_length; |
nucho | 0:77afd7560544 | 51 | long st_ints; |
nucho | 0:77afd7560544 | 52 | long * ints; |
nucho | 0:77afd7560544 | 53 | unsigned char floats_length; |
nucho | 0:77afd7560544 | 54 | float st_floats; |
nucho | 0:77afd7560544 | 55 | float * floats; |
nucho | 0:77afd7560544 | 56 | unsigned char strings_length; |
nucho | 0:77afd7560544 | 57 | char* st_strings; |
nucho | 0:77afd7560544 | 58 | char* * strings; |
nucho | 0:77afd7560544 | 59 | |
nucho | 0:77afd7560544 | 60 | virtual int serialize(unsigned char *outbuffer) |
nucho | 0:77afd7560544 | 61 | { |
nucho | 0:77afd7560544 | 62 | int offset = 0; |
nucho | 0:77afd7560544 | 63 | *(outbuffer + offset++) = ints_length; |
nucho | 0:77afd7560544 | 64 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 65 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 66 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 67 | for( unsigned char i = 0; i < ints_length; i++){ |
nucho | 0:77afd7560544 | 68 | union { |
nucho | 0:77afd7560544 | 69 | long real; |
nucho | 0:77afd7560544 | 70 | unsigned long base; |
nucho | 0:77afd7560544 | 71 | } u_intsi; |
nucho | 0:77afd7560544 | 72 | u_intsi.real = this->ints[i]; |
nucho | 0:77afd7560544 | 73 | *(outbuffer + offset + 0) = (u_intsi.base >> (8 * 0)) & 0xFF; |
nucho | 0:77afd7560544 | 74 | *(outbuffer + offset + 1) = (u_intsi.base >> (8 * 1)) & 0xFF; |
nucho | 0:77afd7560544 | 75 | *(outbuffer + offset + 2) = (u_intsi.base >> (8 * 2)) & 0xFF; |
nucho | 0:77afd7560544 | 76 | *(outbuffer + offset + 3) = (u_intsi.base >> (8 * 3)) & 0xFF; |
nucho | 0:77afd7560544 | 77 | offset += sizeof(this->ints[i]); |
nucho | 0:77afd7560544 | 78 | } |
nucho | 0:77afd7560544 | 79 | *(outbuffer + offset++) = floats_length; |
nucho | 0:77afd7560544 | 80 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 81 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 82 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 83 | for( unsigned char i = 0; i < floats_length; i++){ |
nucho | 0:77afd7560544 | 84 | union { |
nucho | 0:77afd7560544 | 85 | float real; |
nucho | 0:77afd7560544 | 86 | unsigned long base; |
nucho | 0:77afd7560544 | 87 | } u_floatsi; |
nucho | 0:77afd7560544 | 88 | u_floatsi.real = this->floats[i]; |
nucho | 0:77afd7560544 | 89 | *(outbuffer + offset + 0) = (u_floatsi.base >> (8 * 0)) & 0xFF; |
nucho | 0:77afd7560544 | 90 | *(outbuffer + offset + 1) = (u_floatsi.base >> (8 * 1)) & 0xFF; |
nucho | 0:77afd7560544 | 91 | *(outbuffer + offset + 2) = (u_floatsi.base >> (8 * 2)) & 0xFF; |
nucho | 0:77afd7560544 | 92 | *(outbuffer + offset + 3) = (u_floatsi.base >> (8 * 3)) & 0xFF; |
nucho | 0:77afd7560544 | 93 | offset += sizeof(this->floats[i]); |
nucho | 0:77afd7560544 | 94 | } |
nucho | 0:77afd7560544 | 95 | *(outbuffer + offset++) = strings_length; |
nucho | 0:77afd7560544 | 96 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 97 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 98 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 99 | for( unsigned char i = 0; i < strings_length; i++){ |
nucho | 0:77afd7560544 | 100 | long * length_stringsi = (long *)(outbuffer + offset); |
nucho | 0:77afd7560544 | 101 | *length_stringsi = strlen( (const char*) this->strings[i]); |
nucho | 0:77afd7560544 | 102 | offset += 4; |
nucho | 0:77afd7560544 | 103 | memcpy(outbuffer + offset, this->strings[i], *length_stringsi); |
nucho | 0:77afd7560544 | 104 | offset += *length_stringsi; |
nucho | 0:77afd7560544 | 105 | } |
nucho | 0:77afd7560544 | 106 | return offset; |
nucho | 0:77afd7560544 | 107 | } |
nucho | 0:77afd7560544 | 108 | |
nucho | 0:77afd7560544 | 109 | virtual int deserialize(unsigned char *inbuffer) |
nucho | 0:77afd7560544 | 110 | { |
nucho | 0:77afd7560544 | 111 | int offset = 0; |
nucho | 0:77afd7560544 | 112 | unsigned char ints_lengthT = *(inbuffer + offset++); |
nucho | 0:77afd7560544 | 113 | if(ints_lengthT > ints_length) |
nucho | 0:77afd7560544 | 114 | this->ints = (long*)realloc(this->ints, ints_lengthT * sizeof(long)); |
nucho | 0:77afd7560544 | 115 | offset += 3; |
nucho | 0:77afd7560544 | 116 | ints_length = ints_lengthT; |
nucho | 0:77afd7560544 | 117 | for( unsigned char i = 0; i < ints_length; i++){ |
nucho | 0:77afd7560544 | 118 | union { |
nucho | 0:77afd7560544 | 119 | long real; |
nucho | 0:77afd7560544 | 120 | unsigned long base; |
nucho | 0:77afd7560544 | 121 | } u_st_ints; |
nucho | 0:77afd7560544 | 122 | u_st_ints.base = 0; |
nucho | 0:77afd7560544 | 123 | u_st_ints.base |= ((typeof(u_st_ints.base)) (*(inbuffer + offset + 0))) << (8 * 0); |
nucho | 0:77afd7560544 | 124 | u_st_ints.base |= ((typeof(u_st_ints.base)) (*(inbuffer + offset + 1))) << (8 * 1); |
nucho | 0:77afd7560544 | 125 | u_st_ints.base |= ((typeof(u_st_ints.base)) (*(inbuffer + offset + 2))) << (8 * 2); |
nucho | 0:77afd7560544 | 126 | u_st_ints.base |= ((typeof(u_st_ints.base)) (*(inbuffer + offset + 3))) << (8 * 3); |
nucho | 0:77afd7560544 | 127 | this->st_ints = u_st_ints.real; |
nucho | 0:77afd7560544 | 128 | offset += sizeof(this->st_ints); |
nucho | 0:77afd7560544 | 129 | memcpy( &(this->ints[i]), &(this->st_ints), sizeof(long)); |
nucho | 0:77afd7560544 | 130 | } |
nucho | 0:77afd7560544 | 131 | unsigned char floats_lengthT = *(inbuffer + offset++); |
nucho | 0:77afd7560544 | 132 | if(floats_lengthT > floats_length) |
nucho | 0:77afd7560544 | 133 | this->floats = (float*)realloc(this->floats, floats_lengthT * sizeof(float)); |
nucho | 0:77afd7560544 | 134 | offset += 3; |
nucho | 0:77afd7560544 | 135 | floats_length = floats_lengthT; |
nucho | 0:77afd7560544 | 136 | for( unsigned char i = 0; i < floats_length; i++){ |
nucho | 0:77afd7560544 | 137 | union { |
nucho | 0:77afd7560544 | 138 | float real; |
nucho | 0:77afd7560544 | 139 | unsigned long base; |
nucho | 0:77afd7560544 | 140 | } u_st_floats; |
nucho | 0:77afd7560544 | 141 | u_st_floats.base = 0; |
nucho | 0:77afd7560544 | 142 | u_st_floats.base |= ((typeof(u_st_floats.base)) (*(inbuffer + offset + 0))) << (8 * 0); |
nucho | 0:77afd7560544 | 143 | u_st_floats.base |= ((typeof(u_st_floats.base)) (*(inbuffer + offset + 1))) << (8 * 1); |
nucho | 0:77afd7560544 | 144 | u_st_floats.base |= ((typeof(u_st_floats.base)) (*(inbuffer + offset + 2))) << (8 * 2); |
nucho | 0:77afd7560544 | 145 | u_st_floats.base |= ((typeof(u_st_floats.base)) (*(inbuffer + offset + 3))) << (8 * 3); |
nucho | 0:77afd7560544 | 146 | this->st_floats = u_st_floats.real; |
nucho | 0:77afd7560544 | 147 | offset += sizeof(this->st_floats); |
nucho | 0:77afd7560544 | 148 | memcpy( &(this->floats[i]), &(this->st_floats), sizeof(float)); |
nucho | 0:77afd7560544 | 149 | } |
nucho | 0:77afd7560544 | 150 | unsigned char strings_lengthT = *(inbuffer + offset++); |
nucho | 0:77afd7560544 | 151 | if(strings_lengthT > strings_length) |
nucho | 0:77afd7560544 | 152 | this->strings = (char**)realloc(this->strings, strings_lengthT * sizeof(char*)); |
nucho | 0:77afd7560544 | 153 | offset += 3; |
nucho | 0:77afd7560544 | 154 | strings_length = strings_lengthT; |
nucho | 0:77afd7560544 | 155 | for( unsigned char i = 0; i < strings_length; i++){ |
nucho | 0:77afd7560544 | 156 | uint32_t length_st_strings = *(uint32_t *)(inbuffer + offset); |
nucho | 0:77afd7560544 | 157 | offset += 4; |
nucho | 0:77afd7560544 | 158 | for(unsigned int k= offset; k< offset+length_st_strings; ++k){ |
nucho | 0:77afd7560544 | 159 | inbuffer[k-1]=inbuffer[k]; |
nucho | 0:77afd7560544 | 160 | } |
nucho | 0:77afd7560544 | 161 | inbuffer[offset+length_st_strings-1]=0; |
nucho | 0:77afd7560544 | 162 | this->st_strings = (char *)(inbuffer + offset-1); |
nucho | 0:77afd7560544 | 163 | offset += length_st_strings; |
nucho | 0:77afd7560544 | 164 | memcpy( &(this->strings[i]), &(this->st_strings), sizeof(char*)); |
nucho | 0:77afd7560544 | 165 | } |
nucho | 0:77afd7560544 | 166 | return offset; |
nucho | 0:77afd7560544 | 167 | } |
nucho | 0:77afd7560544 | 168 | |
nucho | 0:77afd7560544 | 169 | virtual const char * getType(){ return REQUESTPARAM; }; |
nucho | 0:77afd7560544 | 170 | |
nucho | 0:77afd7560544 | 171 | }; |
nucho | 0:77afd7560544 | 172 | |
nucho | 0:77afd7560544 | 173 | } |
nucho | 0:77afd7560544 | 174 | #endif |