Skip to content

Commit

Permalink
improve getCumulativePosition() (#35)
Browse files Browse the repository at this point in the history
- change **getCumulativePosition()** to use **AS5600_ANGLE**
  so filters can be applied.
- add **AS5600_DEGREES_TO_RAW** to constants.
- add **AS5600_SW_DIRECTION_PIN** to constants.
- minor edits.
  • Loading branch information
RobTillaart committed May 11, 2023
1 parent 8b62620 commit 3232435
Show file tree
Hide file tree
Showing 11 changed files with 191 additions and 60 deletions.
56 changes: 38 additions & 18 deletions AS5600.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
//
// FILE: AS56000.cpp
// AUTHOR: Rob Tillaart
// VERSION: 0.3.6
// VERSION: 0.3.7
// PURPOSE: Arduino library for AS5600 magnetic rotation meter
// DATE: 2022-05-28
// URL: https://github.com/RobTillaart/AS5600
Expand All @@ -12,10 +12,10 @@

// CONFIGURATION REGISTERS
const uint8_t AS5600_ZMCO = 0x00;
const uint8_t AS5600_ZPOS = 0x01; // + 0x02
const uint8_t AS5600_MPOS = 0x03; // + 0x04
const uint8_t AS5600_MANG = 0x05; // + 0x06
const uint8_t AS5600_CONF = 0x07; // + 0x08
const uint8_t AS5600_ZPOS = 0x01; // + 0x02
const uint8_t AS5600_MPOS = 0x03; // + 0x04
const uint8_t AS5600_MANG = 0x05; // + 0x06
const uint8_t AS5600_CONF = 0x07; // + 0x08

// CONFIGURATION BIT MASKS - byte level
const uint8_t AS5600_CONF_POWER_MODE = 0x03;
Expand All @@ -30,8 +30,8 @@ const uint8_t AS5600_CONF_WATCH_DOG = 0x20;
// UNKNOWN REGISTERS 0x09-0x0A

// OUTPUT REGISTERS
const uint8_t AS5600_RAW_ANGLE = 0x0C; // + 0x0D
const uint8_t AS5600_ANGLE = 0x0E; // + 0x0F
const uint8_t AS5600_RAW_ANGLE = 0x0C; // + 0x0D
const uint8_t AS5600_ANGLE = 0x0E; // + 0x0F

// I2C_ADDRESS REGISTERS (AS5600L)
const uint8_t AS5600_I2CADDR = 0x20;
Expand All @@ -40,7 +40,7 @@ const uint8_t AS5600_I2CUPDT = 0x21;
// STATUS REGISTERS
const uint8_t AS5600_STATUS = 0x0B;
const uint8_t AS5600_AGC = 0x1A;
const uint8_t AS5600_MAGNITUDE = 0x1B; // + 0x1C
const uint8_t AS5600_MAGNITUDE = 0x1B; // + 0x1C
const uint8_t AS5600_BURN = 0xFF;

// STATUS BITS
Expand All @@ -59,7 +59,7 @@ AS5600::AS5600(TwoWire *wire)
bool AS5600::begin(int dataPin, int clockPin, uint8_t directionPin)
{
_directionPin = directionPin;
if (_directionPin != 255)
if (_directionPin != AS5600_SW_DIRECTION_PIN)
{
pinMode(_directionPin, OUTPUT);
}
Expand All @@ -81,7 +81,7 @@ bool AS5600::begin(int dataPin, int clockPin, uint8_t directionPin)
bool AS5600::begin(uint8_t directionPin)
{
_directionPin = directionPin;
if (_directionPin != 255)
if (_directionPin != AS5600_SW_DIRECTION_PIN)
{
pinMode(_directionPin, OUTPUT);
}
Expand Down Expand Up @@ -113,7 +113,7 @@ uint8_t AS5600::getAddress()
void AS5600::setDirection(uint8_t direction)
{
_direction = direction;
if (_directionPin != 255)
if (_directionPin != AS5600_SW_DIRECTION_PIN)
{
digitalWrite(_directionPin, _direction);
}
Expand All @@ -122,7 +122,7 @@ void AS5600::setDirection(uint8_t direction)

uint8_t AS5600::getDirection()
{
if (_directionPin != 255)
if (_directionPin != AS5600_SW_DIRECTION_PIN)
{
_direction = digitalRead(_directionPin);
}
Expand Down Expand Up @@ -182,6 +182,10 @@ uint16_t AS5600::getMaxAngle()
}


/////////////////////////////////////////////////////////
//
// CONFIGURATION
//
bool AS5600::setConfigure(uint16_t value)
{
if (value > 0x3FFF) return false;
Expand All @@ -208,11 +212,13 @@ bool AS5600::setPowerMode(uint8_t powerMode)
return true;
}


uint8_t AS5600::getPowerMode()
{
return readReg(AS5600_CONF + 1) & 0x03;
}


bool AS5600::setHysteresis(uint8_t hysteresis)
{
if (hysteresis > 3) return false;
Expand All @@ -223,11 +229,13 @@ bool AS5600::setHysteresis(uint8_t hysteresis)
return true;
}


uint8_t AS5600::getHysteresis()
{
return (readReg(AS5600_CONF + 1) >> 2) & 0x03;
}


bool AS5600::setOutputMode(uint8_t outputMode)
{
if (outputMode > 2) return false;
Expand All @@ -238,11 +246,13 @@ bool AS5600::setOutputMode(uint8_t outputMode)
return true;
}


uint8_t AS5600::getOutputMode()
{
return (readReg(AS5600_CONF + 1) >> 4) & 0x03;
}


bool AS5600::setPWMFrequency(uint8_t pwmFreq)
{
if (pwmFreq > 3) return false;
Expand All @@ -253,11 +263,13 @@ bool AS5600::setPWMFrequency(uint8_t pwmFreq)
return true;
}


uint8_t AS5600::getPWMFrequency()
{
return (readReg(AS5600_CONF + 1) >> 6) & 0x03;
}


bool AS5600::setSlowFilter(uint8_t mask)
{
if (mask > 3) return false;
Expand All @@ -268,11 +280,13 @@ bool AS5600::setSlowFilter(uint8_t mask)
return true;
}


uint8_t AS5600::getSlowFilter()
{
return readReg(AS5600_CONF) & 0x03;
}


bool AS5600::setFastFilter(uint8_t mask)
{
if (mask > 7) return false;
Expand All @@ -283,11 +297,13 @@ bool AS5600::setFastFilter(uint8_t mask)
return true;
}


uint8_t AS5600::getFastFilter()
{
return (readReg(AS5600_CONF) >> 2) & 0x07;
}


bool AS5600::setWatchDog(uint8_t mask)
{
if (mask > 1) return false;
Expand All @@ -298,6 +314,7 @@ bool AS5600::setWatchDog(uint8_t mask)
return true;
}


uint8_t AS5600::getWatchDog()
{
return (readReg(AS5600_CONF) >> 5) & 0x01;
Expand All @@ -313,7 +330,8 @@ uint16_t AS5600::rawAngle()
int16_t value = readReg2(AS5600_RAW_ANGLE) & 0x0FFF;
if (_offset > 0) value = (value + _offset) & 0x0FFF;

if ((_directionPin == 255) && (_direction == AS5600_COUNTERCLOCK_WISE))
if ((_directionPin == AS5600_SW_DIRECTION_PIN) &&
(_direction == AS5600_COUNTERCLOCK_WISE))
{
value = (4096 - value) & 0x0FFF;
}
Expand All @@ -326,7 +344,8 @@ uint16_t AS5600::readAngle()
uint16_t value = readReg2(AS5600_ANGLE) & 0x0FFF;
if (_offset > 0) value = (value + _offset) & 0x0FFF;

if ((_directionPin == 255) && (_direction == AS5600_COUNTERCLOCK_WISE))
if ((_directionPin == AS5600_SW_DIRECTION_PIN) &&
(_direction == AS5600_COUNTERCLOCK_WISE))
{
value = (4096 - value) & 0x0FFF;
}
Expand All @@ -336,12 +355,12 @@ uint16_t AS5600::readAngle()

bool AS5600::setOffset(float degrees)
{
// expect loss of precision.
// expect loss of precision.
if (abs(degrees) > 36000) return false;
bool neg = (degrees < 0);
if (neg) degrees = -degrees;

uint16_t offset = round(degrees * (4096 / 360.0));
uint16_t offset = round(degrees * AS5600_DEGREES_TO_RAW);
offset &= 4095;
if (neg) offset = 4096 - offset;
_offset = offset;
Expand Down Expand Up @@ -433,7 +452,8 @@ float AS5600::getAngularSpeed(uint8_t mode)
// remember last time & angle
_lastMeasurement = now;
_lastAngle = angle;
// return degrees or radians

// return radians, RPM or degrees.
if (mode == AS5600_MODE_RADIANS)
{
return speed * AS5600_RAW_TO_RADIANS;
Expand All @@ -453,7 +473,7 @@ float AS5600::getAngularSpeed(uint8_t mode)
//
int32_t AS5600::getCumulativePosition()
{
int16_t value = readReg2(AS5600_RAW_ANGLE) & 0x0FFF;
int16_t value = readReg2(AS5600_ANGLE) & 0x0FFF;

// whole rotation CW?
// less than half a circle
Expand Down
17 changes: 9 additions & 8 deletions AS5600.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
//
// FILE: AS5600.h
// AUTHOR: Rob Tillaart
// VERSION: 0.3.6
// VERSION: 0.3.7
// PURPOSE: Arduino library for AS5600 magnetic rotation meter
// DATE: 2022-05-28
// URL: https://github.com/RobTillaart/AS5600
Expand All @@ -12,19 +12,20 @@
#include "Wire.h"


#define AS5600_LIB_VERSION (F("0.3.6"))
#define AS5600_LIB_VERSION (F("0.3.7"))

// default addresses
const uint8_t AS5600_DEFAULT_ADDRESS = 0x36;
const uint8_t AS5600L_DEFAULT_ADDRESS = 0x40;

const uint8_t AS5600_SW_DIRECTION_PIN = 255;

// setDirection
const uint8_t AS5600_CLOCK_WISE = 0; // LOW
const uint8_t AS5600_COUNTERCLOCK_WISE = 1; // HIGH

// 0.087890625;
const float AS5600_RAW_TO_DEGREES = 360.0 / 4096;
const float AS5600_DEGREES_TO_RAW = 4096 / 360.0;
// 0.00153398078788564122971808758949;
const float AS5600_RAW_TO_RADIANS = PI * 2.0 / 4096;
// 4.06901041666666e-6
Expand Down Expand Up @@ -89,14 +90,14 @@ class AS5600
AS5600(TwoWire *wire = &Wire);

#if defined (ESP8266) || defined(ESP32)
// 255 is software controlled direction pin
bool begin(int dataPin, int clockPin, uint8_t directionPin = 255);
// AS5600_SW_DIRECTION_PIN is software controlled direction pin
bool begin(int dataPin, int clockPin, uint8_t directionPin = AS5600_SW_DIRECTION_PIN);
#endif
// 255 is software controlled direction pin
bool begin(uint8_t directionPin = 255); // MAGIC NR => const int?
bool begin(uint8_t directionPin = AS5600_SW_DIRECTION_PIN);
bool isConnected();

uint8_t getAddress(); // 0x36 for AS5600, 0x40 for AS5600L
// address = 0x36 for AS5600, 0x40 for AS5600L
uint8_t getAddress();


// SET CONFIGURE REGISTERS
Expand Down
13 changes: 10 additions & 3 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,14 +5,21 @@ The format is based on [Keep a Changelog](http://keepachangelog.com/)
and this project adheres to [Semantic Versioning](http://semver.org/).


## [0.3.7] - 2023-05-09
- change **getCumulativePosition()** to use **AS5600_ANGLE**
so filters can be applied.
- add **AS5600_DEGREES_TO_RAW** to constants.
- add **AS5600_SW_DIRECTION_PIN** to constants.
- minor edits.


## [0.3.6] - 2023-02-20
- add **resetCumulativePosition(int32_t position)** to completely reset the cumulative counter.
- add **resetCumulativePosition(int32_t position)** to completely reset the cumulative counter.
This includes the delta since last call to **getCumulativePosition()**.
- add parameter position to **resetPosition(int32_t position)** so a new position can be set.
- add parameter position to **resetPosition(int32_t position)** so a new position can be set.
This does not reset the delta since last call to **getCumulativePosition()**.
- update readme.md


## [0.3.5] - 2023-02-01
- update GitHub actions
- update license 2023
Expand Down
41 changes: 22 additions & 19 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -185,14 +185,14 @@ Also Configuration bits below for configuration related ones.

- **AS5600(TwoWire \*wire = &Wire)** Constructor with optional Wire
interface as parameter.
- **bool begin(uint8_t directionPin = 255)** set the value for the
directionPin.
If the pin is set to 255, the default value, there will be software
direction control instead of hardware control.
- **bool begin(uint8_t directionPin = AS5600_SW_DIRECTION_PIN)**
set the value for the directionPin.
If the pin is set to AS5600_SW_DIRECTION_PIN, the default value,
there will be software direction control instead of hardware control.
See below.
- **bool begin(int dataPin, int clockPin, uint8_t directionPin = 255)** idem,
- **bool begin(int dataPin, int clockPin, uint8_t directionPin = AS5600_SW_DIRECTION_PIN)** idem,
for the ESP32 where one can choose the I2C pins.
If the pin is set to 255, the default value, there will be software
If the pin is set to AS5600_SW_DIRECTION_PIN, the default value, there will be software
direction control instead of hardware control.
See below.
- **bool isConnected()** checks if the address 0x36 (AS5600) is on the I2C bus.
Expand Down Expand Up @@ -614,32 +614,22 @@ priority is relative.

#### Must

- re-organize readme (0.4.0 ?)
- fix for AS5600L as it does not support analog OUT.
- type field?
- other class hierarchy?
- base class with commonalities?
- just ignore?
- re-organize readme (0.4.0)
- rename revolution functions (0.4.0)
- to what?


#### Should

- investigate **readMagnitude()**
- combination of AGC and MD, ML and MH flags?
- investigate performance
- basic performance per function
- I2C improvements
- software direction
- investigate OUT behaviour in practice
- analogue
- PWM
- need AS5600 on breakout with support
- write examples:
- as5600_calibration.ino (needs HW and lots of time)
- different configuration options
- add mode parameter to offset functions.
- see getAngularSpeed()
- check / verify Power-up time
- 1 minute (need HW)
- check Timing Characteristics (datasheet)
Expand All @@ -654,7 +644,20 @@ priority is relative.
- investigate PGO programming pin.
- check for compatible devices
- AS5200 ?
- investigate performance
- basic performance per function
- I2C improvements
- software direction


#### Wont
#### Wont (unless)

- fix for AS5600L as it does not support analog OUT.
- type field?
- other class hierarchy?
- base class with commonalities?
- ==> just ignore for now.
- add mode parameter to offset functions.
- see getAngularSpeed()


Loading

0 comments on commit 3232435

Please sign in to comment.