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 ShapeGoal.h Source File

ShapeGoal.h

00001 #ifndef _ROS_turtle_actionlib_ShapeGoal_h
00002 #define _ROS_turtle_actionlib_ShapeGoal_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 
00009 namespace turtle_actionlib
00010 {
00011 
00012   class ShapeGoal : public ros::Msg
00013   {
00014     public:
00015       int32_t edges;
00016       float radius;
00017 
00018     ShapeGoal():
00019       edges(0),
00020       radius(0)
00021     {
00022     }
00023 
00024     virtual int serialize(unsigned char *outbuffer) const
00025     {
00026       int offset = 0;
00027       union {
00028         int32_t real;
00029         uint32_t base;
00030       } u_edges;
00031       u_edges.real = this->edges;
00032       *(outbuffer + offset + 0) = (u_edges.base >> (8 * 0)) & 0xFF;
00033       *(outbuffer + offset + 1) = (u_edges.base >> (8 * 1)) & 0xFF;
00034       *(outbuffer + offset + 2) = (u_edges.base >> (8 * 2)) & 0xFF;
00035       *(outbuffer + offset + 3) = (u_edges.base >> (8 * 3)) & 0xFF;
00036       offset += sizeof(this->edges);
00037       union {
00038         float real;
00039         uint32_t base;
00040       } u_radius;
00041       u_radius.real = this->radius;
00042       *(outbuffer + offset + 0) = (u_radius.base >> (8 * 0)) & 0xFF;
00043       *(outbuffer + offset + 1) = (u_radius.base >> (8 * 1)) & 0xFF;
00044       *(outbuffer + offset + 2) = (u_radius.base >> (8 * 2)) & 0xFF;
00045       *(outbuffer + offset + 3) = (u_radius.base >> (8 * 3)) & 0xFF;
00046       offset += sizeof(this->radius);
00047       return offset;
00048     }
00049 
00050     virtual int deserialize(unsigned char *inbuffer)
00051     {
00052       int offset = 0;
00053       union {
00054         int32_t real;
00055         uint32_t base;
00056       } u_edges;
00057       u_edges.base = 0;
00058       u_edges.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00059       u_edges.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00060       u_edges.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00061       u_edges.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00062       this->edges = u_edges.real;
00063       offset += sizeof(this->edges);
00064       union {
00065         float real;
00066         uint32_t base;
00067       } u_radius;
00068       u_radius.base = 0;
00069       u_radius.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00070       u_radius.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00071       u_radius.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00072       u_radius.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00073       this->radius = u_radius.real;
00074       offset += sizeof(this->radius);
00075      return offset;
00076     }
00077 
00078     const char * getType(){ return "turtle_actionlib/ShapeGoal"; };
00079     const char * getMD5(){ return "3b9202ab7292cebe5a95ab2bf6b9c091"; };
00080 
00081   };
00082 
00083 }
00084 #endif