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_visualization_msgs_Marker_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_visualization_msgs_Marker_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 #include "geometry_msgs/Pose.h"
akashvibhute 0:30537dec6e0b 10 #include "geometry_msgs/Vector3.h"
akashvibhute 0:30537dec6e0b 11 #include "std_msgs/ColorRGBA.h"
akashvibhute 0:30537dec6e0b 12 #include "ros/duration.h"
akashvibhute 0:30537dec6e0b 13 #include "geometry_msgs/Point.h"
akashvibhute 0:30537dec6e0b 14
akashvibhute 0:30537dec6e0b 15 namespace visualization_msgs
akashvibhute 0:30537dec6e0b 16 {
akashvibhute 0:30537dec6e0b 17
akashvibhute 0:30537dec6e0b 18 class Marker : public ros::Msg
akashvibhute 0:30537dec6e0b 19 {
akashvibhute 0:30537dec6e0b 20 public:
akashvibhute 0:30537dec6e0b 21 std_msgs::Header header;
akashvibhute 0:30537dec6e0b 22 const char* ns;
akashvibhute 0:30537dec6e0b 23 int32_t id;
akashvibhute 0:30537dec6e0b 24 int32_t type;
akashvibhute 0:30537dec6e0b 25 int32_t action;
akashvibhute 0:30537dec6e0b 26 geometry_msgs::Pose pose;
akashvibhute 0:30537dec6e0b 27 geometry_msgs::Vector3 scale;
akashvibhute 0:30537dec6e0b 28 std_msgs::ColorRGBA color;
akashvibhute 0:30537dec6e0b 29 ros::Duration lifetime;
akashvibhute 0:30537dec6e0b 30 bool frame_locked;
akashvibhute 0:30537dec6e0b 31 uint8_t points_length;
akashvibhute 0:30537dec6e0b 32 geometry_msgs::Point st_points;
akashvibhute 0:30537dec6e0b 33 geometry_msgs::Point * points;
akashvibhute 0:30537dec6e0b 34 uint8_t colors_length;
akashvibhute 0:30537dec6e0b 35 std_msgs::ColorRGBA st_colors;
akashvibhute 0:30537dec6e0b 36 std_msgs::ColorRGBA * colors;
akashvibhute 0:30537dec6e0b 37 const char* text;
akashvibhute 0:30537dec6e0b 38 const char* mesh_resource;
akashvibhute 0:30537dec6e0b 39 bool mesh_use_embedded_materials;
akashvibhute 0:30537dec6e0b 40 enum { ARROW = 0 };
akashvibhute 0:30537dec6e0b 41 enum { CUBE = 1 };
akashvibhute 0:30537dec6e0b 42 enum { SPHERE = 2 };
akashvibhute 0:30537dec6e0b 43 enum { CYLINDER = 3 };
akashvibhute 0:30537dec6e0b 44 enum { LINE_STRIP = 4 };
akashvibhute 0:30537dec6e0b 45 enum { LINE_LIST = 5 };
akashvibhute 0:30537dec6e0b 46 enum { CUBE_LIST = 6 };
akashvibhute 0:30537dec6e0b 47 enum { SPHERE_LIST = 7 };
akashvibhute 0:30537dec6e0b 48 enum { POINTS = 8 };
akashvibhute 0:30537dec6e0b 49 enum { TEXT_VIEW_FACING = 9 };
akashvibhute 0:30537dec6e0b 50 enum { MESH_RESOURCE = 10 };
akashvibhute 0:30537dec6e0b 51 enum { TRIANGLE_LIST = 11 };
akashvibhute 0:30537dec6e0b 52 enum { ADD = 0 };
akashvibhute 0:30537dec6e0b 53 enum { MODIFY = 0 };
akashvibhute 0:30537dec6e0b 54 enum { DELETE = 2 };
akashvibhute 0:30537dec6e0b 55
akashvibhute 0:30537dec6e0b 56 Marker():
akashvibhute 0:30537dec6e0b 57 header(),
akashvibhute 0:30537dec6e0b 58 ns(""),
akashvibhute 0:30537dec6e0b 59 id(0),
akashvibhute 0:30537dec6e0b 60 type(0),
akashvibhute 0:30537dec6e0b 61 action(0),
akashvibhute 0:30537dec6e0b 62 pose(),
akashvibhute 0:30537dec6e0b 63 scale(),
akashvibhute 0:30537dec6e0b 64 color(),
akashvibhute 0:30537dec6e0b 65 lifetime(),
akashvibhute 0:30537dec6e0b 66 frame_locked(0),
akashvibhute 0:30537dec6e0b 67 points_length(0), points(NULL),
akashvibhute 0:30537dec6e0b 68 colors_length(0), colors(NULL),
akashvibhute 0:30537dec6e0b 69 text(""),
akashvibhute 0:30537dec6e0b 70 mesh_resource(""),
akashvibhute 0:30537dec6e0b 71 mesh_use_embedded_materials(0)
akashvibhute 0:30537dec6e0b 72 {
akashvibhute 0:30537dec6e0b 73 }
akashvibhute 0:30537dec6e0b 74
akashvibhute 0:30537dec6e0b 75 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 76 {
akashvibhute 0:30537dec6e0b 77 int offset = 0;
akashvibhute 0:30537dec6e0b 78 offset += this->header.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 79 uint32_t length_ns = strlen(this->ns);
akashvibhute 0:30537dec6e0b 80 memcpy(outbuffer + offset, &length_ns, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 81 offset += 4;
akashvibhute 0:30537dec6e0b 82 memcpy(outbuffer + offset, this->ns, length_ns);
akashvibhute 0:30537dec6e0b 83 offset += length_ns;
akashvibhute 0:30537dec6e0b 84 union {
akashvibhute 0:30537dec6e0b 85 int32_t real;
akashvibhute 0:30537dec6e0b 86 uint32_t base;
akashvibhute 0:30537dec6e0b 87 } u_id;
akashvibhute 0:30537dec6e0b 88 u_id.real = this->id;
akashvibhute 0:30537dec6e0b 89 *(outbuffer + offset + 0) = (u_id.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 90 *(outbuffer + offset + 1) = (u_id.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 91 *(outbuffer + offset + 2) = (u_id.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 92 *(outbuffer + offset + 3) = (u_id.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 93 offset += sizeof(this->id);
akashvibhute 0:30537dec6e0b 94 union {
akashvibhute 0:30537dec6e0b 95 int32_t real;
akashvibhute 0:30537dec6e0b 96 uint32_t base;
akashvibhute 0:30537dec6e0b 97 } u_type;
akashvibhute 0:30537dec6e0b 98 u_type.real = this->type;
akashvibhute 0:30537dec6e0b 99 *(outbuffer + offset + 0) = (u_type.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 100 *(outbuffer + offset + 1) = (u_type.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 101 *(outbuffer + offset + 2) = (u_type.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 102 *(outbuffer + offset + 3) = (u_type.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 103 offset += sizeof(this->type);
akashvibhute 0:30537dec6e0b 104 union {
akashvibhute 0:30537dec6e0b 105 int32_t real;
akashvibhute 0:30537dec6e0b 106 uint32_t base;
akashvibhute 0:30537dec6e0b 107 } u_action;
akashvibhute 0:30537dec6e0b 108 u_action.real = this->action;
akashvibhute 0:30537dec6e0b 109 *(outbuffer + offset + 0) = (u_action.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 110 *(outbuffer + offset + 1) = (u_action.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 111 *(outbuffer + offset + 2) = (u_action.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 112 *(outbuffer + offset + 3) = (u_action.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 113 offset += sizeof(this->action);
akashvibhute 0:30537dec6e0b 114 offset += this->pose.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 115 offset += this->scale.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 116 offset += this->color.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 117 *(outbuffer + offset + 0) = (this->lifetime.sec >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 118 *(outbuffer + offset + 1) = (this->lifetime.sec >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 119 *(outbuffer + offset + 2) = (this->lifetime.sec >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 120 *(outbuffer + offset + 3) = (this->lifetime.sec >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 121 offset += sizeof(this->lifetime.sec);
akashvibhute 0:30537dec6e0b 122 *(outbuffer + offset + 0) = (this->lifetime.nsec >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 123 *(outbuffer + offset + 1) = (this->lifetime.nsec >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 124 *(outbuffer + offset + 2) = (this->lifetime.nsec >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 125 *(outbuffer + offset + 3) = (this->lifetime.nsec >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 126 offset += sizeof(this->lifetime.nsec);
akashvibhute 0:30537dec6e0b 127 union {
akashvibhute 0:30537dec6e0b 128 bool real;
akashvibhute 0:30537dec6e0b 129 uint8_t base;
akashvibhute 0:30537dec6e0b 130 } u_frame_locked;
akashvibhute 0:30537dec6e0b 131 u_frame_locked.real = this->frame_locked;
akashvibhute 0:30537dec6e0b 132 *(outbuffer + offset + 0) = (u_frame_locked.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 133 offset += sizeof(this->frame_locked);
akashvibhute 0:30537dec6e0b 134 *(outbuffer + offset++) = points_length;
akashvibhute 0:30537dec6e0b 135 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 136 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 137 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 138 for( uint8_t i = 0; i < points_length; i++){
akashvibhute 0:30537dec6e0b 139 offset += this->points[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 140 }
akashvibhute 0:30537dec6e0b 141 *(outbuffer + offset++) = colors_length;
akashvibhute 0:30537dec6e0b 142 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 143 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 144 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 145 for( uint8_t i = 0; i < colors_length; i++){
akashvibhute 0:30537dec6e0b 146 offset += this->colors[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 147 }
akashvibhute 0:30537dec6e0b 148 uint32_t length_text = strlen(this->text);
akashvibhute 0:30537dec6e0b 149 memcpy(outbuffer + offset, &length_text, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 150 offset += 4;
akashvibhute 0:30537dec6e0b 151 memcpy(outbuffer + offset, this->text, length_text);
akashvibhute 0:30537dec6e0b 152 offset += length_text;
akashvibhute 0:30537dec6e0b 153 uint32_t length_mesh_resource = strlen(this->mesh_resource);
akashvibhute 0:30537dec6e0b 154 memcpy(outbuffer + offset, &length_mesh_resource, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 155 offset += 4;
akashvibhute 0:30537dec6e0b 156 memcpy(outbuffer + offset, this->mesh_resource, length_mesh_resource);
akashvibhute 0:30537dec6e0b 157 offset += length_mesh_resource;
akashvibhute 0:30537dec6e0b 158 union {
akashvibhute 0:30537dec6e0b 159 bool real;
akashvibhute 0:30537dec6e0b 160 uint8_t base;
akashvibhute 0:30537dec6e0b 161 } u_mesh_use_embedded_materials;
akashvibhute 0:30537dec6e0b 162 u_mesh_use_embedded_materials.real = this->mesh_use_embedded_materials;
akashvibhute 0:30537dec6e0b 163 *(outbuffer + offset + 0) = (u_mesh_use_embedded_materials.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 164 offset += sizeof(this->mesh_use_embedded_materials);
akashvibhute 0:30537dec6e0b 165 return offset;
akashvibhute 0:30537dec6e0b 166 }
akashvibhute 0:30537dec6e0b 167
akashvibhute 0:30537dec6e0b 168 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 169 {
akashvibhute 0:30537dec6e0b 170 int offset = 0;
akashvibhute 0:30537dec6e0b 171 offset += this->header.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 172 uint32_t length_ns;
akashvibhute 0:30537dec6e0b 173 memcpy(&length_ns, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 174 offset += 4;
akashvibhute 0:30537dec6e0b 175 for(unsigned int k= offset; k< offset+length_ns; ++k){
akashvibhute 0:30537dec6e0b 176 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 177 }
akashvibhute 0:30537dec6e0b 178 inbuffer[offset+length_ns-1]=0;
akashvibhute 0:30537dec6e0b 179 this->ns = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 180 offset += length_ns;
akashvibhute 0:30537dec6e0b 181 union {
akashvibhute 0:30537dec6e0b 182 int32_t real;
akashvibhute 0:30537dec6e0b 183 uint32_t base;
akashvibhute 0:30537dec6e0b 184 } u_id;
akashvibhute 0:30537dec6e0b 185 u_id.base = 0;
akashvibhute 0:30537dec6e0b 186 u_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 187 u_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 188 u_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 189 u_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 190 this->id = u_id.real;
akashvibhute 0:30537dec6e0b 191 offset += sizeof(this->id);
akashvibhute 0:30537dec6e0b 192 union {
akashvibhute 0:30537dec6e0b 193 int32_t real;
akashvibhute 0:30537dec6e0b 194 uint32_t base;
akashvibhute 0:30537dec6e0b 195 } u_type;
akashvibhute 0:30537dec6e0b 196 u_type.base = 0;
akashvibhute 0:30537dec6e0b 197 u_type.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 198 u_type.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 199 u_type.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 200 u_type.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 201 this->type = u_type.real;
akashvibhute 0:30537dec6e0b 202 offset += sizeof(this->type);
akashvibhute 0:30537dec6e0b 203 union {
akashvibhute 0:30537dec6e0b 204 int32_t real;
akashvibhute 0:30537dec6e0b 205 uint32_t base;
akashvibhute 0:30537dec6e0b 206 } u_action;
akashvibhute 0:30537dec6e0b 207 u_action.base = 0;
akashvibhute 0:30537dec6e0b 208 u_action.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 209 u_action.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 210 u_action.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 211 u_action.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 212 this->action = u_action.real;
akashvibhute 0:30537dec6e0b 213 offset += sizeof(this->action);
akashvibhute 0:30537dec6e0b 214 offset += this->pose.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 215 offset += this->scale.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 216 offset += this->color.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 217 this->lifetime.sec = ((uint32_t) (*(inbuffer + offset)));
akashvibhute 0:30537dec6e0b 218 this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 219 this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 220 this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 221 offset += sizeof(this->lifetime.sec);
akashvibhute 0:30537dec6e0b 222 this->lifetime.nsec = ((uint32_t) (*(inbuffer + offset)));
akashvibhute 0:30537dec6e0b 223 this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 224 this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 225 this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 226 offset += sizeof(this->lifetime.nsec);
akashvibhute 0:30537dec6e0b 227 union {
akashvibhute 0:30537dec6e0b 228 bool real;
akashvibhute 0:30537dec6e0b 229 uint8_t base;
akashvibhute 0:30537dec6e0b 230 } u_frame_locked;
akashvibhute 0:30537dec6e0b 231 u_frame_locked.base = 0;
akashvibhute 0:30537dec6e0b 232 u_frame_locked.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 233 this->frame_locked = u_frame_locked.real;
akashvibhute 0:30537dec6e0b 234 offset += sizeof(this->frame_locked);
akashvibhute 0:30537dec6e0b 235 uint8_t points_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 236 if(points_lengthT > points_length)
akashvibhute 0:30537dec6e0b 237 this->points = (geometry_msgs::Point*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point));
akashvibhute 0:30537dec6e0b 238 offset += 3;
akashvibhute 0:30537dec6e0b 239 points_length = points_lengthT;
akashvibhute 0:30537dec6e0b 240 for( uint8_t i = 0; i < points_length; i++){
akashvibhute 0:30537dec6e0b 241 offset += this->st_points.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 242 memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point));
akashvibhute 0:30537dec6e0b 243 }
akashvibhute 0:30537dec6e0b 244 uint8_t colors_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 245 if(colors_lengthT > colors_length)
akashvibhute 0:30537dec6e0b 246 this->colors = (std_msgs::ColorRGBA*)realloc(this->colors, colors_lengthT * sizeof(std_msgs::ColorRGBA));
akashvibhute 0:30537dec6e0b 247 offset += 3;
akashvibhute 0:30537dec6e0b 248 colors_length = colors_lengthT;
akashvibhute 0:30537dec6e0b 249 for( uint8_t i = 0; i < colors_length; i++){
akashvibhute 0:30537dec6e0b 250 offset += this->st_colors.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 251 memcpy( &(this->colors[i]), &(this->st_colors), sizeof(std_msgs::ColorRGBA));
akashvibhute 0:30537dec6e0b 252 }
akashvibhute 0:30537dec6e0b 253 uint32_t length_text;
akashvibhute 0:30537dec6e0b 254 memcpy(&length_text, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 255 offset += 4;
akashvibhute 0:30537dec6e0b 256 for(unsigned int k= offset; k< offset+length_text; ++k){
akashvibhute 0:30537dec6e0b 257 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 258 }
akashvibhute 0:30537dec6e0b 259 inbuffer[offset+length_text-1]=0;
akashvibhute 0:30537dec6e0b 260 this->text = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 261 offset += length_text;
akashvibhute 0:30537dec6e0b 262 uint32_t length_mesh_resource;
akashvibhute 0:30537dec6e0b 263 memcpy(&length_mesh_resource, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 264 offset += 4;
akashvibhute 0:30537dec6e0b 265 for(unsigned int k= offset; k< offset+length_mesh_resource; ++k){
akashvibhute 0:30537dec6e0b 266 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 267 }
akashvibhute 0:30537dec6e0b 268 inbuffer[offset+length_mesh_resource-1]=0;
akashvibhute 0:30537dec6e0b 269 this->mesh_resource = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 270 offset += length_mesh_resource;
akashvibhute 0:30537dec6e0b 271 union {
akashvibhute 0:30537dec6e0b 272 bool real;
akashvibhute 0:30537dec6e0b 273 uint8_t base;
akashvibhute 0:30537dec6e0b 274 } u_mesh_use_embedded_materials;
akashvibhute 0:30537dec6e0b 275 u_mesh_use_embedded_materials.base = 0;
akashvibhute 0:30537dec6e0b 276 u_mesh_use_embedded_materials.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 277 this->mesh_use_embedded_materials = u_mesh_use_embedded_materials.real;
akashvibhute 0:30537dec6e0b 278 offset += sizeof(this->mesh_use_embedded_materials);
akashvibhute 0:30537dec6e0b 279 return offset;
akashvibhute 0:30537dec6e0b 280 }
akashvibhute 0:30537dec6e0b 281
akashvibhute 0:30537dec6e0b 282 const char * getType(){ return "visualization_msgs/Marker"; };
akashvibhute 0:30537dec6e0b 283 const char * getMD5(){ return "18326976df9d29249efc939e00342cde"; };
akashvibhute 0:30537dec6e0b 284
akashvibhute 0:30537dec6e0b 285 };
akashvibhute 0:30537dec6e0b 286
akashvibhute 0:30537dec6e0b 287 }
akashvibhute 0:30537dec6e0b 288 #endif