forked from sekomer/ROS-CAN
-
Notifications
You must be signed in to change notification settings - Fork 0
/
static.ino
497 lines (398 loc) · 12.2 KB
/
static.ino
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
/*
@year: 2020/2021
@author: Sekomer
@touch: [email protected]
*/
/* Essential Header Files */
#include <ros.h>
#include <CAN.h>
#include <string.h>
#include <rosserial_arduino/Adc.h>
/* Preprocessing */
#define RADIUS 0.28
#define BUFFER_SIZE 32
#define MAX_RPM 3500
#define MAX_REVERSE_RPM -2000
/* GEARS */
#define NEUTRAL 0
#define FORWARD 1
#define REVERSE 2
/* CAN IDS */
#define BRAKE_ID 0x705
#define STEER_ID 0x700
#define MOTOR_ID 0x501
#define MOTOR_ODOM_ID 0x403
#define BATTERY_INFO_ID 0x402
#define RPM_MODE 1
#define CURRENT_MODE 0
/**
* DATA TYPES FOR CAN COMMUNICATION
*/
typedef union {
float data;
uint8_t data_u8[4];
} CAN_Float;
typedef union {
float data[2];
uint8_t data_u8[8];
} CAN_odom;
typedef union {
uint16_t data_u16[2];
uint8_t data_u8[4];
} STEER;
typedef union {
uint16_t data;
struct {
unsigned int direction : 1;
unsigned int brake_motor_speed : 5;
unsigned int regen : 10;
} bits;
} REGEN_BRAKE;
/* Function Declerations */
int32_t buffer_avg(int32_t *buffer, int32_t size);
float radian2degree(float input);
int32_t kmh2rpm (float vel);
void sekomerizasyon(CAN_Float &);
/* CAN variable decleartions */
static CAN_odom speed_odom;
static CAN_odom battery_odom;
static CAN_Float rpm;
static CAN_Float current;
// for braking //
static STEER recep_tayyip_ercetin;
/* speed, steering and condition info */
static STEER steering_obj;
static int32_t raw_steer;
static float regen = 0;
int current_position = 0;
/* Encoder Variables */
static int32_t desired_pos;
static int32_t pot_odom;
static int32_t pot_sum;
bool turning_right = false;
bool turning_left = false;
/* Constant Steering Motor Speeds */
static int32_t const max_steer_speed = 10; // change STM side
static int32_t const min_steer_speed = 6;
static int32_t const high_steer_speed = 4; // @deprecated
/* */
static volatile int32_t GEAR = NEUTRAL;
static volatile int32_t steer_speed; // speed variable CAN
static volatile int32_t change_value = 0; // momentary change in steering angle
static volatile int32_t AUTONOMOUS = 0;
static volatile int32_t EXTRA;
static int32_t is_braking;
static int32_t brake_speed = 8;
REGEN_BRAKE regen_brake_packet;
/* Encoder Buffer Variables */
static int32_t buffer_index = 0;
static int32_t buffer[BUFFER_SIZE];
static int32_t buffer_average = 0;
static const int32_t EncoderPin = A0;
static int32_t index = 0;
/**/
/* Debug and Log */
static rosserial_arduino::Adc pot_data;
//////////////////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////////////////
/*
* ROS CALLBACK
*/
static int32_t __steer;
bool _debug = 0;
void RosCallback(const rosserial_arduino::Adc &mahmut){
/*
* @param mahmut : Adc => Data sent from ROS to CANBUS
*
* * mahmut.adc0 : uint16 => Speed Data
* * mahmut.adc1 : uint16 => Angle Data
* * mahmut.adc2 : uint16 => Regen Data
* * mahmut.adc3 : uint16 => GEAR Data
* * mahmut.adc4 : uint16 => Auto Data
* * mahmut.adc5 : uint16 => Mode Data
*/
raw_steer = mahmut.adc1;
regen = mahmut.adc2 % 10000;
GEAR = mahmut.adc3;
AUTONOMOUS = mahmut.adc4;
EXTRA = mahmut.adc5;
/******************** Speed Logic ******************/
if (mahmut.adc5 == RPM_MODE) {
switch(GEAR) {
case FORWARD:
//rpm.data = map((long) mahmut.adc0, 0, 1000, 0, MAX_RPM);
rpm.data = mahmut.adc0;
current.data = 1;
break;
case REVERSE:
//rpm.data = map((long) mahmut.adc0, 0, 1000, 0, MAX_REVERSE_RPM);
rpm.data = (-1) * float(mahmut.adc0);
current.data = 0.8;
break;
case NEUTRAL:
rpm.data = 0;
current.data = 0;
break;
}
}
// current mode
else if (mahmut.adc5 == CURRENT_MODE) {
switch(GEAR) {
case FORWARD:
current.data = float(mahmut.adc0) / 1000.0;
rpm.data = 20000;
break;
case REVERSE:
rpm.data = -20000;
current.data = float(mahmut.adc0) / 1000.0;
break;
case NEUTRAL:
current.data = 0;
rpm.data = 0;
break;
}
}
else {
rpm.data = 0;
current.data = 0;
}
if (rpm.data == 0)
current.data = 0.0;
if (regen) {
rpm.data = 0; /* security */
current.data = regen / 1000;
}
/* BRAKING */
/******************************************/
is_braking = int32_t(mahmut.adc2) / 10000;
recep_tayyip_ercetin.data_u16[0] = brake_speed;
recep_tayyip_ercetin.data_u8[2] = ! is_braking;
/***************************************************/
sekomerizasyon(current);
/******************** Steering Logic ******************/
/*
to send data from terminal or to read data from ROS
desired_pos = mahmut.adc1
to read data from pot add a potansiometer to A1 pin
desired_pos = direksiyon_pot (A1)
*/
/* TAM TERSİYSE */
desired_pos = mahmut.adc1;
change_value = (desired_pos - current_position); // get change value
/* Speed Control */
/*
if (abs(change_value) < 75)
steer_speed = low_steer_speed;
else if (change_value < 350 && change_value > -350)
steer_speed = high_steer_speed;
else
steer_speed = max_steer_speed;
*/
__steer = abs(change_value);
if (__steer > 1800)
__steer = 1800;
steer_speed = map(__steer, 0, 1800, min_steer_speed, max_steer_speed);
/*
@steering_obj.data_u16[0] => steering speed
@steering_obj.data_u8[2] => steering
*/
if (change_value > 0) {
steering_obj.data_u16[0] = steer_speed;
steering_obj.data_u8[2] = 1; // left steer direction
_debug = 1;
}
else if (change_value < 0) {
steering_obj.data_u16[0] = steer_speed;
steering_obj.data_u8[2] = 0; // right steer direction
_debug = 0;
}
else
steering_obj.data_u16[0] = 0;
/*
* Driving Motor Packet
*/
/* rpm */
CAN.beginPacket(MOTOR_ID);
CAN.write(rpm.data_u8[0]);
CAN.write(rpm.data_u8[1]);
CAN.write(rpm.data_u8[2]);
CAN.write(rpm.data_u8[3]);
/* current */
CAN.write(current.data_u8[0]);
CAN.write(current.data_u8[1]);
CAN.write(current.data_u8[2]);
CAN.write(current.data_u8[3]);
CAN.endPacket();
/*
* Steering Motor Packet
*/
CAN.beginPacket(STEER_ID);
CAN.write(steering_obj.data_u8[0]);
CAN.write(steering_obj.data_u8[1]);
CAN.write(steering_obj.data_u8[2]);
CAN.endPacket();
/* Braking Packet */
CAN.beginPacket(BRAKE_ID);
CAN.write(recep_tayyip_ercetin.data_u8[0]);
CAN.write(recep_tayyip_ercetin.data_u8[1]);
CAN.write(recep_tayyip_ercetin.data_u8[2]);
CAN.endPacket();
}
/*
* IT DOESN'T WORK WITH A QUEUE VALUE
* @future_debug
*/
/******************** Creating ROS Node ******************/
static ros::NodeHandle nh;
static ros::Subscriber<rosserial_arduino::Adc> sub("/seko", &RosCallback);
static ros::Publisher pub("pot_topic", &pot_data);
/////////////////////////////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////////////////////////////
void sekomerizasyon(CAN_Float ¤t)
{
if (current.data > 1.0)
current.data = 1.0;
else if (current.data < 0.0)
current.data = 0.0;
}
/*
* Function to convert kmh to rpm
*/
int32_t kmh2rpm (float vel)
{
float RPM = 0;
RPM = 2.65 * vel / RADIUS;
return RPM;
}
/*
* @deprecated
* Function for calculating buffer average
*/
int32_t buffer_avg(int32_t *buffer, int32_t size)
{
int32_t sum = 0;
for (size_t i = 0; i < size; ++i)
sum += buffer[i];
return sum / size;
}
/*
* Function for converting radians to degree
*/
float radian2degree(float input)
{
float degree = input * 180 / PI;
return degree;
}
/////////////////////////////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////////////////////////////
// //
// SETUP AND LOOP //
// //
/////////////////////////////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////////////////////////////
/*
* Arduino Setup
*
* rosrun rosserial_arduino serial_node.py _port:=/dev/ttyXXXn _baud:=115200
*/
void setup(){
pinMode(A1, INPUT);
memset(buffer, 0, BUFFER_SIZE * sizeof(int));
Serial.begin(57600);
/****************** ROS Initialization ******************/
nh.getHardware()->setBaud(57600);
nh.initNode();
nh.subscribe(sub);
nh.advertise(pub);
/* security */
rpm.data = 0;
current.data = 0;
steering_obj.data_u16[0] = 0;
CAN_INIT:
if(CAN.begin(1E6)) {
;/* maybe wait */;
}
else {
goto CAN_INIT;
}
/* safety */
/* rpm */
CAN.beginPacket(MOTOR_ID);
CAN.write(rpm.data_u8[0]);
CAN.write(rpm.data_u8[1]);
CAN.write(rpm.data_u8[2]);
CAN.write(rpm.data_u8[3]);
/* current */
CAN.write(current.data_u8[0]);
CAN.write(current.data_u8[1]);
CAN.write(current.data_u8[2]);
CAN.write(current.data_u8[3]);
CAN.endPacket();
/* Steering Motor Packet */
CAN.beginPacket(STEER_ID);
CAN.write(steering_obj.data_u8[0]);
CAN.write(steering_obj.data_u8[1]);
CAN.write(steering_obj.data_u8[2]);
CAN.endPacket();
}
/////////////////////////////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////////////////////////////
/*
* Arduino Loop
*
* rosrun rosserial_arduino serial_node.py _port:=/dev/ttyXXXn _baud:=57600
*/
void loop(){
/************ CAN Packet Read ************/
if (CAN.parsePacket()) {
if (CAN.packetId() == MOTOR_ODOM_ID) {
while (CAN.available())
speed_odom.data_u8[index++] = CAN.read();
}
else if (CAN.packetId() == BATTERY_INFO_ID)
while (CAN.available())
battery_odom.data_u8[index++] = CAN.read();
index ^= index;
}
/****************** Encoder Signal ******************/
/*
* Elder Version, Unnecessary sums
*/
/*
int pot_signal_raw = analogRead(EncoderPin);
int encoder_degree = map(pot_signal_raw, 0, 1023, 0, 3600);
buffer[buffer_index++] = encoder_degree;
buffer_average = buffer_avg(buffer, BUFFER_SIZE);
buffer_index = (buffer_index > BUFFER_SIZE ? 0 : buffer_index);
*/
pot_sum -= buffer[buffer_index];
int32_t analog_read = analogRead(EncoderPin);
buffer[buffer_index] = map(analog_read, 0, 1023, 0, 3600);
pot_sum += buffer[buffer_index];
buffer_index++;
buffer_index = (buffer_index >= BUFFER_SIZE ? 0 : buffer_index);
buffer_average = pot_sum / BUFFER_SIZE;
pot_odom = buffer_average;
/* DRIVING MODE */
if (! AUTONOMOUS)
buffer_average = 1800;
current_position = buffer_average;
/******************** Debug Topic ******************/
/* rpm */
pot_data.adc0 = pot_odom;
/* steer */
pot_data.adc1 = battery_odom.data[1];
/* bus voltage / bus current */
pot_data.adc2 = battery_odom.data[0];
pot_data.adc3 = is_braking;
/* unused */
pot_data.adc4 = speed_odom.data[0];
pot_data.adc5 = speed_odom.data[1];
pub.publish(&pot_data);
nh.spinOnce();
}
//////
/*
End of File
*/
//////