This is a fork from the original, including a small change in the buffer size of the hardware interface (increased to 2048) and decreasing the number of publishers and subscribers to 5. Besides, the library about the message Adc.h was modified so as to increase the number of available Adc channels to be read ( from 6 to 7 ) For this modification, a change in checksum was required

Dependencies:   BufferedSerial

Fork of ros_lib_kinetic by Gary Servin

Committer:
jacobepfl1692
Date:
Tue Oct 17 18:49:03 2017 +0000
Revision:
2:9114cc24ddcf
Parent:
0:9e9b7db60fd5
I increased the channels of the ADC to 6 (hence change in checksum) because my application needed it (STM32f407V6)

Who changed what in which revision?

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