This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial. This program contains an example.
Dependencies: rosserial_mbed_lib mbed Servo
rosserial_msgs/RequestParam.h@0:06fc856e99ca, 2011-08-19 (annotated)
- Committer:
- nucho
- Date:
- Fri Aug 19 09:06:16 2011 +0000
- Revision:
- 0:06fc856e99ca
- Child:
- 3:dff241b66f84
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
nucho | 0:06fc856e99ca | 1 | #ifndef ros_SERVICE_RequestParam_h |
nucho | 0:06fc856e99ca | 2 | #define ros_SERVICE_RequestParam_h |
nucho | 0:06fc856e99ca | 3 | #include <stdint.h> |
nucho | 0:06fc856e99ca | 4 | #include <string.h> |
nucho | 0:06fc856e99ca | 5 | #include <stdlib.h> |
nucho | 0:06fc856e99ca | 6 | #include "../ros/msg.h" |
nucho | 0:06fc856e99ca | 7 | |
nucho | 0:06fc856e99ca | 8 | namespace rosserial_msgs |
nucho | 0:06fc856e99ca | 9 | { |
nucho | 0:06fc856e99ca | 10 | |
nucho | 0:06fc856e99ca | 11 | static const char REQUESTPARAM[] = "rosserial_msgs/RequestParam"; |
nucho | 0:06fc856e99ca | 12 | |
nucho | 0:06fc856e99ca | 13 | class RequestParamRequest : public ros::Msg |
nucho | 0:06fc856e99ca | 14 | { |
nucho | 0:06fc856e99ca | 15 | public: |
nucho | 0:06fc856e99ca | 16 | char * name; |
nucho | 0:06fc856e99ca | 17 | |
nucho | 0:06fc856e99ca | 18 | virtual int serialize(unsigned char *outbuffer) |
nucho | 0:06fc856e99ca | 19 | { |
nucho | 0:06fc856e99ca | 20 | int offset = 0; |
nucho | 0:06fc856e99ca | 21 | long * length_name = (long *)(outbuffer + offset); |
nucho | 0:06fc856e99ca | 22 | *length_name = strlen( (const char*) this->name); |
nucho | 0:06fc856e99ca | 23 | offset += 4; |
nucho | 0:06fc856e99ca | 24 | memcpy(outbuffer + offset, this->name, *length_name); |
nucho | 0:06fc856e99ca | 25 | offset += *length_name; |
nucho | 0:06fc856e99ca | 26 | return offset; |
nucho | 0:06fc856e99ca | 27 | } |
nucho | 0:06fc856e99ca | 28 | |
nucho | 0:06fc856e99ca | 29 | virtual int deserialize(unsigned char *inbuffer) |
nucho | 0:06fc856e99ca | 30 | { |
nucho | 0:06fc856e99ca | 31 | int offset = 0; |
nucho | 0:06fc856e99ca | 32 | uint32_t length_name = *(uint32_t *)(inbuffer + offset); |
nucho | 0:06fc856e99ca | 33 | offset += 4; |
nucho | 0:06fc856e99ca | 34 | for(unsigned int k= offset; k< offset+length_name; ++k){ |
nucho | 0:06fc856e99ca | 35 | inbuffer[k-1]=inbuffer[k]; |
nucho | 0:06fc856e99ca | 36 | } |
nucho | 0:06fc856e99ca | 37 | inbuffer[offset+length_name-1]=0; |
nucho | 0:06fc856e99ca | 38 | this->name = (char *)(inbuffer + offset-1); |
nucho | 0:06fc856e99ca | 39 | offset += length_name; |
nucho | 0:06fc856e99ca | 40 | return offset; |
nucho | 0:06fc856e99ca | 41 | } |
nucho | 0:06fc856e99ca | 42 | |
nucho | 0:06fc856e99ca | 43 | virtual const char * getType(){ return REQUESTPARAM; }; |
nucho | 0:06fc856e99ca | 44 | |
nucho | 0:06fc856e99ca | 45 | }; |
nucho | 0:06fc856e99ca | 46 | |
nucho | 0:06fc856e99ca | 47 | class RequestParamResponse : public ros::Msg |
nucho | 0:06fc856e99ca | 48 | { |
nucho | 0:06fc856e99ca | 49 | public: |
nucho | 0:06fc856e99ca | 50 | unsigned char ints_length; |
nucho | 0:06fc856e99ca | 51 | long st_ints; |
nucho | 0:06fc856e99ca | 52 | long * ints; |
nucho | 0:06fc856e99ca | 53 | unsigned char floats_length; |
nucho | 0:06fc856e99ca | 54 | float st_floats; |
nucho | 0:06fc856e99ca | 55 | float * floats; |
nucho | 0:06fc856e99ca | 56 | unsigned char strings_length; |
nucho | 0:06fc856e99ca | 57 | char* st_strings; |
nucho | 0:06fc856e99ca | 58 | char* * strings; |
nucho | 0:06fc856e99ca | 59 | |
nucho | 0:06fc856e99ca | 60 | virtual int serialize(unsigned char *outbuffer) |
nucho | 0:06fc856e99ca | 61 | { |
nucho | 0:06fc856e99ca | 62 | int offset = 0; |
nucho | 0:06fc856e99ca | 63 | *(outbuffer + offset++) = ints_length; |
nucho | 0:06fc856e99ca | 64 | *(outbuffer + offset++) = 0; |
nucho | 0:06fc856e99ca | 65 | *(outbuffer + offset++) = 0; |
nucho | 0:06fc856e99ca | 66 | *(outbuffer + offset++) = 0; |
nucho | 0:06fc856e99ca | 67 | for( unsigned char i = 0; i < ints_length; i++){ |
nucho | 0:06fc856e99ca | 68 | union { |
nucho | 0:06fc856e99ca | 69 | long real; |
nucho | 0:06fc856e99ca | 70 | unsigned long base; |
nucho | 0:06fc856e99ca | 71 | } u_intsi; |
nucho | 0:06fc856e99ca | 72 | u_intsi.real = this->ints[i]; |
nucho | 0:06fc856e99ca | 73 | *(outbuffer + offset + 0) = (u_intsi.base >> (8 * 0)) & 0xFF; |
nucho | 0:06fc856e99ca | 74 | *(outbuffer + offset + 1) = (u_intsi.base >> (8 * 1)) & 0xFF; |
nucho | 0:06fc856e99ca | 75 | *(outbuffer + offset + 2) = (u_intsi.base >> (8 * 2)) & 0xFF; |
nucho | 0:06fc856e99ca | 76 | *(outbuffer + offset + 3) = (u_intsi.base >> (8 * 3)) & 0xFF; |
nucho | 0:06fc856e99ca | 77 | offset += sizeof(this->ints[i]); |
nucho | 0:06fc856e99ca | 78 | } |
nucho | 0:06fc856e99ca | 79 | *(outbuffer + offset++) = floats_length; |
nucho | 0:06fc856e99ca | 80 | *(outbuffer + offset++) = 0; |
nucho | 0:06fc856e99ca | 81 | *(outbuffer + offset++) = 0; |
nucho | 0:06fc856e99ca | 82 | *(outbuffer + offset++) = 0; |
nucho | 0:06fc856e99ca | 83 | for( unsigned char i = 0; i < floats_length; i++){ |
nucho | 0:06fc856e99ca | 84 | union { |
nucho | 0:06fc856e99ca | 85 | float real; |
nucho | 0:06fc856e99ca | 86 | unsigned long base; |
nucho | 0:06fc856e99ca | 87 | } u_floatsi; |
nucho | 0:06fc856e99ca | 88 | u_floatsi.real = this->floats[i]; |
nucho | 0:06fc856e99ca | 89 | *(outbuffer + offset + 0) = (u_floatsi.base >> (8 * 0)) & 0xFF; |
nucho | 0:06fc856e99ca | 90 | *(outbuffer + offset + 1) = (u_floatsi.base >> (8 * 1)) & 0xFF; |
nucho | 0:06fc856e99ca | 91 | *(outbuffer + offset + 2) = (u_floatsi.base >> (8 * 2)) & 0xFF; |
nucho | 0:06fc856e99ca | 92 | *(outbuffer + offset + 3) = (u_floatsi.base >> (8 * 3)) & 0xFF; |
nucho | 0:06fc856e99ca | 93 | offset += sizeof(this->floats[i]); |
nucho | 0:06fc856e99ca | 94 | } |
nucho | 0:06fc856e99ca | 95 | *(outbuffer + offset++) = strings_length; |
nucho | 0:06fc856e99ca | 96 | *(outbuffer + offset++) = 0; |
nucho | 0:06fc856e99ca | 97 | *(outbuffer + offset++) = 0; |
nucho | 0:06fc856e99ca | 98 | *(outbuffer + offset++) = 0; |
nucho | 0:06fc856e99ca | 99 | for( unsigned char i = 0; i < strings_length; i++){ |
nucho | 0:06fc856e99ca | 100 | long * length_stringsi = (long *)(outbuffer + offset); |
nucho | 0:06fc856e99ca | 101 | *length_stringsi = strlen( (const char*) this->strings[i]); |
nucho | 0:06fc856e99ca | 102 | offset += 4; |
nucho | 0:06fc856e99ca | 103 | memcpy(outbuffer + offset, this->strings[i], *length_stringsi); |
nucho | 0:06fc856e99ca | 104 | offset += *length_stringsi; |
nucho | 0:06fc856e99ca | 105 | } |
nucho | 0:06fc856e99ca | 106 | return offset; |
nucho | 0:06fc856e99ca | 107 | } |
nucho | 0:06fc856e99ca | 108 | |
nucho | 0:06fc856e99ca | 109 | virtual int deserialize(unsigned char *inbuffer) |
nucho | 0:06fc856e99ca | 110 | { |
nucho | 0:06fc856e99ca | 111 | int offset = 0; |
nucho | 0:06fc856e99ca | 112 | unsigned char ints_lengthT = *(inbuffer + offset++); |
nucho | 0:06fc856e99ca | 113 | if(ints_lengthT > ints_length) |
nucho | 0:06fc856e99ca | 114 | this->ints = (long*)realloc(this->ints, ints_lengthT * sizeof(long)); |
nucho | 0:06fc856e99ca | 115 | offset += 3; |
nucho | 0:06fc856e99ca | 116 | ints_length = ints_lengthT; |
nucho | 0:06fc856e99ca | 117 | for( unsigned char i = 0; i < ints_length; i++){ |
nucho | 0:06fc856e99ca | 118 | union { |
nucho | 0:06fc856e99ca | 119 | long real; |
nucho | 0:06fc856e99ca | 120 | unsigned long base; |
nucho | 0:06fc856e99ca | 121 | } u_st_ints; |
nucho | 0:06fc856e99ca | 122 | u_st_ints.base = 0; |
nucho | 0:06fc856e99ca | 123 | u_st_ints.base |= ((typeof(u_st_ints.base)) (*(inbuffer + offset + 0))) << (8 * 0); |
nucho | 0:06fc856e99ca | 124 | u_st_ints.base |= ((typeof(u_st_ints.base)) (*(inbuffer + offset + 1))) << (8 * 1); |
nucho | 0:06fc856e99ca | 125 | u_st_ints.base |= ((typeof(u_st_ints.base)) (*(inbuffer + offset + 2))) << (8 * 2); |
nucho | 0:06fc856e99ca | 126 | u_st_ints.base |= ((typeof(u_st_ints.base)) (*(inbuffer + offset + 3))) << (8 * 3); |
nucho | 0:06fc856e99ca | 127 | this->st_ints = u_st_ints.real; |
nucho | 0:06fc856e99ca | 128 | offset += sizeof(this->st_ints); |
nucho | 0:06fc856e99ca | 129 | memcpy( &(this->ints[i]), &(this->st_ints), sizeof(long)); |
nucho | 0:06fc856e99ca | 130 | } |
nucho | 0:06fc856e99ca | 131 | unsigned char floats_lengthT = *(inbuffer + offset++); |
nucho | 0:06fc856e99ca | 132 | if(floats_lengthT > floats_length) |
nucho | 0:06fc856e99ca | 133 | this->floats = (float*)realloc(this->floats, floats_lengthT * sizeof(float)); |
nucho | 0:06fc856e99ca | 134 | offset += 3; |
nucho | 0:06fc856e99ca | 135 | floats_length = floats_lengthT; |
nucho | 0:06fc856e99ca | 136 | for( unsigned char i = 0; i < floats_length; i++){ |
nucho | 0:06fc856e99ca | 137 | union { |
nucho | 0:06fc856e99ca | 138 | float real; |
nucho | 0:06fc856e99ca | 139 | unsigned long base; |
nucho | 0:06fc856e99ca | 140 | } u_st_floats; |
nucho | 0:06fc856e99ca | 141 | u_st_floats.base = 0; |
nucho | 0:06fc856e99ca | 142 | u_st_floats.base |= ((typeof(u_st_floats.base)) (*(inbuffer + offset + 0))) << (8 * 0); |
nucho | 0:06fc856e99ca | 143 | u_st_floats.base |= ((typeof(u_st_floats.base)) (*(inbuffer + offset + 1))) << (8 * 1); |
nucho | 0:06fc856e99ca | 144 | u_st_floats.base |= ((typeof(u_st_floats.base)) (*(inbuffer + offset + 2))) << (8 * 2); |
nucho | 0:06fc856e99ca | 145 | u_st_floats.base |= ((typeof(u_st_floats.base)) (*(inbuffer + offset + 3))) << (8 * 3); |
nucho | 0:06fc856e99ca | 146 | this->st_floats = u_st_floats.real; |
nucho | 0:06fc856e99ca | 147 | offset += sizeof(this->st_floats); |
nucho | 0:06fc856e99ca | 148 | memcpy( &(this->floats[i]), &(this->st_floats), sizeof(float)); |
nucho | 0:06fc856e99ca | 149 | } |
nucho | 0:06fc856e99ca | 150 | unsigned char strings_lengthT = *(inbuffer + offset++); |
nucho | 0:06fc856e99ca | 151 | if(strings_lengthT > strings_length) |
nucho | 0:06fc856e99ca | 152 | this->strings = (char**)realloc(this->strings, strings_lengthT * sizeof(char*)); |
nucho | 0:06fc856e99ca | 153 | offset += 3; |
nucho | 0:06fc856e99ca | 154 | strings_length = strings_lengthT; |
nucho | 0:06fc856e99ca | 155 | for( unsigned char i = 0; i < strings_length; i++){ |
nucho | 0:06fc856e99ca | 156 | uint32_t length_st_strings = *(uint32_t *)(inbuffer + offset); |
nucho | 0:06fc856e99ca | 157 | offset += 4; |
nucho | 0:06fc856e99ca | 158 | for(unsigned int k= offset; k< offset+length_st_strings; ++k){ |
nucho | 0:06fc856e99ca | 159 | inbuffer[k-1]=inbuffer[k]; |
nucho | 0:06fc856e99ca | 160 | } |
nucho | 0:06fc856e99ca | 161 | inbuffer[offset+length_st_strings-1]=0; |
nucho | 0:06fc856e99ca | 162 | this->st_strings = (char *)(inbuffer + offset-1); |
nucho | 0:06fc856e99ca | 163 | offset += length_st_strings; |
nucho | 0:06fc856e99ca | 164 | memcpy( &(this->strings[i]), &(this->st_strings), sizeof(char*)); |
nucho | 0:06fc856e99ca | 165 | } |
nucho | 0:06fc856e99ca | 166 | return offset; |
nucho | 0:06fc856e99ca | 167 | } |
nucho | 0:06fc856e99ca | 168 | |
nucho | 0:06fc856e99ca | 169 | virtual const char * getType(){ return REQUESTPARAM; }; |
nucho | 0:06fc856e99ca | 170 | |
nucho | 0:06fc856e99ca | 171 | }; |
nucho | 0:06fc856e99ca | 172 | |
nucho | 0:06fc856e99ca | 173 | } |
nucho | 0:06fc856e99ca | 174 | #endif |