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