test_adafruit_motor_controller.cpp
Go to the documentation of this file.
1 /*
2  * Author: Franz Pucher
3  */
4 
5 // Include unity library
6 // For details see https://docs.platformio.org/en/latest/plus/unit-testing.html#api
7 #include <unity.h>
8 
10 
11 using namespace diffbot;
12 
15 
16 
18 {
19  int i;
20  for (i=0; i<255; i++) {
21  i_pMotorController->setSpeed(i);
22  delay(10);
23  }
24  for (i=255; i!=0; i--) {
25  i_pMotorController->setSpeed(i);
26  delay(10);
27  }
28 
29  Serial.print("tock");
30 
31  for (i=0; i > -255; i--) {
32  i_pMotorController->setSpeed(i);
33  delay(10);
34  }
35  for (i=-255; i!=0; i++) {
36  i_pMotorController->setSpeed(i);
37  delay(10);
38  }
39 
40  Serial.print("tech");
41  i_pMotorController->setSpeed(0);
42  delay(1000);
43 }
44 
45 
46 void setup() {
47  // NOTE!!! Wait for >2 secs
48  // if board doesn't support software reset via Serial.DTR/RTS
49  delay(2000);
50  UNITY_BEGIN();
51 
52  Serial.begin(9600); // set up Serial library at 9600 bps
53  Serial.println("AdafruitMotorController Test");
54 
55  AMC.begin(); // create with the default frequency 1.6KHz
56  //AFMS.begin(1000); // OR with a different frequency, say 1KHz
57 }
58 
59 uint8_t cycle = 0;
60 uint8_t max_loop_cycles = 1;
61 
62 void loop() {
63 
64  if (cycle < max_loop_cycles)
65  {
66  Serial.print("tick");
67 
69  }
70  else
71  {
73  delay(1000);
74  UNITY_END();
75  }
76 
77  cycle++;
78 }
diffbot
Definition: base_controller.h:23
diffbot::MotorControllerIntf::setSpeed
virtual void setSpeed(int value)=0
Set the speed of the a motor.
pMotorController
MotorControllerIntf< Adafruit_MotorShield > * pMotorController
Definition: test_adafruit_motor_controller.cpp:14
motorSweep
void motorSweep(MotorControllerIntf< Adafruit_MotorShield > *i_pMotorController)
Definition: test_adafruit_motor_controller.cpp:17
adafruit_feather_wing.h
AMC
AdafruitMotorController AMC
Definition: test_adafruit_motor_controller.cpp:13
cycle
uint8_t cycle
Definition: test_adafruit_motor_controller.cpp:59
max_loop_cycles
uint8_t max_loop_cycles
Definition: test_adafruit_motor_controller.cpp:60
diffbot::AdafruitMotorController
Implementation of the MotorControllerIntf for the Adafruit_MotorShield.
Definition: adafruit_feather_wing.h:28
setup
void setup()
Definition: test_adafruit_motor_controller.cpp:46
loop
void loop()
Definition: test_adafruit_motor_controller.cpp:62
diffbot::MotorControllerIntf< Adafruit_MotorShield >
diffbot::AdafruitMotorController::begin
void begin(uint16_t freq=1600)
Initializes the communication with the motor driver.
Definition: adafruit_feather_wing.cpp:11


diffbot_base
Author(s):
autogenerated on Thu Sep 7 2023 02:35:23