ros melodic library with custom message

Dependents:   Robot_team1_QEI_Douglas Robot_team1

Committer:
scarter1
Date:
Wed Oct 30 14:59:49 2019 +0000
Revision:
0:020db18a476d
melodic library;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
scarter1 0:020db18a476d 1 #ifndef _ROS_SERVICE_GetLinkProperties_h
scarter1 0:020db18a476d 2 #define _ROS_SERVICE_GetLinkProperties_h
scarter1 0:020db18a476d 3 #include <stdint.h>
scarter1 0:020db18a476d 4 #include <string.h>
scarter1 0:020db18a476d 5 #include <stdlib.h>
scarter1 0:020db18a476d 6 #include "ros/msg.h"
scarter1 0:020db18a476d 7 #include "geometry_msgs/Pose.h"
scarter1 0:020db18a476d 8
scarter1 0:020db18a476d 9 namespace gazebo_msgs
scarter1 0:020db18a476d 10 {
scarter1 0:020db18a476d 11
scarter1 0:020db18a476d 12 static const char GETLINKPROPERTIES[] = "gazebo_msgs/GetLinkProperties";
scarter1 0:020db18a476d 13
scarter1 0:020db18a476d 14 class GetLinkPropertiesRequest : public ros::Msg
scarter1 0:020db18a476d 15 {
scarter1 0:020db18a476d 16 public:
scarter1 0:020db18a476d 17 typedef const char* _link_name_type;
scarter1 0:020db18a476d 18 _link_name_type link_name;
scarter1 0:020db18a476d 19
scarter1 0:020db18a476d 20 GetLinkPropertiesRequest():
scarter1 0:020db18a476d 21 link_name("")
scarter1 0:020db18a476d 22 {
scarter1 0:020db18a476d 23 }
scarter1 0:020db18a476d 24
scarter1 0:020db18a476d 25 virtual int serialize(unsigned char *outbuffer) const
scarter1 0:020db18a476d 26 {
scarter1 0:020db18a476d 27 int offset = 0;
scarter1 0:020db18a476d 28 uint32_t length_link_name = strlen(this->link_name);
scarter1 0:020db18a476d 29 varToArr(outbuffer + offset, length_link_name);
scarter1 0:020db18a476d 30 offset += 4;
scarter1 0:020db18a476d 31 memcpy(outbuffer + offset, this->link_name, length_link_name);
scarter1 0:020db18a476d 32 offset += length_link_name;
scarter1 0:020db18a476d 33 return offset;
scarter1 0:020db18a476d 34 }
scarter1 0:020db18a476d 35
scarter1 0:020db18a476d 36 virtual int deserialize(unsigned char *inbuffer)
scarter1 0:020db18a476d 37 {
scarter1 0:020db18a476d 38 int offset = 0;
scarter1 0:020db18a476d 39 uint32_t length_link_name;
scarter1 0:020db18a476d 40 arrToVar(length_link_name, (inbuffer + offset));
scarter1 0:020db18a476d 41 offset += 4;
scarter1 0:020db18a476d 42 for(unsigned int k= offset; k< offset+length_link_name; ++k){
scarter1 0:020db18a476d 43 inbuffer[k-1]=inbuffer[k];
scarter1 0:020db18a476d 44 }
scarter1 0:020db18a476d 45 inbuffer[offset+length_link_name-1]=0;
scarter1 0:020db18a476d 46 this->link_name = (char *)(inbuffer + offset-1);
scarter1 0:020db18a476d 47 offset += length_link_name;
scarter1 0:020db18a476d 48 return offset;
scarter1 0:020db18a476d 49 }
scarter1 0:020db18a476d 50
scarter1 0:020db18a476d 51 const char * getType(){ return GETLINKPROPERTIES; };
scarter1 0:020db18a476d 52 const char * getMD5(){ return "7d82d60381f1b66a30f2157f60884345"; };
scarter1 0:020db18a476d 53
scarter1 0:020db18a476d 54 };
scarter1 0:020db18a476d 55
scarter1 0:020db18a476d 56 class GetLinkPropertiesResponse : public ros::Msg
scarter1 0:020db18a476d 57 {
scarter1 0:020db18a476d 58 public:
scarter1 0:020db18a476d 59 typedef geometry_msgs::Pose _com_type;
scarter1 0:020db18a476d 60 _com_type com;
scarter1 0:020db18a476d 61 typedef bool _gravity_mode_type;
scarter1 0:020db18a476d 62 _gravity_mode_type gravity_mode;
scarter1 0:020db18a476d 63 typedef double _mass_type;
scarter1 0:020db18a476d 64 _mass_type mass;
scarter1 0:020db18a476d 65 typedef double _ixx_type;
scarter1 0:020db18a476d 66 _ixx_type ixx;
scarter1 0:020db18a476d 67 typedef double _ixy_type;
scarter1 0:020db18a476d 68 _ixy_type ixy;
scarter1 0:020db18a476d 69 typedef double _ixz_type;
scarter1 0:020db18a476d 70 _ixz_type ixz;
scarter1 0:020db18a476d 71 typedef double _iyy_type;
scarter1 0:020db18a476d 72 _iyy_type iyy;
scarter1 0:020db18a476d 73 typedef double _iyz_type;
scarter1 0:020db18a476d 74 _iyz_type iyz;
scarter1 0:020db18a476d 75 typedef double _izz_type;
scarter1 0:020db18a476d 76 _izz_type izz;
scarter1 0:020db18a476d 77 typedef bool _success_type;
scarter1 0:020db18a476d 78 _success_type success;
scarter1 0:020db18a476d 79 typedef const char* _status_message_type;
scarter1 0:020db18a476d 80 _status_message_type status_message;
scarter1 0:020db18a476d 81
scarter1 0:020db18a476d 82 GetLinkPropertiesResponse():
scarter1 0:020db18a476d 83 com(),
scarter1 0:020db18a476d 84 gravity_mode(0),
scarter1 0:020db18a476d 85 mass(0),
scarter1 0:020db18a476d 86 ixx(0),
scarter1 0:020db18a476d 87 ixy(0),
scarter1 0:020db18a476d 88 ixz(0),
scarter1 0:020db18a476d 89 iyy(0),
scarter1 0:020db18a476d 90 iyz(0),
scarter1 0:020db18a476d 91 izz(0),
scarter1 0:020db18a476d 92 success(0),
scarter1 0:020db18a476d 93 status_message("")
scarter1 0:020db18a476d 94 {
scarter1 0:020db18a476d 95 }
scarter1 0:020db18a476d 96
scarter1 0:020db18a476d 97 virtual int serialize(unsigned char *outbuffer) const
scarter1 0:020db18a476d 98 {
scarter1 0:020db18a476d 99 int offset = 0;
scarter1 0:020db18a476d 100 offset += this->com.serialize(outbuffer + offset);
scarter1 0:020db18a476d 101 union {
scarter1 0:020db18a476d 102 bool real;
scarter1 0:020db18a476d 103 uint8_t base;
scarter1 0:020db18a476d 104 } u_gravity_mode;
scarter1 0:020db18a476d 105 u_gravity_mode.real = this->gravity_mode;
scarter1 0:020db18a476d 106 *(outbuffer + offset + 0) = (u_gravity_mode.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 107 offset += sizeof(this->gravity_mode);
scarter1 0:020db18a476d 108 union {
scarter1 0:020db18a476d 109 double real;
scarter1 0:020db18a476d 110 uint64_t base;
scarter1 0:020db18a476d 111 } u_mass;
scarter1 0:020db18a476d 112 u_mass.real = this->mass;
scarter1 0:020db18a476d 113 *(outbuffer + offset + 0) = (u_mass.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 114 *(outbuffer + offset + 1) = (u_mass.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 115 *(outbuffer + offset + 2) = (u_mass.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 116 *(outbuffer + offset + 3) = (u_mass.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 117 *(outbuffer + offset + 4) = (u_mass.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 118 *(outbuffer + offset + 5) = (u_mass.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 119 *(outbuffer + offset + 6) = (u_mass.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 120 *(outbuffer + offset + 7) = (u_mass.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 121 offset += sizeof(this->mass);
scarter1 0:020db18a476d 122 union {
scarter1 0:020db18a476d 123 double real;
scarter1 0:020db18a476d 124 uint64_t base;
scarter1 0:020db18a476d 125 } u_ixx;
scarter1 0:020db18a476d 126 u_ixx.real = this->ixx;
scarter1 0:020db18a476d 127 *(outbuffer + offset + 0) = (u_ixx.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 128 *(outbuffer + offset + 1) = (u_ixx.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 129 *(outbuffer + offset + 2) = (u_ixx.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 130 *(outbuffer + offset + 3) = (u_ixx.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 131 *(outbuffer + offset + 4) = (u_ixx.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 132 *(outbuffer + offset + 5) = (u_ixx.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 133 *(outbuffer + offset + 6) = (u_ixx.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 134 *(outbuffer + offset + 7) = (u_ixx.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 135 offset += sizeof(this->ixx);
scarter1 0:020db18a476d 136 union {
scarter1 0:020db18a476d 137 double real;
scarter1 0:020db18a476d 138 uint64_t base;
scarter1 0:020db18a476d 139 } u_ixy;
scarter1 0:020db18a476d 140 u_ixy.real = this->ixy;
scarter1 0:020db18a476d 141 *(outbuffer + offset + 0) = (u_ixy.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 142 *(outbuffer + offset + 1) = (u_ixy.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 143 *(outbuffer + offset + 2) = (u_ixy.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 144 *(outbuffer + offset + 3) = (u_ixy.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 145 *(outbuffer + offset + 4) = (u_ixy.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 146 *(outbuffer + offset + 5) = (u_ixy.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 147 *(outbuffer + offset + 6) = (u_ixy.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 148 *(outbuffer + offset + 7) = (u_ixy.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 149 offset += sizeof(this->ixy);
scarter1 0:020db18a476d 150 union {
scarter1 0:020db18a476d 151 double real;
scarter1 0:020db18a476d 152 uint64_t base;
scarter1 0:020db18a476d 153 } u_ixz;
scarter1 0:020db18a476d 154 u_ixz.real = this->ixz;
scarter1 0:020db18a476d 155 *(outbuffer + offset + 0) = (u_ixz.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 156 *(outbuffer + offset + 1) = (u_ixz.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 157 *(outbuffer + offset + 2) = (u_ixz.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 158 *(outbuffer + offset + 3) = (u_ixz.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 159 *(outbuffer + offset + 4) = (u_ixz.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 160 *(outbuffer + offset + 5) = (u_ixz.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 161 *(outbuffer + offset + 6) = (u_ixz.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 162 *(outbuffer + offset + 7) = (u_ixz.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 163 offset += sizeof(this->ixz);
scarter1 0:020db18a476d 164 union {
scarter1 0:020db18a476d 165 double real;
scarter1 0:020db18a476d 166 uint64_t base;
scarter1 0:020db18a476d 167 } u_iyy;
scarter1 0:020db18a476d 168 u_iyy.real = this->iyy;
scarter1 0:020db18a476d 169 *(outbuffer + offset + 0) = (u_iyy.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 170 *(outbuffer + offset + 1) = (u_iyy.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 171 *(outbuffer + offset + 2) = (u_iyy.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 172 *(outbuffer + offset + 3) = (u_iyy.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 173 *(outbuffer + offset + 4) = (u_iyy.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 174 *(outbuffer + offset + 5) = (u_iyy.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 175 *(outbuffer + offset + 6) = (u_iyy.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 176 *(outbuffer + offset + 7) = (u_iyy.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 177 offset += sizeof(this->iyy);
scarter1 0:020db18a476d 178 union {
scarter1 0:020db18a476d 179 double real;
scarter1 0:020db18a476d 180 uint64_t base;
scarter1 0:020db18a476d 181 } u_iyz;
scarter1 0:020db18a476d 182 u_iyz.real = this->iyz;
scarter1 0:020db18a476d 183 *(outbuffer + offset + 0) = (u_iyz.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 184 *(outbuffer + offset + 1) = (u_iyz.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 185 *(outbuffer + offset + 2) = (u_iyz.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 186 *(outbuffer + offset + 3) = (u_iyz.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 187 *(outbuffer + offset + 4) = (u_iyz.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 188 *(outbuffer + offset + 5) = (u_iyz.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 189 *(outbuffer + offset + 6) = (u_iyz.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 190 *(outbuffer + offset + 7) = (u_iyz.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 191 offset += sizeof(this->iyz);
scarter1 0:020db18a476d 192 union {
scarter1 0:020db18a476d 193 double real;
scarter1 0:020db18a476d 194 uint64_t base;
scarter1 0:020db18a476d 195 } u_izz;
scarter1 0:020db18a476d 196 u_izz.real = this->izz;
scarter1 0:020db18a476d 197 *(outbuffer + offset + 0) = (u_izz.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 198 *(outbuffer + offset + 1) = (u_izz.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 199 *(outbuffer + offset + 2) = (u_izz.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 200 *(outbuffer + offset + 3) = (u_izz.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 201 *(outbuffer + offset + 4) = (u_izz.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 202 *(outbuffer + offset + 5) = (u_izz.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 203 *(outbuffer + offset + 6) = (u_izz.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 204 *(outbuffer + offset + 7) = (u_izz.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 205 offset += sizeof(this->izz);
scarter1 0:020db18a476d 206 union {
scarter1 0:020db18a476d 207 bool real;
scarter1 0:020db18a476d 208 uint8_t base;
scarter1 0:020db18a476d 209 } u_success;
scarter1 0:020db18a476d 210 u_success.real = this->success;
scarter1 0:020db18a476d 211 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 212 offset += sizeof(this->success);
scarter1 0:020db18a476d 213 uint32_t length_status_message = strlen(this->status_message);
scarter1 0:020db18a476d 214 varToArr(outbuffer + offset, length_status_message);
scarter1 0:020db18a476d 215 offset += 4;
scarter1 0:020db18a476d 216 memcpy(outbuffer + offset, this->status_message, length_status_message);
scarter1 0:020db18a476d 217 offset += length_status_message;
scarter1 0:020db18a476d 218 return offset;
scarter1 0:020db18a476d 219 }
scarter1 0:020db18a476d 220
scarter1 0:020db18a476d 221 virtual int deserialize(unsigned char *inbuffer)
scarter1 0:020db18a476d 222 {
scarter1 0:020db18a476d 223 int offset = 0;
scarter1 0:020db18a476d 224 offset += this->com.deserialize(inbuffer + offset);
scarter1 0:020db18a476d 225 union {
scarter1 0:020db18a476d 226 bool real;
scarter1 0:020db18a476d 227 uint8_t base;
scarter1 0:020db18a476d 228 } u_gravity_mode;
scarter1 0:020db18a476d 229 u_gravity_mode.base = 0;
scarter1 0:020db18a476d 230 u_gravity_mode.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 231 this->gravity_mode = u_gravity_mode.real;
scarter1 0:020db18a476d 232 offset += sizeof(this->gravity_mode);
scarter1 0:020db18a476d 233 union {
scarter1 0:020db18a476d 234 double real;
scarter1 0:020db18a476d 235 uint64_t base;
scarter1 0:020db18a476d 236 } u_mass;
scarter1 0:020db18a476d 237 u_mass.base = 0;
scarter1 0:020db18a476d 238 u_mass.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 239 u_mass.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 240 u_mass.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 241 u_mass.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 242 u_mass.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 243 u_mass.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 244 u_mass.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 245 u_mass.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 246 this->mass = u_mass.real;
scarter1 0:020db18a476d 247 offset += sizeof(this->mass);
scarter1 0:020db18a476d 248 union {
scarter1 0:020db18a476d 249 double real;
scarter1 0:020db18a476d 250 uint64_t base;
scarter1 0:020db18a476d 251 } u_ixx;
scarter1 0:020db18a476d 252 u_ixx.base = 0;
scarter1 0:020db18a476d 253 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 254 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 255 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 256 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 257 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 258 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 259 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 260 u_ixx.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 261 this->ixx = u_ixx.real;
scarter1 0:020db18a476d 262 offset += sizeof(this->ixx);
scarter1 0:020db18a476d 263 union {
scarter1 0:020db18a476d 264 double real;
scarter1 0:020db18a476d 265 uint64_t base;
scarter1 0:020db18a476d 266 } u_ixy;
scarter1 0:020db18a476d 267 u_ixy.base = 0;
scarter1 0:020db18a476d 268 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 269 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 270 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 271 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 272 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 273 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 274 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 275 u_ixy.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 276 this->ixy = u_ixy.real;
scarter1 0:020db18a476d 277 offset += sizeof(this->ixy);
scarter1 0:020db18a476d 278 union {
scarter1 0:020db18a476d 279 double real;
scarter1 0:020db18a476d 280 uint64_t base;
scarter1 0:020db18a476d 281 } u_ixz;
scarter1 0:020db18a476d 282 u_ixz.base = 0;
scarter1 0:020db18a476d 283 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 284 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 285 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 286 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 287 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 288 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 289 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 290 u_ixz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 291 this->ixz = u_ixz.real;
scarter1 0:020db18a476d 292 offset += sizeof(this->ixz);
scarter1 0:020db18a476d 293 union {
scarter1 0:020db18a476d 294 double real;
scarter1 0:020db18a476d 295 uint64_t base;
scarter1 0:020db18a476d 296 } u_iyy;
scarter1 0:020db18a476d 297 u_iyy.base = 0;
scarter1 0:020db18a476d 298 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 299 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 300 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 301 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 302 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 303 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 304 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 305 u_iyy.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 306 this->iyy = u_iyy.real;
scarter1 0:020db18a476d 307 offset += sizeof(this->iyy);
scarter1 0:020db18a476d 308 union {
scarter1 0:020db18a476d 309 double real;
scarter1 0:020db18a476d 310 uint64_t base;
scarter1 0:020db18a476d 311 } u_iyz;
scarter1 0:020db18a476d 312 u_iyz.base = 0;
scarter1 0:020db18a476d 313 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 314 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 315 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 316 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 317 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 318 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 319 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 320 u_iyz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 321 this->iyz = u_iyz.real;
scarter1 0:020db18a476d 322 offset += sizeof(this->iyz);
scarter1 0:020db18a476d 323 union {
scarter1 0:020db18a476d 324 double real;
scarter1 0:020db18a476d 325 uint64_t base;
scarter1 0:020db18a476d 326 } u_izz;
scarter1 0:020db18a476d 327 u_izz.base = 0;
scarter1 0:020db18a476d 328 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 329 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 330 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 331 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 332 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 333 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 334 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 335 u_izz.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 336 this->izz = u_izz.real;
scarter1 0:020db18a476d 337 offset += sizeof(this->izz);
scarter1 0:020db18a476d 338 union {
scarter1 0:020db18a476d 339 bool real;
scarter1 0:020db18a476d 340 uint8_t base;
scarter1 0:020db18a476d 341 } u_success;
scarter1 0:020db18a476d 342 u_success.base = 0;
scarter1 0:020db18a476d 343 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 344 this->success = u_success.real;
scarter1 0:020db18a476d 345 offset += sizeof(this->success);
scarter1 0:020db18a476d 346 uint32_t length_status_message;
scarter1 0:020db18a476d 347 arrToVar(length_status_message, (inbuffer + offset));
scarter1 0:020db18a476d 348 offset += 4;
scarter1 0:020db18a476d 349 for(unsigned int k= offset; k< offset+length_status_message; ++k){
scarter1 0:020db18a476d 350 inbuffer[k-1]=inbuffer[k];
scarter1 0:020db18a476d 351 }
scarter1 0:020db18a476d 352 inbuffer[offset+length_status_message-1]=0;
scarter1 0:020db18a476d 353 this->status_message = (char *)(inbuffer + offset-1);
scarter1 0:020db18a476d 354 offset += length_status_message;
scarter1 0:020db18a476d 355 return offset;
scarter1 0:020db18a476d 356 }
scarter1 0:020db18a476d 357
scarter1 0:020db18a476d 358 const char * getType(){ return GETLINKPROPERTIES; };
scarter1 0:020db18a476d 359 const char * getMD5(){ return "a8619f92d17cfcc3958c0fd13299443d"; };
scarter1 0:020db18a476d 360
scarter1 0:020db18a476d 361 };
scarter1 0:020db18a476d 362
scarter1 0:020db18a476d 363 class GetLinkProperties {
scarter1 0:020db18a476d 364 public:
scarter1 0:020db18a476d 365 typedef GetLinkPropertiesRequest Request;
scarter1 0:020db18a476d 366 typedef GetLinkPropertiesResponse Response;
scarter1 0:020db18a476d 367 };
scarter1 0:020db18a476d 368
scarter1 0:020db18a476d 369 }
scarter1 0:020db18a476d 370 #endif