Just changed OUTPUT_SIZE and INPUT_SIZE in ros/node_handle.h
Dependents: WRS2020_mecanum_node
ModelState.h
00001 #ifndef _ROS_gazebo_msgs_ModelState_h 00002 #define _ROS_gazebo_msgs_ModelState_h 00003 00004 #include <stdint.h> 00005 #include <string.h> 00006 #include <stdlib.h> 00007 #include "ros/msg.h" 00008 #include "geometry_msgs/Pose.h" 00009 #include "geometry_msgs/Twist.h" 00010 00011 namespace gazebo_msgs 00012 { 00013 00014 class ModelState : public ros::Msg 00015 { 00016 public: 00017 typedef const char* _model_name_type; 00018 _model_name_type model_name; 00019 typedef geometry_msgs::Pose _pose_type; 00020 _pose_type pose; 00021 typedef geometry_msgs::Twist _twist_type; 00022 _twist_type twist; 00023 typedef const char* _reference_frame_type; 00024 _reference_frame_type reference_frame; 00025 00026 ModelState(): 00027 model_name(""), 00028 pose(), 00029 twist(), 00030 reference_frame("") 00031 { 00032 } 00033 00034 virtual int serialize(unsigned char *outbuffer) const 00035 { 00036 int offset = 0; 00037 uint32_t length_model_name = strlen(this->model_name); 00038 varToArr(outbuffer + offset, length_model_name); 00039 offset += 4; 00040 memcpy(outbuffer + offset, this->model_name, length_model_name); 00041 offset += length_model_name; 00042 offset += this->pose.serialize(outbuffer + offset); 00043 offset += this->twist.serialize(outbuffer + offset); 00044 uint32_t length_reference_frame = strlen(this->reference_frame); 00045 varToArr(outbuffer + offset, length_reference_frame); 00046 offset += 4; 00047 memcpy(outbuffer + offset, this->reference_frame, length_reference_frame); 00048 offset += length_reference_frame; 00049 return offset; 00050 } 00051 00052 virtual int deserialize(unsigned char *inbuffer) 00053 { 00054 int offset = 0; 00055 uint32_t length_model_name; 00056 arrToVar(length_model_name, (inbuffer + offset)); 00057 offset += 4; 00058 for(unsigned int k= offset; k< offset+length_model_name; ++k){ 00059 inbuffer[k-1]=inbuffer[k]; 00060 } 00061 inbuffer[offset+length_model_name-1]=0; 00062 this->model_name = (char *)(inbuffer + offset-1); 00063 offset += length_model_name; 00064 offset += this->pose.deserialize(inbuffer + offset); 00065 offset += this->twist.deserialize(inbuffer + offset); 00066 uint32_t length_reference_frame; 00067 arrToVar(length_reference_frame, (inbuffer + offset)); 00068 offset += 4; 00069 for(unsigned int k= offset; k< offset+length_reference_frame; ++k){ 00070 inbuffer[k-1]=inbuffer[k]; 00071 } 00072 inbuffer[offset+length_reference_frame-1]=0; 00073 this->reference_frame = (char *)(inbuffer + offset-1); 00074 offset += length_reference_frame; 00075 return offset; 00076 } 00077 00078 const char * getType(){ return "gazebo_msgs/ModelState"; }; 00079 const char * getMD5(){ return "9330fd35f2fcd82d457e54bd54e10593"; }; 00080 00081 }; 00082 00083 } 00084 #endif
Generated on Tue Jul 12 2022 18:49:19 by 1.7.2