-
Notifications
You must be signed in to change notification settings - Fork 1
/
motor.c
228 lines (192 loc) · 5.3 KB
/
motor.c
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
/*********************************************************************
*
* File :
* motor.c
*
* Date :
* 11/05/2014
*
* Contributors :
* TSAO, CHIA-CHENG <[email protected]> , From NTUT
*
*********************************************************************/
#include <wiringPi.h>
#include <stdio.h>
#include <stdlib.h>
#include <stdint.h>
#include <errno.h>
#include <softPwm.h>
#include "motor.h"
#define L298N_ENA 0
#define L298N_ENB 2
#define L298N_IN1 1
#define L298N_IN2 4
#define L298N_IN3 5
#define L298N_IN4 6
int l298n_test (void)
{
int ena = L298N_ENA;
int enb = L298N_ENB;
int in1 = L298N_IN1;
int in2 = L298N_IN2;
int in3 = L298N_IN3;
int in4 = L298N_IN4;
if (wiringPiSetup() == -1)
exit (1);
printf ("Raspberry Pi SoftwarePWM HBridge Test\n");
softPwmCreate (ena, 0,255);
softPwmCreate (enb, 0,255);
pinMode (in1, OUTPUT);
pinMode (in2, OUTPUT);
pinMode (in3, OUTPUT);
pinMode (in4, OUTPUT);
for (;;)
{
printf ("Forward\n");
digitalWrite (in1, 1);
digitalWrite (in2, 0);
softPwmWrite (ena, 250);
digitalWrite (in3, 1);
digitalWrite (in4, 0);
softPwmWrite (enb, 250);
delay (1000);
printf ("Stop\n");
digitalWrite (in1, 1);
digitalWrite (in2, 0);
softPwmWrite (ena, 0);
digitalWrite (in3, 1);
digitalWrite (in4, 0);
softPwmWrite (enb, 0);
delay (250);
printf ("Reverse\n");
digitalWrite (in1, 0);
digitalWrite (in2, 1);
softPwmWrite (ena, 250);
digitalWrite (in3, 0);
digitalWrite (in4, 1);
softPwmWrite (enb, 250);
delay (1000);
printf ("Stop\n");
digitalWrite (in1, 1);
digitalWrite (in2, 0);
softPwmWrite (ena, 0);
digitalWrite (in3, 1);
digitalWrite (in4, 0);
softPwmWrite (enb, 0);
delay (250);
printf ("Right\n");
digitalWrite (in1, 0);
digitalWrite (in2, 1);
softPwmWrite (ena, 250);
digitalWrite (in3, 1);
digitalWrite (in4, 0);
softPwmWrite (enb, 250);
delay (1000);
printf ("Stop\n");
digitalWrite (in1, 1);
digitalWrite (in2, 0);
softPwmWrite (ena, 0);
digitalWrite (in3, 1);
digitalWrite (in4, 0);
softPwmWrite (enb, 0);
delay (250);
printf ("Left\n");
digitalWrite (in1, 1);
digitalWrite (in2, 0);
softPwmWrite (ena, 250);
digitalWrite (in3, 0);
digitalWrite (in4, 1);
softPwmWrite (enb, 250);
delay (1000);
printf ("Stop\n");
digitalWrite (in1, 1);
digitalWrite (in2, 0);
softPwmWrite (ena, 0);
digitalWrite (in3, 1);
digitalWrite (in4, 0);
softPwmWrite (enb, 0);
delay (1250);
}
return 0;
}
typedef struct _motor
{
int ena;
int enb;
int in1;
int in2;
int in3;
int in4;
}motor_t;
void motor_initialize(void)
{
//setreuid(geteuid(), getuid());
//seteuid(0);
if (wiringPiSetup() == -1)
exit (1);
softPwmCreate (L298N_ENA, 0,255);
softPwmCreate (L298N_ENB, 0,255);
pinMode (L298N_IN1, OUTPUT);
pinMode (L298N_IN2, OUTPUT);
pinMode (L298N_IN3, OUTPUT);
pinMode (L298N_IN4, OUTPUT);
}
void motor_update(m_ctrl_t mode, int pwm1, int pwm2)
{
pwm1 = abs(pwm1);
pwm2 = abs(pwm2);
switch(mode)
{
case M_FWD :
digitalWrite (L298N_IN1, 1);
digitalWrite (L298N_IN2, 0);
softPwmWrite (L298N_ENA, pwm1);
digitalWrite (L298N_IN3, 1);
digitalWrite (L298N_IN4, 0);
softPwmWrite (L298N_ENB, pwm2);
break;
case M_BWD :
digitalWrite (L298N_IN1, 0);
digitalWrite (L298N_IN2, 1);
softPwmWrite (L298N_ENA, pwm1);
digitalWrite (L298N_IN3, 0);
digitalWrite (L298N_IN4, 1);
softPwmWrite (L298N_ENB, pwm2);
break;
case M_TNL :
digitalWrite (L298N_IN1, 1);
digitalWrite (L298N_IN2, 0);
softPwmWrite (L298N_ENA, pwm1);
digitalWrite (L298N_IN3, 0);
digitalWrite (L298N_IN4, 1);
softPwmWrite (L298N_ENB, pwm2);
break;
case M_TNR :
digitalWrite (L298N_IN1, 0);
digitalWrite (L298N_IN2, 1);
softPwmWrite (L298N_ENA, pwm1);
digitalWrite (L298N_IN3, 1);
digitalWrite (L298N_IN4, 0);
softPwmWrite (L298N_ENB, pwm2);
break;
case M_BRK :
#if 0 /* Motor Off */
digitalWrite (L298N_IN1, 1);
digitalWrite (L298N_IN2, 0);
softPwmWrite (L298N_ENA, 0);
digitalWrite (L298N_IN3, 1);
digitalWrite (L298N_IN4, 0);
softPwmWrite (L298N_ENB, 0);
#else /* Motor Break */
digitalWrite (L298N_IN1, 1);
digitalWrite (L298N_IN2, 1);
softPwmWrite (L298N_ENA, 1);
digitalWrite (L298N_IN3, 1);
digitalWrite (L298N_IN4, 1);
softPwmWrite (L298N_ENB, 1);
#endif
break;
default :
break;
}
}