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 uint8_t type; 00016 uint8_t 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) const 00023 { 00024 int offset = 0; 00025 *(outbuffer + offset + 0) = (this->type >> (8 * 0)) & 0xFF; 00026 offset += sizeof(this->type); 00027 *(outbuffer + offset + 0) = (this->id >> (8 * 0)) & 0xFF; 00028 offset += sizeof(this->id); 00029 union { 00030 float real; 00031 uint32_t base; 00032 } u_intensity; 00033 u_intensity.real = this->intensity; 00034 *(outbuffer + offset + 0) = (u_intensity.base >> (8 * 0)) & 0xFF; 00035 *(outbuffer + offset + 1) = (u_intensity.base >> (8 * 1)) & 0xFF; 00036 *(outbuffer + offset + 2) = (u_intensity.base >> (8 * 2)) & 0xFF; 00037 *(outbuffer + offset + 3) = (u_intensity.base >> (8 * 3)) & 0xFF; 00038 offset += sizeof(this->intensity); 00039 return offset; 00040 } 00041 00042 virtual int deserialize(unsigned char *inbuffer) 00043 { 00044 int offset = 0; 00045 this->type |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00046 offset += sizeof(this->type); 00047 this->id |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00048 offset += sizeof(this->id); 00049 union { 00050 float real; 00051 uint32_t base; 00052 } u_intensity; 00053 u_intensity.base = 0; 00054 u_intensity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00055 u_intensity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00056 u_intensity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00057 u_intensity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00058 this->intensity = u_intensity.real; 00059 offset += sizeof(this->intensity); 00060 return offset; 00061 } 00062 00063 const char * getType(){ return "sensor_msgs/JoyFeedback"; }; 00064 const char * getMD5(){ return "f4dcd73460360d98f36e55ee7f2e46f1"; }; 00065 00066 }; 00067 00068 } 00069 #endif