try to fix submodule
This commit is contained in:
229
firmware/lib/Arduino-FOC/src/sensors/Encoder.cpp
Normal file
229
firmware/lib/Arduino-FOC/src/sensors/Encoder.cpp
Normal file
@@ -0,0 +1,229 @@
|
||||
#include "Encoder.h"
|
||||
|
||||
|
||||
/*
|
||||
Encoder(int encA, int encB , int cpr, int index)
|
||||
- encA, encB - encoder A and B pins
|
||||
- cpr - counts per rotation number (cpm=ppm*4)
|
||||
- index pin - (optional input)
|
||||
*/
|
||||
|
||||
Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){
|
||||
|
||||
// Encoder measurement structure init
|
||||
// hardware pins
|
||||
pinA = _encA;
|
||||
pinB = _encB;
|
||||
// counter setup
|
||||
pulse_counter = 0;
|
||||
pulse_timestamp = 0;
|
||||
|
||||
cpr = _ppr;
|
||||
A_active = 0;
|
||||
B_active = 0;
|
||||
I_active = 0;
|
||||
// index pin
|
||||
index_pin = _index; // its 0 if not used
|
||||
|
||||
// velocity calculation variables
|
||||
prev_Th = 0;
|
||||
pulse_per_second = 0;
|
||||
prev_pulse_counter = 0;
|
||||
prev_timestamp_us = _micros();
|
||||
|
||||
// extern pullup as default
|
||||
pullup = Pullup::USE_EXTERN;
|
||||
// enable quadrature encoder by default
|
||||
quadrature = Quadrature::ON;
|
||||
}
|
||||
|
||||
// Encoder interrupt callback functions
|
||||
// A channel
|
||||
void Encoder::handleA() {
|
||||
bool A = digitalRead(pinA);
|
||||
switch (quadrature){
|
||||
case Quadrature::ON:
|
||||
// CPR = 4xPPR
|
||||
if ( A != A_active ) {
|
||||
pulse_counter += (A_active == B_active) ? 1 : -1;
|
||||
pulse_timestamp = _micros();
|
||||
A_active = A;
|
||||
}
|
||||
break;
|
||||
case Quadrature::OFF:
|
||||
// CPR = PPR
|
||||
if(A && !digitalRead(pinB)){
|
||||
pulse_counter++;
|
||||
pulse_timestamp = _micros();
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
// B channel
|
||||
void Encoder::handleB() {
|
||||
bool B = digitalRead(pinB);
|
||||
switch (quadrature){
|
||||
case Quadrature::ON:
|
||||
// // CPR = 4xPPR
|
||||
if ( B != B_active ) {
|
||||
pulse_counter += (A_active != B_active) ? 1 : -1;
|
||||
pulse_timestamp = _micros();
|
||||
B_active = B;
|
||||
}
|
||||
break;
|
||||
case Quadrature::OFF:
|
||||
// CPR = PPR
|
||||
if(B && !digitalRead(pinA)){
|
||||
pulse_counter--;
|
||||
pulse_timestamp = _micros();
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// Index channel
|
||||
void Encoder::handleIndex() {
|
||||
if(hasIndex()){
|
||||
bool I = digitalRead(index_pin);
|
||||
if(I && !I_active){
|
||||
index_found = true;
|
||||
// align encoder on each index
|
||||
long tmp = pulse_counter;
|
||||
// corrent the counter value
|
||||
pulse_counter = round((double)pulse_counter/(double)cpr)*cpr;
|
||||
// preserve relative speed
|
||||
prev_pulse_counter += pulse_counter - tmp;
|
||||
}
|
||||
I_active = I;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Sensor update function. Safely copy volatile interrupt variables into Sensor base class state variables.
|
||||
void Encoder::update() {
|
||||
// Copy volatile variables in minimal-duration blocking section to ensure no interrupts are missed
|
||||
noInterrupts();
|
||||
angle_prev_ts = pulse_timestamp;
|
||||
long copy_pulse_counter = pulse_counter;
|
||||
interrupts();
|
||||
// TODO: numerical precision issue here if the pulse_counter overflows the angle will be lost
|
||||
full_rotations = copy_pulse_counter / (int)cpr;
|
||||
angle_prev = _2PI * ((copy_pulse_counter) % ((int)cpr)) / ((float)cpr);
|
||||
}
|
||||
|
||||
/*
|
||||
Shaft angle calculation
|
||||
*/
|
||||
float Encoder::getSensorAngle(){
|
||||
return _2PI * (pulse_counter) / ((float)cpr);
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*
|
||||
Shaft velocity calculation
|
||||
function using mixed time and frequency measurement technique
|
||||
*/
|
||||
float Encoder::getVelocity(){
|
||||
// Copy volatile variables in minimal-duration blocking section to ensure no interrupts are missed
|
||||
noInterrupts();
|
||||
long copy_pulse_counter = pulse_counter;
|
||||
long copy_pulse_timestamp = pulse_timestamp;
|
||||
interrupts();
|
||||
// timestamp
|
||||
long timestamp_us = _micros();
|
||||
// sampling time calculation
|
||||
float Ts = (timestamp_us - prev_timestamp_us) * 1e-6f;
|
||||
// quick fix for strange cases (micros overflow)
|
||||
if(Ts <= 0 || Ts > 0.5f) Ts = 1e-3f;
|
||||
|
||||
// time from last impulse
|
||||
float Th = (timestamp_us - copy_pulse_timestamp) * 1e-6f;
|
||||
long dN = copy_pulse_counter - prev_pulse_counter;
|
||||
|
||||
// Pulse per second calculation (Eq.3.)
|
||||
// dN - impulses received
|
||||
// Ts - sampling time - time in between function calls
|
||||
// Th - time from last impulse
|
||||
// Th_1 - time form last impulse of the previous call
|
||||
// only increment if some impulses received
|
||||
float dt = Ts + prev_Th - Th;
|
||||
pulse_per_second = (dN != 0 && dt > Ts/2) ? dN / dt : pulse_per_second;
|
||||
|
||||
// if more than 0.05f passed in between impulses
|
||||
if ( Th > 0.1f) pulse_per_second = 0;
|
||||
|
||||
// velocity calculation
|
||||
float velocity = pulse_per_second / ((float)cpr) * (_2PI);
|
||||
|
||||
// save variables for next pass
|
||||
prev_timestamp_us = timestamp_us;
|
||||
// save velocity calculation variables
|
||||
prev_Th = Th;
|
||||
prev_pulse_counter = copy_pulse_counter;
|
||||
return velocity;
|
||||
}
|
||||
|
||||
// getter for index pin
|
||||
// return -1 if no index
|
||||
int Encoder::needsSearch(){
|
||||
return hasIndex() && !index_found;
|
||||
}
|
||||
|
||||
// private function used to determine if encoder has index
|
||||
int Encoder::hasIndex(){
|
||||
return index_pin != 0;
|
||||
}
|
||||
|
||||
|
||||
// encoder initialisation of the hardware pins
|
||||
// and calculation variables
|
||||
void Encoder::init(){
|
||||
|
||||
// Encoder - check if pullup needed for your encoder
|
||||
if(pullup == Pullup::USE_INTERN){
|
||||
pinMode(pinA, INPUT_PULLUP);
|
||||
pinMode(pinB, INPUT_PULLUP);
|
||||
if(hasIndex()) pinMode(index_pin,INPUT_PULLUP);
|
||||
}else{
|
||||
pinMode(pinA, INPUT);
|
||||
pinMode(pinB, INPUT);
|
||||
if(hasIndex()) pinMode(index_pin,INPUT);
|
||||
}
|
||||
|
||||
// counter setup
|
||||
pulse_counter = 0;
|
||||
pulse_timestamp = _micros();
|
||||
// velocity calculation variables
|
||||
prev_Th = 0;
|
||||
pulse_per_second = 0;
|
||||
prev_pulse_counter = 0;
|
||||
prev_timestamp_us = _micros();
|
||||
|
||||
// initial cpr = PPR
|
||||
// change it if the mode is quadrature
|
||||
if(quadrature == Quadrature::ON) cpr = 4*cpr;
|
||||
|
||||
// we don't call Sensor::init() here because init is handled in Encoder class.
|
||||
}
|
||||
|
||||
// function enabling hardware interrupts of the for the callback provided
|
||||
// if callback is not provided then the interrupt is not enabled
|
||||
void Encoder::enableInterrupts(void (*doA)(), void(*doB)(), void(*doIndex)()){
|
||||
// attach interrupt if functions provided
|
||||
switch(quadrature){
|
||||
case Quadrature::ON:
|
||||
// A callback and B callback
|
||||
if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE);
|
||||
if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE);
|
||||
break;
|
||||
case Quadrature::OFF:
|
||||
// A callback and B callback
|
||||
if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, RISING);
|
||||
if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, RISING);
|
||||
break;
|
||||
}
|
||||
|
||||
// if index used initialize the index interrupt
|
||||
if(hasIndex() && doIndex != nullptr) attachInterrupt(digitalPinToInterrupt(index_pin), doIndex, CHANGE);
|
||||
}
|
||||
91
firmware/lib/Arduino-FOC/src/sensors/Encoder.h
Normal file
91
firmware/lib/Arduino-FOC/src/sensors/Encoder.h
Normal file
@@ -0,0 +1,91 @@
|
||||
#ifndef ENCODER_LIB_H
|
||||
#define ENCODER_LIB_H
|
||||
|
||||
#include "Arduino.h"
|
||||
#include "../common/foc_utils.h"
|
||||
#include "../common/time_utils.h"
|
||||
#include "../common/base_classes/Sensor.h"
|
||||
|
||||
|
||||
/**
|
||||
* Quadrature mode configuration structure
|
||||
*/
|
||||
enum Quadrature : uint8_t {
|
||||
ON = 0x00, //!< Enable quadrature mode CPR = 4xPPR
|
||||
OFF = 0x01 //!< Disable quadrature mode / CPR = PPR
|
||||
};
|
||||
|
||||
class Encoder: public Sensor{
|
||||
public:
|
||||
/**
|
||||
Encoder class constructor
|
||||
@param encA encoder B pin
|
||||
@param encB encoder B pin
|
||||
@param ppr impulses per rotation (cpr=ppr*4)
|
||||
@param index index pin number (optional input)
|
||||
*/
|
||||
Encoder(int encA, int encB , float ppr, int index = 0);
|
||||
|
||||
/** encoder initialise pins */
|
||||
void init() override;
|
||||
/**
|
||||
* function enabling hardware interrupts for the encoder channels with provided callback functions
|
||||
* if callback is not provided then the interrupt is not enabled
|
||||
*
|
||||
* @param doA pointer to the A channel interrupt handler function
|
||||
* @param doB pointer to the B channel interrupt handler function
|
||||
* @param doIndex pointer to the Index channel interrupt handler function
|
||||
*
|
||||
*/
|
||||
void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doIndex)() = nullptr);
|
||||
|
||||
// Encoder interrupt callback functions
|
||||
/** A channel callback function */
|
||||
void handleA();
|
||||
/** B channel callback function */
|
||||
void handleB();
|
||||
/** Index channel callback function */
|
||||
void handleIndex();
|
||||
|
||||
|
||||
// pins A and B
|
||||
int pinA; //!< encoder hardware pin A
|
||||
int pinB; //!< encoder hardware pin B
|
||||
int index_pin; //!< index pin
|
||||
|
||||
// Encoder configuration
|
||||
Pullup pullup; //!< Configuration parameter internal or external pullups
|
||||
Quadrature quadrature;//!< Configuration parameter enable or disable quadrature mode
|
||||
float cpr;//!< encoder cpr number
|
||||
|
||||
// Abstract functions of the Sensor class implementation
|
||||
/** get current angle (rad) */
|
||||
float getSensorAngle() override;
|
||||
/** get current angular velocity (rad/s) */
|
||||
float getVelocity() override;
|
||||
virtual void update() override;
|
||||
|
||||
/**
|
||||
* returns 0 if it does need search for absolute zero
|
||||
* 0 - encoder without index
|
||||
* 1 - ecoder with index
|
||||
*/
|
||||
int needsSearch() override;
|
||||
|
||||
private:
|
||||
int hasIndex(); //!< function returning 1 if encoder has index pin and 0 if not.
|
||||
|
||||
volatile long pulse_counter;//!< current pulse counter
|
||||
volatile long pulse_timestamp;//!< last impulse timestamp in us
|
||||
volatile int A_active; //!< current active states of A channel
|
||||
volatile int B_active; //!< current active states of B channel
|
||||
volatile int I_active; //!< current active states of Index channel
|
||||
volatile bool index_found = false; //!< flag stating that the index has been found
|
||||
|
||||
// velocity calculation variables
|
||||
float prev_Th, pulse_per_second;
|
||||
volatile long prev_pulse_counter, prev_timestamp_us;
|
||||
};
|
||||
|
||||
|
||||
#endif
|
||||
26
firmware/lib/Arduino-FOC/src/sensors/GenericSensor.cpp
Normal file
26
firmware/lib/Arduino-FOC/src/sensors/GenericSensor.cpp
Normal file
@@ -0,0 +1,26 @@
|
||||
#include "GenericSensor.h"
|
||||
|
||||
|
||||
/*
|
||||
GenericSensor( float (*readCallback)() )
|
||||
- readCallback - pointer to the function which reads the sensor angle.
|
||||
*/
|
||||
|
||||
GenericSensor::GenericSensor(float (*readCallback)(), void (*initCallback)()){
|
||||
// if function provided add it to the
|
||||
if(readCallback != nullptr) this->readCallback = readCallback;
|
||||
if(initCallback != nullptr) this->initCallback = initCallback;
|
||||
}
|
||||
|
||||
void GenericSensor::init(){
|
||||
// if init callback specified run it
|
||||
if(initCallback != nullptr) this->initCallback();
|
||||
this->Sensor::init(); // call base class init
|
||||
}
|
||||
|
||||
/*
|
||||
Shaft angle calculation
|
||||
*/
|
||||
float GenericSensor::getSensorAngle(){
|
||||
return this->readCallback();
|
||||
}
|
||||
31
firmware/lib/Arduino-FOC/src/sensors/GenericSensor.h
Normal file
31
firmware/lib/Arduino-FOC/src/sensors/GenericSensor.h
Normal file
@@ -0,0 +1,31 @@
|
||||
#ifndef GENERIC_SENSOR_LIB_H
|
||||
#define GENERIC_SENSOR_LIB_H
|
||||
|
||||
#include "Arduino.h"
|
||||
#include "../common/foc_utils.h"
|
||||
#include "../common/time_utils.h"
|
||||
#include "../common/base_classes/Sensor.h"
|
||||
|
||||
|
||||
class GenericSensor: public Sensor{
|
||||
public:
|
||||
/**
|
||||
GenericSensor class constructor
|
||||
* @param readCallback pointer to the function reading the sensor angle
|
||||
* @param initCallback pointer to the function initialising the sensor
|
||||
*/
|
||||
GenericSensor(float (*readCallback)() = nullptr, void (*initCallback)() = nullptr);
|
||||
|
||||
float (*readCallback)() = nullptr; //!< function pointer to sensor reading
|
||||
void (*initCallback)() = nullptr; //!< function pointer to sensor initialisation
|
||||
|
||||
void init() override;
|
||||
|
||||
// Abstract functions of the Sensor class implementation
|
||||
/** get current angle (rad) */
|
||||
float getSensorAngle() override;
|
||||
|
||||
};
|
||||
|
||||
|
||||
#endif
|
||||
173
firmware/lib/Arduino-FOC/src/sensors/HallSensor.cpp
Normal file
173
firmware/lib/Arduino-FOC/src/sensors/HallSensor.cpp
Normal file
@@ -0,0 +1,173 @@
|
||||
#include "HallSensor.h"
|
||||
|
||||
|
||||
/*
|
||||
HallSensor(int hallA, int hallB , int cpr, int index)
|
||||
- hallA, hallB, hallC - HallSensor A, B and C pins
|
||||
- pp - pole pairs
|
||||
*/
|
||||
HallSensor::HallSensor(int _hallA, int _hallB, int _hallC, int _pp){
|
||||
|
||||
// hardware pins
|
||||
pinA = _hallA;
|
||||
pinB = _hallB;
|
||||
pinC = _hallC;
|
||||
|
||||
// hall has 6 segments per electrical revolution
|
||||
cpr = _pp * 6;
|
||||
|
||||
// extern pullup as default
|
||||
pullup = Pullup::USE_EXTERN;
|
||||
}
|
||||
|
||||
// HallSensor interrupt callback functions
|
||||
// A channel
|
||||
void HallSensor::handleA() {
|
||||
A_active= digitalRead(pinA);
|
||||
updateState();
|
||||
}
|
||||
// B channel
|
||||
void HallSensor::handleB() {
|
||||
B_active = digitalRead(pinB);
|
||||
updateState();
|
||||
}
|
||||
|
||||
// C channel
|
||||
void HallSensor::handleC() {
|
||||
C_active = digitalRead(pinC);
|
||||
updateState();
|
||||
}
|
||||
|
||||
/**
|
||||
* Updates the state and sector following an interrupt
|
||||
*/
|
||||
void HallSensor::updateState() {
|
||||
long new_pulse_timestamp = _micros();
|
||||
|
||||
int8_t new_hall_state = C_active + (B_active << 1) + (A_active << 2);
|
||||
|
||||
// glitch avoidance #1 - sometimes we get an interrupt but pins haven't changed
|
||||
if (new_hall_state == hall_state) {
|
||||
return;
|
||||
}
|
||||
hall_state = new_hall_state;
|
||||
|
||||
int8_t new_electric_sector = ELECTRIC_SECTORS[hall_state];
|
||||
static Direction old_direction;
|
||||
if (new_electric_sector - electric_sector > 3) {
|
||||
//underflow
|
||||
direction = Direction::CCW;
|
||||
electric_rotations += direction;
|
||||
} else if (new_electric_sector - electric_sector < (-3)) {
|
||||
//overflow
|
||||
direction = Direction::CW;
|
||||
electric_rotations += direction;
|
||||
} else {
|
||||
direction = (new_electric_sector > electric_sector)? Direction::CW : Direction::CCW;
|
||||
}
|
||||
electric_sector = new_electric_sector;
|
||||
|
||||
// glitch avoidance #2 changes in direction can cause velocity spikes. Possible improvements needed in this area
|
||||
if (direction == old_direction) {
|
||||
// not oscilating or just changed direction
|
||||
pulse_diff = new_pulse_timestamp - pulse_timestamp;
|
||||
} else {
|
||||
pulse_diff = 0;
|
||||
}
|
||||
|
||||
pulse_timestamp = new_pulse_timestamp;
|
||||
total_interrupts++;
|
||||
old_direction = direction;
|
||||
if (onSectorChange != nullptr) onSectorChange(electric_sector);
|
||||
}
|
||||
|
||||
/**
|
||||
* Optionally set a function callback to be fired when sector changes
|
||||
* void onSectorChange(int sector) {
|
||||
* ... // for debug or call driver directly?
|
||||
* }
|
||||
* sensor.attachSectorCallback(onSectorChange);
|
||||
*/
|
||||
void HallSensor::attachSectorCallback(void (*_onSectorChange)(int sector)) {
|
||||
onSectorChange = _onSectorChange;
|
||||
}
|
||||
|
||||
|
||||
|
||||
// Sensor update function. Safely copy volatile interrupt variables into Sensor base class state variables.
|
||||
void HallSensor::update() {
|
||||
// Copy volatile variables in minimal-duration blocking section to ensure no interrupts are missed
|
||||
noInterrupts();
|
||||
angle_prev_ts = pulse_timestamp;
|
||||
long last_electric_rotations = electric_rotations;
|
||||
int8_t last_electric_sector = electric_sector;
|
||||
interrupts();
|
||||
angle_prev = ((float)((last_electric_rotations * 6 + last_electric_sector) % cpr) / (float)cpr) * _2PI ;
|
||||
full_rotations = (int32_t)((last_electric_rotations * 6 + last_electric_sector) / cpr);
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*
|
||||
Shaft angle calculation
|
||||
TODO: numerical precision issue here if the electrical rotation overflows the angle will be lost
|
||||
*/
|
||||
float HallSensor::getSensorAngle() {
|
||||
return ((float)(electric_rotations * 6 + electric_sector) / (float)cpr) * _2PI ;
|
||||
}
|
||||
|
||||
/*
|
||||
Shaft velocity calculation
|
||||
function using mixed time and frequency measurement technique
|
||||
*/
|
||||
float HallSensor::getVelocity(){
|
||||
noInterrupts();
|
||||
long last_pulse_timestamp = pulse_timestamp;
|
||||
long last_pulse_diff = pulse_diff;
|
||||
interrupts();
|
||||
if (last_pulse_diff == 0 || ((long)(_micros() - last_pulse_timestamp) > last_pulse_diff*2) ) { // last velocity isn't accurate if too old
|
||||
return 0;
|
||||
} else {
|
||||
return direction * (_2PI / (float)cpr) / (last_pulse_diff / 1000000.0f);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// HallSensor initialisation of the hardware pins
|
||||
// and calculation variables
|
||||
void HallSensor::init(){
|
||||
// initialise the electrical rotations to 0
|
||||
electric_rotations = 0;
|
||||
|
||||
// HallSensor - check if pullup needed for your HallSensor
|
||||
if(pullup == Pullup::USE_INTERN){
|
||||
pinMode(pinA, INPUT_PULLUP);
|
||||
pinMode(pinB, INPUT_PULLUP);
|
||||
pinMode(pinC, INPUT_PULLUP);
|
||||
}else{
|
||||
pinMode(pinA, INPUT);
|
||||
pinMode(pinB, INPUT);
|
||||
pinMode(pinC, INPUT);
|
||||
}
|
||||
|
||||
// init hall_state
|
||||
A_active= digitalRead(pinA);
|
||||
B_active = digitalRead(pinB);
|
||||
C_active = digitalRead(pinC);
|
||||
updateState();
|
||||
|
||||
pulse_timestamp = _micros();
|
||||
|
||||
// we don't call Sensor::init() here because init is handled in HallSensor class.
|
||||
}
|
||||
|
||||
// function enabling hardware interrupts for the callback provided
|
||||
// if callback is not provided then the interrupt is not enabled
|
||||
void HallSensor::enableInterrupts(void (*doA)(), void(*doB)(), void(*doC)()){
|
||||
// attach interrupt if functions provided
|
||||
|
||||
// A, B and C callback
|
||||
if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE);
|
||||
if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE);
|
||||
if(doC != nullptr) attachInterrupt(digitalPinToInterrupt(pinC), doC, CHANGE);
|
||||
}
|
||||
98
firmware/lib/Arduino-FOC/src/sensors/HallSensor.h
Normal file
98
firmware/lib/Arduino-FOC/src/sensors/HallSensor.h
Normal file
@@ -0,0 +1,98 @@
|
||||
#ifndef HALL_SENSOR_LIB_H
|
||||
#define HALL_SENSOR_LIB_H
|
||||
|
||||
#include "Arduino.h"
|
||||
#include "../common/base_classes/Sensor.h"
|
||||
#include "../common/foc_utils.h"
|
||||
#include "../common/time_utils.h"
|
||||
|
||||
// seq 1 > 5 > 4 > 6 > 2 > 3 > 1 000 001 010 011 100 101 110 111
|
||||
const int8_t ELECTRIC_SECTORS[8] = { -1, 0, 4, 5, 2, 1, 3 , -1 };
|
||||
|
||||
class HallSensor: public Sensor{
|
||||
public:
|
||||
/**
|
||||
HallSensor class constructor
|
||||
@param encA HallSensor A pin
|
||||
@param encB HallSensor B pin
|
||||
@param encC HallSensor C pin
|
||||
@param pp pole pairs (e.g hoverboard motor has 15pp and small gimbals often have 7pp)
|
||||
@param index index pin number (optional input)
|
||||
*/
|
||||
HallSensor(int encA, int encB, int encC, int pp);
|
||||
|
||||
/** HallSensor initialise pins */
|
||||
void init();
|
||||
/**
|
||||
* function enabling hardware interrupts for the HallSensor channels with provided callback functions
|
||||
* if callback is not provided then the interrupt is not enabled
|
||||
*
|
||||
* @param doA pointer to the A channel interrupt handler function
|
||||
* @param doB pointer to the B channel interrupt handler function
|
||||
* @param doIndex pointer to the Index channel interrupt handler function
|
||||
*
|
||||
*/
|
||||
void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doC)() = nullptr);
|
||||
|
||||
// HallSensor interrupt callback functions
|
||||
/** A channel callback function */
|
||||
void handleA();
|
||||
/** B channel callback function */
|
||||
void handleB();
|
||||
/** C channel callback function */
|
||||
void handleC();
|
||||
|
||||
|
||||
// pins A and B
|
||||
int pinA; //!< HallSensor hardware pin A
|
||||
int pinB; //!< HallSensor hardware pin B
|
||||
int pinC; //!< HallSensor hardware pin C
|
||||
|
||||
// HallSensor configuration
|
||||
Pullup pullup; //!< Configuration parameter internal or external pullups
|
||||
int cpr;//!< HallSensor cpr number
|
||||
|
||||
// Abstract functions of the Sensor class implementation
|
||||
/** Interrupt-safe update */
|
||||
void update() override;
|
||||
/** get current angle (rad) */
|
||||
float getSensorAngle() override;
|
||||
/** get current angular velocity (rad/s) */
|
||||
float getVelocity() override;
|
||||
|
||||
// whether last step was CW (+1) or CCW (-1).
|
||||
Direction direction;
|
||||
|
||||
void attachSectorCallback(void (*onSectorChange)(int a) = nullptr);
|
||||
|
||||
// the current 3bit state of the hall sensors
|
||||
volatile int8_t hall_state;
|
||||
// the current sector of the sensor. Each sector is 60deg electrical
|
||||
volatile int8_t electric_sector;
|
||||
// the number of electric rotations
|
||||
volatile long electric_rotations;
|
||||
// this is sometimes useful to identify interrupt issues (e.g. weak or no pullup resulting in 1000s of interrupts)
|
||||
volatile long total_interrupts;
|
||||
|
||||
// variable used to filter outliers - rad/s
|
||||
float velocity_max = 1000.0f;
|
||||
|
||||
private:
|
||||
|
||||
Direction decodeDirection(int oldState, int newState);
|
||||
void updateState();
|
||||
|
||||
volatile unsigned long pulse_timestamp;//!< last impulse timestamp in us
|
||||
volatile int A_active; //!< current active states of A channel
|
||||
volatile int B_active; //!< current active states of B channel
|
||||
volatile int C_active; //!< current active states of C channel
|
||||
|
||||
// function pointer for on sector change call back
|
||||
void (*onSectorChange)(int sector) = nullptr;
|
||||
|
||||
volatile long pulse_diff;
|
||||
|
||||
};
|
||||
|
||||
|
||||
#endif
|
||||
@@ -0,0 +1,42 @@
|
||||
#include "MagneticSensorAnalog.h"
|
||||
|
||||
/** MagneticSensorAnalog(uint8_t _pinAnalog, int _min, int _max)
|
||||
* @param _pinAnalog the pin that is reading the pwm from magnetic sensor
|
||||
* @param _min_raw_count the smallest expected reading. Whilst you might expect it to be 0 it is often ~15. Getting this wrong results in a small click once per revolution
|
||||
* @param _max_raw_count the largest value read. whilst you might expect it to be 2^10 = 1023 it is often ~ 1020. Note: For ESP32 (with 12bit ADC the value will be nearer 4096)
|
||||
*/
|
||||
MagneticSensorAnalog::MagneticSensorAnalog(uint8_t _pinAnalog, int _min_raw_count, int _max_raw_count){
|
||||
|
||||
pinAnalog = _pinAnalog;
|
||||
|
||||
cpr = _max_raw_count - _min_raw_count;
|
||||
min_raw_count = _min_raw_count;
|
||||
max_raw_count = _max_raw_count;
|
||||
|
||||
if(pullup == Pullup::USE_INTERN){
|
||||
pinMode(pinAnalog, INPUT_PULLUP);
|
||||
}else{
|
||||
pinMode(pinAnalog, INPUT);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
void MagneticSensorAnalog::init(){
|
||||
raw_count = getRawCount();
|
||||
|
||||
this->Sensor::init(); // call base class init
|
||||
}
|
||||
|
||||
// Shaft angle calculation
|
||||
// angle is in radians [rad]
|
||||
float MagneticSensorAnalog::getSensorAngle(){
|
||||
// raw data from the sensor
|
||||
raw_count = getRawCount();
|
||||
return ( (float) (raw_count) / (float)cpr) * _2PI;
|
||||
}
|
||||
|
||||
// function reading the raw counter of the magnetic sensor
|
||||
int MagneticSensorAnalog::getRawCount(){
|
||||
return analogRead(pinAnalog);
|
||||
}
|
||||
51
firmware/lib/Arduino-FOC/src/sensors/MagneticSensorAnalog.h
Normal file
51
firmware/lib/Arduino-FOC/src/sensors/MagneticSensorAnalog.h
Normal file
@@ -0,0 +1,51 @@
|
||||
#ifndef MAGNETICSENSORANALOG_LIB_H
|
||||
#define MAGNETICSENSORANALOG_LIB_H
|
||||
|
||||
#include "Arduino.h"
|
||||
#include "../common/base_classes/Sensor.h"
|
||||
#include "../common/foc_utils.h"
|
||||
#include "../common/time_utils.h"
|
||||
|
||||
/**
|
||||
* This sensor has been tested with AS5600 running in 'analog mode'. This is where output pin of AS6000 is connected to an analog pin on your microcontroller.
|
||||
* This approach is very simple but you may more accurate results with MagneticSensorI2C if that is also supported as its skips the DAC -> ADC conversion (ADC supports MagneticSensorI2C)
|
||||
*/
|
||||
class MagneticSensorAnalog: public Sensor{
|
||||
public:
|
||||
/**
|
||||
* MagneticSensorAnalog class constructor
|
||||
* @param _pinAnalog the pin to read the PWM signal
|
||||
*/
|
||||
MagneticSensorAnalog(uint8_t _pinAnalog, int _min = 0, int _max = 0);
|
||||
|
||||
|
||||
/** sensor initialise pins */
|
||||
void init();
|
||||
|
||||
int pinAnalog; //!< encoder hardware pin A
|
||||
|
||||
// Encoder configuration
|
||||
Pullup pullup;
|
||||
|
||||
// implementation of abstract functions of the Sensor class
|
||||
/** get current angle (rad) */
|
||||
float getSensorAngle() override;
|
||||
/** raw count (typically in range of 0-1023), useful for debugging resolution issues */
|
||||
int raw_count;
|
||||
|
||||
private:
|
||||
int min_raw_count;
|
||||
int max_raw_count;
|
||||
int cpr;
|
||||
int read();
|
||||
|
||||
/**
|
||||
* Function getting current angle register value
|
||||
* it uses angle_register variable
|
||||
*/
|
||||
int getRawCount();
|
||||
|
||||
};
|
||||
|
||||
|
||||
#endif
|
||||
156
firmware/lib/Arduino-FOC/src/sensors/MagneticSensorI2C.cpp
Normal file
156
firmware/lib/Arduino-FOC/src/sensors/MagneticSensorI2C.cpp
Normal file
@@ -0,0 +1,156 @@
|
||||
#include "MagneticSensorI2C.h"
|
||||
|
||||
/** Typical configuration for the 12bit AMS AS5600 magnetic sensor over I2C interface */
|
||||
MagneticSensorI2CConfig_s AS5600_I2C = {
|
||||
.chip_address = 0x36,
|
||||
.bit_resolution = 12,
|
||||
.angle_register = 0x0C,
|
||||
.data_start_bit = 11
|
||||
};
|
||||
|
||||
/** Typical configuration for the 12bit AMS AS5048 magnetic sensor over I2C interface */
|
||||
MagneticSensorI2CConfig_s AS5048_I2C = {
|
||||
.chip_address = 0x40, // highly configurable. if A1 and A2 are held low, this is probable value
|
||||
.bit_resolution = 14,
|
||||
.angle_register = 0xFE,
|
||||
.data_start_bit = 15
|
||||
};
|
||||
|
||||
|
||||
// MagneticSensorI2C(uint8_t _chip_address, float _cpr, uint8_t _angle_register_msb)
|
||||
// @param _chip_address I2C chip address
|
||||
// @param _bit_resolution bit resolution of the sensor
|
||||
// @param _angle_register_msb angle read register
|
||||
// @param _bits_used_msb number of used bits in msb
|
||||
MagneticSensorI2C::MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, uint8_t _angle_register_msb, int _bits_used_msb){
|
||||
// chip I2C address
|
||||
chip_address = _chip_address;
|
||||
// angle read register of the magnetic sensor
|
||||
angle_register_msb = _angle_register_msb;
|
||||
// register maximum value (counts per revolution)
|
||||
cpr = _powtwo(_bit_resolution);
|
||||
|
||||
// depending on the sensor architecture there are different combinations of
|
||||
// LSB and MSB register used bits
|
||||
// AS5600 uses 0..7 LSB and 8..11 MSB
|
||||
// AS5048 uses 0..5 LSB and 6..13 MSB
|
||||
// used bits in LSB
|
||||
lsb_used = _bit_resolution - _bits_used_msb;
|
||||
// extraction masks
|
||||
lsb_mask = (uint8_t)( (2 << lsb_used) - 1 );
|
||||
msb_mask = (uint8_t)( (2 << _bits_used_msb) - 1 );
|
||||
wire = &Wire;
|
||||
}
|
||||
|
||||
MagneticSensorI2C::MagneticSensorI2C(MagneticSensorI2CConfig_s config){
|
||||
chip_address = config.chip_address;
|
||||
|
||||
// angle read register of the magnetic sensor
|
||||
angle_register_msb = config.angle_register;
|
||||
// register maximum value (counts per revolution)
|
||||
cpr = _powtwo(config.bit_resolution);
|
||||
|
||||
int bits_used_msb = config.data_start_bit - 7;
|
||||
lsb_used = config.bit_resolution - bits_used_msb;
|
||||
// extraction masks
|
||||
lsb_mask = (uint8_t)( (2 << lsb_used) - 1 );
|
||||
msb_mask = (uint8_t)( (2 << bits_used_msb) - 1 );
|
||||
wire = &Wire;
|
||||
}
|
||||
|
||||
void MagneticSensorI2C::init(TwoWire* _wire){
|
||||
|
||||
wire = _wire;
|
||||
|
||||
// I2C communication begin
|
||||
wire->begin();
|
||||
|
||||
this->Sensor::init(); // call base class init
|
||||
}
|
||||
|
||||
// Shaft angle calculation
|
||||
// angle is in radians [rad]
|
||||
float MagneticSensorI2C::getSensorAngle(){
|
||||
// (number of full rotations)*2PI + current sensor angle
|
||||
return ( getRawCount() / (float)cpr) * _2PI ;
|
||||
}
|
||||
|
||||
|
||||
|
||||
// function reading the raw counter of the magnetic sensor
|
||||
int MagneticSensorI2C::getRawCount(){
|
||||
return (int)MagneticSensorI2C::read(angle_register_msb);
|
||||
}
|
||||
|
||||
// I2C functions
|
||||
/*
|
||||
* Read a register from the sensor
|
||||
* Takes the address of the register as a uint8_t
|
||||
* Returns the value of the register
|
||||
*/
|
||||
int MagneticSensorI2C::read(uint8_t angle_reg_msb) {
|
||||
// read the angle register first MSB then LSB
|
||||
byte readArray[2];
|
||||
uint16_t readValue = 0;
|
||||
// notify the device that is aboout to be read
|
||||
wire->beginTransmission(chip_address);
|
||||
wire->write(angle_reg_msb);
|
||||
currWireError = wire->endTransmission(false);
|
||||
|
||||
// read the data msb and lsb
|
||||
wire->requestFrom(chip_address, (uint8_t)2);
|
||||
for (byte i=0; i < 2; i++) {
|
||||
readArray[i] = wire->read();
|
||||
}
|
||||
|
||||
// depending on the sensor architecture there are different combinations of
|
||||
// LSB and MSB register used bits
|
||||
// AS5600 uses 0..7 LSB and 8..11 MSB
|
||||
// AS5048 uses 0..5 LSB and 6..13 MSB
|
||||
readValue = ( readArray[1] & lsb_mask );
|
||||
readValue += ( ( readArray[0] & msb_mask ) << lsb_used );
|
||||
return readValue;
|
||||
}
|
||||
|
||||
/*
|
||||
* Checks whether other devices have locked the bus. Can clear SDA locks.
|
||||
* This should be called before sensor.init() on devices that suffer i2c slaves locking sda
|
||||
* e.g some stm32 boards with AS5600 chips
|
||||
* Takes the sda_pin and scl_pin
|
||||
* Returns 0 for OK, 1 for other master and 2 for unfixable sda locked LOW
|
||||
*/
|
||||
int MagneticSensorI2C::checkBus(byte sda_pin, byte scl_pin) {
|
||||
|
||||
pinMode(scl_pin, INPUT_PULLUP);
|
||||
pinMode(sda_pin, INPUT_PULLUP);
|
||||
delay(250);
|
||||
|
||||
if (digitalRead(scl_pin) == LOW) {
|
||||
// Someone else has claimed master!");
|
||||
return 1;
|
||||
}
|
||||
|
||||
if(digitalRead(sda_pin) == LOW) {
|
||||
// slave is communicating and awaiting clocks, we are blocked
|
||||
pinMode(scl_pin, OUTPUT);
|
||||
for (byte i = 0; i < 16; i++) {
|
||||
// toggle clock for 2 bytes of data
|
||||
digitalWrite(scl_pin, LOW);
|
||||
delayMicroseconds(20);
|
||||
digitalWrite(scl_pin, HIGH);
|
||||
delayMicroseconds(20);
|
||||
}
|
||||
pinMode(sda_pin, INPUT);
|
||||
delayMicroseconds(20);
|
||||
if (digitalRead(sda_pin) == LOW) {
|
||||
// SDA still blocked
|
||||
return 2;
|
||||
}
|
||||
_delay(1000);
|
||||
}
|
||||
// SDA is clear (HIGH)
|
||||
pinMode(sda_pin, INPUT);
|
||||
pinMode(scl_pin, INPUT);
|
||||
|
||||
return 0;
|
||||
}
|
||||
84
firmware/lib/Arduino-FOC/src/sensors/MagneticSensorI2C.h
Normal file
84
firmware/lib/Arduino-FOC/src/sensors/MagneticSensorI2C.h
Normal file
@@ -0,0 +1,84 @@
|
||||
#ifndef MAGNETICSENSORI2C_LIB_H
|
||||
#define MAGNETICSENSORI2C_LIB_H
|
||||
|
||||
#include "Arduino.h"
|
||||
#include <Wire.h>
|
||||
#include "../common/base_classes/Sensor.h"
|
||||
#include "../common/foc_utils.h"
|
||||
#include "../common/time_utils.h"
|
||||
|
||||
struct MagneticSensorI2CConfig_s {
|
||||
int chip_address;
|
||||
int bit_resolution;
|
||||
int angle_register;
|
||||
int data_start_bit;
|
||||
};
|
||||
// some predefined structures
|
||||
extern MagneticSensorI2CConfig_s AS5600_I2C,AS5048_I2C;
|
||||
|
||||
#if defined(TARGET_RP2040)
|
||||
#define SDA I2C_SDA
|
||||
#define SCL I2C_SCL
|
||||
#endif
|
||||
|
||||
|
||||
class MagneticSensorI2C: public Sensor{
|
||||
public:
|
||||
/**
|
||||
* MagneticSensorI2C class constructor
|
||||
* @param chip_address I2C chip address
|
||||
* @param bits number of bits of the sensor resolution
|
||||
* @param angle_register_msb angle read register msb
|
||||
* @param _bits_used_msb number of used bits in msb
|
||||
*/
|
||||
MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, uint8_t _angle_register_msb, int _msb_bits_used);
|
||||
|
||||
/**
|
||||
* MagneticSensorI2C class constructor
|
||||
* @param config I2C config
|
||||
*/
|
||||
MagneticSensorI2C(MagneticSensorI2CConfig_s config);
|
||||
|
||||
static MagneticSensorI2C AS5600();
|
||||
|
||||
/** sensor initialise pins */
|
||||
void init(TwoWire* _wire = &Wire);
|
||||
|
||||
// implementation of abstract functions of the Sensor class
|
||||
/** get current angle (rad) */
|
||||
float getSensorAngle() override;
|
||||
|
||||
/** experimental function to check and fix SDA locked LOW issues */
|
||||
int checkBus(byte sda_pin , byte scl_pin );
|
||||
|
||||
/** current error code from Wire endTransmission() call **/
|
||||
uint8_t currWireError = 0;
|
||||
|
||||
private:
|
||||
float cpr; //!< Maximum range of the magnetic sensor
|
||||
uint16_t lsb_used; //!< Number of bits used in LSB register
|
||||
uint8_t lsb_mask;
|
||||
uint8_t msb_mask;
|
||||
|
||||
// I2C variables
|
||||
uint8_t angle_register_msb; //!< I2C angle register to read
|
||||
uint8_t chip_address; //!< I2C chip select pins
|
||||
|
||||
// I2C functions
|
||||
/** Read one I2C register value */
|
||||
int read(uint8_t angle_register_msb);
|
||||
|
||||
/**
|
||||
* Function getting current angle register value
|
||||
* it uses angle_register variable
|
||||
*/
|
||||
int getRawCount();
|
||||
|
||||
/* the two wire instance for this sensor */
|
||||
TwoWire* wire;
|
||||
|
||||
|
||||
};
|
||||
|
||||
|
||||
#endif
|
||||
117
firmware/lib/Arduino-FOC/src/sensors/MagneticSensorPWM.cpp
Normal file
117
firmware/lib/Arduino-FOC/src/sensors/MagneticSensorPWM.cpp
Normal file
@@ -0,0 +1,117 @@
|
||||
#include "MagneticSensorPWM.h"
|
||||
#include "Arduino.h"
|
||||
|
||||
/** MagneticSensorPWM(uint8_t _pinPWM, int _min, int _max)
|
||||
* @param _pinPWM the pin that is reading the pwm from magnetic sensor
|
||||
* @param _min_raw_count the smallest expected reading
|
||||
* @param _max_raw_count the largest expected reading
|
||||
*/
|
||||
MagneticSensorPWM::MagneticSensorPWM(uint8_t _pinPWM, int _min_raw_count, int _max_raw_count){
|
||||
|
||||
pinPWM = _pinPWM;
|
||||
|
||||
cpr = _max_raw_count - _min_raw_count + 1;
|
||||
min_raw_count = _min_raw_count;
|
||||
max_raw_count = _max_raw_count;
|
||||
|
||||
// define if the sensor uses interrupts
|
||||
is_interrupt_based = false;
|
||||
|
||||
// define as not set
|
||||
last_call_us = _micros();
|
||||
}
|
||||
|
||||
|
||||
/** MagneticSensorPWM(uint8_t _pinPWM, int freqHz, int _total_pwm_clocks, int _min_pwm_clocks, int _max_pwm_clocks)
|
||||
*
|
||||
* Constructor that computes the min and max raw counts based on the PWM frequency and the number of PWM clocks in one period
|
||||
*
|
||||
* @param _pinPWM the pin that is reading the pwm from magnetic sensor
|
||||
* @param freqHz the frequency of the PWM signal, in Hz, e.g. 115, 230, 460 or 920 for the AS5600, depending on the PWM frequency setting
|
||||
* @param _total_pwm_clocks the total number of PWM clocks in one period, e.g. 4351 for the AS5600
|
||||
* @param _min_pwm_clocks the 0 value returned by the sensor, in PWM clocks, e.g. 128 for the AS5600
|
||||
* @param _max_pwm_clocks the largest value returned by the sensor, in PWM clocks, e.g. 4223 for the AS5600
|
||||
*/
|
||||
MagneticSensorPWM::MagneticSensorPWM(uint8_t _pinPWM, int freqHz, int _total_pwm_clocks, int _min_pwm_clocks, int _max_pwm_clocks){
|
||||
|
||||
pinPWM = _pinPWM;
|
||||
|
||||
min_raw_count = lroundf(1000000.0f/freqHz/_total_pwm_clocks*_min_pwm_clocks);
|
||||
max_raw_count = lroundf(1000000.0f/freqHz/_total_pwm_clocks*_max_pwm_clocks);
|
||||
cpr = max_raw_count - min_raw_count + 1;
|
||||
|
||||
// define if the sensor uses interrupts
|
||||
is_interrupt_based = false;
|
||||
|
||||
min_elapsed_time = 1.0f/freqHz; // set the minimum time between two readings
|
||||
|
||||
// define as not set
|
||||
last_call_us = _micros();
|
||||
}
|
||||
|
||||
|
||||
|
||||
void MagneticSensorPWM::init(){
|
||||
|
||||
// initial hardware
|
||||
pinMode(pinPWM, INPUT);
|
||||
raw_count = getRawCount();
|
||||
pulse_timestamp = _micros();
|
||||
|
||||
this->Sensor::init(); // call base class init
|
||||
}
|
||||
|
||||
// Sensor update function. Safely copy volatile interrupt variables into Sensor base class state variables.
|
||||
void MagneticSensorPWM::update() {
|
||||
if (is_interrupt_based)
|
||||
noInterrupts();
|
||||
Sensor::update();
|
||||
angle_prev_ts = pulse_timestamp; // Timestamp of actual sample, before the time-consuming PWM communication
|
||||
if (is_interrupt_based)
|
||||
interrupts();
|
||||
}
|
||||
|
||||
// get current angle (rad)
|
||||
float MagneticSensorPWM::getSensorAngle(){
|
||||
// raw data from sensor
|
||||
raw_count = getRawCount();
|
||||
if (raw_count > max_raw_count) raw_count = max_raw_count;
|
||||
if (raw_count < min_raw_count) raw_count = min_raw_count;
|
||||
return( (float) (raw_count - min_raw_count) / (float)cpr) * _2PI;
|
||||
}
|
||||
|
||||
|
||||
// read the raw counter of the magnetic sensor
|
||||
int MagneticSensorPWM::getRawCount(){
|
||||
if (!is_interrupt_based){ // if it's not interrupt based read the value in a blocking way
|
||||
pulse_timestamp = _micros(); // ideally this should be done right at the rising edge of the pulse
|
||||
pulse_length_us = pulseIn(pinPWM, HIGH, 1200); // 1200us timeout, should this be configurable?
|
||||
}
|
||||
return pulse_length_us;
|
||||
}
|
||||
|
||||
|
||||
void MagneticSensorPWM::handlePWM() {
|
||||
// unsigned long now_us = ticks();
|
||||
unsigned long now_us = _micros();
|
||||
|
||||
// if falling edge, calculate the pulse length
|
||||
if (!digitalRead(pinPWM)) {
|
||||
pulse_length_us = now_us - last_call_us;
|
||||
pulse_timestamp = last_call_us; // angle was sampled at the rising edge of the pulse, so use that timestamp
|
||||
}
|
||||
|
||||
// save the currrent timestamp for the next call
|
||||
last_call_us = now_us;
|
||||
is_interrupt_based = true; // set the flag to true
|
||||
}
|
||||
|
||||
// function enabling hardware interrupts of the for the callback provided
|
||||
// if callback is not provided then the interrupt is not enabled
|
||||
void MagneticSensorPWM::enableInterrupt(void (*doPWM)()){
|
||||
// declare it's interrupt based
|
||||
is_interrupt_based = true;
|
||||
|
||||
// enable interrupts on pwm input pin
|
||||
attachInterrupt(digitalPinToInterrupt(pinPWM), doPWM, CHANGE);
|
||||
}
|
||||
73
firmware/lib/Arduino-FOC/src/sensors/MagneticSensorPWM.h
Normal file
73
firmware/lib/Arduino-FOC/src/sensors/MagneticSensorPWM.h
Normal file
@@ -0,0 +1,73 @@
|
||||
#ifndef MAGNETICSENSORPWM_LIB_H
|
||||
#define MAGNETICSENSORPWM_LIB_H
|
||||
|
||||
#include "Arduino.h"
|
||||
#include "../common/base_classes/Sensor.h"
|
||||
#include "../common/foc_utils.h"
|
||||
#include "../common/time_utils.h"
|
||||
|
||||
// This sensor has been tested with AS5048a running in PWM mode.
|
||||
|
||||
class MagneticSensorPWM: public Sensor{
|
||||
public:
|
||||
/** MagneticSensorPWM(uint8_t _pinPWM, int _min, int _max)
|
||||
* @param _pinPWM the pin that is reading the pwm from magnetic sensor
|
||||
* @param _min_raw_count the smallest expected reading
|
||||
* @param _max_raw_count the largest expected reading
|
||||
*/
|
||||
MagneticSensorPWM(uint8_t _pinPWM,int _min = 0, int _max = 0);
|
||||
/** MagneticSensorPWM(uint8_t _pinPWM, int freqHz, int _total_pwm_clocks, int _min_pwm_clocks, int _max_pwm_clocks)
|
||||
*
|
||||
* Constructor that computes the min and max raw counts based on the PWM frequency and the number of PWM clocks in one period
|
||||
*
|
||||
* @param _pinPWM the pin that is reading the pwm from magnetic sensor
|
||||
* @param freqHz the frequency of the PWM signal, in Hz, e.g. 115, 230, 460 or 920 for the AS5600, depending on the PWM frequency setting
|
||||
* @param _total_pwm_clocks the total number of PWM clocks in one period, e.g. 4351 for the AS5600
|
||||
* @param _min_pwm_clocks the 0 value returned by the sensor, in PWM clocks, e.g. 128 for the AS5600
|
||||
* @param _max_pwm_clocks the largest value returned by the sensor, in PWM clocks, e.g. 4223 for the AS5600
|
||||
*/
|
||||
MagneticSensorPWM(uint8_t _pinPWM, int freqHz, int _total_pwm_clocks, int _min_pwm_clocks, int _max_pwm_clocks);
|
||||
|
||||
// initialize the sensor hardware
|
||||
void init();
|
||||
|
||||
int pinPWM;
|
||||
|
||||
// Interrupt-safe update
|
||||
void update() override;
|
||||
|
||||
// get current angle (rad)
|
||||
float getSensorAngle() override;
|
||||
|
||||
// pwm handler
|
||||
void handlePWM();
|
||||
void enableInterrupt(void (*doPWM)());
|
||||
unsigned long pulse_length_us;
|
||||
|
||||
private:
|
||||
// raw count (typically in range of 0-1023)
|
||||
int raw_count;
|
||||
int min_raw_count;
|
||||
int max_raw_count;
|
||||
int cpr;
|
||||
|
||||
// flag saying if the readings are interrupt based or not
|
||||
bool is_interrupt_based;
|
||||
|
||||
int read();
|
||||
|
||||
/**
|
||||
* Function getting current angle register value
|
||||
* it uses angle_register variable
|
||||
*/
|
||||
int getRawCount();
|
||||
|
||||
// time tracking variables
|
||||
unsigned long last_call_us;
|
||||
// unsigned long pulse_length_us;
|
||||
unsigned long pulse_timestamp;
|
||||
|
||||
|
||||
};
|
||||
|
||||
#endif
|
||||
161
firmware/lib/Arduino-FOC/src/sensors/MagneticSensorSPI.cpp
Normal file
161
firmware/lib/Arduino-FOC/src/sensors/MagneticSensorSPI.cpp
Normal file
@@ -0,0 +1,161 @@
|
||||
|
||||
#include "MagneticSensorSPI.h"
|
||||
|
||||
/** Typical configuration for the 14bit AMS AS5147 magnetic sensor over SPI interface */
|
||||
MagneticSensorSPIConfig_s AS5147_SPI = {
|
||||
.spi_mode = SPI_MODE1,
|
||||
.clock_speed = 1000000,
|
||||
.bit_resolution = 14,
|
||||
.angle_register = 0x3FFF,
|
||||
.data_start_bit = 13,
|
||||
.command_rw_bit = 14,
|
||||
.command_parity_bit = 15
|
||||
};
|
||||
// AS5048 and AS5047 are the same as AS5147
|
||||
MagneticSensorSPIConfig_s AS5048_SPI = AS5147_SPI;
|
||||
MagneticSensorSPIConfig_s AS5047_SPI = AS5147_SPI;
|
||||
|
||||
/** Typical configuration for the 14bit MonolithicPower MA730 magnetic sensor over SPI interface */
|
||||
MagneticSensorSPIConfig_s MA730_SPI = {
|
||||
.spi_mode = SPI_MODE0,
|
||||
.clock_speed = 1000000,
|
||||
.bit_resolution = 14,
|
||||
.angle_register = 0x0000,
|
||||
.data_start_bit = 15,
|
||||
.command_rw_bit = 0, // not required
|
||||
.command_parity_bit = 0 // parity not implemented
|
||||
};
|
||||
|
||||
|
||||
// MagneticSensorSPI(int cs, float _bit_resolution, int _angle_register)
|
||||
// cs - SPI chip select pin
|
||||
// _bit_resolution sensor resolution bit number
|
||||
// _angle_register - (optional) angle read register - default 0x3FFF
|
||||
MagneticSensorSPI::MagneticSensorSPI(int cs, int _bit_resolution, int _angle_register){
|
||||
|
||||
chip_select_pin = cs;
|
||||
// angle read register of the magnetic sensor
|
||||
angle_register = _angle_register ? _angle_register : DEF_ANGLE_REGISTER;
|
||||
// register maximum value (counts per revolution)
|
||||
cpr = _powtwo(_bit_resolution);
|
||||
spi_mode = SPI_MODE1;
|
||||
clock_speed = 1000000;
|
||||
bit_resolution = _bit_resolution;
|
||||
|
||||
command_parity_bit = 15; // for backwards compatibilty
|
||||
command_rw_bit = 14; // for backwards compatibilty
|
||||
data_start_bit = 13; // for backwards compatibilty
|
||||
}
|
||||
|
||||
MagneticSensorSPI::MagneticSensorSPI(MagneticSensorSPIConfig_s config, int cs){
|
||||
chip_select_pin = cs;
|
||||
// angle read register of the magnetic sensor
|
||||
angle_register = config.angle_register ? config.angle_register : DEF_ANGLE_REGISTER;
|
||||
// register maximum value (counts per revolution)
|
||||
cpr = _powtwo(config.bit_resolution);
|
||||
spi_mode = config.spi_mode;
|
||||
clock_speed = config.clock_speed;
|
||||
bit_resolution = config.bit_resolution;
|
||||
|
||||
command_parity_bit = config.command_parity_bit; // for backwards compatibilty
|
||||
command_rw_bit = config.command_rw_bit; // for backwards compatibilty
|
||||
data_start_bit = config.data_start_bit; // for backwards compatibilty
|
||||
}
|
||||
|
||||
void MagneticSensorSPI::init(SPIClass* _spi){
|
||||
spi = _spi;
|
||||
// 1MHz clock (AMS should be able to accept up to 10MHz)
|
||||
settings = SPISettings(clock_speed, MSBFIRST, spi_mode);
|
||||
//setup pins
|
||||
pinMode(chip_select_pin, OUTPUT);
|
||||
//SPI has an internal SPI-device counter, it is possible to call "begin()" from different devices
|
||||
spi->begin();
|
||||
// do any architectures need to set the clock divider for SPI? Why was this in the code?
|
||||
//spi->setClockDivider(SPI_CLOCK_DIV8);
|
||||
digitalWrite(chip_select_pin, HIGH);
|
||||
|
||||
this->Sensor::init(); // call base class init
|
||||
}
|
||||
|
||||
// Shaft angle calculation
|
||||
// angle is in radians [rad]
|
||||
float MagneticSensorSPI::getSensorAngle(){
|
||||
return (getRawCount() / (float)cpr) * _2PI;
|
||||
}
|
||||
|
||||
// function reading the raw counter of the magnetic sensor
|
||||
int MagneticSensorSPI::getRawCount(){
|
||||
return (int)MagneticSensorSPI::read(angle_register);
|
||||
}
|
||||
|
||||
// SPI functions
|
||||
/**
|
||||
* Utility function used to calculate even parity of word
|
||||
*/
|
||||
byte MagneticSensorSPI::spiCalcEvenParity(word value){
|
||||
byte cnt = 0;
|
||||
byte i;
|
||||
|
||||
for (i = 0; i < 16; i++)
|
||||
{
|
||||
if (value & 0x1) cnt++;
|
||||
value >>= 1;
|
||||
}
|
||||
return cnt & 0x1;
|
||||
}
|
||||
|
||||
/*
|
||||
* Read a register from the sensor
|
||||
* Takes the address of the register as a 16 bit word
|
||||
* Returns the value of the register
|
||||
*/
|
||||
word MagneticSensorSPI::read(word angle_register){
|
||||
|
||||
word command = angle_register;
|
||||
|
||||
if (command_rw_bit > 0) {
|
||||
command = angle_register | (1 << command_rw_bit);
|
||||
}
|
||||
if (command_parity_bit > 0) {
|
||||
//Add a parity bit on the the MSB
|
||||
command |= ((word)spiCalcEvenParity(command) << command_parity_bit);
|
||||
}
|
||||
|
||||
//SPI - begin transaction
|
||||
spi->beginTransaction(settings);
|
||||
|
||||
//Send the command
|
||||
digitalWrite(chip_select_pin, LOW);
|
||||
spi->transfer16(command);
|
||||
digitalWrite(chip_select_pin,HIGH);
|
||||
|
||||
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) // if ESP32 board
|
||||
delayMicroseconds(50); // why do we need to delay 50us on ESP32? In my experience no extra delays are needed, on any of the architectures I've tested...
|
||||
#else
|
||||
delayMicroseconds(1); // delay 1us, the minimum time possible in plain arduino. 350ns is the required time for AMS sensors, 80ns for MA730, MA702
|
||||
#endif
|
||||
|
||||
//Now read the response
|
||||
digitalWrite(chip_select_pin, LOW);
|
||||
word register_value = spi->transfer16(0x00);
|
||||
digitalWrite(chip_select_pin, HIGH);
|
||||
|
||||
//SPI - end transaction
|
||||
spi->endTransaction();
|
||||
|
||||
register_value = register_value >> (1 + data_start_bit - bit_resolution); //this should shift data to the rightmost bits of the word
|
||||
|
||||
const static word data_mask = 0xFFFF >> (16 - bit_resolution);
|
||||
|
||||
return register_value & data_mask; // Return the data, stripping the non data (e.g parity) bits
|
||||
}
|
||||
|
||||
/**
|
||||
* Closes the SPI connection
|
||||
* SPI has an internal SPI-device counter, for each init()-call the close() function must be called exactly 1 time
|
||||
*/
|
||||
void MagneticSensorSPI::close(){
|
||||
spi->end();
|
||||
}
|
||||
|
||||
|
||||
84
firmware/lib/Arduino-FOC/src/sensors/MagneticSensorSPI.h
Normal file
84
firmware/lib/Arduino-FOC/src/sensors/MagneticSensorSPI.h
Normal file
@@ -0,0 +1,84 @@
|
||||
#ifndef MAGNETICSENSORSPI_LIB_H
|
||||
#define MAGNETICSENSORSPI_LIB_H
|
||||
|
||||
|
||||
#include "Arduino.h"
|
||||
#include <SPI.h>
|
||||
#include "../common/base_classes/Sensor.h"
|
||||
#include "../common/foc_utils.h"
|
||||
#include "../common/time_utils.h"
|
||||
|
||||
#define DEF_ANGLE_REGISTER 0x3FFF
|
||||
|
||||
struct MagneticSensorSPIConfig_s {
|
||||
int spi_mode;
|
||||
long clock_speed;
|
||||
int bit_resolution;
|
||||
int angle_register;
|
||||
int data_start_bit;
|
||||
int command_rw_bit;
|
||||
int command_parity_bit;
|
||||
};
|
||||
// typical configuration structures
|
||||
extern MagneticSensorSPIConfig_s AS5147_SPI,AS5048_SPI,AS5047_SPI, MA730_SPI;
|
||||
|
||||
class MagneticSensorSPI: public Sensor{
|
||||
public:
|
||||
/**
|
||||
* MagneticSensorSPI class constructor
|
||||
* @param cs SPI chip select pin
|
||||
* @param bit_resolution sensor resolution bit number
|
||||
* @param angle_register (optional) angle read register - default 0x3FFF
|
||||
*/
|
||||
MagneticSensorSPI(int cs, int bit_resolution, int angle_register = 0);
|
||||
/**
|
||||
* MagneticSensorSPI class constructor
|
||||
* @param config SPI config
|
||||
* @param cs SPI chip select pin
|
||||
*/
|
||||
MagneticSensorSPI(MagneticSensorSPIConfig_s config, int cs);
|
||||
|
||||
/** sensor initialise pins */
|
||||
void init(SPIClass* _spi = &SPI);
|
||||
|
||||
// implementation of abstract functions of the Sensor class
|
||||
/** get current angle (rad) */
|
||||
float getSensorAngle() override;
|
||||
|
||||
// returns the spi mode (phase/polarity of read/writes) i.e one of SPI_MODE0 | SPI_MODE1 | SPI_MODE2 | SPI_MODE3
|
||||
int spi_mode;
|
||||
|
||||
/* returns the speed of the SPI clock signal */
|
||||
long clock_speed;
|
||||
|
||||
|
||||
private:
|
||||
float cpr; //!< Maximum range of the magnetic sensor
|
||||
// spi variables
|
||||
int angle_register; //!< SPI angle register to read
|
||||
int chip_select_pin; //!< SPI chip select pin
|
||||
SPISettings settings; //!< SPI settings variable
|
||||
// spi functions
|
||||
/** Stop SPI communication */
|
||||
void close();
|
||||
/** Read one SPI register value */
|
||||
word read(word angle_register);
|
||||
/** Calculate parity value */
|
||||
byte spiCalcEvenParity(word value);
|
||||
|
||||
/**
|
||||
* Function getting current angle register value
|
||||
* it uses angle_register variable
|
||||
*/
|
||||
int getRawCount();
|
||||
|
||||
int bit_resolution; //!< the number of bites of angle data
|
||||
int command_parity_bit; //!< the bit where parity flag is stored in command
|
||||
int command_rw_bit; //!< the bit where read/write flag is stored in command
|
||||
int data_start_bit; //!< the the position of first bit
|
||||
|
||||
SPIClass* spi;
|
||||
};
|
||||
|
||||
|
||||
#endif
|
||||
Reference in New Issue
Block a user