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.
MultiDOFJointState.h
00001 #ifndef _ROS_sensor_msgs_MultiDOFJointState_h 00002 #define _ROS_sensor_msgs_MultiDOFJointState_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 #include "geometry_msgs/Transform.h" 00010 #include "geometry_msgs/Twist.h" 00011 #include "geometry_msgs/Wrench.h" 00012 00013 namespace sensor_msgs 00014 { 00015 00016 class MultiDOFJointState : public ros::Msg 00017 { 00018 public: 00019 typedef std_msgs::Header _header_type; 00020 _header_type header; 00021 uint32_t joint_names_length; 00022 typedef char* _joint_names_type; 00023 _joint_names_type st_joint_names; 00024 _joint_names_type * joint_names; 00025 uint32_t transforms_length; 00026 typedef geometry_msgs::Transform _transforms_type; 00027 _transforms_type st_transforms; 00028 _transforms_type * transforms; 00029 uint32_t twist_length; 00030 typedef geometry_msgs::Twist _twist_type; 00031 _twist_type st_twist; 00032 _twist_type * twist; 00033 uint32_t wrench_length; 00034 typedef geometry_msgs::Wrench _wrench_type; 00035 _wrench_type st_wrench; 00036 _wrench_type * wrench; 00037 00038 MultiDOFJointState(): 00039 header(), 00040 joint_names_length(0), joint_names(NULL), 00041 transforms_length(0), transforms(NULL), 00042 twist_length(0), twist(NULL), 00043 wrench_length(0), wrench(NULL) 00044 { 00045 } 00046 00047 virtual int serialize(unsigned char *outbuffer) const 00048 { 00049 int offset = 0; 00050 offset += this->header.serialize(outbuffer + offset); 00051 *(outbuffer + offset + 0) = (this->joint_names_length >> (8 * 0)) & 0xFF; 00052 *(outbuffer + offset + 1) = (this->joint_names_length >> (8 * 1)) & 0xFF; 00053 *(outbuffer + offset + 2) = (this->joint_names_length >> (8 * 2)) & 0xFF; 00054 *(outbuffer + offset + 3) = (this->joint_names_length >> (8 * 3)) & 0xFF; 00055 offset += sizeof(this->joint_names_length); 00056 for( uint32_t i = 0; i < joint_names_length; i++){ 00057 uint32_t length_joint_namesi = strlen(this->joint_names[i]); 00058 varToArr(outbuffer + offset, length_joint_namesi); 00059 offset += 4; 00060 memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi); 00061 offset += length_joint_namesi; 00062 } 00063 *(outbuffer + offset + 0) = (this->transforms_length >> (8 * 0)) & 0xFF; 00064 *(outbuffer + offset + 1) = (this->transforms_length >> (8 * 1)) & 0xFF; 00065 *(outbuffer + offset + 2) = (this->transforms_length >> (8 * 2)) & 0xFF; 00066 *(outbuffer + offset + 3) = (this->transforms_length >> (8 * 3)) & 0xFF; 00067 offset += sizeof(this->transforms_length); 00068 for( uint32_t i = 0; i < transforms_length; i++){ 00069 offset += this->transforms[i].serialize(outbuffer + offset); 00070 } 00071 *(outbuffer + offset + 0) = (this->twist_length >> (8 * 0)) & 0xFF; 00072 *(outbuffer + offset + 1) = (this->twist_length >> (8 * 1)) & 0xFF; 00073 *(outbuffer + offset + 2) = (this->twist_length >> (8 * 2)) & 0xFF; 00074 *(outbuffer + offset + 3) = (this->twist_length >> (8 * 3)) & 0xFF; 00075 offset += sizeof(this->twist_length); 00076 for( uint32_t i = 0; i < twist_length; i++){ 00077 offset += this->twist[i].serialize(outbuffer + offset); 00078 } 00079 *(outbuffer + offset + 0) = (this->wrench_length >> (8 * 0)) & 0xFF; 00080 *(outbuffer + offset + 1) = (this->wrench_length >> (8 * 1)) & 0xFF; 00081 *(outbuffer + offset + 2) = (this->wrench_length >> (8 * 2)) & 0xFF; 00082 *(outbuffer + offset + 3) = (this->wrench_length >> (8 * 3)) & 0xFF; 00083 offset += sizeof(this->wrench_length); 00084 for( uint32_t i = 0; i < wrench_length; i++){ 00085 offset += this->wrench[i].serialize(outbuffer + offset); 00086 } 00087 return offset; 00088 } 00089 00090 virtual int deserialize(unsigned char *inbuffer) 00091 { 00092 int offset = 0; 00093 offset += this->header.deserialize(inbuffer + offset); 00094 uint32_t joint_names_lengthT = ((uint32_t) (*(inbuffer + offset))); 00095 joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00096 joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00097 joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00098 offset += sizeof(this->joint_names_length); 00099 if(joint_names_lengthT > joint_names_length) 00100 this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*)); 00101 joint_names_length = joint_names_lengthT; 00102 for( uint32_t i = 0; i < joint_names_length; i++){ 00103 uint32_t length_st_joint_names; 00104 arrToVar(length_st_joint_names, (inbuffer + offset)); 00105 offset += 4; 00106 for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){ 00107 inbuffer[k-1]=inbuffer[k]; 00108 } 00109 inbuffer[offset+length_st_joint_names-1]=0; 00110 this->st_joint_names = (char *)(inbuffer + offset-1); 00111 offset += length_st_joint_names; 00112 memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*)); 00113 } 00114 uint32_t transforms_lengthT = ((uint32_t) (*(inbuffer + offset))); 00115 transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00116 transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00117 transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00118 offset += sizeof(this->transforms_length); 00119 if(transforms_lengthT > transforms_length) 00120 this->transforms = (geometry_msgs::Transform*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::Transform)); 00121 transforms_length = transforms_lengthT; 00122 for( uint32_t i = 0; i < transforms_length; i++){ 00123 offset += this->st_transforms.deserialize(inbuffer + offset); 00124 memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::Transform)); 00125 } 00126 uint32_t twist_lengthT = ((uint32_t) (*(inbuffer + offset))); 00127 twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00128 twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00129 twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00130 offset += sizeof(this->twist_length); 00131 if(twist_lengthT > twist_length) 00132 this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist)); 00133 twist_length = twist_lengthT; 00134 for( uint32_t i = 0; i < twist_length; i++){ 00135 offset += this->st_twist.deserialize(inbuffer + offset); 00136 memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist)); 00137 } 00138 uint32_t wrench_lengthT = ((uint32_t) (*(inbuffer + offset))); 00139 wrench_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00140 wrench_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00141 wrench_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00142 offset += sizeof(this->wrench_length); 00143 if(wrench_lengthT > wrench_length) 00144 this->wrench = (geometry_msgs::Wrench*)realloc(this->wrench, wrench_lengthT * sizeof(geometry_msgs::Wrench)); 00145 wrench_length = wrench_lengthT; 00146 for( uint32_t i = 0; i < wrench_length; i++){ 00147 offset += this->st_wrench.deserialize(inbuffer + offset); 00148 memcpy( &(this->wrench[i]), &(this->st_wrench), sizeof(geometry_msgs::Wrench)); 00149 } 00150 return offset; 00151 } 00152 00153 const char * getType(){ return "sensor_msgs/MultiDOFJointState"; }; 00154 const char * getMD5(){ return "690f272f0640d2631c305eeb8301e59d"; }; 00155 00156 }; 00157 00158 } 00159 #endif
Generated on Wed Jul 13 2022 23:30:18 by
