ROS Serial library for Mbed platforms for ROS Melodic Morenia. Check http://wiki.ros.org/rosserial_mbed/ for more information.

Dependencies:   BufferedSerial

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?

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