first commit

This commit is contained in:
Jérôme Delacotte
2025-03-06 11:15:32 +01:00
commit 7b30d6e298
5276 changed files with 2108927 additions and 0 deletions

View File

@@ -0,0 +1,126 @@
#include "A4990MotorShield.h"
const unsigned char A4990MotorShield::_M1DIR = 7;
const unsigned char A4990MotorShield::_M2DIR = 8;
const unsigned char A4990MotorShield::_M1PWM = 9;
const unsigned char A4990MotorShield::_M2PWM = 10;
const unsigned char A4990MotorShield::_FAULT = 6;
boolean A4990MotorShield::_flipM1 = false;
boolean A4990MotorShield::_flipM2 = false;
void A4990MotorShield::initPinsAndMaybeTimer()
{
// Initialize the pin states used by the motor driver shield
// digitalWrite is called before and after setting pinMode.
// It called before pinMode to handle the case where the board
// is using an ATmega AVR to avoid ever driving the pin high,
// even for a short time.
// It is called after pinMode to handle the case where the board
// is based on the Atmel SAM3X8E ARM Cortex-M3 CPU, like the Arduino
// Due. This is necessary because when pinMode is called for the Due
// it sets the output to high (or 3.3V) regardless of previous
// digitalWrite calls.
digitalWrite(_M1PWM, LOW);
pinMode(_M1PWM, OUTPUT);
digitalWrite(_M1PWM, LOW);
digitalWrite(_M2PWM, LOW);
pinMode(_M2PWM, OUTPUT);
digitalWrite(_M2PWM, LOW);
digitalWrite(_M1DIR, LOW);
pinMode(_M1DIR, OUTPUT);
digitalWrite(_M1DIR, LOW);
digitalWrite(_M2DIR, LOW);
pinMode(_M2DIR, OUTPUT);
digitalWrite(_M2DIR, LOW);
pinMode(_FAULT, INPUT_PULLUP);
#ifdef A4990MOTORSHIELD_USE_20KHZ_PWM
// timer 1 configuration
// prescaler: clockI/O / 1
// outputs enabled
// phase-correct PWM
// top of 400
//
// PWM frequency calculation
// 16MHz / 1 (prescaler) / 2 (phase-correct) / 400 (top) = 20kHz
TCCR1A = 0b10100000;
TCCR1B = 0b00010001;
ICR1 = 400;
#endif
}
// speed should be a number between -400 and 400
void A4990MotorShield::setM1Speed(int speed)
{
init(); // initialize if necessary
boolean reverse = 0;
if (speed < 0)
{
speed = -speed; // make speed a positive quantity
reverse = 1; // preserve the direction
}
if (speed > 400) // max
speed = 400;
#ifdef A4990MOTORSHIELD_USE_20KHZ_PWM
OCR1A = speed;
#else
analogWrite(_M1PWM, speed * 51 / 80); // default to using analogWrite, mapping 400 to 255
#endif
if (reverse ^ _flipM1) // flip if speed was negative or _flipM1 setting is active, but not both
digitalWrite(_M1DIR, HIGH);
else
digitalWrite(_M1DIR, LOW);
}
// speed should be a number between -400 and 400
void A4990MotorShield::setM2Speed(int speed)
{
init(); // initialize if necessary
boolean reverse = 0;
if (speed < 0)
{
speed = -speed; // make speed a positive quantity
reverse = 1; // preserve the direction
}
if (speed > 400) // max PWM duty cycle
speed = 400;
#ifdef A4990MOTORSHIELD_USE_20KHZ_PWM
OCR1B = speed;
#else
analogWrite(_M2PWM, speed * 51 / 80); // default to using analogWrite, mapping 400 to 255
#endif
if (reverse ^ _flipM2) // flip if speed was negative or _flipM2 setting is active, but not both
digitalWrite(_M2DIR, HIGH);
else
digitalWrite(_M2DIR, LOW);
}
// set speed for both motors
// speed should be a number between -400 and 400
void A4990MotorShield::setSpeeds(int m1Speed, int m2Speed)
{
setM1Speed(m1Speed);
setM2Speed(m2Speed);
}
void A4990MotorShield::flipM1(boolean flip)
{
A4990MotorShield::_flipM1 = flip;
}
void A4990MotorShield::flipM2(boolean flip)
{
A4990MotorShield::_flipM2 = flip;
}
boolean A4990MotorShield::getFault()
{
init(); // initialize if necessary
return digitalRead(_FAULT) == LOW;
}

View File

