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