ImageMarker.h
Go to the documentation of this file.
00001 #ifndef _ROS_visualization_msgs_ImageMarker_h
00002 #define _ROS_visualization_msgs_ImageMarker_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/Point.h"
00010 #include "std_msgs/ColorRGBA.h"
00011 #include "ros/duration.h"
00012 
00013 namespace visualization_msgs
00014 {
00015 
00016   class ImageMarker : public ros::Msg
00017   {
00018     public:
00019       std_msgs::Header header;
00020       const char* ns;
00021       int32_t id;
00022       int32_t type;
00023       int32_t action;
00024       geometry_msgs::Point position;
00025       float scale;
00026       std_msgs::ColorRGBA outline_color;
00027       uint8_t filled;
00028       std_msgs::ColorRGBA fill_color;
00029       ros::Duration lifetime;
00030       uint8_t points_length;
00031       geometry_msgs::Point st_points;
00032       geometry_msgs::Point * points;
00033       uint8_t outline_colors_length;
00034       std_msgs::ColorRGBA st_outline_colors;
00035       std_msgs::ColorRGBA * outline_colors;
00036       enum { CIRCLE = 0 };
00037       enum { LINE_STRIP = 1 };
00038       enum { LINE_LIST = 2 };
00039       enum { POLYGON = 3 };
00040       enum { POINTS = 4 };
00041       enum { ADD = 0 };
00042       enum { REMOVE = 1 };
00043 
00044     virtual int serialize(unsigned char *outbuffer) const
00045     {
00046       int offset = 0;
00047       offset += this->header.serialize(outbuffer + offset);
00048       uint32_t length_ns = strlen(this->ns);
00049       memcpy(outbuffer + offset, &length_ns, sizeof(uint32_t));
00050       offset += 4;
00051       memcpy(outbuffer + offset, this->ns, length_ns);
00052       offset += length_ns;
00053       union {
00054         int32_t real;
00055         uint32_t base;
00056       } u_id;
00057       u_id.real = this->id;
00058       *(outbuffer + offset + 0) = (u_id.base >> (8 * 0)) & 0xFF;
00059       *(outbuffer + offset + 1) = (u_id.base >> (8 * 1)) & 0xFF;
00060       *(outbuffer + offset + 2) = (u_id.base >> (8 * 2)) & 0xFF;
00061       *(outbuffer + offset + 3) = (u_id.base >> (8 * 3)) & 0xFF;
00062       offset += sizeof(this->id);
00063       union {
00064         int32_t real;
00065         uint32_t base;
00066       } u_type;
00067       u_type.real = this->type;
00068       *(outbuffer + offset + 0) = (u_type.base >> (8 * 0)) & 0xFF;
00069       *(outbuffer + offset + 1) = (u_type.base >> (8 * 1)) & 0xFF;
00070       *(outbuffer + offset + 2) = (u_type.base >> (8 * 2)) & 0xFF;
00071       *(outbuffer + offset + 3) = (u_type.base >> (8 * 3)) & 0xFF;
00072       offset += sizeof(this->type);
00073       union {
00074         int32_t real;
00075         uint32_t base;
00076       } u_action;
00077       u_action.real = this->action;
00078       *(outbuffer + offset + 0) = (u_action.base >> (8 * 0)) & 0xFF;
00079       *(outbuffer + offset + 1) = (u_action.base >> (8 * 1)) & 0xFF;
00080       *(outbuffer + offset + 2) = (u_action.base >> (8 * 2)) & 0xFF;
00081       *(outbuffer + offset + 3) = (u_action.base >> (8 * 3)) & 0xFF;
00082       offset += sizeof(this->action);
00083       offset += this->position.serialize(outbuffer + offset);
00084       union {
00085         float real;
00086         uint32_t base;
00087       } u_scale;
00088       u_scale.real = this->scale;
00089       *(outbuffer + offset + 0) = (u_scale.base >> (8 * 0)) & 0xFF;
00090       *(outbuffer + offset + 1) = (u_scale.base >> (8 * 1)) & 0xFF;
00091       *(outbuffer + offset + 2) = (u_scale.base >> (8 * 2)) & 0xFF;
00092       *(outbuffer + offset + 3) = (u_scale.base >> (8 * 3)) & 0xFF;
00093       offset += sizeof(this->scale);
00094       offset += this->outline_color.serialize(outbuffer + offset);
00095       *(outbuffer + offset + 0) = (this->filled >> (8 * 0)) & 0xFF;
00096       offset += sizeof(this->filled);
00097       offset += this->fill_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       *(outbuffer + offset++) = points_length;
00109       *(outbuffer + offset++) = 0;
00110       *(outbuffer + offset++) = 0;
00111       *(outbuffer + offset++) = 0;
00112       for( uint8_t i = 0; i < points_length; i++){
00113       offset += this->points[i].serialize(outbuffer + offset);
00114       }
00115       *(outbuffer + offset++) = outline_colors_length;
00116       *(outbuffer + offset++) = 0;
00117       *(outbuffer + offset++) = 0;
00118       *(outbuffer + offset++) = 0;
00119       for( uint8_t i = 0; i < outline_colors_length; i++){
00120       offset += this->outline_colors[i].serialize(outbuffer + offset);
00121       }
00122       return offset;
00123     }
00124 
00125     virtual int deserialize(unsigned char *inbuffer)
00126     {
00127       int offset = 0;
00128       offset += this->header.deserialize(inbuffer + offset);
00129       uint32_t length_ns;
00130       memcpy(&length_ns, (inbuffer + offset), sizeof(uint32_t));
00131       offset += 4;
00132       for(unsigned int k= offset; k< offset+length_ns; ++k){
00133           inbuffer[k-1]=inbuffer[k];
00134       }
00135       inbuffer[offset+length_ns-1]=0;
00136       this->ns = (char *)(inbuffer + offset-1);
00137       offset += length_ns;
00138       union {
00139         int32_t real;
00140         uint32_t base;
00141       } u_id;
00142       u_id.base = 0;
00143       u_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00144       u_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00145       u_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00146       u_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00147       this->id = u_id.real;
00148       offset += sizeof(this->id);
00149       union {
00150         int32_t real;
00151         uint32_t base;
00152       } u_type;
00153       u_type.base = 0;
00154       u_type.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00155       u_type.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00156       u_type.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00157       u_type.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00158       this->type = u_type.real;
00159       offset += sizeof(this->type);
00160       union {
00161         int32_t real;
00162         uint32_t base;
00163       } u_action;
00164       u_action.base = 0;
00165       u_action.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00166       u_action.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00167       u_action.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00168       u_action.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00169       this->action = u_action.real;
00170       offset += sizeof(this->action);
00171       offset += this->position.deserialize(inbuffer + offset);
00172       union {
00173         float real;
00174         uint32_t base;
00175       } u_scale;
00176       u_scale.base = 0;
00177       u_scale.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00178       u_scale.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00179       u_scale.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00180       u_scale.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00181       this->scale = u_scale.real;
00182       offset += sizeof(this->scale);
00183       offset += this->outline_color.deserialize(inbuffer + offset);
00184       this->filled =  ((uint8_t) (*(inbuffer + offset)));
00185       offset += sizeof(this->filled);
00186       offset += this->fill_color.deserialize(inbuffer + offset);
00187       this->lifetime.sec =  ((uint32_t) (*(inbuffer + offset)));
00188       this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00189       this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00190       this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00191       offset += sizeof(this->lifetime.sec);
00192       this->lifetime.nsec =  ((uint32_t) (*(inbuffer + offset)));
00193       this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00194       this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00195       this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00196       offset += sizeof(this->lifetime.nsec);
00197       uint8_t points_lengthT = *(inbuffer + offset++);
00198       if(points_lengthT > points_length)
00199         this->points = (geometry_msgs::Point*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point));
00200       offset += 3;
00201       points_length = points_lengthT;
00202       for( uint8_t i = 0; i < points_length; i++){
00203       offset += this->st_points.deserialize(inbuffer + offset);
00204         memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point));
00205       }
00206       uint8_t outline_colors_lengthT = *(inbuffer + offset++);
00207       if(outline_colors_lengthT > outline_colors_length)
00208         this->outline_colors = (std_msgs::ColorRGBA*)realloc(this->outline_colors, outline_colors_lengthT * sizeof(std_msgs::ColorRGBA));
00209       offset += 3;
00210       outline_colors_length = outline_colors_lengthT;
00211       for( uint8_t i = 0; i < outline_colors_length; i++){
00212       offset += this->st_outline_colors.deserialize(inbuffer + offset);
00213         memcpy( &(this->outline_colors[i]), &(this->st_outline_colors), sizeof(std_msgs::ColorRGBA));
00214       }
00215      return offset;
00216     }
00217 
00218     const char * getType(){ return "visualization_msgs/ImageMarker"; };
00219     const char * getMD5(){ return "1de93c67ec8858b831025a08fbf1b35c"; };
00220 
00221   };
00222 
00223 }
00224 #endif


ric_mc
Author(s): RoboTiCan
autogenerated on Fri May 20 2016 03:48:55