

The Sketch:
/* Hovermotor_Hall_Encoders.ino Arduining DIC 10,2019
*
* Code repeats every six values:
* Hall Sensor U 0 0 0 1 1 1 0 0 0 ... (Green cable)
* Hall Sensor Y 1 1 0 0 0 1 1 1 0 ... (Yellow cable)
* Hall Sensor W 0 1 1 1 0 0 0 1 1 ... (Blue cable)
* 2 6 4 5 1 3 2 6 4 ...
*
* Using RC Low Pass filters and a 74LS07 inverter buffer. R=1.5k and C= 0.1uF (fo=1.06kHz)
* -----------------------------------------------------------------------------
* Using RobotDyn STM32F1103C8T6, STM32 ARM Arduino Mini System
* Development board with Arduino bootloader.
* STM32F1 Boards (STM32duino.com)
* Board: "Generic STM32F103C series"
* Variant: "STM32F103C8 (20k RAM, 64k Flash)"
* Upload method: "STM32duino booloader"
* Port: "COM124 (Maple Mini)"
* -----------------------------------------------------------------------------
*/
#include "LedControl.h" // LedControl Library must be included (Use Sketch>Include Library>Manage Libraries...)
#define CLKPIN PA2 // The CLK pin
#define CSPIN PA1 // The CS pin
#define DINPIN PA0 // The DIN pin
#define MAXS 1 // Using 1 MAX7219 only
#define CLEAR PA7 // Clear the pulseCounter
#define HS_U PB6 // STM32 Blue Pill 5 Volts tolereant
#define HS_V PB7 // STM32 Blue Pill 5 Volts tolereant
#define HS_W PB8 // STM32 Blue Pill 5 Volts tolereant
#define CW 1 // Assign a value to represent clock wise rotation
#define CCW -1 // Assign a value to represent counter-clock wise rotation
#define SAMPLE_PERIOD 500 // in microseconds; should give an interrupt every 500 microseconds
char numbuff [10];
//HardwareTimer timer2(2);
LedControl Max7219 = LedControl(DINPIN, CLKPIN, CSPIN, MAXS);
void handler_Check_H_Sensors(void);
/***************************** Variables *************************************/
bool hallchanged= false;
bool checkSensors= false;
volatile byte lastcode; // last code from the hall encoder
//volatile uint8_t lastcode; // same as byte.
volatile byte newcode; // new code from the encoder
volatile int change; // Integer variable to add or substrat to the pulseCounter
volatile int pulseCounter; // Integer variable to store the pulse count
byte lastInc[] = {0, 5, 3, 1, 6, 4, 2}; // Increment counter, the index is the newcode
byte lastDec[] = {0, 3, 6, 2, 5, 1, 4}; // Decrement counter, the index is the newcode
/*==============================================================================
* setup()
==============================================================================*/
void setup()
{
pinMode(CLEAR, INPUT_PULLUP); // Pin CLEAR as input.
// Pins HS_U, HS_V and HS_W as inputs.
pinMode(HS_U, INPUT_PULLUP);
pinMode(HS_V, INPUT_PULLUP);
pinMode(HS_W, INPUT_PULLUP);
// Configuree MAX7219 8 7-segment display:
Max7219.shutdown(0,false); // turn off power saving, enables display
Max7219.setIntensity(0,2); // sets brightness (0~15 possible values)
Max7219.clearDisplay(0); // clear screen
// Configure channel 1 of Timer 2 to generate an interrupt every 250 microseconds.
Timer2.setChannel2Mode(TIMER_OUTPUT_COMPARE);
Timer2.setPeriod(SAMPLE_PERIOD); // configures prescaler and overflow to generate a timer reload in microseconds,
Timer2.setCompare(TIMER_CH1, 1);
// Pins HS_U, HS_V and HS_W as interrupts . Call functions on change
attachInterrupt(digitalPinToInterrupt(HS_U), HallSensorU, CHANGE); // Green cable
attachInterrupt(digitalPinToInterrupt(HS_V), HallSensorV, CHANGE); // Yellow cable
attachInterrupt(digitalPinToInterrupt(HS_W), HallSensorW, CHANGE); // BLue cable
Serial.begin(115200);
lastcode= digitalRead(HS_U) | digitalRead(HS_V)<<1 | digitalRead(HS_W)<<2 ;
}
/*==============================================================================
* loop()
==============================================================================*/
void loop()
{
Serial.println(pulseCounter); // Display the pulse count
sprintf (numbuff, "%08i", pulseCounter);
for( int i=0 ; i<8 ; i++)
{
Max7219.setChar(0, 7-i, numbuff[i], false);
}
delay(100); // to limit the printing flow...
if(!digitalRead(CLEAR))pulseCounter= 0; // Reset the pulse counter.
}
/************************ Interrupt Functions *********************************/
/*-----------------------------------------------------------------------------
* Check_H_Sensors()
-----------------------------------------------------------------------------*/
void Check_H_Sensors() // Executed every 500 microseconds
{
if(checkSensors)
{
newcode= digitalRead(HS_U) | digitalRead(HS_V)<<1 | digitalRead(HS_W)<<2 ;
if (lastcode == lastInc[newcode]){
pulseCounter--;
lastcode= newcode;
}
if (lastcode == lastDec[newcode]){
pulseCounter++;
lastcode= newcode;
}
hallchanged== false;
checkSensors= false;
}
if(hallchanged== true)checkSensors= true;
}
/*------------------------------------------------------------------------------
* HallSensorW()
------------------------------------------------------------------------------*/
void HallSensorW()
{
// hallchanged= true;
delayMicroseconds(80);
newcode= digitalRead(HS_U) | digitalRead(HS_V)<<1 | digitalRead(HS_W)<<2 ;
if (lastcode == lastInc[newcode]){
pulseCounter--;
lastcode= newcode;
}
if (lastcode == lastDec[newcode]){
pulseCounter++;
lastcode= newcode;
}
}
/*-----------------------------------------------------------------------------
* HallSensorV()
-----------------------------------------------------------------------------*/
void HallSensorV()
{
// hallchanged= true;
delayMicroseconds(80);
newcode= digitalRead(HS_U) | digitalRead(HS_V)<<1 | digitalRead(HS_W)<<2 ;
if (lastcode == lastInc[newcode]){
pulseCounter--;
lastcode= newcode;
}
if (lastcode == lastDec[newcode]){
pulseCounter++;
lastcode= newcode;
}
}
/*-----------------------------------------------------------------------------
* HallSensorU()
-----------------------------------------------------------------------------*/
void HallSensorU()
{
// hallchanged= true;
delayMicroseconds(80);
newcode= digitalRead(HS_U) | digitalRead(HS_V)<<1 | digitalRead(HS_W)<<2 ;
if (lastcode == lastInc[newcode]){
pulseCounter--;
lastcode= newcode;
}
if (lastcode == lastDec[newcode]){
pulseCounter++;
lastcode= newcode;
}
}