Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
JoyFeedback.h
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 typedef uint8_t _type_type; 00016 _type_type type; 00017 typedef uint8_t _id_type; 00018 _id_type id; 00019 typedef float _intensity_type; 00020 _intensity_type intensity; 00021 enum { TYPE_LED = 0 }; 00022 enum { TYPE_RUMBLE = 1 }; 00023 enum { TYPE_BUZZER = 2 }; 00024 00025 JoyFeedback(): 00026 type(0), 00027 id(0), 00028 intensity(0) 00029 { 00030 } 00031 00032 virtual int serialize(unsigned char *outbuffer) const 00033 { 00034 int offset = 0; 00035 *(outbuffer + offset + 0) = (this->type >> (8 * 0)) & 0xFF; 00036 offset += sizeof(this->type); 00037 *(outbuffer + offset + 0) = (this->id >> (8 * 0)) & 0xFF; 00038 offset += sizeof(this->id); 00039 union { 00040 float real; 00041 uint32_t 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 this->type = ((uint8_t) (*(inbuffer + offset))); 00056 offset += sizeof(this->type); 00057 this->id = ((uint8_t) (*(inbuffer + offset))); 00058 offset += sizeof(this->id); 00059 union { 00060 float real; 00061 uint32_t base; 00062 } u_intensity; 00063 u_intensity.base = 0; 00064 u_intensity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00065 u_intensity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00066 u_intensity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00067 u_intensity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00068 this->intensity = u_intensity.real; 00069 offset += sizeof(this->intensity); 00070 return offset; 00071 } 00072 00073 const char * getType(){ return "sensor_msgs/JoyFeedback"; }; 00074 const char * getMD5(){ return "f4dcd73460360d98f36e55ee7f2e46f1"; }; 00075 00076 }; 00077 00078 } 00079 #endif
Generated on Wed Jul 13 2022 23:30:18 by
