Just changed OUTPUT_SIZE and INPUT_SIZE in ros/node_handle.h

Dependencies:   BufferedSerial

Dependents:   WRS2020_mecanum_node

Committer:
sgrsn
Date:
Mon Nov 02 09:00:01 2020 +0000
Revision:
2:5d429be7d0aa
Parent:
0:04ac6be8229a
Change INPUT_SIZE and OUTPUT_SIZE on node_handle.h to pub sub

Who changed what in which revision?

UserRevisionLine numberNew contents of line
Gary Servin 0:04ac6be8229a 1 #ifndef _ROS_SERVICE_SetPidGains_h
Gary Servin 0:04ac6be8229a 2 #define _ROS_SERVICE_SetPidGains_h
Gary Servin 0:04ac6be8229a 3 #include <stdint.h>
Gary Servin 0:04ac6be8229a 4 #include <string.h>
Gary Servin 0:04ac6be8229a 5 #include <stdlib.h>
Gary Servin 0:04ac6be8229a 6 #include "ros/msg.h"
Gary Servin 0:04ac6be8229a 7
Gary Servin 0:04ac6be8229a 8 namespace control_toolbox
Gary Servin 0:04ac6be8229a 9 {
Gary Servin 0:04ac6be8229a 10
Gary Servin 0:04ac6be8229a 11 static const char SETPIDGAINS[] = "control_toolbox/SetPidGains";
Gary Servin 0:04ac6be8229a 12
Gary Servin 0:04ac6be8229a 13 class SetPidGainsRequest : public ros::Msg
Gary Servin 0:04ac6be8229a 14 {
Gary Servin 0:04ac6be8229a 15 public:
Gary Servin 0:04ac6be8229a 16 typedef double _p_type;
Gary Servin 0:04ac6be8229a 17 _p_type p;
Gary Servin 0:04ac6be8229a 18 typedef double _i_type;
Gary Servin 0:04ac6be8229a 19 _i_type i;
Gary Servin 0:04ac6be8229a 20 typedef double _d_type;
Gary Servin 0:04ac6be8229a 21 _d_type d;
Gary Servin 0:04ac6be8229a 22 typedef double _i_clamp_type;
Gary Servin 0:04ac6be8229a 23 _i_clamp_type i_clamp;
Gary Servin 0:04ac6be8229a 24 typedef bool _antiwindup_type;
Gary Servin 0:04ac6be8229a 25 _antiwindup_type antiwindup;
Gary Servin 0:04ac6be8229a 26
Gary Servin 0:04ac6be8229a 27 SetPidGainsRequest():
Gary Servin 0:04ac6be8229a 28 p(0),
Gary Servin 0:04ac6be8229a 29 i(0),
Gary Servin 0:04ac6be8229a 30 d(0),
Gary Servin 0:04ac6be8229a 31 i_clamp(0),
Gary Servin 0:04ac6be8229a 32 antiwindup(0)
Gary Servin 0:04ac6be8229a 33 {
Gary Servin 0:04ac6be8229a 34 }
Gary Servin 0:04ac6be8229a 35
Gary Servin 0:04ac6be8229a 36 virtual int serialize(unsigned char *outbuffer) const
Gary Servin 0:04ac6be8229a 37 {
Gary Servin 0:04ac6be8229a 38 int offset = 0;
Gary Servin 0:04ac6be8229a 39 union {
Gary Servin 0:04ac6be8229a 40 double real;
Gary Servin 0:04ac6be8229a 41 uint64_t base;
Gary Servin 0:04ac6be8229a 42 } u_p;
Gary Servin 0:04ac6be8229a 43 u_p.real = this->p;
Gary Servin 0:04ac6be8229a 44 *(outbuffer + offset + 0) = (u_p.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 45 *(outbuffer + offset + 1) = (u_p.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 46 *(outbuffer + offset + 2) = (u_p.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 47 *(outbuffer + offset + 3) = (u_p.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 48 *(outbuffer + offset + 4) = (u_p.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 49 *(outbuffer + offset + 5) = (u_p.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 50 *(outbuffer + offset + 6) = (u_p.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 51 *(outbuffer + offset + 7) = (u_p.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 52 offset += sizeof(this->p);
Gary Servin 0:04ac6be8229a 53 union {
Gary Servin 0:04ac6be8229a 54 double real;
Gary Servin 0:04ac6be8229a 55 uint64_t base;
Gary Servin 0:04ac6be8229a 56 } u_i;
Gary Servin 0:04ac6be8229a 57 u_i.real = this->i;
Gary Servin 0:04ac6be8229a 58 *(outbuffer + offset + 0) = (u_i.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 59 *(outbuffer + offset + 1) = (u_i.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 60 *(outbuffer + offset + 2) = (u_i.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 61 *(outbuffer + offset + 3) = (u_i.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 62 *(outbuffer + offset + 4) = (u_i.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 63 *(outbuffer + offset + 5) = (u_i.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 64 *(outbuffer + offset + 6) = (u_i.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 65 *(outbuffer + offset + 7) = (u_i.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 66 offset += sizeof(this->i);
Gary Servin 0:04ac6be8229a 67 union {
Gary Servin 0:04ac6be8229a 68 double real;
Gary Servin 0:04ac6be8229a 69 uint64_t base;
Gary Servin 0:04ac6be8229a 70 } u_d;
Gary Servin 0:04ac6be8229a 71 u_d.real = this->d;
Gary Servin 0:04ac6be8229a 72 *(outbuffer + offset + 0) = (u_d.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 73 *(outbuffer + offset + 1) = (u_d.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 74 *(outbuffer + offset + 2) = (u_d.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 75 *(outbuffer + offset + 3) = (u_d.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 76 *(outbuffer + offset + 4) = (u_d.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 77 *(outbuffer + offset + 5) = (u_d.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 78 *(outbuffer + offset + 6) = (u_d.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 79 *(outbuffer + offset + 7) = (u_d.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 80 offset += sizeof(this->d);
Gary Servin 0:04ac6be8229a 81 union {
Gary Servin 0:04ac6be8229a 82 double real;
Gary Servin 0:04ac6be8229a 83 uint64_t base;
Gary Servin 0:04ac6be8229a 84 } u_i_clamp;
Gary Servin 0:04ac6be8229a 85 u_i_clamp.real = this->i_clamp;
Gary Servin 0:04ac6be8229a 86 *(outbuffer + offset + 0) = (u_i_clamp.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 87 *(outbuffer + offset + 1) = (u_i_clamp.base >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 88 *(outbuffer + offset + 2) = (u_i_clamp.base >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 89 *(outbuffer + offset + 3) = (u_i_clamp.base >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 90 *(outbuffer + offset + 4) = (u_i_clamp.base >> (8 * 4)) & 0xFF;
Gary Servin 0:04ac6be8229a 91 *(outbuffer + offset + 5) = (u_i_clamp.base >> (8 * 5)) & 0xFF;
Gary Servin 0:04ac6be8229a 92 *(outbuffer + offset + 6) = (u_i_clamp.base >> (8 * 6)) & 0xFF;
Gary Servin 0:04ac6be8229a 93 *(outbuffer + offset + 7) = (u_i_clamp.base >> (8 * 7)) & 0xFF;
Gary Servin 0:04ac6be8229a 94 offset += sizeof(this->i_clamp);
Gary Servin 0:04ac6be8229a 95 union {
Gary Servin 0:04ac6be8229a 96 bool real;
Gary Servin 0:04ac6be8229a 97 uint8_t base;
Gary Servin 0:04ac6be8229a 98 } u_antiwindup;
Gary Servin 0:04ac6be8229a 99 u_antiwindup.real = this->antiwindup;
Gary Servin 0:04ac6be8229a 100 *(outbuffer + offset + 0) = (u_antiwindup.base >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 101 offset += sizeof(this->antiwindup);
Gary Servin 0:04ac6be8229a 102 return offset;
Gary Servin 0:04ac6be8229a 103 }
Gary Servin 0:04ac6be8229a 104
Gary Servin 0:04ac6be8229a 105 virtual int deserialize(unsigned char *inbuffer)
Gary Servin 0:04ac6be8229a 106 {
Gary Servin 0:04ac6be8229a 107 int offset = 0;
Gary Servin 0:04ac6be8229a 108 union {
Gary Servin 0:04ac6be8229a 109 double real;
Gary Servin 0:04ac6be8229a 110 uint64_t base;
Gary Servin 0:04ac6be8229a 111 } u_p;
Gary Servin 0:04ac6be8229a 112 u_p.base = 0;
Gary Servin 0:04ac6be8229a 113 u_p.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 114 u_p.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 115 u_p.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 116 u_p.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 117 u_p.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 118 u_p.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 119 u_p.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 120 u_p.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 121 this->p = u_p.real;
Gary Servin 0:04ac6be8229a 122 offset += sizeof(this->p);
Gary Servin 0:04ac6be8229a 123 union {
Gary Servin 0:04ac6be8229a 124 double real;
Gary Servin 0:04ac6be8229a 125 uint64_t base;
Gary Servin 0:04ac6be8229a 126 } u_i;
Gary Servin 0:04ac6be8229a 127 u_i.base = 0;
Gary Servin 0:04ac6be8229a 128 u_i.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 129 u_i.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 130 u_i.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 131 u_i.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 132 u_i.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 133 u_i.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 134 u_i.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 135 u_i.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 136 this->i = u_i.real;
Gary Servin 0:04ac6be8229a 137 offset += sizeof(this->i);
Gary Servin 0:04ac6be8229a 138 union {
Gary Servin 0:04ac6be8229a 139 double real;
Gary Servin 0:04ac6be8229a 140 uint64_t base;
Gary Servin 0:04ac6be8229a 141 } u_d;
Gary Servin 0:04ac6be8229a 142 u_d.base = 0;
Gary Servin 0:04ac6be8229a 143 u_d.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 144 u_d.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 145 u_d.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 146 u_d.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 147 u_d.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 148 u_d.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 149 u_d.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 150 u_d.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 151 this->d = u_d.real;
Gary Servin 0:04ac6be8229a 152 offset += sizeof(this->d);
Gary Servin 0:04ac6be8229a 153 union {
Gary Servin 0:04ac6be8229a 154 double real;
Gary Servin 0:04ac6be8229a 155 uint64_t base;
Gary Servin 0:04ac6be8229a 156 } u_i_clamp;
Gary Servin 0:04ac6be8229a 157 u_i_clamp.base = 0;
Gary Servin 0:04ac6be8229a 158 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 159 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 160 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 161 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 162 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
Gary Servin 0:04ac6be8229a 163 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
Gary Servin 0:04ac6be8229a 164 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
Gary Servin 0:04ac6be8229a 165 u_i_clamp.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
Gary Servin 0:04ac6be8229a 166 this->i_clamp = u_i_clamp.real;
Gary Servin 0:04ac6be8229a 167 offset += sizeof(this->i_clamp);
Gary Servin 0:04ac6be8229a 168 union {
Gary Servin 0:04ac6be8229a 169 bool real;
Gary Servin 0:04ac6be8229a 170 uint8_t base;
Gary Servin 0:04ac6be8229a 171 } u_antiwindup;
Gary Servin 0:04ac6be8229a 172 u_antiwindup.base = 0;
Gary Servin 0:04ac6be8229a 173 u_antiwindup.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
Gary Servin 0:04ac6be8229a 174 this->antiwindup = u_antiwindup.real;
Gary Servin 0:04ac6be8229a 175 offset += sizeof(this->antiwindup);
Gary Servin 0:04ac6be8229a 176 return offset;
Gary Servin 0:04ac6be8229a 177 }
Gary Servin 0:04ac6be8229a 178
Gary Servin 0:04ac6be8229a 179 const char * getType(){ return SETPIDGAINS; };
Gary Servin 0:04ac6be8229a 180 const char * getMD5(){ return "4a43159879643e60937bf2893b633607"; };
Gary Servin 0:04ac6be8229a 181
Gary Servin 0:04ac6be8229a 182 };
Gary Servin 0:04ac6be8229a 183
Gary Servin 0:04ac6be8229a 184 class SetPidGainsResponse : public ros::Msg
Gary Servin 0:04ac6be8229a 185 {
Gary Servin 0:04ac6be8229a 186 public:
Gary Servin 0:04ac6be8229a 187
Gary Servin 0:04ac6be8229a 188 SetPidGainsResponse()
Gary Servin 0:04ac6be8229a 189 {
Gary Servin 0:04ac6be8229a 190 }
Gary Servin 0:04ac6be8229a 191
Gary Servin 0:04ac6be8229a 192 virtual int serialize(unsigned char *outbuffer) const
Gary Servin 0:04ac6be8229a 193 {
Gary Servin 0:04ac6be8229a 194 int offset = 0;
Gary Servin 0:04ac6be8229a 195 return offset;
Gary Servin 0:04ac6be8229a 196 }
Gary Servin 0:04ac6be8229a 197
Gary Servin 0:04ac6be8229a 198 virtual int deserialize(unsigned char *inbuffer)
Gary Servin 0:04ac6be8229a 199 {
Gary Servin 0:04ac6be8229a 200 int offset = 0;
Gary Servin 0:04ac6be8229a 201 return offset;
Gary Servin 0:04ac6be8229a 202 }
Gary Servin 0:04ac6be8229a 203
Gary Servin 0:04ac6be8229a 204 const char * getType(){ return SETPIDGAINS; };
Gary Servin 0:04ac6be8229a 205 const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
Gary Servin 0:04ac6be8229a 206
Gary Servin 0:04ac6be8229a 207 };
Gary Servin 0:04ac6be8229a 208
Gary Servin 0:04ac6be8229a 209 class SetPidGains {
Gary Servin 0:04ac6be8229a 210 public:
Gary Servin 0:04ac6be8229a 211 typedef SetPidGainsRequest Request;
Gary Servin 0:04ac6be8229a 212 typedef SetPidGainsResponse Response;
Gary Servin 0:04ac6be8229a 213 };
Gary Servin 0:04ac6be8229a 214
Gary Servin 0:04ac6be8229a 215 }
Gary Servin 0:04ac6be8229a 216 #endif