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_smach_msgs_SmachContainerStructure_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_smach_msgs_SmachContainerStructure_h
akashvibhute 0:30537dec6e0b 3
akashvibhute 0:30537dec6e0b 4 #include <stdint.h>
akashvibhute 0:30537dec6e0b 5 #include <string.h>
akashvibhute 0:30537dec6e0b 6 #include <stdlib.h>
akashvibhute 0:30537dec6e0b 7 #include "ros/msg.h"
akashvibhute 0:30537dec6e0b 8 #include "std_msgs/Header.h"
akashvibhute 0:30537dec6e0b 9
akashvibhute 0:30537dec6e0b 10 namespace smach_msgs
akashvibhute 0:30537dec6e0b 11 {
akashvibhute 0:30537dec6e0b 12
akashvibhute 0:30537dec6e0b 13 class SmachContainerStructure : public ros::Msg
akashvibhute 0:30537dec6e0b 14 {
akashvibhute 0:30537dec6e0b 15 public:
akashvibhute 0:30537dec6e0b 16 std_msgs::Header header;
akashvibhute 0:30537dec6e0b 17 const char* path;
akashvibhute 0:30537dec6e0b 18 uint8_t children_length;
akashvibhute 0:30537dec6e0b 19 char* st_children;
akashvibhute 0:30537dec6e0b 20 char* * children;
akashvibhute 0:30537dec6e0b 21 uint8_t internal_outcomes_length;
akashvibhute 0:30537dec6e0b 22 char* st_internal_outcomes;
akashvibhute 0:30537dec6e0b 23 char* * internal_outcomes;
akashvibhute 0:30537dec6e0b 24 uint8_t outcomes_from_length;
akashvibhute 0:30537dec6e0b 25 char* st_outcomes_from;
akashvibhute 0:30537dec6e0b 26 char* * outcomes_from;
akashvibhute 0:30537dec6e0b 27 uint8_t outcomes_to_length;
akashvibhute 0:30537dec6e0b 28 char* st_outcomes_to;
akashvibhute 0:30537dec6e0b 29 char* * outcomes_to;
akashvibhute 0:30537dec6e0b 30 uint8_t container_outcomes_length;
akashvibhute 0:30537dec6e0b 31 char* st_container_outcomes;
akashvibhute 0:30537dec6e0b 32 char* * container_outcomes;
akashvibhute 0:30537dec6e0b 33
akashvibhute 0:30537dec6e0b 34 SmachContainerStructure():
akashvibhute 0:30537dec6e0b 35 header(),
akashvibhute 0:30537dec6e0b 36 path(""),
akashvibhute 0:30537dec6e0b 37 children_length(0), children(NULL),
akashvibhute 0:30537dec6e0b 38 internal_outcomes_length(0), internal_outcomes(NULL),
akashvibhute 0:30537dec6e0b 39 outcomes_from_length(0), outcomes_from(NULL),
akashvibhute 0:30537dec6e0b 40 outcomes_to_length(0), outcomes_to(NULL),
akashvibhute 0:30537dec6e0b 41 container_outcomes_length(0), container_outcomes(NULL)
akashvibhute 0:30537dec6e0b 42 {
akashvibhute 0:30537dec6e0b 43 }
akashvibhute 0:30537dec6e0b 44
akashvibhute 0:30537dec6e0b 45 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 46 {
akashvibhute 0:30537dec6e0b 47 int offset = 0;
akashvibhute 0:30537dec6e0b 48 offset += this->header.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 49 uint32_t length_path = strlen(this->path);
akashvibhute 0:30537dec6e0b 50 memcpy(outbuffer + offset, &length_path, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 51 offset += 4;
akashvibhute 0:30537dec6e0b 52 memcpy(outbuffer + offset, this->path, length_path);
akashvibhute 0:30537dec6e0b 53 offset += length_path;
akashvibhute 0:30537dec6e0b 54 *(outbuffer + offset++) = children_length;
akashvibhute 0:30537dec6e0b 55 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 56 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 57 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 58 for( uint8_t i = 0; i < children_length; i++){
akashvibhute 0:30537dec6e0b 59 uint32_t length_childreni = strlen(this->children[i]);
akashvibhute 0:30537dec6e0b 60 memcpy(outbuffer + offset, &length_childreni, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 61 offset += 4;
akashvibhute 0:30537dec6e0b 62 memcpy(outbuffer + offset, this->children[i], length_childreni);
akashvibhute 0:30537dec6e0b 63 offset += length_childreni;
akashvibhute 0:30537dec6e0b 64 }
akashvibhute 0:30537dec6e0b 65 *(outbuffer + offset++) = internal_outcomes_length;
akashvibhute 0:30537dec6e0b 66 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 67 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 68 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 69 for( uint8_t i = 0; i < internal_outcomes_length; i++){
akashvibhute 0:30537dec6e0b 70 uint32_t length_internal_outcomesi = strlen(this->internal_outcomes[i]);
akashvibhute 0:30537dec6e0b 71 memcpy(outbuffer + offset, &length_internal_outcomesi, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 72 offset += 4;
akashvibhute 0:30537dec6e0b 73 memcpy(outbuffer + offset, this->internal_outcomes[i], length_internal_outcomesi);
akashvibhute 0:30537dec6e0b 74 offset += length_internal_outcomesi;
akashvibhute 0:30537dec6e0b 75 }
akashvibhute 0:30537dec6e0b 76 *(outbuffer + offset++) = outcomes_from_length;
akashvibhute 0:30537dec6e0b 77 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 78 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 79 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 80 for( uint8_t i = 0; i < outcomes_from_length; i++){
akashvibhute 0:30537dec6e0b 81 uint32_t length_outcomes_fromi = strlen(this->outcomes_from[i]);
akashvibhute 0:30537dec6e0b 82 memcpy(outbuffer + offset, &length_outcomes_fromi, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 83 offset += 4;
akashvibhute 0:30537dec6e0b 84 memcpy(outbuffer + offset, this->outcomes_from[i], length_outcomes_fromi);
akashvibhute 0:30537dec6e0b 85 offset += length_outcomes_fromi;
akashvibhute 0:30537dec6e0b 86 }
akashvibhute 0:30537dec6e0b 87 *(outbuffer + offset++) = outcomes_to_length;
akashvibhute 0:30537dec6e0b 88 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 89 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 90 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 91 for( uint8_t i = 0; i < outcomes_to_length; i++){
akashvibhute 0:30537dec6e0b 92 uint32_t length_outcomes_toi = strlen(this->outcomes_to[i]);
akashvibhute 0:30537dec6e0b 93 memcpy(outbuffer + offset, &length_outcomes_toi, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 94 offset += 4;
akashvibhute 0:30537dec6e0b 95 memcpy(outbuffer + offset, this->outcomes_to[i], length_outcomes_toi);
akashvibhute 0:30537dec6e0b 96 offset += length_outcomes_toi;
akashvibhute 0:30537dec6e0b 97 }
akashvibhute 0:30537dec6e0b 98 *(outbuffer + offset++) = container_outcomes_length;
akashvibhute 0:30537dec6e0b 99 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 100 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 101 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 102 for( uint8_t i = 0; i < container_outcomes_length; i++){
akashvibhute 0:30537dec6e0b 103 uint32_t length_container_outcomesi = strlen(this->container_outcomes[i]);
akashvibhute 0:30537dec6e0b 104 memcpy(outbuffer + offset, &length_container_outcomesi, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 105 offset += 4;
akashvibhute 0:30537dec6e0b 106 memcpy(outbuffer + offset, this->container_outcomes[i], length_container_outcomesi);
akashvibhute 0:30537dec6e0b 107 offset += length_container_outcomesi;
akashvibhute 0:30537dec6e0b 108 }
akashvibhute 0:30537dec6e0b 109 return offset;
akashvibhute 0:30537dec6e0b 110 }
akashvibhute 0:30537dec6e0b 111
akashvibhute 0:30537dec6e0b 112 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 113 {
akashvibhute 0:30537dec6e0b 114 int offset = 0;
akashvibhute 0:30537dec6e0b 115 offset += this->header.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 116 uint32_t length_path;
akashvibhute 0:30537dec6e0b 117 memcpy(&length_path, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 118 offset += 4;
akashvibhute 0:30537dec6e0b 119 for(unsigned int k= offset; k< offset+length_path; ++k){
akashvibhute 0:30537dec6e0b 120 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 121 }
akashvibhute 0:30537dec6e0b 122 inbuffer[offset+length_path-1]=0;
akashvibhute 0:30537dec6e0b 123 this->path = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 124 offset += length_path;
akashvibhute 0:30537dec6e0b 125 uint8_t children_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 126 if(children_lengthT > children_length)
akashvibhute 0:30537dec6e0b 127 this->children = (char**)realloc(this->children, children_lengthT * sizeof(char*));
akashvibhute 0:30537dec6e0b 128 offset += 3;
akashvibhute 0:30537dec6e0b 129 children_length = children_lengthT;
akashvibhute 0:30537dec6e0b 130 for( uint8_t i = 0; i < children_length; i++){
akashvibhute 0:30537dec6e0b 131 uint32_t length_st_children;
akashvibhute 0:30537dec6e0b 132 memcpy(&length_st_children, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 133 offset += 4;
akashvibhute 0:30537dec6e0b 134 for(unsigned int k= offset; k< offset+length_st_children; ++k){
akashvibhute 0:30537dec6e0b 135 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 136 }
akashvibhute 0:30537dec6e0b 137 inbuffer[offset+length_st_children-1]=0;
akashvibhute 0:30537dec6e0b 138 this->st_children = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 139 offset += length_st_children;
akashvibhute 0:30537dec6e0b 140 memcpy( &(this->children[i]), &(this->st_children), sizeof(char*));
akashvibhute 0:30537dec6e0b 141 }
akashvibhute 0:30537dec6e0b 142 uint8_t internal_outcomes_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 143 if(internal_outcomes_lengthT > internal_outcomes_length)
akashvibhute 0:30537dec6e0b 144 this->internal_outcomes = (char**)realloc(this->internal_outcomes, internal_outcomes_lengthT * sizeof(char*));
akashvibhute 0:30537dec6e0b 145 offset += 3;
akashvibhute 0:30537dec6e0b 146 internal_outcomes_length = internal_outcomes_lengthT;
akashvibhute 0:30537dec6e0b 147 for( uint8_t i = 0; i < internal_outcomes_length; i++){
akashvibhute 0:30537dec6e0b 148 uint32_t length_st_internal_outcomes;
akashvibhute 0:30537dec6e0b 149 memcpy(&length_st_internal_outcomes, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 150 offset += 4;
akashvibhute 0:30537dec6e0b 151 for(unsigned int k= offset; k< offset+length_st_internal_outcomes; ++k){
akashvibhute 0:30537dec6e0b 152 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 153 }
akashvibhute 0:30537dec6e0b 154 inbuffer[offset+length_st_internal_outcomes-1]=0;
akashvibhute 0:30537dec6e0b 155 this->st_internal_outcomes = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 156 offset += length_st_internal_outcomes;
akashvibhute 0:30537dec6e0b 157 memcpy( &(this->internal_outcomes[i]), &(this->st_internal_outcomes), sizeof(char*));
akashvibhute 0:30537dec6e0b 158 }
akashvibhute 0:30537dec6e0b 159 uint8_t outcomes_from_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 160 if(outcomes_from_lengthT > outcomes_from_length)
akashvibhute 0:30537dec6e0b 161 this->outcomes_from = (char**)realloc(this->outcomes_from, outcomes_from_lengthT * sizeof(char*));
akashvibhute 0:30537dec6e0b 162 offset += 3;
akashvibhute 0:30537dec6e0b 163 outcomes_from_length = outcomes_from_lengthT;
akashvibhute 0:30537dec6e0b 164 for( uint8_t i = 0; i < outcomes_from_length; i++){
akashvibhute 0:30537dec6e0b 165 uint32_t length_st_outcomes_from;
akashvibhute 0:30537dec6e0b 166 memcpy(&length_st_outcomes_from, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 167 offset += 4;
akashvibhute 0:30537dec6e0b 168 for(unsigned int k= offset; k< offset+length_st_outcomes_from; ++k){
akashvibhute 0:30537dec6e0b 169 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 170 }
akashvibhute 0:30537dec6e0b 171 inbuffer[offset+length_st_outcomes_from-1]=0;
akashvibhute 0:30537dec6e0b 172 this->st_outcomes_from = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 173 offset += length_st_outcomes_from;
akashvibhute 0:30537dec6e0b 174 memcpy( &(this->outcomes_from[i]), &(this->st_outcomes_from), sizeof(char*));
akashvibhute 0:30537dec6e0b 175 }
akashvibhute 0:30537dec6e0b 176 uint8_t outcomes_to_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 177 if(outcomes_to_lengthT > outcomes_to_length)
akashvibhute 0:30537dec6e0b 178 this->outcomes_to = (char**)realloc(this->outcomes_to, outcomes_to_lengthT * sizeof(char*));
akashvibhute 0:30537dec6e0b 179 offset += 3;
akashvibhute 0:30537dec6e0b 180 outcomes_to_length = outcomes_to_lengthT;
akashvibhute 0:30537dec6e0b 181 for( uint8_t i = 0; i < outcomes_to_length; i++){
akashvibhute 0:30537dec6e0b 182 uint32_t length_st_outcomes_to;
akashvibhute 0:30537dec6e0b 183 memcpy(&length_st_outcomes_to, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 184 offset += 4;
akashvibhute 0:30537dec6e0b 185 for(unsigned int k= offset; k< offset+length_st_outcomes_to; ++k){
akashvibhute 0:30537dec6e0b 186 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 187 }
akashvibhute 0:30537dec6e0b 188 inbuffer[offset+length_st_outcomes_to-1]=0;
akashvibhute 0:30537dec6e0b 189 this->st_outcomes_to = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 190 offset += length_st_outcomes_to;
akashvibhute 0:30537dec6e0b 191 memcpy( &(this->outcomes_to[i]), &(this->st_outcomes_to), sizeof(char*));
akashvibhute 0:30537dec6e0b 192 }
akashvibhute 0:30537dec6e0b 193 uint8_t container_outcomes_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 194 if(container_outcomes_lengthT > container_outcomes_length)
akashvibhute 0:30537dec6e0b 195 this->container_outcomes = (char**)realloc(this->container_outcomes, container_outcomes_lengthT * sizeof(char*));
akashvibhute 0:30537dec6e0b 196 offset += 3;
akashvibhute 0:30537dec6e0b 197 container_outcomes_length = container_outcomes_lengthT;
akashvibhute 0:30537dec6e0b 198 for( uint8_t i = 0; i < container_outcomes_length; i++){
akashvibhute 0:30537dec6e0b 199 uint32_t length_st_container_outcomes;
akashvibhute 0:30537dec6e0b 200 memcpy(&length_st_container_outcomes, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 201 offset += 4;
akashvibhute 0:30537dec6e0b 202 for(unsigned int k= offset; k< offset+length_st_container_outcomes; ++k){
akashvibhute 0:30537dec6e0b 203 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 204 }
akashvibhute 0:30537dec6e0b 205 inbuffer[offset+length_st_container_outcomes-1]=0;
akashvibhute 0:30537dec6e0b 206 this->st_container_outcomes = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 207 offset += length_st_container_outcomes;
akashvibhute 0:30537dec6e0b 208 memcpy( &(this->container_outcomes[i]), &(this->st_container_outcomes), sizeof(char*));
akashvibhute 0:30537dec6e0b 209 }
akashvibhute 0:30537dec6e0b 210 return offset;
akashvibhute 0:30537dec6e0b 211 }
akashvibhute 0:30537dec6e0b 212
akashvibhute 0:30537dec6e0b 213 const char * getType(){ return "smach_msgs/SmachContainerStructure"; };
akashvibhute 0:30537dec6e0b 214 const char * getMD5(){ return "3d3d1e0d0f99779ee9e58101a5dcf7ea"; };
akashvibhute 0:30537dec6e0b 215
akashvibhute 0:30537dec6e0b 216 };
akashvibhute 0:30537dec6e0b 217
akashvibhute 0:30537dec6e0b 218 }
akashvibhute 0:30537dec6e0b 219 #endif