rosserial library for mbed Inspired by nucho's rosserial library This library is still under development

Dependencies:   MODSERIAL mbed

Dependents:   mbed_roshydro_test

Library still under development!

Committer:
akashvibhute
Date:
Sun Feb 15 10:53:43 2015 +0000
Revision:
0:30537dec6e0b
First commit; Library still need to be debugged, compilation issues with new mbed and modserial updates.

Who changed what in which revision?

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