It has only one change from original one. I added robotfeedback message on it.

Dependencies:   BufferedSerial

Dependents:   RobotFeedback mobileRobotITU

Fork of ros_lib_indigo by Gary Servin

Committer:
randalthor
Date:
Sat Mar 04 14:07:56 2017 +0000
Revision:
4:80d9bee5079a
Parent:
0:fd24f7ca9688
fatih

Who changed what in which revision?

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