@@ -0,0 +1,40 @@
#ifndef A4990MotorShield_h
#define A4990MotorShield_h
#if defined(__AVR_ATmega168__) || defined(__AVR_ATmega328P__) || defined (__AVR_ATmega32U4__)
#define A4990MOTORSHIELD_USE_20KHZ_PWM
#endif
#include <Arduino.h>
class A4990MotorShield
{
public:
static void setM1Speed(int speed);
static void setM2Speed(int speed);
static void setSpeeds(int m1Speed, int m2Speed);
static void flipM1(boolean flip);
static void flipM2(boolean flip);
static boolean getFault();
private:
static void initPinsAndMaybeTimer();
const static unsigned char _M1DIR;
const static unsigned char _M2DIR;
const static unsigned char _M1PWM;
const static unsigned char _M2PWM;
const static unsigned char _FAULT;
static boolean _flipM1;
static boolean _flipM2;
static inline void init()
{
static boolean initialized = false;
if (!initialized)
{
initialized = true;
initPinsAndMaybeTimer();
}
}
};
#endif

View File

@@ -0,0 +1,25 @@
Copyright (c) 2014 Pololu Corporation. For more information, see
http://www.pololu.com/
http://forum.pololu.com/
Permission is hereby granted, free of charge, to any person
obtaining a copy of this software and associated documentation
files (the "Software"), to deal in the Software without
restriction, including without limitation the rights to use,
copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the
Software is furnished to do so, subject to the following
conditions:
The above copyright notice and this permission notice shall be
included in all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES
OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT
HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
OTHER DEALINGS IN THE SOFTWARE.

View File

