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

TestRequestResult.h

00001 #ifndef _ROS_actionlib_TestRequestResult_h
00002 #define _ROS_actionlib_TestRequestResult_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 
00009 namespace actionlib
00010 {
00011 
00012   class TestRequestResult : public ros::Msg
00013   {
00014     public:
00015       int32_t the_result;
00016       bool is_simple_server;
00017 
00018     TestRequestResult():
00019       the_result(0),
00020       is_simple_server(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_the_result;
00031       u_the_result.real = this->the_result;
00032       *(outbuffer + offset + 0) = (u_the_result.base >> (8 * 0)) & 0xFF;
00033       *(outbuffer + offset + 1) = (u_the_result.base >> (8 * 1)) & 0xFF;
00034       *(outbuffer + offset + 2) = (u_the_result.base >> (8 * 2)) & 0xFF;
00035       *(outbuffer + offset + 3) = (u_the_result.base >> (8 * 3)) & 0xFF;
00036       offset += sizeof(this->the_result);
00037       union {
00038         bool real;
00039         uint8_t base;
00040       } u_is_simple_server;
00041       u_is_simple_server.real = this->is_simple_server;
00042       *(outbuffer + offset + 0) = (u_is_simple_server.base >> (8 * 0)) & 0xFF;
00043       offset += sizeof(this->is_simple_server);
00044       return offset;
00045     }
00046 
00047     virtual int deserialize(unsigned char *inbuffer)
00048     {
00049       int offset = 0;
00050       union {
00051         int32_t real;
00052         uint32_t base;
00053       } u_the_result;
00054       u_the_result.base = 0;
00055       u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00056       u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00057       u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00058       u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00059       this->the_result = u_the_result.real;
00060       offset += sizeof(this->the_result);
00061       union {
00062         bool real;
00063         uint8_t base;
00064       } u_is_simple_server;
00065       u_is_simple_server.base = 0;
00066       u_is_simple_server.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00067       this->is_simple_server = u_is_simple_server.real;
00068       offset += sizeof(this->is_simple_server);
00069      return offset;
00070     }
00071 
00072     const char * getType(){ return "actionlib/TestRequestResult"; };
00073     const char * getMD5(){ return "61c2364524499c7c5017e2f3fce7ba06"; };
00074 
00075   };
00076 
00077 }
00078 #endif