Just changed OUTPUT_SIZE and INPUT_SIZE in ros/node_handle.h
Dependents: WRS2020_mecanum_node
JointState.h
00001 #ifndef _ROS_sensor_msgs_JointState_h 00002 #define _ROS_sensor_msgs_JointState_h 00003 00004 #include <stdint.h> 00005 #include <string.h> 00006 #include <stdlib.h> 00007 #include "ros/msg.h" 00008 #include "std_msgs/Header.h" 00009 00010 namespace sensor_msgs 00011 { 00012 00013 class JointState : public ros::Msg 00014 { 00015 public: 00016 typedef std_msgs::Header _header_type; 00017 _header_type header; 00018 uint32_t name_length; 00019 typedef char* _name_type; 00020 _name_type st_name; 00021 _name_type * name; 00022 uint32_t position_length; 00023 typedef double _position_type; 00024 _position_type st_position; 00025 _position_type * position; 00026 uint32_t velocity_length; 00027 typedef double _velocity_type; 00028 _velocity_type st_velocity; 00029 _velocity_type * velocity; 00030 uint32_t effort_length; 00031 typedef double _effort_type; 00032 _effort_type st_effort; 00033 _effort_type * effort; 00034 00035 JointState(): 00036 header(), 00037 name_length(0), name(NULL), 00038 position_length(0), position(NULL), 00039 velocity_length(0), velocity(NULL), 00040 effort_length(0), effort(NULL) 00041 { 00042 } 00043 00044 virtual int serialize(unsigned char *outbuffer) const 00045 { 00046 int offset = 0; 00047 offset += this->header.serialize(outbuffer + offset); 00048 *(outbuffer + offset + 0) = (this->name_length >> (8 * 0)) & 0xFF; 00049 *(outbuffer + offset + 1) = (this->name_length >> (8 * 1)) & 0xFF; 00050 *(outbuffer + offset + 2) = (this->name_length >> (8 * 2)) & 0xFF; 00051 *(outbuffer + offset + 3) = (this->name_length >> (8 * 3)) & 0xFF; 00052 offset += sizeof(this->name_length); 00053 for( uint32_t i = 0; i < name_length; i++){ 00054 uint32_t length_namei = strlen(this->name[i]); 00055 varToArr(outbuffer + offset, length_namei); 00056 offset += 4; 00057 memcpy(outbuffer + offset, this->name[i], length_namei); 00058 offset += length_namei; 00059 } 00060 *(outbuffer + offset + 0) = (this->position_length >> (8 * 0)) & 0xFF; 00061 *(outbuffer + offset + 1) = (this->position_length >> (8 * 1)) & 0xFF; 00062 *(outbuffer + offset + 2) = (this->position_length >> (8 * 2)) & 0xFF; 00063 *(outbuffer + offset + 3) = (this->position_length >> (8 * 3)) & 0xFF; 00064 offset += sizeof(this->position_length); 00065 for( uint32_t i = 0; i < position_length; i++){ 00066 union { 00067 double real; 00068 uint64_t base; 00069 } u_positioni; 00070 u_positioni.real = this->position[i]; 00071 *(outbuffer + offset + 0) = (u_positioni.base >> (8 * 0)) & 0xFF; 00072 *(outbuffer + offset + 1) = (u_positioni.base >> (8 * 1)) & 0xFF; 00073 *(outbuffer + offset + 2) = (u_positioni.base >> (8 * 2)) & 0xFF; 00074 *(outbuffer + offset + 3) = (u_positioni.base >> (8 * 3)) & 0xFF; 00075 *(outbuffer + offset + 4) = (u_positioni.base >> (8 * 4)) & 0xFF; 00076 *(outbuffer + offset + 5) = (u_positioni.base >> (8 * 5)) & 0xFF; 00077 *(outbuffer + offset + 6) = (u_positioni.base >> (8 * 6)) & 0xFF; 00078 *(outbuffer + offset + 7) = (u_positioni.base >> (8 * 7)) & 0xFF; 00079 offset += sizeof(this->position[i]); 00080 } 00081 *(outbuffer + offset + 0) = (this->velocity_length >> (8 * 0)) & 0xFF; 00082 *(outbuffer + offset + 1) = (this->velocity_length >> (8 * 1)) & 0xFF; 00083 *(outbuffer + offset + 2) = (this->velocity_length >> (8 * 2)) & 0xFF; 00084 *(outbuffer + offset + 3) = (this->velocity_length >> (8 * 3)) & 0xFF; 00085 offset += sizeof(this->velocity_length); 00086 for( uint32_t i = 0; i < velocity_length; i++){ 00087 union { 00088 double real; 00089 uint64_t base; 00090 } u_velocityi; 00091 u_velocityi.real = this->velocity[i]; 00092 *(outbuffer + offset + 0) = (u_velocityi.base >> (8 * 0)) & 0xFF; 00093 *(outbuffer + offset + 1) = (u_velocityi.base >> (8 * 1)) & 0xFF; 00094 *(outbuffer + offset + 2) = (u_velocityi.base >> (8 * 2)) & 0xFF; 00095 *(outbuffer + offset + 3) = (u_velocityi.base >> (8 * 3)) & 0xFF; 00096 *(outbuffer + offset + 4) = (u_velocityi.base >> (8 * 4)) & 0xFF; 00097 *(outbuffer + offset + 5) = (u_velocityi.base >> (8 * 5)) & 0xFF; 00098 *(outbuffer + offset + 6) = (u_velocityi.base >> (8 * 6)) & 0xFF; 00099 *(outbuffer + offset + 7) = (u_velocityi.base >> (8 * 7)) & 0xFF; 00100 offset += sizeof(this->velocity[i]); 00101 } 00102 *(outbuffer + offset + 0) = (this->effort_length >> (8 * 0)) & 0xFF; 00103 *(outbuffer + offset + 1) = (this->effort_length >> (8 * 1)) & 0xFF; 00104 *(outbuffer + offset + 2) = (this->effort_length >> (8 * 2)) & 0xFF; 00105 *(outbuffer + offset + 3) = (this->effort_length >> (8 * 3)) & 0xFF; 00106 offset += sizeof(this->effort_length); 00107 for( uint32_t i = 0; i < effort_length; i++){ 00108 union { 00109 double real; 00110 uint64_t base; 00111 } u_efforti; 00112 u_efforti.real = this->effort[i]; 00113 *(outbuffer + offset + 0) = (u_efforti.base >> (8 * 0)) & 0xFF; 00114 *(outbuffer + offset + 1) = (u_efforti.base >> (8 * 1)) & 0xFF; 00115 *(outbuffer + offset + 2) = (u_efforti.base >> (8 * 2)) & 0xFF; 00116 *(outbuffer + offset + 3) = (u_efforti.base >> (8 * 3)) & 0xFF; 00117 *(outbuffer + offset + 4) = (u_efforti.base >> (8 * 4)) & 0xFF; 00118 *(outbuffer + offset + 5) = (u_efforti.base >> (8 * 5)) & 0xFF; 00119 *(outbuffer + offset + 6) = (u_efforti.base >> (8 * 6)) & 0xFF; 00120 *(outbuffer + offset + 7) = (u_efforti.base >> (8 * 7)) & 0xFF; 00121 offset += sizeof(this->effort[i]); 00122 } 00123 return offset; 00124 } 00125 00126 virtual int deserialize(unsigned char *inbuffer) 00127 { 00128 int offset = 0; 00129 offset += this->header.deserialize(inbuffer + offset); 00130 uint32_t name_lengthT = ((uint32_t) (*(inbuffer + offset))); 00131 name_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00132 name_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00133 name_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00134 offset += sizeof(this->name_length); 00135 if(name_lengthT > name_length) 00136 this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*)); 00137 name_length = name_lengthT; 00138 for( uint32_t i = 0; i < name_length; i++){ 00139 uint32_t length_st_name; 00140 arrToVar(length_st_name, (inbuffer + offset)); 00141 offset += 4; 00142 for(unsigned int k= offset; k< offset+length_st_name; ++k){ 00143 inbuffer[k-1]=inbuffer[k]; 00144 } 00145 inbuffer[offset+length_st_name-1]=0; 00146 this->st_name = (char *)(inbuffer + offset-1); 00147 offset += length_st_name; 00148 memcpy( &(this->name[i]), &(this->st_name), sizeof(char*)); 00149 } 00150 uint32_t position_lengthT = ((uint32_t) (*(inbuffer + offset))); 00151 position_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00152 position_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00153 position_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00154 offset += sizeof(this->position_length); 00155 if(position_lengthT > position_length) 00156 this->position = (double*)realloc(this->position, position_lengthT * sizeof(double)); 00157 position_length = position_lengthT; 00158 for( uint32_t i = 0; i < position_length; i++){ 00159 union { 00160 double real; 00161 uint64_t base; 00162 } u_st_position; 00163 u_st_position.base = 0; 00164 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00165 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00166 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00167 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00168 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00169 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00170 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00171 u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00172 this->st_position = u_st_position.real; 00173 offset += sizeof(this->st_position); 00174 memcpy( &(this->position[i]), &(this->st_position), sizeof(double)); 00175 } 00176 uint32_t velocity_lengthT = ((uint32_t) (*(inbuffer + offset))); 00177 velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00178 velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00179 velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00180 offset += sizeof(this->velocity_length); 00181 if(velocity_lengthT > velocity_length) 00182 this->velocity = (double*)realloc(this->velocity, velocity_lengthT * sizeof(double)); 00183 velocity_length = velocity_lengthT; 00184 for( uint32_t i = 0; i < velocity_length; i++){ 00185 union { 00186 double real; 00187 uint64_t base; 00188 } u_st_velocity; 00189 u_st_velocity.base = 0; 00190 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00191 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00192 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00193 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00194 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00195 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00196 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00197 u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00198 this->st_velocity = u_st_velocity.real; 00199 offset += sizeof(this->st_velocity); 00200 memcpy( &(this->velocity[i]), &(this->st_velocity), sizeof(double)); 00201 } 00202 uint32_t effort_lengthT = ((uint32_t) (*(inbuffer + offset))); 00203 effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00204 effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00205 effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00206 offset += sizeof(this->effort_length); 00207 if(effort_lengthT > effort_length) 00208 this->effort = (double*)realloc(this->effort, effort_lengthT * sizeof(double)); 00209 effort_length = effort_lengthT; 00210 for( uint32_t i = 0; i < effort_length; i++){ 00211 union { 00212 double real; 00213 uint64_t base; 00214 } u_st_effort; 00215 u_st_effort.base = 0; 00216 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00217 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00218 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00219 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00220 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00221 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00222 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00223 u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00224 this->st_effort = u_st_effort.real; 00225 offset += sizeof(this->st_effort); 00226 memcpy( &(this->effort[i]), &(this->st_effort), sizeof(double)); 00227 } 00228 return offset; 00229 } 00230 00231 const char * getType(){ return "sensor_msgs/JointState"; }; 00232 const char * getMD5(){ return "3066dcd76a6cfaef579bd0f34173e9fd"; }; 00233 00234 }; 00235 00236 } 00237 #endif
Generated on Tue Jul 12 2022 18:49:19 by
![doxygen](doxygen.png)