CRINSA-team2025 V1
Documentation du Club Robot INSA Rennes 2025
Chargement...
Recherche...
Aucune correspondance
wb_const.h
1#ifndef __WB_CONST_H__
2#define __WB_CONST_H__
3
4#include <Wheeledbase.h>
5
6//Really traveled distance > thought traveled distance -> decrease codewheels radius
7//Really rotated angle > thought rotated angle -> increase axle track
8//Turn right when thinking moving forward -> increase left codewheel radius
9//Turn left when thinking moving forward -> increase right codewheel radius
10
11
12inline WBConstants wb_consts = {
13 .LEFTWHEEL_RADIUS = 23.8125,
14 .LEFTWHEEL_CONSTANT = 0.209380534*2,
15 .LEFTWHEEL_MAXPWM = 1.0,
16 .RIGHTWHEEL_RADIUS = 23.8125,
17 .RIGHTWHEEL_CONSTANT = 0.209380534*2,
18 .RIGHTWHEEL_MAXPWM = 1.0,
19 .LEFTCODEWHEEL_COUNTSPERREV = 5000,
20 .RIGHTCODEWHEEL_COUNTSPERREV = 5000,
21 .LEFTCODEWHEEL_RADIUS = 22.734851011,
22 .RIGHTCODEWHEEL_RADIUS = 22.734851011,
23
24 .ODOMETRY_AXLETRACK = 207.5496406,
25 .ODOMETRY_SLIPPAGE = 0,
26
27 .VELOCITYCONTROL_AXLETRACK = 125.0,//201.5
28 .VELOCITYCONTROL_MAXLINACC = 300,
29 .VELOCITYCONTROL_MAXLINDEC = 125,
30 .VELOCITYCONTROL_MAXANGACC = PI/2,
31 .VELOCITYCONTROL_MAXANGDEC = PI/2,
32 .VELOCITYCONTROL_SPINSHUTDOWN = false,
33
34 /*---- LINEAR VELOCITIES PID ----*/
35
36 .LINVELPID_KP = 1.4,
37 .LINVELPID_KI = 2.2,
38 .LINVELPID_KD = 0.01,
39
40 /*
41 .LINVELPID_KP = 1.4,
42 .LINVELPID_KI = 3.2,
43 .LINVELPID_KD = 0,*/
44
45 .LINVELPID_MINOUTPUT = -350,
46 .LINVELPID_MAXOUTPUT = 350,
47
48 /*---- ANGULAR VELOCITIES PID ----*/
49 .ANGVELPID_KP = 3, //.5 3 0.8,
50 .ANGVELPID_KI = 3,//.1 1.5 0.5,
51 .ANGVELPID_KD = 0,
52
53 .ANGVELPID_MINOUTPUT = -2*PI/3,
54 .ANGVELPID_MAXOUTPUT = 2*PI/3,
55
56 /*---- POSITION PID ----*/
57 .POSITIONCONTROL_LINVELKP = 1,
58 .POSITIONCONTROL_ANGVELKP = 1,
59
60 .POSITIONCONTROL_LINVELMAX = 350,
61 .POSITIONCONTROL_ANGVELMAX = PI/2,
62 .POSITIONCONTROL_LINPOSTHRESHOLD = 1,
63 .POSITIONCONTROL_ANGPOSTHRESHOLD = 0.008,
64 .PUREPURSUIT_LOOKAHEAD = 30.0,
65 .PUREPURSUIT_LOOKAHEADBIS = 40.0,
66
67 // Timesteps
68 .ODOMETRY_TIMESTEP = 20e-3,
69 .PID_CONTROLLERS_TIMESTEP = 20e-3,
70 .POSITIONCONTROL_TIMESTEP = 20e-3,
71
72 // DC motors driver
73 .LEFT_MOTOR_EN = PD1,
74 .LEFT_MOTOR_PWM = PC6,
75 .LEFT_MOTOR_DIR = PD3,
76 .RIGHT_MOTOR_EN = PD0,
77 .RIGHT_MOTOR_PWM = PC7,
78 .RIGHT_MOTOR_DIR = PD2,
79 .DRIVER_RESET = PC11,
80 .DRIVER_FAULT = PC12,
81};
82
83#endif // __WB_CONST_H__
Definition Wheeledbase.h:68