ros melodic library with custom message

Dependents:   Robot_team1_QEI_Douglas Robot_team1

Committer:
scarter1
Date:
Wed Oct 30 14:59:49 2019 +0000
Revision:
0:020db18a476d
melodic library;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
scarter1 0:020db18a476d 1 #ifndef _ROS_control_msgs_JointControllerState_h
scarter1 0:020db18a476d 2 #define _ROS_control_msgs_JointControllerState_h
scarter1 0:020db18a476d 3
scarter1 0:020db18a476d 4 #include <stdint.h>
scarter1 0:020db18a476d 5 #include <string.h>
scarter1 0:020db18a476d 6 #include <stdlib.h>
scarter1 0:020db18a476d 7 #include "ros/msg.h"
scarter1 0:020db18a476d 8 #include "std_msgs/Header.h"
scarter1 0:020db18a476d 9
scarter1 0:020db18a476d 10 namespace control_msgs
scarter1 0:020db18a476d 11 {
scarter1 0:020db18a476d 12
scarter1 0:020db18a476d 13 class JointControllerState : public ros::Msg
scarter1 0:020db18a476d 14 {
scarter1 0:020db18a476d 15 public:
scarter1 0:020db18a476d 16 typedef std_msgs::Header _header_type;
scarter1 0:020db18a476d 17 _header_type header;
scarter1 0:020db18a476d 18 typedef double _set_point_type;
scarter1 0:020db18a476d 19 _set_point_type set_point;
scarter1 0:020db18a476d 20 typedef double _process_value_type;
scarter1 0:020db18a476d 21 _process_value_type process_value;
scarter1 0:020db18a476d 22 typedef double _process_value_dot_type;
scarter1 0:020db18a476d 23 _process_value_dot_type process_value_dot;
scarter1 0:020db18a476d 24 typedef double _error_type;
scarter1 0:020db18a476d 25 _error_type error;
scarter1 0:020db18a476d 26 typedef double _time_step_type;
scarter1 0:020db18a476d 27 _time_step_type time_step;
scarter1 0:020db18a476d 28 typedef double _command_type;
scarter1 0:020db18a476d 29 _command_type command;
scarter1 0:020db18a476d 30 typedef double _p_type;
scarter1 0:020db18a476d 31 _p_type p;
scarter1 0:020db18a476d 32 typedef double _i_type;
scarter1 0:020db18a476d 33 _i_type i;
scarter1 0:020db18a476d 34 typedef double _d_type;
scarter1 0:020db18a476d 35 _d_type d;
scarter1 0:020db18a476d 36 typedef double _i_clamp_type;
scarter1 0:020db18a476d 37 _i_clamp_type i_clamp;
scarter1 0:020db18a476d 38 typedef bool _antiwindup_type;
scarter1 0:020db18a476d 39 _antiwindup_type antiwindup;
scarter1 0:020db18a476d 40
scarter1 0:020db18a476d 41 JointControllerState():
scarter1 0:020db18a476d 42 header(),
scarter1 0:020db18a476d 43 set_point(0),
scarter1 0:020db18a476d 44 process_value(0),
scarter1 0:020db18a476d 45 process_value_dot(0),
scarter1 0:020db18a476d 46 error(0),
scarter1 0:020db18a476d 47 time_step(0),
scarter1 0:020db18a476d 48 command(0),
scarter1 0:020db18a476d 49 p(0),
scarter1 0:020db18a476d 50 i(0),
scarter1 0:020db18a476d 51 d(0),
scarter1 0:020db18a476d 52 i_clamp(0),
scarter1 0:020db18a476d 53 antiwindup(0)
scarter1 0:020db18a476d 54 {
scarter1 0:020db18a476d 55 }
scarter1 0:020db18a476d 56
scarter1 0:020db18a476d 57 virtual int serialize(unsigned char *outbuffer) const
scarter1 0:020db18a476d 58 {
scarter1 0:020db18a476d 59 int offset = 0;
scarter1 0:020db18a476d 60 offset += this->header.serialize(outbuffer + offset);
scarter1 0:020db18a476d 61 union {
scarter1 0:020db18a476d 62 double real;
scarter1 0:020db18a476d 63 uint64_t base;
scarter1 0:020db18a476d 64 } u_set_point;
scarter1 0:020db18a476d 65 u_set_point.real = this->set_point;
scarter1 0:020db18a476d 66 *(outbuffer + offset + 0) = (u_set_point.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 67 *(outbuffer + offset + 1) = (u_set_point.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 68 *(outbuffer + offset + 2) = (u_set_point.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 69 *(outbuffer + offset + 3) = (u_set_point.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 70 *(outbuffer + offset + 4) = (u_set_point.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 71 *(outbuffer + offset + 5) = (u_set_point.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 72 *(outbuffer + offset + 6) = (u_set_point.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 73 *(outbuffer + offset + 7) = (u_set_point.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 74 offset += sizeof(this->set_point);
scarter1 0:020db18a476d 75 union {
scarter1 0:020db18a476d 76 double real;
scarter1 0:020db18a476d 77 uint64_t base;
scarter1 0:020db18a476d 78 } u_process_value;
scarter1 0:020db18a476d 79 u_process_value.real = this->process_value;
scarter1 0:020db18a476d 80 *(outbuffer + offset + 0) = (u_process_value.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 81 *(outbuffer + offset + 1) = (u_process_value.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 82 *(outbuffer + offset + 2) = (u_process_value.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 83 *(outbuffer + offset + 3) = (u_process_value.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 84 *(outbuffer + offset + 4) = (u_process_value.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 85 *(outbuffer + offset + 5) = (u_process_value.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 86 *(outbuffer + offset + 6) = (u_process_value.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 87 *(outbuffer + offset + 7) = (u_process_value.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 88 offset += sizeof(this->process_value);
scarter1 0:020db18a476d 89 union {
scarter1 0:020db18a476d 90 double real;
scarter1 0:020db18a476d 91 uint64_t base;
scarter1 0:020db18a476d 92 } u_process_value_dot;
scarter1 0:020db18a476d 93 u_process_value_dot.real = this->process_value_dot;
scarter1 0:020db18a476d 94 *(outbuffer + offset + 0) = (u_process_value_dot.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 95 *(outbuffer + offset + 1) = (u_process_value_dot.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 96 *(outbuffer + offset + 2) = (u_process_value_dot.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 97 *(outbuffer + offset + 3) = (u_process_value_dot.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 98 *(outbuffer + offset + 4) = (u_process_value_dot.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 99 *(outbuffer + offset + 5) = (u_process_value_dot.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 100 *(outbuffer + offset + 6) = (u_process_value_dot.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 101 *(outbuffer + offset + 7) = (u_process_value_dot.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 102 offset += sizeof(this->process_value_dot);
scarter1 0:020db18a476d 103 union {
scarter1 0:020db18a476d 104 double real;
scarter1 0:020db18a476d 105 uint64_t base;
scarter1 0:020db18a476d 106 } u_error;
scarter1 0:020db18a476d 107 u_error.real = this->error;
scarter1 0:020db18a476d 108 *(outbuffer + offset + 0) = (u_error.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 109 *(outbuffer + offset + 1) = (u_error.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 110 *(outbuffer + offset + 2) = (u_error.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 111 *(outbuffer + offset + 3) = (u_error.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 112 *(outbuffer + offset + 4) = (u_error.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 113 *(outbuffer + offset + 5) = (u_error.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 114 *(outbuffer + offset + 6) = (u_error.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 115 *(outbuffer + offset + 7) = (u_error.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 116 offset += sizeof(this->error);
scarter1 0:020db18a476d 117 union {
scarter1 0:020db18a476d 118 double real;
scarter1 0:020db18a476d 119 uint64_t base;
scarter1 0:020db18a476d 120 } u_time_step;
scarter1 0:020db18a476d 121 u_time_step.real = this->time_step;
scarter1 0:020db18a476d 122 *(outbuffer + offset + 0) = (u_time_step.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 123 *(outbuffer + offset + 1) = (u_time_step.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 124 *(outbuffer + offset + 2) = (u_time_step.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 125 *(outbuffer + offset + 3) = (u_time_step.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 126 *(outbuffer + offset + 4) = (u_time_step.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 127 *(outbuffer + offset + 5) = (u_time_step.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 128 *(outbuffer + offset + 6) = (u_time_step.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 129 *(outbuffer + offset + 7) = (u_time_step.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 130 offset += sizeof(this->time_step);
scarter1 0:020db18a476d 131 union {
scarter1 0:020db18a476d 132 double real;
scarter1 0:020db18a476d 133 uint64_t base;
scarter1 0:020db18a476d 134 } u_command;
scarter1 0:020db18a476d 135 u_command.real = this->command;
scarter1 0:020db18a476d 136 *(outbuffer + offset + 0) = (u_command.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 137 *(outbuffer + offset + 1) = (u_command.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 138 *(outbuffer + offset + 2) = (u_command.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 139 *(outbuffer + offset + 3) = (u_command.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 140 *(outbuffer + offset + 4) = (u_command.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 141 *(outbuffer + offset + 5) = (u_command.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 142 *(outbuffer + offset + 6) = (u_command.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 143 *(outbuffer + offset + 7) = (u_command.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 144 offset += sizeof(this->command);
scarter1 0:020db18a476d 145 union {
scarter1 0:020db18a476d 146 double real;
scarter1 0:020db18a476d 147 uint64_t base;
scarter1 0:020db18a476d 148 } u_p;
scarter1 0:020db18a476d 149 u_p.real = this->p;
scarter1 0:020db18a476d 150 *(outbuffer + offset + 0) = (u_p.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 151 *(outbuffer + offset + 1) = (u_p.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 152 *(outbuffer + offset + 2) = (u_p.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 153 *(outbuffer + offset + 3) = (u_p.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 154 *(outbuffer + offset + 4) = (u_p.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 155 *(outbuffer + offset + 5) = (u_p.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 156 *(outbuffer + offset + 6) = (u_p.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 157 *(outbuffer + offset + 7) = (u_p.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 158 offset += sizeof(this->p);
scarter1 0:020db18a476d 159 union {
scarter1 0:020db18a476d 160 double real;
scarter1 0:020db18a476d 161 uint64_t base;
scarter1 0:020db18a476d 162 } u_i;
scarter1 0:020db18a476d 163 u_i.real = this->i;
scarter1 0:020db18a476d 164 *(outbuffer + offset + 0) = (u_i.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 165 *(outbuffer + offset + 1) = (u_i.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 166 *(outbuffer + offset + 2) = (u_i.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 167 *(outbuffer + offset + 3) = (u_i.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 168 *(outbuffer + offset + 4) = (u_i.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 169 *(outbuffer + offset + 5) = (u_i.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 170 *(outbuffer + offset + 6) = (u_i.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 171 *(outbuffer + offset + 7) = (u_i.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 172 offset += sizeof(this->i);
scarter1 0:020db18a476d 173 union {
scarter1 0:020db18a476d 174 double real;
scarter1 0:020db18a476d 175 uint64_t base;
scarter1 0:020db18a476d 176 } u_d;
scarter1 0:020db18a476d 177 u_d.real = this->d;
scarter1 0:020db18a476d 178 *(outbuffer + offset + 0) = (u_d.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 179 *(outbuffer + offset + 1) = (u_d.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 180 *(outbuffer + offset + 2) = (u_d.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 181 *(outbuffer + offset + 3) = (u_d.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 182 *(outbuffer + offset + 4) = (u_d.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 183 *(outbuffer + offset + 5) = (u_d.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 184 *(outbuffer + offset + 6) = (u_d.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 185 *(outbuffer + offset + 7) = (u_d.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 186 offset += sizeof(this->d);
scarter1 0:020db18a476d 187 union {
scarter1 0:020db18a476d 188 double real;
scarter1 0:020db18a476d 189 uint64_t base;
scarter1 0:020db18a476d 190 } u_i_clamp;
scarter1 0:020db18a476d 191 u_i_clamp.real = this->i_clamp;
scarter1 0:020db18a476d 192 *(outbuffer + offset + 0) = (u_i_clamp.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 193 *(outbuffer + offset + 1) = (u_i_clamp.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 194 *(outbuffer + offset + 2) = (u_i_clamp.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 195 *(outbuffer + offset + 3) = (u_i_clamp.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 196 *(outbuffer + offset + 4) = (u_i_clamp.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 197 *(outbuffer + offset + 5) = (u_i_clamp.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 198 *(outbuffer + offset + 6) = (u_i_clamp.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 199 *(outbuffer + offset + 7) = (u_i_clamp.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 200 offset += sizeof(this->i_clamp);
scarter1 0:020db18a476d 201 union {
scarter1 0:020db18a476d 202 bool real;
scarter1 0:020db18a476d 203 uint8_t base;
scarter1 0:020db18a476d 204 } u_antiwindup;
scarter1 0:020db18a476d 205 u_antiwindup.real = this->antiwindup;
scarter1 0:020db18a476d 206 *(outbuffer + offset + 0) = (u_antiwindup.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 207 offset += sizeof(this->antiwindup);
scarter1 0:020db18a476d 208 return offset;
scarter1 0:020db18a476d 209 }
scarter1 0:020db18a476d 210
scarter1 0:020db18a476d 211 virtual int deserialize(unsigned char *inbuffer)
scarter1 0:020db18a476d 212 {
scarter1 0:020db18a476d 213 int offset = 0;
scarter1 0:020db18a476d 214 offset += this->header.deserialize(inbuffer + offset);
scarter1 0:020db18a476d 215 union {
scarter1 0:020db18a476d 216 double real;
scarter1 0:020db18a476d 217 uint64_t base;
scarter1 0:020db18a476d 218 } u_set_point;
scarter1 0:020db18a476d 219 u_set_point.base = 0;
scarter1 0:020db18a476d 220 u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 221 u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 222 u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 223 u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 224 u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 225 u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 226 u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 227 u_set_point.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 228 this->set_point = u_set_point.real;
scarter1 0:020db18a476d 229 offset += sizeof(this->set_point);
scarter1 0:020db18a476d 230 union {
scarter1 0:020db18a476d 231 double real;
scarter1 0:020db18a476d 232 uint64_t base;
scarter1 0:020db18a476d 233 } u_process_value;
scarter1 0:020db18a476d 234 u_process_value.base = 0;
scarter1 0:020db18a476d 235 u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 236 u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 237 u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 238 u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 239 u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 240 u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 241 u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 242 u_process_value.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 243 this->process_value = u_process_value.real;
scarter1 0:020db18a476d 244 offset += sizeof(this->process_value);
scarter1 0:020db18a476d 245 union {
scarter1 0:020db18a476d 246 double real;
scarter1 0:020db18a476d 247 uint64_t base;
scarter1 0:020db18a476d 248 } u_process_value_dot;
scarter1 0:020db18a476d 249 u_process_value_dot.base = 0;
scarter1 0:020db18a476d 250 u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 251 u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 252 u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 253 u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 254 u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 255 u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 256 u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 257 u_process_value_dot.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 258 this->process_value_dot = u_process_value_dot.real;
scarter1 0:020db18a476d 259 offset += sizeof(this->process_value_dot);
scarter1 0:020db18a476d 260 union {
scarter1 0:020db18a476d 261 double real;
scarter1 0:020db18a476d 262 uint64_t base;
scarter1 0:020db18a476d 263 } u_error;
scarter1 0:020db18a476d 264 u_error.base = 0;
scarter1 0:020db18a476d 265 u_error.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 266 u_error.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 267 u_error.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 268 u_error.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 269 u_error.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 270 u_error.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 271 u_error.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 272 u_error.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 273 this->error = u_error.real;
scarter1 0:020db18a476d 274 offset += sizeof(this->error);
scarter1 0:020db18a476d 275 union {
scarter1 0:020db18a476d 276 double real;
scarter1 0:020db18a476d 277 uint64_t base;
scarter1 0:020db18a476d 278 } u_time_step;
scarter1 0:020db18a476d 279 u_time_step.base = 0;
scarter1 0:020db18a476d 280 u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 281 u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 282 u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 283 u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 284 u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 285 u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 286 u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 287 u_time_step.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 288 this->time_step = u_time_step.real;
scarter1 0:020db18a476d 289 offset += sizeof(this->time_step);
scarter1 0:020db18a476d 290 union {
scarter1 0:020db18a476d 291 double real;
scarter1 0:020db18a476d 292 uint64_t base;
scarter1 0:020db18a476d 293 } u_command;
scarter1 0:020db18a476d 294 u_command.base = 0;
scarter1 0:020db18a476d 295 u_command.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 296 u_command.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 297 u_command.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 298 u_command.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 299 u_command.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 300 u_command.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 301 u_command.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 302 u_command.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 303 this->command = u_command.real;
scarter1 0:020db18a476d 304 offset += sizeof(this->command);
scarter1 0:020db18a476d 305 union {
scarter1 0:020db18a476d 306 double real;
scarter1 0:020db18a476d 307 uint64_t base;
scarter1 0:020db18a476d 308 } u_p;
scarter1 0:020db18a476d 309 u_p.base = 0;
scarter1 0:020db18a476d 310 u_p.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 311 u_p.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 312 u_p.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 313 u_p.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 314 u_p.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 315 u_p.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 316 u_p.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 317 u_p.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 318 this->p = u_p.real;
scarter1 0:020db18a476d 319 offset += sizeof(this->p);
scarter1 0:020db18a476d 320 union {
scarter1 0:020db18a476d 321 double real;
scarter1 0:020db18a476d 322 uint64_t base;
scarter1 0:020db18a476d 323 } u_i;
scarter1 0:020db18a476d 324 u_i.base = 0;
scarter1 0:020db18a476d 325 u_i.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 326 u_i.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 327 u_i.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 328 u_i.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 329 u_i.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 330 u_i.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 331 u_i.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 332 u_i.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 333 this->i = u_i.real;
scarter1 0:020db18a476d 334 offset += sizeof(this->i);
scarter1 0:020db18a476d 335 union {
scarter1 0:020db18a476d 336 double real;
scarter1 0:020db18a476d 337 uint64_t base;
scarter1 0:020db18a476d 338 } u_d;
scarter1 0:020db18a476d 339 u_d.base = 0;
scarter1 0:020db18a476d 340 u_d.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 341 u_d.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 342 u_d.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 343 u_d.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 344 u_d.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 345 u_d.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 346 u_d.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 347 u_d.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 348 this->d = u_d.real;
scarter1 0:020db18a476d 349 offset += sizeof(this->d);
scarter1 0:020db18a476d 350 union {
scarter1 0:020db18a476d 351 double real;
scarter1 0:020db18a476d 352 uint64_t base;
scarter1 0:020db18a476d 353 } u_i_clamp;
scarter1 0:020db18a476d 354 u_i_clamp.base = 0;
scarter1 0:020db18a476d 355 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 356 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 357 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 358 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 359 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 360 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 361 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 362 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 363 this->i_clamp = u_i_clamp.real;
scarter1 0:020db18a476d 364 offset += sizeof(this->i_clamp);
scarter1 0:020db18a476d 365 union {
scarter1 0:020db18a476d 366 bool real;
scarter1 0:020db18a476d 367 uint8_t base;
scarter1 0:020db18a476d 368 } u_antiwindup;
scarter1 0:020db18a476d 369 u_antiwindup.base = 0;
scarter1 0:020db18a476d 370 u_antiwindup.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 371 this->antiwindup = u_antiwindup.real;
scarter1 0:020db18a476d 372 offset += sizeof(this->antiwindup);
scarter1 0:020db18a476d 373 return offset;
scarter1 0:020db18a476d 374 }
scarter1 0:020db18a476d 375
scarter1 0:020db18a476d 376 const char * getType(){ return "control_msgs/JointControllerState"; };
scarter1 0:020db18a476d 377 const char * getMD5(){ return "987ad85e4756f3aef7f1e5e7fe0595d1"; };
scarter1 0:020db18a476d 378
scarter1 0:020db18a476d 379 };
scarter1 0:020db18a476d 380
scarter1 0:020db18a476d 381 }
scarter1 0:020db18a476d 382 #endif