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