@@ -0,0 +1,110 @@
# Arduino library for the Pololu A4990 Dual Motor Driver Shield
Version: 2.0.0 <br>
Release date: 2016-08-18 <br>
[![Build Status](https://travis-ci.org/pololu/a4990-motor-shield.svg?branch=master)](https://travis-ci.org/pololu/a4990-motor-shield) <br>
[www.pololu.com](https://www.pololu.com/)
## Summary
This is a library for an
[Arduino-compatible controller](https://www.pololu.com/arduino) that
interfaces with the
[Pololu A4990 Dual Motor Driver Shield for Arduino](https://www.pololu.com/catalog/product/2512).
It makes it simple to drive two brushed, DC motors.
## Getting started
### Hardware
The
[Pololu A4990 Dual Motor Driver Shield for Arduino](https://www.pololu.com/catalog/product/2512)
can be purchased on Pololu's website. Before continuing, careful
reading of the product page is recommended.
#### Compatible Arduino boards
This shield should work with all Arduino boards and clones that behave
like a standard Arduino board. We have specifically tested this shield
(using this Arduino library) with:
* Arduino Uno R3
* Arduino Leonardo
* Arduino Mega 2560
* Arduino Due
* Arduino Duemilanove (ATmega328P)
This library configures Timer 1 on the Uno R3, Leonardo, and
Duemilanove to generate a 20 kHz PWM frequency for the motors. The
library uses analogWrite on any board that does not use an ATmega168,
ATmega328P or ATmega32U4. On the Mega 2560 and Due, analogWrite
generates 489 Hz and 1 kHz PWM frequencies, respectively, with the
default timer configuration.
### Software
If you are using version 1.6.2 or later of the
[Arduino software (IDE)](https://www.arduino.cc/en/Main/Software), you can use
the Library Manager to install this library:
1. In the Arduino IDE, open the "Sketch" menu, select "Include Library", then
"Manage Libraries...".
2. Search for "A4990MotorShield".
3. Click the A4990MotorShield entry in the list.
4. Click "Install".
If this does not work, you can manually install the library:
1. Download the
[latest release archive from GitHub](https://github.com/pololu/a4990-motor-shield/releases)
and decompress it.
2. Rename the folder "lps-arduino-xxxx" to "A4990MotorShield".
3. Drag the "A4990MotorShield" folder into the "libraries" directory inside your
Arduino sketchbook directory. You can view your sketchbook location by
opening the "File" menu and selecting "Preferences" in the Arduino IDE. If
there is not already a "libraries" folder in that location, you should make
the folder yourself.
4. After installing the library, restart the Arduino IDE.
## Example program
An example sketch is available that shows how to use the library. You
can access it from the Arduino IDE by opening the "File" menu,
selecting "Examples", and then selecting "A4990MotorShield". If
you cannot find these examples, the library was probably installed
incorrectly and you should retry the installation instructions above.
### Demo
The demo ramps motor 1 from stopped to full speed forward, ramps down
to full speed reverse, and back to stopped. Then, it does the same
with the other motor.
## Documentatation
- `void setM1Speed(int speed)` <br> Set speed and direction for
motor 1. Speed should be between -400 and 400. The motors brake at 0
speed. Positive speeds correspond to motor current flowing from M1A
to M1B. Negative speeds correspond to motor current flowing from M1B
to M1A.
- `void setM2Speed(int speed)` <br> Set speed and direction for
motor 2. Speed should be between -400 and 400. The motors brake at 0
speed. Positive speeds correspond to motor current flowing from M2A
to M2B. Negative speeds correspond to motor current flowing from M2B
to M2A.
- `void setSpeeds(int m1Speed, int m2Speed)` <br> Set speed and
direction for motor 1 and 2.
- `void flipM1(bool flip)` <br> Flip the direction meaning of the
speed passed to the setSpeeds function for motor 1. The default
direction corresponds to flipM1(false) having been called.
- `void flipM2(bool flip)` <br> Flip the direction meaning of the
speed passed to the setSpeeds function for motor 2. The default
direction corresponds to flipM2(false) having been called.
- `bool getFault()` <br> Returns true if pin 6 is being driven low by
one of the error flag outputs.
## Version history
* 2.0.0 (2016-08-18): Updated library to work with the Arduino Library Manager.
* 1.0.0 (2014-08-15): Original release.

View File

@@ -0,0 +1,115 @@
#include <A4990MotorShield.h>
/*
* This example uses the A4990MotorShield library to drive each motor with the
* Pololu A4990 Dual Motor Driver Shield for Arduino forward, then backward.
* The yellow user LED is on when a motor is set to a positive speed and off when
* a motor is set to a negative speed.
*/
#define LED_PIN 13
A4990MotorShield motors;
/*
* For safety, it is good practice to monitor motor driver faults and handle
* them in an appropriate way. If a fault is detected, both motor speeds are set
* to zero and it is reported on the serial port.
*/
void stopIfFault()
{
if (motors.getFault())
{
motors.setSpeeds(0,0);
Serial.println("Fault");
while(1);
}
}
void setup()
{
pinMode(LED_PIN, OUTPUT);
Serial.begin(115200);
Serial.println("Pololu A4990 Dual Motor Driver Shield for Arduino");
// uncomment one or both of the following lines if your motors' directions need to be flipped
//motors.flipM1(true);
//motors.flipM2(true);
}
void loop()
{
// run M1 motor with positive speed
digitalWrite(LED_PIN, HIGH);
for (int speed = 0; speed <= 400; speed++)
{
motors.setM1Speed(speed);
stopIfFault();
delay(2);
}
for (int speed = 400; speed >= 0; speed--)
{
motors.setM1Speed(speed);
stopIfFault();
delay(2);
}
// run M1 motor with negative speed
digitalWrite(LED_PIN, LOW);
for (int speed = 0; speed >= -400; speed--)
{
motors.setM1Speed(speed);
stopIfFault();
delay(2);
}
for (int speed = -400; speed <= 0; speed++)
{
motors.setM1Speed(speed);
stopIfFault();
delay(2);
}
// run M2 motor with positive speed
digitalWrite(LED_PIN, HIGH);
for (int speed = 0; speed <= 400; speed++)
{
motors.setM2Speed(speed);
stopIfFault();
delay(2);
}
for (int speed = 400; speed >= 0; speed--)
{
motors.setM2Speed(speed);
stopIfFault();
delay(2);
}
// run M2 motor with negative speed
digitalWrite(LED_PIN, LOW);
for (int speed = 0; speed >= -400; speed--)
{
motors.setM2Speed(speed);
stopIfFault();
delay(2);
}
for (int speed = -400; speed <= 0; speed++)
{
motors.setM2Speed(speed);
stopIfFault();
delay(2);
}
delay(500);
}

View File

@@ -0,0 +1,8 @@
A4990MotorShield KEYWORD1
flipM1 KEYWORD2
flipM2 KEYWORD2
setM1Speed KEYWORD2
setM2Speed KEYWORD2
setSpeeds KEYWORD2
getFault KEYWORD2

View File

@@ -0,0 +1,9 @@
name=A4990MotorShield
version=2.0.0
author=Pololu
maintainer=Pololu <inbox@pololu.com>
sentence=Arduino library for the Pololu A4990 Dual Motor Driver Shield
paragraph=This is a library for an Arduino-compatible controller that interfaces with the Pololu A4990 Dual Motor Driver Shield for Arduino.
category=Device Control
url=https://github.com/pololu/a4990-motor-shield
architectures=*