Go to the documentation of this file.00001 #ifndef ros_sensor_msgs_JoyFeedback_h
00002 #define ros_sensor_msgs_JoyFeedback_h
00003
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "../ros/msg.h"
00008
00009 namespace sensor_msgs
00010 {
00011
00012 class JoyFeedback : public ros::Msg
00013 {
00014 public:
00015 unsigned char type;
00016 unsigned char id;
00017 float intensity;
00018 enum { TYPE_LED = 0 };
00019 enum { TYPE_RUMBLE = 1 };
00020 enum { TYPE_BUZZER = 2 };
00021
00022 virtual int serialize(unsigned char *outbuffer)
00023 {
00024 int offset = 0;
00025 union {
00026 unsigned char real;
00027 unsigned char base;
00028 } u_type;
00029 u_type.real = this->type;
00030 *(outbuffer + offset + 0) = (u_type.base >> (8 * 0)) & 0xFF;
00031 offset += sizeof(this->type);
00032 union {
00033 unsigned char real;
00034 unsigned char base;
00035 } u_id;
00036 u_id.real = this->id;
00037 *(outbuffer + offset + 0) = (u_id.base >> (8 * 0)) & 0xFF;
00038 offset += sizeof(this->id);
00039 union {
00040 float real;
00041 unsigned long base;
00042 } u_intensity;
00043 u_intensity.real = this->intensity;
00044 *(outbuffer + offset + 0) = (u_intensity.base >> (8 * 0)) & 0xFF;
00045 *(outbuffer + offset + 1) = (u_intensity.base >> (8 * 1)) & 0xFF;
00046 *(outbuffer + offset + 2) = (u_intensity.base >> (8 * 2)) & 0xFF;
00047 *(outbuffer + offset + 3) = (u_intensity.base >> (8 * 3)) & 0xFF;
00048 offset += sizeof(this->intensity);
00049 return offset;
00050 }
00051
00052 virtual int deserialize(unsigned char *inbuffer)
00053 {
00054 int offset = 0;
00055 union {
00056 unsigned char real;
00057 unsigned char base;
00058 } u_type;
00059 u_type.base = 0;
00060 u_type.base |= ((typeof(u_type.base)) (*(inbuffer + offset + 0))) << (8 * 0);
00061 this->type = u_type.real;
00062 offset += sizeof(this->type);
00063 union {
00064 unsigned char real;
00065 unsigned char base;
00066 } u_id;
00067 u_id.base = 0;
00068 u_id.base |= ((typeof(u_id.base)) (*(inbuffer + offset + 0))) << (8 * 0);
00069 this->id = u_id.real;
00070 offset += sizeof(this->id);
00071 union {
00072 float real;
00073 unsigned long base;
00074 } u_intensity;
00075 u_intensity.base = 0;
00076 u_intensity.base |= ((typeof(u_intensity.base)) (*(inbuffer + offset + 0))) << (8 * 0);
00077 u_intensity.base |= ((typeof(u_intensity.base)) (*(inbuffer + offset + 1))) << (8 * 1);
00078 u_intensity.base |= ((typeof(u_intensity.base)) (*(inbuffer + offset + 2))) << (8 * 2);
00079 u_intensity.base |= ((typeof(u_intensity.base)) (*(inbuffer + offset + 3))) << (8 * 3);
00080 this->intensity = u_intensity.real;
00081 offset += sizeof(this->intensity);
00082 return offset;
00083 }
00084
00085 const char * getType(){ return "sensor_msgs/JoyFeedback"; };
00086
00087 };
00088
00089 }
00090 #endif