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