ROS Serial library for Mbed platforms for ROS Indigo Igloo. Check http://wiki.ros.org/rosserial_mbed/ for more information

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers ImageMarker.h Source File

ImageMarker.h

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     ImageMarker():
00045       header(),
00046       ns(""),
00047       id(0),
00048       type(0),
00049       action(0),
00050       position(),
00051       scale(0),
00052       outline_color(),
00053       filled(0),
00054       fill_color(),
00055       lifetime(),
00056       points_length(0), points(NULL),
00057       outline_colors_length(0), outline_colors(NULL)
00058     {
00059     }
00060 
00061     virtual int serialize(unsigned char *outbuffer) const
00062     {
00063       int offset = 0;
00064       offset += this->header.serialize(outbuffer + offset);
00065       uint32_t length_ns = strlen(this->ns);
00066       memcpy(outbuffer + offset, &length_ns, sizeof(uint32_t));
00067       offset += 4;
00068       memcpy(outbuffer + offset, this->ns, length_ns);
00069       offset += length_ns;
00070       union {
00071         int32_t real;
00072         uint32_t base;
00073       } u_id;
00074       u_id.real = this->id;
00075       *(outbuffer + offset + 0) = (u_id.base >> (8 * 0)) & 0xFF;
00076       *(outbuffer + offset + 1) = (u_id.base >> (8 * 1)) & 0xFF;
00077       *(outbuffer + offset + 2) = (u_id.base >> (8 * 2)) & 0xFF;
00078       *(outbuffer + offset + 3) = (u_id.base >> (8 * 3)) & 0xFF;
00079       offset += sizeof(this->id);
00080       union {
00081         int32_t real;
00082         uint32_t base;
00083       } u_type;
00084       u_type.real = this->type;
00085       *(outbuffer + offset + 0) = (u_type.base >> (8 * 0)) & 0xFF;
00086       *(outbuffer + offset + 1) = (u_type.base >> (8 * 1)) & 0xFF;
00087       *(outbuffer + offset + 2) = (u_type.base >> (8 * 2)) & 0xFF;
00088       *(outbuffer + offset + 3) = (u_type.base >> (8 * 3)) & 0xFF;
00089       offset += sizeof(this->type);
00090       union {
00091         int32_t real;
00092         uint32_t base;
00093       } u_action;
00094       u_action.real = this->action;
00095       *(outbuffer + offset + 0) = (u_action.base >> (8 * 0)) & 0xFF;
00096       *(outbuffer + offset + 1) = (u_action.base >> (8 * 1)) & 0xFF;
00097       *(outbuffer + offset + 2) = (u_action.base >> (8 * 2)) & 0xFF;
00098       *(outbuffer + offset + 3) = (u_action.base >> (8 * 3)) & 0xFF;
00099       offset += sizeof(this->action);
00100       offset += this->position.serialize(outbuffer + offset);
00101       union {
00102         float real;
00103         uint32_t base;
00104       } u_scale;
00105       u_scale.real = this->scale;
00106       *(outbuffer + offset + 0) = (u_scale.base >> (8 * 0)) & 0xFF;
00107       *(outbuffer + offset + 1) = (u_scale.base >> (8 * 1)) & 0xFF;
00108       *(outbuffer + offset + 2) = (u_scale.base >> (8 * 2)) & 0xFF;
00109       *(outbuffer + offset + 3) = (u_scale.base >> (8 * 3)) & 0xFF;
00110       offset += sizeof(this->scale);
00111       offset += this->outline_color.serialize(outbuffer + offset);
00112       *(outbuffer + offset + 0) = (this->filled >> (8 * 0)) & 0xFF;
00113       offset += sizeof(this->filled);
00114       offset += this->fill_color.serialize(outbuffer + offset);
00115       *(outbuffer + offset + 0) = (this->lifetime.sec >> (8 * 0)) & 0xFF;
00116       *(outbuffer + offset + 1) = (this->lifetime.sec >> (8 * 1)) & 0xFF;
00117       *(outbuffer + offset + 2) = (this->lifetime.sec >> (8 * 2)) & 0xFF;
00118       *(outbuffer + offset + 3) = (this->lifetime.sec >> (8 * 3)) & 0xFF;
00119       offset += sizeof(this->lifetime.sec);
00120       *(outbuffer + offset + 0) = (this->lifetime.nsec >> (8 * 0)) & 0xFF;
00121       *(outbuffer + offset + 1) = (this->lifetime.nsec >> (8 * 1)) & 0xFF;
00122       *(outbuffer + offset + 2) = (this->lifetime.nsec >> (8 * 2)) & 0xFF;
00123       *(outbuffer + offset + 3) = (this->lifetime.nsec >> (8 * 3)) & 0xFF;
00124       offset += sizeof(this->lifetime.nsec);
00125       *(outbuffer + offset++) = points_length;
00126       *(outbuffer + offset++) = 0;
00127       *(outbuffer + offset++) = 0;
00128       *(outbuffer + offset++) = 0;
00129       for( uint8_t i = 0; i < points_length; i++){
00130       offset += this->points[i].serialize(outbuffer + offset);
00131       }
00132       *(outbuffer + offset++) = outline_colors_length;
00133       *(outbuffer + offset++) = 0;
00134       *(outbuffer + offset++) = 0;
00135       *(outbuffer + offset++) = 0;
00136       for( uint8_t i = 0; i < outline_colors_length; i++){
00137       offset += this->outline_colors[i].serialize(outbuffer + offset);
00138       }
00139       return offset;
00140     }
00141 
00142     virtual int deserialize(unsigned char *inbuffer)
00143     {
00144       int offset = 0;
00145       offset += this->header.deserialize(inbuffer + offset);
00146       uint32_t length_ns;
00147       memcpy(&length_ns, (inbuffer + offset), sizeof(uint32_t));
00148       offset += 4;
00149       for(unsigned int k= offset; k< offset+length_ns; ++k){
00150           inbuffer[k-1]=inbuffer[k];
00151       }
00152       inbuffer[offset+length_ns-1]=0;
00153       this->ns = (char *)(inbuffer + offset-1);
00154       offset += length_ns;
00155       union {
00156         int32_t real;
00157         uint32_t base;
00158       } u_id;
00159       u_id.base = 0;
00160       u_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00161       u_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00162       u_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00163       u_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00164       this->id = u_id.real;
00165       offset += sizeof(this->id);
00166       union {
00167         int32_t real;
00168         uint32_t base;
00169       } u_type;
00170       u_type.base = 0;
00171       u_type.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00172       u_type.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00173       u_type.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00174       u_type.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00175       this->type = u_type.real;
00176       offset += sizeof(this->type);
00177       union {
00178         int32_t real;
00179         uint32_t base;
00180       } u_action;
00181       u_action.base = 0;
00182       u_action.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00183       u_action.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00184       u_action.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00185       u_action.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00186       this->action = u_action.real;
00187       offset += sizeof(this->action);
00188       offset += this->position.deserialize(inbuffer + offset);
00189       union {
00190         float real;
00191         uint32_t base;
00192       } u_scale;
00193       u_scale.base = 0;
00194       u_scale.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00195       u_scale.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00196       u_scale.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00197       u_scale.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00198       this->scale = u_scale.real;
00199       offset += sizeof(this->scale);
00200       offset += this->outline_color.deserialize(inbuffer + offset);
00201       this->filled =  ((uint8_t) (*(inbuffer + offset)));
00202       offset += sizeof(this->filled);
00203       offset += this->fill_color.deserialize(inbuffer + offset);
00204       this->lifetime.sec =  ((uint32_t) (*(inbuffer + offset)));
00205       this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00206       this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00207       this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00208       offset += sizeof(this->lifetime.sec);
00209       this->lifetime.nsec =  ((uint32_t) (*(inbuffer + offset)));
00210       this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00211       this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00212       this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00213       offset += sizeof(this->lifetime.nsec);
00214       uint8_t points_lengthT = *(inbuffer + offset++);
00215       if(points_lengthT > points_length)
00216         this->points = (geometry_msgs::Point*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point));
00217       offset += 3;
00218       points_length = points_lengthT;
00219       for( uint8_t i = 0; i < points_length; i++){
00220       offset += this->st_points.deserialize(inbuffer + offset);
00221         memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point));
00222       }
00223       uint8_t outline_colors_lengthT = *(inbuffer + offset++);
00224       if(outline_colors_lengthT > outline_colors_length)
00225         this->outline_colors = (std_msgs::ColorRGBA*)realloc(this->outline_colors, outline_colors_lengthT * sizeof(std_msgs::ColorRGBA));
00226       offset += 3;
00227       outline_colors_length = outline_colors_lengthT;
00228       for( uint8_t i = 0; i < outline_colors_length; i++){
00229       offset += this->st_outline_colors.deserialize(inbuffer + offset);
00230         memcpy( &(this->outline_colors[i]), &(this->st_outline_colors), sizeof(std_msgs::ColorRGBA));
00231       }
00232      return offset;
00233     }
00234 
00235     const char * getType(){ return "visualization_msgs/ImageMarker"; };
00236     const char * getMD5(){ return "1de93c67ec8858b831025a08fbf1b35c"; };
00237 
00238   };
00239 
00240 }
00241 #endif