ros melodic library with custom message
Dependents: Robot_team1_QEI_Douglas Robot_team1
ros_lib/gazebo_msgs/ContactState.h@0:020db18a476d, 2019-10-30 (annotated)
- Committer:
- scarter1
- Date:
- Wed Oct 30 14:59:49 2019 +0000
- Revision:
- 0:020db18a476d
melodic library;
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
scarter1 | 0:020db18a476d | 1 | #ifndef _ROS_gazebo_msgs_ContactState_h |
scarter1 | 0:020db18a476d | 2 | #define _ROS_gazebo_msgs_ContactState_h |
scarter1 | 0:020db18a476d | 3 | |
scarter1 | 0:020db18a476d | 4 | #include <stdint.h> |
scarter1 | 0:020db18a476d | 5 | #include <string.h> |
scarter1 | 0:020db18a476d | 6 | #include <stdlib.h> |
scarter1 | 0:020db18a476d | 7 | #include "ros/msg.h" |
scarter1 | 0:020db18a476d | 8 | #include "geometry_msgs/Wrench.h" |
scarter1 | 0:020db18a476d | 9 | #include "geometry_msgs/Vector3.h" |
scarter1 | 0:020db18a476d | 10 | |
scarter1 | 0:020db18a476d | 11 | namespace gazebo_msgs |
scarter1 | 0:020db18a476d | 12 | { |
scarter1 | 0:020db18a476d | 13 | |
scarter1 | 0:020db18a476d | 14 | class ContactState : public ros::Msg |
scarter1 | 0:020db18a476d | 15 | { |
scarter1 | 0:020db18a476d | 16 | public: |
scarter1 | 0:020db18a476d | 17 | typedef const char* _info_type; |
scarter1 | 0:020db18a476d | 18 | _info_type info; |
scarter1 | 0:020db18a476d | 19 | typedef const char* _collision1_name_type; |
scarter1 | 0:020db18a476d | 20 | _collision1_name_type collision1_name; |
scarter1 | 0:020db18a476d | 21 | typedef const char* _collision2_name_type; |
scarter1 | 0:020db18a476d | 22 | _collision2_name_type collision2_name; |
scarter1 | 0:020db18a476d | 23 | uint32_t wrenches_length; |
scarter1 | 0:020db18a476d | 24 | typedef geometry_msgs::Wrench _wrenches_type; |
scarter1 | 0:020db18a476d | 25 | _wrenches_type st_wrenches; |
scarter1 | 0:020db18a476d | 26 | _wrenches_type * wrenches; |
scarter1 | 0:020db18a476d | 27 | typedef geometry_msgs::Wrench _total_wrench_type; |
scarter1 | 0:020db18a476d | 28 | _total_wrench_type total_wrench; |
scarter1 | 0:020db18a476d | 29 | uint32_t contact_positions_length; |
scarter1 | 0:020db18a476d | 30 | typedef geometry_msgs::Vector3 _contact_positions_type; |
scarter1 | 0:020db18a476d | 31 | _contact_positions_type st_contact_positions; |
scarter1 | 0:020db18a476d | 32 | _contact_positions_type * contact_positions; |
scarter1 | 0:020db18a476d | 33 | uint32_t contact_normals_length; |
scarter1 | 0:020db18a476d | 34 | typedef geometry_msgs::Vector3 _contact_normals_type; |
scarter1 | 0:020db18a476d | 35 | _contact_normals_type st_contact_normals; |
scarter1 | 0:020db18a476d | 36 | _contact_normals_type * contact_normals; |
scarter1 | 0:020db18a476d | 37 | uint32_t depths_length; |
scarter1 | 0:020db18a476d | 38 | typedef double _depths_type; |
scarter1 | 0:020db18a476d | 39 | _depths_type st_depths; |
scarter1 | 0:020db18a476d | 40 | _depths_type * depths; |
scarter1 | 0:020db18a476d | 41 | |
scarter1 | 0:020db18a476d | 42 | ContactState(): |
scarter1 | 0:020db18a476d | 43 | info(""), |
scarter1 | 0:020db18a476d | 44 | collision1_name(""), |
scarter1 | 0:020db18a476d | 45 | collision2_name(""), |
scarter1 | 0:020db18a476d | 46 | wrenches_length(0), wrenches(NULL), |
scarter1 | 0:020db18a476d | 47 | total_wrench(), |
scarter1 | 0:020db18a476d | 48 | contact_positions_length(0), contact_positions(NULL), |
scarter1 | 0:020db18a476d | 49 | contact_normals_length(0), contact_normals(NULL), |
scarter1 | 0:020db18a476d | 50 | depths_length(0), depths(NULL) |
scarter1 | 0:020db18a476d | 51 | { |
scarter1 | 0:020db18a476d | 52 | } |
scarter1 | 0:020db18a476d | 53 | |
scarter1 | 0:020db18a476d | 54 | virtual int serialize(unsigned char *outbuffer) const |
scarter1 | 0:020db18a476d | 55 | { |
scarter1 | 0:020db18a476d | 56 | int offset = 0; |
scarter1 | 0:020db18a476d | 57 | uint32_t length_info = strlen(this->info); |
scarter1 | 0:020db18a476d | 58 | varToArr(outbuffer + offset, length_info); |
scarter1 | 0:020db18a476d | 59 | offset += 4; |
scarter1 | 0:020db18a476d | 60 | memcpy(outbuffer + offset, this->info, length_info); |
scarter1 | 0:020db18a476d | 61 | offset += length_info; |
scarter1 | 0:020db18a476d | 62 | uint32_t length_collision1_name = strlen(this->collision1_name); |
scarter1 | 0:020db18a476d | 63 | varToArr(outbuffer + offset, length_collision1_name); |
scarter1 | 0:020db18a476d | 64 | offset += 4; |
scarter1 | 0:020db18a476d | 65 | memcpy(outbuffer + offset, this->collision1_name, length_collision1_name); |
scarter1 | 0:020db18a476d | 66 | offset += length_collision1_name; |
scarter1 | 0:020db18a476d | 67 | uint32_t length_collision2_name = strlen(this->collision2_name); |
scarter1 | 0:020db18a476d | 68 | varToArr(outbuffer + offset, length_collision2_name); |
scarter1 | 0:020db18a476d | 69 | offset += 4; |
scarter1 | 0:020db18a476d | 70 | memcpy(outbuffer + offset, this->collision2_name, length_collision2_name); |
scarter1 | 0:020db18a476d | 71 | offset += length_collision2_name; |
scarter1 | 0:020db18a476d | 72 | *(outbuffer + offset + 0) = (this->wrenches_length >> (8 * 0)) & 0xFF; |
scarter1 | 0:020db18a476d | 73 | *(outbuffer + offset + 1) = (this->wrenches_length >> (8 * 1)) & 0xFF; |
scarter1 | 0:020db18a476d | 74 | *(outbuffer + offset + 2) = (this->wrenches_length >> (8 * 2)) & 0xFF; |
scarter1 | 0:020db18a476d | 75 | *(outbuffer + offset + 3) = (this->wrenches_length >> (8 * 3)) & 0xFF; |
scarter1 | 0:020db18a476d | 76 | offset += sizeof(this->wrenches_length); |
scarter1 | 0:020db18a476d | 77 | for( uint32_t i = 0; i < wrenches_length; i++){ |
scarter1 | 0:020db18a476d | 78 | offset += this->wrenches[i].serialize(outbuffer + offset); |
scarter1 | 0:020db18a476d | 79 | } |
scarter1 | 0:020db18a476d | 80 | offset += this->total_wrench.serialize(outbuffer + offset); |
scarter1 | 0:020db18a476d | 81 | *(outbuffer + offset + 0) = (this->contact_positions_length >> (8 * 0)) & 0xFF; |
scarter1 | 0:020db18a476d | 82 | *(outbuffer + offset + 1) = (this->contact_positions_length >> (8 * 1)) & 0xFF; |
scarter1 | 0:020db18a476d | 83 | *(outbuffer + offset + 2) = (this->contact_positions_length >> (8 * 2)) & 0xFF; |
scarter1 | 0:020db18a476d | 84 | *(outbuffer + offset + 3) = (this->contact_positions_length >> (8 * 3)) & 0xFF; |
scarter1 | 0:020db18a476d | 85 | offset += sizeof(this->contact_positions_length); |
scarter1 | 0:020db18a476d | 86 | for( uint32_t i = 0; i < contact_positions_length; i++){ |
scarter1 | 0:020db18a476d | 87 | offset += this->contact_positions[i].serialize(outbuffer + offset); |
scarter1 | 0:020db18a476d | 88 | } |
scarter1 | 0:020db18a476d | 89 | *(outbuffer + offset + 0) = (this->contact_normals_length >> (8 * 0)) & 0xFF; |
scarter1 | 0:020db18a476d | 90 | *(outbuffer + offset + 1) = (this->contact_normals_length >> (8 * 1)) & 0xFF; |
scarter1 | 0:020db18a476d | 91 | *(outbuffer + offset + 2) = (this->contact_normals_length >> (8 * 2)) & 0xFF; |
scarter1 | 0:020db18a476d | 92 | *(outbuffer + offset + 3) = (this->contact_normals_length >> (8 * 3)) & 0xFF; |
scarter1 | 0:020db18a476d | 93 | offset += sizeof(this->contact_normals_length); |
scarter1 | 0:020db18a476d | 94 | for( uint32_t i = 0; i < contact_normals_length; i++){ |
scarter1 | 0:020db18a476d | 95 | offset += this->contact_normals[i].serialize(outbuffer + offset); |
scarter1 | 0:020db18a476d | 96 | } |
scarter1 | 0:020db18a476d | 97 | *(outbuffer + offset + 0) = (this->depths_length >> (8 * 0)) & 0xFF; |
scarter1 | 0:020db18a476d | 98 | *(outbuffer + offset + 1) = (this->depths_length >> (8 * 1)) & 0xFF; |
scarter1 | 0:020db18a476d | 99 | *(outbuffer + offset + 2) = (this->depths_length >> (8 * 2)) & 0xFF; |
scarter1 | 0:020db18a476d | 100 | *(outbuffer + offset + 3) = (this->depths_length >> (8 * 3)) & 0xFF; |
scarter1 | 0:020db18a476d | 101 | offset += sizeof(this->depths_length); |
scarter1 | 0:020db18a476d | 102 | for( uint32_t i = 0; i < depths_length; i++){ |
scarter1 | 0:020db18a476d | 103 | union { |
scarter1 | 0:020db18a476d | 104 | double real; |
scarter1 | 0:020db18a476d | 105 | uint64_t base; |
scarter1 | 0:020db18a476d | 106 | } u_depthsi; |
scarter1 | 0:020db18a476d | 107 | u_depthsi.real = this->depths[i]; |
scarter1 | 0:020db18a476d | 108 | *(outbuffer + offset + 0) = (u_depthsi.base >> (8 * 0)) & 0xFF; |
scarter1 | 0:020db18a476d | 109 | *(outbuffer + offset + 1) = (u_depthsi.base >> (8 * 1)) & 0xFF; |
scarter1 | 0:020db18a476d | 110 | *(outbuffer + offset + 2) = (u_depthsi.base >> (8 * 2)) & 0xFF; |
scarter1 | 0:020db18a476d | 111 | *(outbuffer + offset + 3) = (u_depthsi.base >> (8 * 3)) & 0xFF; |
scarter1 | 0:020db18a476d | 112 | *(outbuffer + offset + 4) = (u_depthsi.base >> (8 * 4)) & 0xFF; |
scarter1 | 0:020db18a476d | 113 | *(outbuffer + offset + 5) = (u_depthsi.base >> (8 * 5)) & 0xFF; |
scarter1 | 0:020db18a476d | 114 | *(outbuffer + offset + 6) = (u_depthsi.base >> (8 * 6)) & 0xFF; |
scarter1 | 0:020db18a476d | 115 | *(outbuffer + offset + 7) = (u_depthsi.base >> (8 * 7)) & 0xFF; |
scarter1 | 0:020db18a476d | 116 | offset += sizeof(this->depths[i]); |
scarter1 | 0:020db18a476d | 117 | } |
scarter1 | 0:020db18a476d | 118 | return offset; |
scarter1 | 0:020db18a476d | 119 | } |
scarter1 | 0:020db18a476d | 120 | |
scarter1 | 0:020db18a476d | 121 | virtual int deserialize(unsigned char *inbuffer) |
scarter1 | 0:020db18a476d | 122 | { |
scarter1 | 0:020db18a476d | 123 | int offset = 0; |
scarter1 | 0:020db18a476d | 124 | uint32_t length_info; |
scarter1 | 0:020db18a476d | 125 | arrToVar(length_info, (inbuffer + offset)); |
scarter1 | 0:020db18a476d | 126 | offset += 4; |
scarter1 | 0:020db18a476d | 127 | for(unsigned int k= offset; k< offset+length_info; ++k){ |
scarter1 | 0:020db18a476d | 128 | inbuffer[k-1]=inbuffer[k]; |
scarter1 | 0:020db18a476d | 129 | } |
scarter1 | 0:020db18a476d | 130 | inbuffer[offset+length_info-1]=0; |
scarter1 | 0:020db18a476d | 131 | this->info = (char *)(inbuffer + offset-1); |
scarter1 | 0:020db18a476d | 132 | offset += length_info; |
scarter1 | 0:020db18a476d | 133 | uint32_t length_collision1_name; |
scarter1 | 0:020db18a476d | 134 | arrToVar(length_collision1_name, (inbuffer + offset)); |
scarter1 | 0:020db18a476d | 135 | offset += 4; |
scarter1 | 0:020db18a476d | 136 | for(unsigned int k= offset; k< offset+length_collision1_name; ++k){ |
scarter1 | 0:020db18a476d | 137 | inbuffer[k-1]=inbuffer[k]; |
scarter1 | 0:020db18a476d | 138 | } |
scarter1 | 0:020db18a476d | 139 | inbuffer[offset+length_collision1_name-1]=0; |
scarter1 | 0:020db18a476d | 140 | this->collision1_name = (char *)(inbuffer + offset-1); |
scarter1 | 0:020db18a476d | 141 | offset += length_collision1_name; |
scarter1 | 0:020db18a476d | 142 | uint32_t length_collision2_name; |
scarter1 | 0:020db18a476d | 143 | arrToVar(length_collision2_name, (inbuffer + offset)); |
scarter1 | 0:020db18a476d | 144 | offset += 4; |
scarter1 | 0:020db18a476d | 145 | for(unsigned int k= offset; k< offset+length_collision2_name; ++k){ |
scarter1 | 0:020db18a476d | 146 | inbuffer[k-1]=inbuffer[k]; |
scarter1 | 0:020db18a476d | 147 | } |
scarter1 | 0:020db18a476d | 148 | inbuffer[offset+length_collision2_name-1]=0; |
scarter1 | 0:020db18a476d | 149 | this->collision2_name = (char *)(inbuffer + offset-1); |
scarter1 | 0:020db18a476d | 150 | offset += length_collision2_name; |
scarter1 | 0:020db18a476d | 151 | uint32_t wrenches_lengthT = ((uint32_t) (*(inbuffer + offset))); |
scarter1 | 0:020db18a476d | 152 | wrenches_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
scarter1 | 0:020db18a476d | 153 | wrenches_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
scarter1 | 0:020db18a476d | 154 | wrenches_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
scarter1 | 0:020db18a476d | 155 | offset += sizeof(this->wrenches_length); |
scarter1 | 0:020db18a476d | 156 | if(wrenches_lengthT > wrenches_length) |
scarter1 | 0:020db18a476d | 157 | this->wrenches = (geometry_msgs::Wrench*)realloc(this->wrenches, wrenches_lengthT * sizeof(geometry_msgs::Wrench)); |
scarter1 | 0:020db18a476d | 158 | wrenches_length = wrenches_lengthT; |
scarter1 | 0:020db18a476d | 159 | for( uint32_t i = 0; i < wrenches_length; i++){ |
scarter1 | 0:020db18a476d | 160 | offset += this->st_wrenches.deserialize(inbuffer + offset); |
scarter1 | 0:020db18a476d | 161 | memcpy( &(this->wrenches[i]), &(this->st_wrenches), sizeof(geometry_msgs::Wrench)); |
scarter1 | 0:020db18a476d | 162 | } |
scarter1 | 0:020db18a476d | 163 | offset += this->total_wrench.deserialize(inbuffer + offset); |
scarter1 | 0:020db18a476d | 164 | uint32_t contact_positions_lengthT = ((uint32_t) (*(inbuffer + offset))); |
scarter1 | 0:020db18a476d | 165 | contact_positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
scarter1 | 0:020db18a476d | 166 | contact_positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
scarter1 | 0:020db18a476d | 167 | contact_positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
scarter1 | 0:020db18a476d | 168 | offset += sizeof(this->contact_positions_length); |
scarter1 | 0:020db18a476d | 169 | if(contact_positions_lengthT > contact_positions_length) |
scarter1 | 0:020db18a476d | 170 | this->contact_positions = (geometry_msgs::Vector3*)realloc(this->contact_positions, contact_positions_lengthT * sizeof(geometry_msgs::Vector3)); |
scarter1 | 0:020db18a476d | 171 | contact_positions_length = contact_positions_lengthT; |
scarter1 | 0:020db18a476d | 172 | for( uint32_t i = 0; i < contact_positions_length; i++){ |
scarter1 | 0:020db18a476d | 173 | offset += this->st_contact_positions.deserialize(inbuffer + offset); |
scarter1 | 0:020db18a476d | 174 | memcpy( &(this->contact_positions[i]), &(this->st_contact_positions), sizeof(geometry_msgs::Vector3)); |
scarter1 | 0:020db18a476d | 175 | } |
scarter1 | 0:020db18a476d | 176 | uint32_t contact_normals_lengthT = ((uint32_t) (*(inbuffer + offset))); |
scarter1 | 0:020db18a476d | 177 | contact_normals_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
scarter1 | 0:020db18a476d | 178 | contact_normals_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
scarter1 | 0:020db18a476d | 179 | contact_normals_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
scarter1 | 0:020db18a476d | 180 | offset += sizeof(this->contact_normals_length); |
scarter1 | 0:020db18a476d | 181 | if(contact_normals_lengthT > contact_normals_length) |
scarter1 | 0:020db18a476d | 182 | this->contact_normals = (geometry_msgs::Vector3*)realloc(this->contact_normals, contact_normals_lengthT * sizeof(geometry_msgs::Vector3)); |
scarter1 | 0:020db18a476d | 183 | contact_normals_length = contact_normals_lengthT; |
scarter1 | 0:020db18a476d | 184 | for( uint32_t i = 0; i < contact_normals_length; i++){ |
scarter1 | 0:020db18a476d | 185 | offset += this->st_contact_normals.deserialize(inbuffer + offset); |
scarter1 | 0:020db18a476d | 186 | memcpy( &(this->contact_normals[i]), &(this->st_contact_normals), sizeof(geometry_msgs::Vector3)); |
scarter1 | 0:020db18a476d | 187 | } |
scarter1 | 0:020db18a476d | 188 | uint32_t depths_lengthT = ((uint32_t) (*(inbuffer + offset))); |
scarter1 | 0:020db18a476d | 189 | depths_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
scarter1 | 0:020db18a476d | 190 | depths_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
scarter1 | 0:020db18a476d | 191 | depths_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
scarter1 | 0:020db18a476d | 192 | offset += sizeof(this->depths_length); |
scarter1 | 0:020db18a476d | 193 | if(depths_lengthT > depths_length) |
scarter1 | 0:020db18a476d | 194 | this->depths = (double*)realloc(this->depths, depths_lengthT * sizeof(double)); |
scarter1 | 0:020db18a476d | 195 | depths_length = depths_lengthT; |
scarter1 | 0:020db18a476d | 196 | for( uint32_t i = 0; i < depths_length; i++){ |
scarter1 | 0:020db18a476d | 197 | union { |
scarter1 | 0:020db18a476d | 198 | double real; |
scarter1 | 0:020db18a476d | 199 | uint64_t base; |
scarter1 | 0:020db18a476d | 200 | } u_st_depths; |
scarter1 | 0:020db18a476d | 201 | u_st_depths.base = 0; |
scarter1 | 0:020db18a476d | 202 | u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); |
scarter1 | 0:020db18a476d | 203 | u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); |
scarter1 | 0:020db18a476d | 204 | u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); |
scarter1 | 0:020db18a476d | 205 | u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); |
scarter1 | 0:020db18a476d | 206 | u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); |
scarter1 | 0:020db18a476d | 207 | u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); |
scarter1 | 0:020db18a476d | 208 | u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); |
scarter1 | 0:020db18a476d | 209 | u_st_depths.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); |
scarter1 | 0:020db18a476d | 210 | this->st_depths = u_st_depths.real; |
scarter1 | 0:020db18a476d | 211 | offset += sizeof(this->st_depths); |
scarter1 | 0:020db18a476d | 212 | memcpy( &(this->depths[i]), &(this->st_depths), sizeof(double)); |
scarter1 | 0:020db18a476d | 213 | } |
scarter1 | 0:020db18a476d | 214 | return offset; |
scarter1 | 0:020db18a476d | 215 | } |
scarter1 | 0:020db18a476d | 216 | |
scarter1 | 0:020db18a476d | 217 | const char * getType(){ return "gazebo_msgs/ContactState"; }; |
scarter1 | 0:020db18a476d | 218 | const char * getMD5(){ return "48c0ffb054b8c444f870cecea1ee50d9"; }; |
scarter1 | 0:020db18a476d | 219 | |
scarter1 | 0:020db18a476d | 220 | }; |
scarter1 | 0:020db18a476d | 221 | |
scarter1 | 0:020db18a476d | 222 | } |
scarter1 | 0:020db18a476d | 223 | #endif |