Main Page
Namespaces
Namespace List
Namespace Members
All
Variables
Classes
Class List
Class Hierarchy
Class Members
All
_
a
b
c
d
e
f
g
h
i
j
k
l
m
n
o
p
r
s
t
u
v
w
~
Functions
a
b
c
d
e
g
i
j
l
m
n
o
p
r
s
t
u
w
~
Variables
a
c
d
e
f
g
h
i
j
k
l
m
n
o
p
s
t
u
v
w
Typedefs
Files
File List
File Members
All
a
b
c
e
k
l
m
n
p
r
s
t
u
Functions
Variables
Typedefs
Macros
scripts
base_controller
test
adafruit_motorshieldv2
test_adafruit_motorshieldv2.cpp
Go to the documentation of this file.
1
/*
2
* Test for Adafruit motor shield v2 library
3
* This can be used to test the Adafruit Stepper + DC Motor FeatherWing
4
* https://learn.adafruit.com/adafruit-stepper-dc-motor-featherwing
5
*
6
* Test base on the following example
7
* https://github.com/adafruit/Adafruit_Motor_Shield_V2_Library/blob/master/examples/DCMotorTest/DCMotorTest.ino
8
*
9
* Author: Franz Pucher
10
*
11
*/
12
13
// Include unity library
14
// For details see https://docs.platformio.org/en/latest/plus/unit-testing.html#api
15
#include <unity.h>
16
17
// The special bit of code in this example is the use of Arduino's Wire library.
18
// Wire is a I2C library that simplifies reading and writing to the I2C bus.
19
#include <Wire.h>
20
#include <Adafruit_MotorShield.h>
21
22
#include "
diffbot_base_config.h
"
23
24
25
// Create the motor shield object with the default I2C address
26
Adafruit_MotorShield
AFMS
= Adafruit_MotorShield(
MOTOR_DRIVER_ADDR
);
27
// Or, create it with a different I2C address (say for stacking)
28
// Adafruit_MotorShield AFMS = Adafruit_MotorShield(0x61);
29
30
// Select which 'port' M1, M2, M3 or M4. In this case, M1
31
Adafruit_DCMotor *
rightMotor
=
AFMS
.getMotor(
MOTOR_RIGHT
);
32
// You can also make another motor on port M2
33
Adafruit_DCMotor *
leftMotor
=
AFMS
.getMotor(
MOTOR_LEFT
);
34
35
36
void
motorSweep
(Adafruit_DCMotor *motor)
37
{
38
uint8_t i;
39
motor->run(FORWARD);
40
for
(i=0; i<255; i++) {
41
motor->setSpeed(i);
42
delay(10);
43
}
44
for
(i=255; i!=0; i--) {
45
motor->setSpeed(i);
46
delay(10);
47
}
48
49
Serial.print(
"tock"
);
50
51
motor->run(BACKWARD);
52
for
(i=0; i<255; i++) {
53
motor->setSpeed(i);
54
delay(10);
55
}
56
for
(i=255; i!=0; i--) {
57
motor->setSpeed(i);
58
delay(10);
59
}
60
61
Serial.print(
"tech"
);
62
motor->run(RELEASE);
63
delay(1000);
64
}
65
66
void
setup
() {
67
// NOTE!!! Wait for >2 secs
68
// if board doesn't support software reset via Serial.DTR/RTS
69
delay(2000);
70
UNITY_BEGIN();
71
72
Serial.begin(9600);
// set up Serial library at 9600 bps
73
Serial.println(
"Adafruit Motorshield v2 - DC Motor test!"
);
74
75
AFMS
.begin();
// create with the default frequency 1.6KHz
76
//AFMS.begin(1000); // OR with a different frequency, say 1KHz
77
78
79
// Set the speed to start, from 0 (off) to 255 (max speed)
80
Serial.println(
"setSpeed(150)"
);
81
leftMotor
->setSpeed(150);
82
leftMotor
->run(FORWARD);
83
// turn on motor
84
leftMotor
->run(RELEASE);
85
86
// Set the speed to start, from 0 (off) to 255 (max speed)
87
rightMotor
->setSpeed(150);
88
rightMotor
->run(FORWARD);
89
// turn on motor
90
rightMotor
->run(RELEASE);
91
}
92
93
uint8_t
cycle
= 0;
94
uint8_t
max_loop_cycles
= 1;
95
96
void
loop
() {
97
98
if
(
cycle
<
max_loop_cycles
)
99
{
100
Serial.print(
"tick"
);
101
102
motorSweep
(
leftMotor
);
103
motorSweep
(
rightMotor
);
104
}
105
else
106
{
107
leftMotor
->setSpeed(0);
108
leftMotor
->run(RELEASE);
109
rightMotor
->setSpeed(0);
110
rightMotor
->run(RELEASE);
111
delay(1000);
112
UNITY_END();
113
}
114
115
cycle
++;
116
}
diffbot_base_config.h
cycle
uint8_t cycle
Definition:
test_adafruit_motorshieldv2.cpp:93
MOTOR_RIGHT
#define MOTOR_RIGHT
Definition:
diffbot_base_config.h:16
rightMotor
Adafruit_DCMotor * rightMotor
Definition:
test_adafruit_motorshieldv2.cpp:31
MOTOR_DRIVER_ADDR
#define MOTOR_DRIVER_ADDR
Motor i2c address.
Definition:
diffbot_base_config.h:14
AFMS
Adafruit_MotorShield AFMS
Definition:
test_adafruit_motorshieldv2.cpp:26
setup
void setup()
Definition:
test_adafruit_motorshieldv2.cpp:66
leftMotor
Adafruit_DCMotor * leftMotor
Definition:
test_adafruit_motorshieldv2.cpp:33
MOTOR_LEFT
#define MOTOR_LEFT
Definition:
diffbot_base_config.h:15
motorSweep
void motorSweep(Adafruit_DCMotor *motor)
Definition:
test_adafruit_motorshieldv2.cpp:36
max_loop_cycles
uint8_t max_loop_cycles
Definition:
test_adafruit_motorshieldv2.cpp:94
loop
void loop()
Definition:
test_adafruit_motorshieldv2.cpp:96
diffbot_base
Author(s):
autogenerated on Thu Sep 7 2023 02:35:23