Marker.h
Go to the documentation of this file.
00001 #ifndef _ROS_visualization_msgs_Marker_h
00002 #define _ROS_visualization_msgs_Marker_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "std_msgs/Header.h"
00009 #include "geometry_msgs/Pose.h"
00010 #include "geometry_msgs/Vector3.h"
00011 #include "std_msgs/ColorRGBA.h"
00012 #include "ros/duration.h"
00013 #include "geometry_msgs/Point.h"
00014 
00015 namespace visualization_msgs
00016 {
00017 
00018   class Marker : public ros::Msg
00019   {
00020     public:
00021       std_msgs::Header header;
00022       const char* ns;
00023       int32_t id;
00024       int32_t type;
00025       int32_t action;
00026       geometry_msgs::Pose pose;
00027       geometry_msgs::Vector3 scale;
00028       std_msgs::ColorRGBA color;
00029       ros::Duration lifetime;
00030       bool frame_locked;
00031       uint8_t points_length;
00032       geometry_msgs::Point st_points;
00033       geometry_msgs::Point * points;
00034       uint8_t colors_length;
00035       std_msgs::ColorRGBA st_colors;
00036       std_msgs::ColorRGBA * colors;
00037       const char* text;
00038       const char* mesh_resource;
00039       bool mesh_use_embedded_materials;
00040       enum { ARROW = 0 };
00041       enum { CUBE = 1 };
00042       enum { SPHERE = 2 };
00043       enum { CYLINDER = 3 };
00044       enum { LINE_STRIP = 4 };
00045       enum { LINE_LIST = 5 };
00046       enum { CUBE_LIST = 6 };
00047       enum { SPHERE_LIST = 7 };
00048       enum { POINTS = 8 };
00049       enum { TEXT_VIEW_FACING = 9 };
00050       enum { MESH_RESOURCE = 10 };
00051       enum { TRIANGLE_LIST = 11 };
00052       enum { ADD = 0 };
00053       enum { MODIFY = 0 };
00054       enum { DELETE = 2 };
00055 
00056     virtual int serialize(unsigned char *outbuffer) const
00057     {
00058       int offset = 0;
00059       offset += this->header.serialize(outbuffer + offset);
00060       uint32_t length_ns = strlen(this->ns);
00061       memcpy(outbuffer + offset, &length_ns, sizeof(uint32_t));
00062       offset += 4;
00063       memcpy(outbuffer + offset, this->ns, length_ns);
00064       offset += length_ns;
00065       union {
00066         int32_t real;
00067         uint32_t base;
00068       } u_id;
00069       u_id.real = this->id;
00070       *(outbuffer + offset + 0) = (u_id.base >> (8 * 0)) & 0xFF;
00071       *(outbuffer + offset + 1) = (u_id.base >> (8 * 1)) & 0xFF;
00072       *(outbuffer + offset + 2) = (u_id.base >> (8 * 2)) & 0xFF;
00073       *(outbuffer + offset + 3) = (u_id.base >> (8 * 3)) & 0xFF;
00074       offset += sizeof(this->id);
00075       union {
00076         int32_t real;
00077         uint32_t base;
00078       } u_type;
00079       u_type.real = this->type;
00080       *(outbuffer + offset + 0) = (u_type.base >> (8 * 0)) & 0xFF;
00081       *(outbuffer + offset + 1) = (u_type.base >> (8 * 1)) & 0xFF;
00082       *(outbuffer + offset + 2) = (u_type.base >> (8 * 2)) & 0xFF;
00083       *(outbuffer + offset + 3) = (u_type.base >> (8 * 3)) & 0xFF;
00084       offset += sizeof(this->type);
00085       union {
00086         int32_t real;
00087         uint32_t base;
00088       } u_action;
00089       u_action.real = this->action;
00090       *(outbuffer + offset + 0) = (u_action.base >> (8 * 0)) & 0xFF;
00091       *(outbuffer + offset + 1) = (u_action.base >> (8 * 1)) & 0xFF;
00092       *(outbuffer + offset + 2) = (u_action.base >> (8 * 2)) & 0xFF;
00093       *(outbuffer + offset + 3) = (u_action.base >> (8 * 3)) & 0xFF;
00094       offset += sizeof(this->action);
00095       offset += this->pose.serialize(outbuffer + offset);
00096       offset += this->scale.serialize(outbuffer + offset);
00097       offset += this->color.serialize(outbuffer + offset);
00098       *(outbuffer + offset + 0) = (this->lifetime.sec >> (8 * 0)) & 0xFF;
00099       *(outbuffer + offset + 1) = (this->lifetime.sec >> (8 * 1)) & 0xFF;
00100       *(outbuffer + offset + 2) = (this->lifetime.sec >> (8 * 2)) & 0xFF;
00101       *(outbuffer + offset + 3) = (this->lifetime.sec >> (8 * 3)) & 0xFF;
00102       offset += sizeof(this->lifetime.sec);
00103       *(outbuffer + offset + 0) = (this->lifetime.nsec >> (8 * 0)) & 0xFF;
00104       *(outbuffer + offset + 1) = (this->lifetime.nsec >> (8 * 1)) & 0xFF;
00105       *(outbuffer + offset + 2) = (this->lifetime.nsec >> (8 * 2)) & 0xFF;
00106       *(outbuffer + offset + 3) = (this->lifetime.nsec >> (8 * 3)) & 0xFF;
00107       offset += sizeof(this->lifetime.nsec);
00108       union {
00109         bool real;
00110         uint8_t base;
00111       } u_frame_locked;
00112       u_frame_locked.real = this->frame_locked;
00113       *(outbuffer + offset + 0) = (u_frame_locked.base >> (8 * 0)) & 0xFF;
00114       offset += sizeof(this->frame_locked);
00115       *(outbuffer + offset++) = points_length;
00116       *(outbuffer + offset++) = 0;
00117       *(outbuffer + offset++) = 0;
00118       *(outbuffer + offset++) = 0;
00119       for( uint8_t i = 0; i < points_length; i++){
00120       offset += this->points[i].serialize(outbuffer + offset);
00121       }
00122       *(outbuffer + offset++) = colors_length;
00123       *(outbuffer + offset++) = 0;
00124       *(outbuffer + offset++) = 0;
00125       *(outbuffer + offset++) = 0;
00126       for( uint8_t i = 0; i < colors_length; i++){
00127       offset += this->colors[i].serialize(outbuffer + offset);
00128       }
00129       uint32_t length_text = strlen(this->text);
00130       memcpy(outbuffer + offset, &length_text, sizeof(uint32_t));
00131       offset += 4;
00132       memcpy(outbuffer + offset, this->text, length_text);
00133       offset += length_text;
00134       uint32_t length_mesh_resource = strlen(this->mesh_resource);
00135       memcpy(outbuffer + offset, &length_mesh_resource, sizeof(uint32_t));
00136       offset += 4;
00137       memcpy(outbuffer + offset, this->mesh_resource, length_mesh_resource);
00138       offset += length_mesh_resource;
00139       union {
00140         bool real;
00141         uint8_t base;
00142       } u_mesh_use_embedded_materials;
00143       u_mesh_use_embedded_materials.real = this->mesh_use_embedded_materials;
00144       *(outbuffer + offset + 0) = (u_mesh_use_embedded_materials.base >> (8 * 0)) & 0xFF;
00145       offset += sizeof(this->mesh_use_embedded_materials);
00146       return offset;
00147     }
00148 
00149     virtual int deserialize(unsigned char *inbuffer)
00150     {
00151       int offset = 0;
00152       offset += this->header.deserialize(inbuffer + offset);
00153       uint32_t length_ns;
00154       memcpy(&length_ns, (inbuffer + offset), sizeof(uint32_t));
00155       offset += 4;
00156       for(unsigned int k= offset; k< offset+length_ns; ++k){
00157           inbuffer[k-1]=inbuffer[k];
00158       }
00159       inbuffer[offset+length_ns-1]=0;
00160       this->ns = (char *)(inbuffer + offset-1);
00161       offset += length_ns;
00162       union {
00163         int32_t real;
00164         uint32_t base;
00165       } u_id;
00166       u_id.base = 0;
00167       u_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00168       u_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00169       u_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00170       u_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00171       this->id = u_id.real;
00172       offset += sizeof(this->id);
00173       union {
00174         int32_t real;
00175         uint32_t base;
00176       } u_type;
00177       u_type.base = 0;
00178       u_type.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00179       u_type.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00180       u_type.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00181       u_type.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00182       this->type = u_type.real;
00183       offset += sizeof(this->type);
00184       union {
00185         int32_t real;
00186         uint32_t base;
00187       } u_action;
00188       u_action.base = 0;
00189       u_action.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00190       u_action.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00191       u_action.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00192       u_action.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00193       this->action = u_action.real;
00194       offset += sizeof(this->action);
00195       offset += this->pose.deserialize(inbuffer + offset);
00196       offset += this->scale.deserialize(inbuffer + offset);
00197       offset += this->color.deserialize(inbuffer + offset);
00198       this->lifetime.sec =  ((uint32_t) (*(inbuffer + offset)));
00199       this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00200       this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00201       this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00202       offset += sizeof(this->lifetime.sec);
00203       this->lifetime.nsec =  ((uint32_t) (*(inbuffer + offset)));
00204       this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00205       this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00206       this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00207       offset += sizeof(this->lifetime.nsec);
00208       union {
00209         bool real;
00210         uint8_t base;
00211       } u_frame_locked;
00212       u_frame_locked.base = 0;
00213       u_frame_locked.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00214       this->frame_locked = u_frame_locked.real;
00215       offset += sizeof(this->frame_locked);
00216       uint8_t points_lengthT = *(inbuffer + offset++);
00217       if(points_lengthT > points_length)
00218         this->points = (geometry_msgs::Point*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point));
00219       offset += 3;
00220       points_length = points_lengthT;
00221       for( uint8_t i = 0; i < points_length; i++){
00222       offset += this->st_points.deserialize(inbuffer + offset);
00223         memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point));
00224       }
00225       uint8_t colors_lengthT = *(inbuffer + offset++);
00226       if(colors_lengthT > colors_length)
00227         this->colors = (std_msgs::ColorRGBA*)realloc(this->colors, colors_lengthT * sizeof(std_msgs::ColorRGBA));
00228       offset += 3;
00229       colors_length = colors_lengthT;
00230       for( uint8_t i = 0; i < colors_length; i++){
00231       offset += this->st_colors.deserialize(inbuffer + offset);
00232         memcpy( &(this->colors[i]), &(this->st_colors), sizeof(std_msgs::ColorRGBA));
00233       }
00234       uint32_t length_text;
00235       memcpy(&length_text, (inbuffer + offset), sizeof(uint32_t));
00236       offset += 4;
00237       for(unsigned int k= offset; k< offset+length_text; ++k){
00238           inbuffer[k-1]=inbuffer[k];
00239       }
00240       inbuffer[offset+length_text-1]=0;
00241       this->text = (char *)(inbuffer + offset-1);
00242       offset += length_text;
00243       uint32_t length_mesh_resource;
00244       memcpy(&length_mesh_resource, (inbuffer + offset), sizeof(uint32_t));
00245       offset += 4;
00246       for(unsigned int k= offset; k< offset+length_mesh_resource; ++k){
00247           inbuffer[k-1]=inbuffer[k];
00248       }
00249       inbuffer[offset+length_mesh_resource-1]=0;
00250       this->mesh_resource = (char *)(inbuffer + offset-1);
00251       offset += length_mesh_resource;
00252       union {
00253         bool real;
00254         uint8_t base;
00255       } u_mesh_use_embedded_materials;
00256       u_mesh_use_embedded_materials.base = 0;
00257       u_mesh_use_embedded_materials.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00258       this->mesh_use_embedded_materials = u_mesh_use_embedded_materials.real;
00259       offset += sizeof(this->mesh_use_embedded_materials);
00260      return offset;
00261     }
00262 
00263     const char * getType(){ return "visualization_msgs/Marker"; };
00264     const char * getMD5(){ return "18326976df9d29249efc939e00342cde"; };
00265 
00266   };
00267 
00268 }
00269 #endif


ric_mc
Author(s): RoboTiCan
autogenerated on Thu Aug 27 2015 14:39:49