Skip to content

Instantly share code, notes, and snippets.

@jonas-merkle
Last active April 10, 2021 12:08
Show Gist options
  • Select an option

  • Save jonas-merkle/767becf922b0faf8d1c69d7a5ba3b4aa to your computer and use it in GitHub Desktop.

Select an option

Save jonas-merkle/767becf922b0faf8d1c69d7a5ba3b4aa to your computer and use it in GitHub Desktop.
This demo software reads an AS5047P sensor while generating a pulse series to control a stepper motor which is connected to an A4988 stepper driver.
/**
* @file StepperAndAS5047P.cpp
* @author Jonas Merkle [JJM] ([email protected])
* @brief This software reads an AS5047P sensor while generating a pulse series
* to control a stepper motor which is connected to an A4988 stepper driver.
* @version 0.2
* @date 2021-04-10
*
* @copyright Copyright (c) 2021
*
*
* generated pulse series (pin: 4):
*
* |--------| |--------| |--------|
* | | | | | |
* ... ---| |--------| |--------| |--------...
*
* |--StepInterval---|
*
* performance data:
*
* - while reading the sensor a minimal step-interval of 12 µSec can be achieved.
* - used hardware: Teenys 4.1, AS5047P, Logic Analyzer, Not tested with a stepper motor
* - used software: StepperAndAS5047P.cpp, AS5047P library version 2.1.4
* - used SPI speed: 28000000 Hz
*
* - limitations:
* - the absolut minimum step interval is 2 µSec (according to the A4988 datasheet)
* - the step interval must be a multiple of 2
* - small deviations of the actual pulse widths from the theoretically specified values can be observed.
*/
//////////////
// Includes //
//////////////
#include <inttypes.h> ///< Include the inttypes library for uint8_t ...
#include <AS5047P.h> ///< Include the library for the AS5047P sensor.
/////////////
// Defines //
/////////////
#define SERIAL_BAUDRATE 115200
#define AS5047P_CHIP_SELECT_PORT 10 ///< Define the chip select port for the AS5047P sensor.
#define AS5047P_CUSTOM_SPI_BUS_SPEED 28000000 ///< Define the spi bus speed.
#define AS5047P_ENABLED true ///< Define if the AS5047P sensor is enabled and will be read.
#define ENABLE_PIN 2 ///< Define the enable pin.
#define DIR_PIN 3 ///< Define the direction pin.
#define STEP_PIN 4 ///< Define the step output pin.
////////////////////
// Global Objects //
////////////////////
AS5047P as5047p(AS5047P_CHIP_SELECT_PORT, AS5047P_CUSTOM_SPI_BUS_SPEED); ///< initialize a new AS5047P sensor object.
//////////////////////
// Global Variables //
//////////////////////
bool EnableState = LOW; ///< Enable pin state (default: LOW = enabled).
bool DirState = HIGH; ///< Direction pin state (default: HIGH = spin clockwise).
bool StepState = LOW; ///< Step pin state (defaut: LOW).
uint32_t StepInterval = 100; ///< Represents the interval between two steps in microseconds. (must be at least 2 µSec!)
uint32_t TimeOfLastStepEdge = 0; ///< Represents the last time the step pin changed it's state.
///////////////////////////
// arduino setup routine //
///////////////////////////
void setup()
{
// set pinmodes
pinMode(ENABLE_PIN, OUTPUT);
pinMode(DIR_PIN, OUTPUT);
pinMode(STEP_PIN, OUTPUT);
// set inital pin stats
digitalWrite(ENABLE_PIN, EnableState);
digitalWrite(DIR_PIN, DirState);
digitalWrite(STEP_PIN, StepState);
// initialize the serial bus for the communication with your pc.
Serial.begin(SERIAL_BAUDRATE);
//while (!Serial) {} // wait until a serial communication is established (native usb only?)
// initialize the AS5047P sensor and hold if sensor can't be initialized.
while (!as5047p.initSPI())
{
Serial.println(F("Can't connect to the AS5047P sensor! Please check the connection..."));
delay(5000);
}
}
//////////////////////////
// arduino loop routine //
//////////////////////////
void loop()
{
// read the AS5047P sensor if the enable flag is set to true
if (AS5047P_ENABLED == true)
{
uint16_t angle = as5047p.readAngleRaw();
// change the direction
if (angle > 1000 && DirState == HIGH)
{
DirState = LOW;
}
else if (angle < 100 && DirState == LOW)
{
DirState = HIGH;
}
digitalWrite(STEP_PIN, StepState);
}
// check if the time has reached to changed the pin state
if (micros() - TimeOfLastStepEdge >= StepInterval/2)
{
/*
if (StepState == HIGH)
{
StepState = LOW;
}
else
{
StepState = HIGH;
}
*/
// The following line equals the if statement above
StepState == HIGH ? StepState = LOW : StepState = HIGH;
// write the new pin state
digitalWrite(STEP_PIN, StepState);
// reset the TimeOfLastStepEdge variable
TimeOfLastStepEdge = micros();
}
}
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment