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_Spawn_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_SERVICE_Spawn_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 turtlesim
akashvibhute 0:30537dec6e0b 9 {
akashvibhute 0:30537dec6e0b 10
akashvibhute 0:30537dec6e0b 11 static const char SPAWN[] = "turtlesim/Spawn";
akashvibhute 0:30537dec6e0b 12
akashvibhute 0:30537dec6e0b 13 class SpawnRequest : public ros::Msg
akashvibhute 0:30537dec6e0b 14 {
akashvibhute 0:30537dec6e0b 15 public:
akashvibhute 0:30537dec6e0b 16 float x;
akashvibhute 0:30537dec6e0b 17 float y;
akashvibhute 0:30537dec6e0b 18 float theta;
akashvibhute 0:30537dec6e0b 19 const char* name;
akashvibhute 0:30537dec6e0b 20
akashvibhute 0:30537dec6e0b 21 SpawnRequest():
akashvibhute 0:30537dec6e0b 22 x(0),
akashvibhute 0:30537dec6e0b 23 y(0),
akashvibhute 0:30537dec6e0b 24 theta(0),
akashvibhute 0:30537dec6e0b 25 name("")
akashvibhute 0:30537dec6e0b 26 {
akashvibhute 0:30537dec6e0b 27 }
akashvibhute 0:30537dec6e0b 28
akashvibhute 0:30537dec6e0b 29 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 30 {
akashvibhute 0:30537dec6e0b 31 int offset = 0;
akashvibhute 0:30537dec6e0b 32 union {
akashvibhute 0:30537dec6e0b 33 float real;
akashvibhute 0:30537dec6e0b 34 uint32_t base;
akashvibhute 0:30537dec6e0b 35 } u_x;
akashvibhute 0:30537dec6e0b 36 u_x.real = this->x;
akashvibhute 0:30537dec6e0b 37 *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 38 *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 39 *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 40 *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 41 offset += sizeof(this->x);
akashvibhute 0:30537dec6e0b 42 union {
akashvibhute 0:30537dec6e0b 43 float real;
akashvibhute 0:30537dec6e0b 44 uint32_t base;
akashvibhute 0:30537dec6e0b 45 } u_y;
akashvibhute 0:30537dec6e0b 46 u_y.real = this->y;
akashvibhute 0:30537dec6e0b 47 *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 48 *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 49 *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 50 *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 51 offset += sizeof(this->y);
akashvibhute 0:30537dec6e0b 52 union {
akashvibhute 0:30537dec6e0b 53 float real;
akashvibhute 0:30537dec6e0b 54 uint32_t base;
akashvibhute 0:30537dec6e0b 55 } u_theta;
akashvibhute 0:30537dec6e0b 56 u_theta.real = this->theta;
akashvibhute 0:30537dec6e0b 57 *(outbuffer + offset + 0) = (u_theta.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 58 *(outbuffer + offset + 1) = (u_theta.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 59 *(outbuffer + offset + 2) = (u_theta.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 60 *(outbuffer + offset + 3) = (u_theta.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 61 offset += sizeof(this->theta);
akashvibhute 0:30537dec6e0b 62 uint32_t length_name = strlen(this->name);
akashvibhute 0:30537dec6e0b 63 memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 64 offset += 4;
akashvibhute 0:30537dec6e0b 65 memcpy(outbuffer + offset, this->name, length_name);
akashvibhute 0:30537dec6e0b 66 offset += length_name;
akashvibhute 0:30537dec6e0b 67 return offset;
akashvibhute 0:30537dec6e0b 68 }
akashvibhute 0:30537dec6e0b 69
akashvibhute 0:30537dec6e0b 70 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 71 {
akashvibhute 0:30537dec6e0b 72 int offset = 0;
akashvibhute 0:30537dec6e0b 73 union {
akashvibhute 0:30537dec6e0b 74 float real;
akashvibhute 0:30537dec6e0b 75 uint32_t base;
akashvibhute 0:30537dec6e0b 76 } u_x;
akashvibhute 0:30537dec6e0b 77 u_x.base = 0;
akashvibhute 0:30537dec6e0b 78 u_x.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 79 u_x.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 80 u_x.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 81 u_x.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 82 this->x = u_x.real;
akashvibhute 0:30537dec6e0b 83 offset += sizeof(this->x);
akashvibhute 0:30537dec6e0b 84 union {
akashvibhute 0:30537dec6e0b 85 float real;
akashvibhute 0:30537dec6e0b 86 uint32_t base;
akashvibhute 0:30537dec6e0b 87 } u_y;
akashvibhute 0:30537dec6e0b 88 u_y.base = 0;
akashvibhute 0:30537dec6e0b 89 u_y.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 90 u_y.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 91 u_y.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 92 u_y.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 93 this->y = u_y.real;
akashvibhute 0:30537dec6e0b 94 offset += sizeof(this->y);
akashvibhute 0:30537dec6e0b 95 union {
akashvibhute 0:30537dec6e0b 96 float real;
akashvibhute 0:30537dec6e0b 97 uint32_t base;
akashvibhute 0:30537dec6e0b 98 } u_theta;
akashvibhute 0:30537dec6e0b 99 u_theta.base = 0;
akashvibhute 0:30537dec6e0b 100 u_theta.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 101 u_theta.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 102 u_theta.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 103 u_theta.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 104 this->theta = u_theta.real;
akashvibhute 0:30537dec6e0b 105 offset += sizeof(this->theta);
akashvibhute 0:30537dec6e0b 106 uint32_t length_name;
akashvibhute 0:30537dec6e0b 107 memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 108 offset += 4;
akashvibhute 0:30537dec6e0b 109 for(unsigned int k= offset; k< offset+length_name; ++k){
akashvibhute 0:30537dec6e0b 110 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 111 }
akashvibhute 0:30537dec6e0b 112 inbuffer[offset+length_name-1]=0;
akashvibhute 0:30537dec6e0b 113 this->name = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 114 offset += length_name;
akashvibhute 0:30537dec6e0b 115 return offset;
akashvibhute 0:30537dec6e0b 116 }
akashvibhute 0:30537dec6e0b 117
akashvibhute 0:30537dec6e0b 118 const char * getType(){ return SPAWN; };
akashvibhute 0:30537dec6e0b 119 const char * getMD5(){ return "57f001c49ab7b11d699f8606c1f4f7ff"; };
akashvibhute 0:30537dec6e0b 120
akashvibhute 0:30537dec6e0b 121 };
akashvibhute 0:30537dec6e0b 122
akashvibhute 0:30537dec6e0b 123 class SpawnResponse : public ros::Msg
akashvibhute 0:30537dec6e0b 124 {
akashvibhute 0:30537dec6e0b 125 public:
akashvibhute 0:30537dec6e0b 126 const char* name;
akashvibhute 0:30537dec6e0b 127
akashvibhute 0:30537dec6e0b 128 SpawnResponse():
akashvibhute 0:30537dec6e0b 129 name("")
akashvibhute 0:30537dec6e0b 130 {
akashvibhute 0:30537dec6e0b 131 }
akashvibhute 0:30537dec6e0b 132
akashvibhute 0:30537dec6e0b 133 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 134 {
akashvibhute 0:30537dec6e0b 135 int offset = 0;
akashvibhute 0:30537dec6e0b 136 uint32_t length_name = strlen(this->name);
akashvibhute 0:30537dec6e0b 137 memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 138 offset += 4;
akashvibhute 0:30537dec6e0b 139 memcpy(outbuffer + offset, this->name, length_name);
akashvibhute 0:30537dec6e0b 140 offset += length_name;
akashvibhute 0:30537dec6e0b 141 return offset;
akashvibhute 0:30537dec6e0b 142 }
akashvibhute 0:30537dec6e0b 143
akashvibhute 0:30537dec6e0b 144 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 145 {
akashvibhute 0:30537dec6e0b 146 int offset = 0;
akashvibhute 0:30537dec6e0b 147 uint32_t length_name;
akashvibhute 0:30537dec6e0b 148 memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 149 offset += 4;
akashvibhute 0:30537dec6e0b 150 for(unsigned int k= offset; k< offset+length_name; ++k){
akashvibhute 0:30537dec6e0b 151 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 152 }
akashvibhute 0:30537dec6e0b 153 inbuffer[offset+length_name-1]=0;
akashvibhute 0:30537dec6e0b 154 this->name = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 155 offset += length_name;
akashvibhute 0:30537dec6e0b 156 return offset;
akashvibhute 0:30537dec6e0b 157 }
akashvibhute 0:30537dec6e0b 158
akashvibhute 0:30537dec6e0b 159 const char * getType(){ return SPAWN; };
akashvibhute 0:30537dec6e0b 160 const char * getMD5(){ return "c1f3d28f1b044c871e6eff2e9fc3c667"; };
akashvibhute 0:30537dec6e0b 161
akashvibhute 0:30537dec6e0b 162 };
akashvibhute 0:30537dec6e0b 163
akashvibhute 0:30537dec6e0b 164 class Spawn {
akashvibhute 0:30537dec6e0b 165 public:
akashvibhute 0:30537dec6e0b 166 typedef SpawnRequest Request;
akashvibhute 0:30537dec6e0b 167 typedef SpawnResponse Response;
akashvibhute 0:30537dec6e0b 168 };
akashvibhute 0:30537dec6e0b 169
akashvibhute 0:30537dec6e0b 170 }
akashvibhute 0:30537dec6e0b 171 #endif
akashvibhute 0:30537dec6e0b 172