Working towards recieving twists

Dependencies:   BufferedSerial

Fork of ros_lib_kinetic by Gary Servin

Committer:
jvfausto
Date:
Fri Nov 02 21:48:22 2018 +0000
Revision:
2:ab8333331642
Parent:
0:9e9b7db60fd5
Working towards twists

Who changed what in which revision?

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