mirror of
https://github.com/RobTillaart/Arduino.git
synced 2024-10-03 18:09:02 -04:00
add AD5144A
This commit is contained in:
parent
a1426e325d
commit
105ec63998
7
libraries/AD5144A/.arduino-ci.yml
Normal file
7
libraries/AD5144A/.arduino-ci.yml
Normal file
@ -0,0 +1,7 @@
|
||||
compile:
|
||||
# Choosing to run compilation tests on 2 different Arduino platforms
|
||||
platforms:
|
||||
- uno
|
||||
- leonardo
|
||||
- due
|
||||
- zero
|
13
libraries/AD5144A/.github/workflows/arduino_test_runner.yml
vendored
Normal file
13
libraries/AD5144A/.github/workflows/arduino_test_runner.yml
vendored
Normal file
@ -0,0 +1,13 @@
|
||||
---
|
||||
name: Arduino CI
|
||||
|
||||
on: [push, pull_request]
|
||||
|
||||
jobs:
|
||||
arduino_ci:
|
||||
runs-on: ubuntu-latest
|
||||
|
||||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
- uses: Arduino-CI/action@master
|
||||
# Arduino-CI/action@v0.1.1
|
18
libraries/AD5144A/.github/workflows/jsoncheck.yml
vendored
Normal file
18
libraries/AD5144A/.github/workflows/jsoncheck.yml
vendored
Normal file
@ -0,0 +1,18 @@
|
||||
name: JSON check
|
||||
|
||||
on:
|
||||
push:
|
||||
paths:
|
||||
- '**.json'
|
||||
pull_request:
|
||||
|
||||
jobs:
|
||||
test:
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
- name: json-syntax-check
|
||||
uses: limitusus/json-syntax-check@v1
|
||||
with:
|
||||
pattern: "\\.json$"
|
||||
|
440
libraries/AD5144A/AD5144A.cpp
Normal file
440
libraries/AD5144A/AD5144A.cpp
Normal file
@ -0,0 +1,440 @@
|
||||
//
|
||||
// FILE: AD5144A.cpp
|
||||
// AUTHOR: Rob Tillaart
|
||||
// VERSION: 0.1.2
|
||||
// PURPOSE: I2C digital potentiometer AD5144A
|
||||
// DATE: 2021-04-30
|
||||
// URL: https://github.com/RobTillaart/AD5144A
|
||||
//
|
||||
// HISTORY
|
||||
// 0.1.0 2021-04-30 initial version
|
||||
// 0.1.1 2021-05-12 add topScale() and bottomScale()
|
||||
// 0.1.2 2021-05-12 add increment() and decrement() functions
|
||||
|
||||
|
||||
#include "AD5144A.h"
|
||||
|
||||
|
||||
// Commands page 29 datasheet
|
||||
//
|
||||
// not implemented (yet)
|
||||
// 0 NOP
|
||||
// 4 5 linear RDAC in/decrement
|
||||
// 6 7 6dB RDAC in/decrement
|
||||
// 12 13 topscale bottom scale ???
|
||||
|
||||
|
||||
AD51XX::AD51XX(const uint8_t address, TwoWire *wire)
|
||||
{
|
||||
_address = address;
|
||||
_wire = wire;
|
||||
}
|
||||
|
||||
|
||||
#if defined (ESP8266) || defined(ESP32)
|
||||
bool AD51XX::begin(uint8_t dataPin, uint8_t clockPin)
|
||||
{
|
||||
_wire = &Wire;
|
||||
if ((dataPin < 255) && (clockPin < 255))
|
||||
{
|
||||
_wire->begin(dataPin, clockPin);
|
||||
} else {
|
||||
_wire->begin();
|
||||
}
|
||||
if (! isConnected()) return false;
|
||||
reset();
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
bool AD51XX::begin()
|
||||
{
|
||||
_wire->begin();
|
||||
if (! isConnected()) return false;
|
||||
midScaleAll(); // is this what we want?
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
bool AD51XX::isConnected()
|
||||
{
|
||||
_wire->beginTransmission(_address);
|
||||
return ( _wire->endTransmission() == 0);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::reset()
|
||||
{
|
||||
// COMMAND 14 - page 29
|
||||
return send(0xB0, 0x00); // to be tested
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::writeAll(const uint8_t value)
|
||||
{
|
||||
// COMMAND 1 - page 29
|
||||
for (uint8_t pm = 0; pm < _potCount; pm++)
|
||||
{
|
||||
_lastValue[pm] = value;
|
||||
}
|
||||
uint8_t cmd = 0x18;
|
||||
return send(cmd, value);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::write(const uint8_t rdac, const uint8_t value)
|
||||
{
|
||||
// COMMAND 1 - page 29
|
||||
if (rdac >= _potCount) return AD51XXA_INVALID_POT;
|
||||
_lastValue[rdac] = value;
|
||||
uint8_t cmd = 0x10 | rdac;
|
||||
return send(cmd, _lastValue[rdac]);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::storeEEPROM(const uint8_t rdac)
|
||||
{
|
||||
// COMMAND 9 - page 29
|
||||
if (rdac >= _potCount) return AD51XXA_INVALID_POT;
|
||||
uint8_t cmd = 0x70 | rdac;
|
||||
return send(cmd, 0x01);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::recallEEPROM(const uint8_t rdac)
|
||||
{
|
||||
// COMMAND 10 - page 29
|
||||
if (rdac >= _potCount) return AD51XXA_INVALID_POT;
|
||||
_lastValue[rdac] = readBackEEPROM(rdac);
|
||||
uint8_t cmd = 0x70 | rdac;
|
||||
return send(cmd, 0x00);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::storeEEPROM(const uint8_t rdac, const uint8_t value)
|
||||
{
|
||||
// COMMAND 11 - page 29
|
||||
if (rdac >= _potCount) return AD51XXA_INVALID_POT;
|
||||
uint8_t cmd = 0x80 | rdac;
|
||||
return send(cmd, value);
|
||||
}
|
||||
|
||||
///////////////////////////////////////////////////////////
|
||||
|
||||
uint8_t AD51XX::setTopScale(const uint8_t rdac)
|
||||
{
|
||||
// COMMAND 12
|
||||
if (rdac >= _potCount) return AD51XXA_INVALID_POT;
|
||||
uint8_t cmd = 0x90 | rdac;
|
||||
return send(cmd, 0x81);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::clrTopScale(const uint8_t rdac)
|
||||
{
|
||||
// COMMAND 12
|
||||
if (rdac >= _potCount) return AD51XXA_INVALID_POT;
|
||||
uint8_t cmd = 0x90 | rdac;
|
||||
return send(cmd, 0x80);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::setTopScaleAll()
|
||||
{
|
||||
// COMMAND 12
|
||||
uint8_t cmd = 0x98;
|
||||
return send(cmd, 0x81);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::clrTopScaleAll()
|
||||
{
|
||||
// COMMAND 12
|
||||
uint8_t cmd = 0x98;
|
||||
return send(cmd, 0x80);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::setBottomScale(const uint8_t rdac)
|
||||
{
|
||||
// COMMAND 13
|
||||
if (rdac >= _potCount) return AD51XXA_INVALID_POT;
|
||||
uint8_t cmd = 0x90 | rdac;
|
||||
return send(cmd, 0x01);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::clrBottomScale(const uint8_t rdac)
|
||||
{
|
||||
// COMMAND 13
|
||||
if (rdac >= _potCount) return AD51XXA_INVALID_POT;
|
||||
uint8_t cmd = 0x90 | rdac;
|
||||
return send(cmd, 0x00);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::setBottomScaleAll()
|
||||
{
|
||||
// COMMAND 13
|
||||
uint8_t cmd = 0x98;
|
||||
return send(cmd, 0x01);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::clrBottomScaleAll()
|
||||
{
|
||||
// COMMAND 13
|
||||
uint8_t cmd = 0x98;
|
||||
return send(cmd, 0x00);
|
||||
}
|
||||
|
||||
///////////////////////////////////////////////////////////
|
||||
|
||||
uint8_t AD51XX::setLinearMode(const uint8_t rdac)
|
||||
{
|
||||
// COMMAND 3
|
||||
uint8_t mask = readBack(rdac, 0x02);
|
||||
// COMMAND 16 - page 29
|
||||
uint8_t cmd = 0xD0;
|
||||
return send(cmd, mask | 0x04);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::setPotentiometerMode(const uint8_t rdac)
|
||||
{
|
||||
// COMMAND 3
|
||||
uint8_t mask = readBack(rdac, 0x02);
|
||||
// COMMAND 16 - page 29
|
||||
uint8_t cmd = 0xD0;
|
||||
return send(cmd, mask & (~0x04));
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::getOperationalMode(const uint8_t rdac)
|
||||
{
|
||||
uint8_t mask = readBack(rdac, 0x02);
|
||||
return ((mask & 0x04) > 0);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::incrementLinear(const uint8_t rdac)
|
||||
{
|
||||
// COMMAND 4
|
||||
if (rdac >= _potCount) return AD51XXA_INVALID_POT;
|
||||
uint8_t cmd = 0x40 | rdac;
|
||||
return send(cmd, 0x01);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::incrementLinearAll()
|
||||
{
|
||||
// COMMAND 4
|
||||
uint8_t cmd = 0x48;
|
||||
return send(cmd, 0x01);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::decrementLineair(const uint8_t rdac)
|
||||
{
|
||||
// COMMAND 4
|
||||
if (rdac >= _potCount) return AD51XXA_INVALID_POT;
|
||||
uint8_t cmd = 0x40 | rdac;
|
||||
return send(cmd, 0x00);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::decrementLineairAll()
|
||||
{
|
||||
// COMMAND 4
|
||||
uint8_t cmd = 0x48;
|
||||
return send(cmd, 0x00);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::increment6dB(const uint8_t rdac)
|
||||
{
|
||||
// COMMAND 5
|
||||
if (rdac >= _potCount) return AD51XXA_INVALID_POT;
|
||||
uint8_t cmd = 0x50 | rdac;
|
||||
return send(cmd, 0x01);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::increment6dBAll()
|
||||
{
|
||||
// COMMAND 5
|
||||
uint8_t cmd = 0x58;
|
||||
return send(cmd, 0x01);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::decrement6dB(const uint8_t rdac)
|
||||
{
|
||||
// COMMAND 5
|
||||
if (rdac >= _potCount) return AD51XXA_INVALID_POT;
|
||||
uint8_t cmd = 0x50 | rdac;
|
||||
return send(cmd, 0x00);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::decrement6dBAll()
|
||||
{
|
||||
// COMMAND 5
|
||||
uint8_t cmd = 0x58;
|
||||
return send(cmd, 0x00);
|
||||
}
|
||||
|
||||
|
||||
///////////////////////////////////////////////////////////
|
||||
|
||||
uint8_t AD51XX::preload(const uint8_t rdac, const uint8_t value)
|
||||
{
|
||||
// COMMAND 2 - page 29
|
||||
if (rdac >= _potCount) return AD51XXA_INVALID_POT;
|
||||
_lastValue[rdac] = value;
|
||||
uint8_t cmd = 0x20 | rdac;
|
||||
return send(cmd, _lastValue[rdac]);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::preloadAll(const uint8_t value)
|
||||
{
|
||||
// COMMAND 2 - page 29
|
||||
uint8_t cmd = 0x28;
|
||||
return send(cmd, value);
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::sync(const uint8_t mask)
|
||||
{
|
||||
// COMMAND 8 - page 29
|
||||
uint8_t cmd = 0x60 | mask;
|
||||
return send(cmd, 0x00);
|
||||
// keep cache correct.
|
||||
uint8_t m = 0x01;
|
||||
for (uint8_t rdac = 0; rdac < _potCount; rdac++)
|
||||
{
|
||||
if (mask & m)
|
||||
{
|
||||
_lastValue[rdac] = readBackRDAC(rdac);
|
||||
m <<= 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::shutDown()
|
||||
{
|
||||
// COMMAND 15 - table 29
|
||||
return send(0xC8, 0x01); // to be tested
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::writeControlRegister(uint8_t mask)
|
||||
{
|
||||
// COMMAND 16 - page 29
|
||||
uint8_t cmd = 0xD0;
|
||||
return send(cmd, mask);
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////////////
|
||||
//
|
||||
// PRIVATE
|
||||
//
|
||||
/*
|
||||
_wire->endTransmission
|
||||
0:success
|
||||
1:data too long to fit in transmit buffer
|
||||
2:received NACK on transmit of address
|
||||
3:received NACK on transmit of data
|
||||
4:other error
|
||||
*/
|
||||
uint8_t AD51XX::send(const uint8_t cmd, const uint8_t value)
|
||||
{
|
||||
// COMMAND 1 - page 20
|
||||
_wire->beginTransmission(_address); // returns nothing.
|
||||
_wire->write(cmd); // returns bytes written
|
||||
_wire->write(value); // returns bytes written
|
||||
return _wire->endTransmission(); // returns status of actual write..
|
||||
}
|
||||
|
||||
|
||||
uint8_t AD51XX::readBack(const uint8_t rdac, const uint8_t mask)
|
||||
{
|
||||
// COMMAND 3 - page 20
|
||||
_wire->beginTransmission(_address);
|
||||
int a = _wire->write(0x30 | rdac);
|
||||
// Serial.print("READBACK cmd: ");
|
||||
// Serial.print(a);
|
||||
a = _wire->write(mask);
|
||||
// Serial.print(" val: ");
|
||||
// Serial.print(a);
|
||||
a = _wire->endTransmission();
|
||||
// Serial.print(" TX: ");
|
||||
// Serial.println(a);
|
||||
|
||||
a = _wire->requestFrom(_address, (uint8_t)1);
|
||||
Serial.print(" RF: ");
|
||||
Serial.println(a);
|
||||
return _wire->read();
|
||||
}
|
||||
|
||||
/////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
|
||||
AD5123::AD5123(const uint8_t address, TwoWire *wire) : AD51XX(address, wire)
|
||||
{
|
||||
_potCount = 4;
|
||||
_maxValue = 127;
|
||||
}
|
||||
|
||||
AD5124::AD5124(const uint8_t address, TwoWire *wire) : AD51XX(address, wire)
|
||||
{
|
||||
_potCount = 4;
|
||||
_maxValue = 127;
|
||||
}
|
||||
|
||||
AD5143::AD5143(const uint8_t address, TwoWire *wire) : AD51XX(address, wire)
|
||||
{
|
||||
_potCount = 4;
|
||||
_maxValue = 255;
|
||||
}
|
||||
|
||||
AD5144::AD5144(const uint8_t address, TwoWire *wire) : AD51XX(address, wire)
|
||||
{
|
||||
_potCount = 4;
|
||||
_maxValue = 255;
|
||||
}
|
||||
|
||||
AD5144A::AD5144A(const uint8_t address, TwoWire *wire) : AD51XX(address, wire)
|
||||
{
|
||||
_potCount = 4;
|
||||
_maxValue = 255;
|
||||
}
|
||||
|
||||
AD5122A::AD5122A(const uint8_t address, TwoWire *wire) : AD51XX(address, wire)
|
||||
{
|
||||
_potCount = 2;
|
||||
_maxValue = 128;
|
||||
}
|
||||
|
||||
AD5142A::AD5142A(const uint8_t address, TwoWire *wire) : AD51XX(address, wire)
|
||||
{
|
||||
_potCount = 2;
|
||||
_maxValue = 255;
|
||||
}
|
||||
|
||||
AD5121::AD5121(const uint8_t address, TwoWire *wire) : AD51XX(address, wire)
|
||||
{
|
||||
_potCount = 1;
|
||||
_maxValue = 128;
|
||||
}
|
||||
|
||||
AD5141::AD5141(const uint8_t address, TwoWire *wire) : AD51XX(address, wire)
|
||||
{
|
||||
_potCount = 1;
|
||||
_maxValue = 255;
|
||||
}
|
||||
|
||||
// -- END OF FILE --
|
189
libraries/AD5144A/AD5144A.h
Normal file
189
libraries/AD5144A/AD5144A.h
Normal file
@ -0,0 +1,189 @@
|
||||
#pragma once
|
||||
//
|
||||
// FILE: AD5144A.h
|
||||
// AUTHOR: Rob Tillaart
|
||||
// VERSION: 0.1.2
|
||||
// PURPOSE: I2C digital PotentioMeter AD5144A
|
||||
// DATE: 2021-04-30
|
||||
// URL: https://github.com/RobTillaart/AD5144A
|
||||
//
|
||||
|
||||
#include "Arduino.h"
|
||||
#include "Wire.h"
|
||||
|
||||
|
||||
#define AD51XXA_VERSION (F("0.1.2_experimental"))
|
||||
|
||||
|
||||
#define AD51XXA_OK 0
|
||||
#define AD51XXA_ERROR 100
|
||||
#define AD51XXA_INVALID_POT 101
|
||||
|
||||
|
||||
class AD51XX
|
||||
{
|
||||
public:
|
||||
explicit AD51XX(const uint8_t address, TwoWire *wire = &Wire);
|
||||
|
||||
#if defined (ESP8266) || defined(ESP32)
|
||||
bool begin(uint8_t sda, uint8_t scl);
|
||||
#endif
|
||||
bool begin();
|
||||
bool isConnected();
|
||||
|
||||
uint8_t reset();
|
||||
|
||||
// BASE functions
|
||||
// rdac = 0..3 - zero based indexing...
|
||||
uint8_t write(const uint8_t rdac, const uint8_t value);
|
||||
// fast read from cache
|
||||
uint8_t read(const uint8_t rdac) { return _lastValue[rdac]; };
|
||||
|
||||
|
||||
// EEPROM functions
|
||||
// defines power up value; copies between RDAC and EEPROM
|
||||
uint8_t storeEEPROM(const uint8_t rdac);
|
||||
uint8_t storeEEPROM(const uint8_t rdac, const uint8_t value);
|
||||
uint8_t recallEEPROM(const uint8_t rdac);
|
||||
|
||||
|
||||
// ASYNC functions
|
||||
uint8_t writeAll(const uint8_t value); // set all channels to same value
|
||||
uint8_t zeroAll() { return writeAll(0); };
|
||||
uint8_t midScaleAll() { return writeAll((_maxValue + 1)/2); };
|
||||
uint8_t maxAll() { return writeAll(_maxValue); };
|
||||
uint8_t zero(const uint8_t rdac) { return write(rdac, 0); };
|
||||
uint8_t midScale(const uint8_t rdac) { return write(rdac, (_maxValue + 1)/2); };
|
||||
uint8_t mid(const uint8_t rdac) { return midScale(rdac); }; // will be obsolete
|
||||
uint8_t maxValue(const uint8_t rdac) { return write(rdac, _maxValue); };
|
||||
|
||||
|
||||
// page 27
|
||||
uint8_t setTopScale(const uint8_t rdac);
|
||||
uint8_t clrTopScale(const uint8_t rdac);
|
||||
uint8_t setTopScaleAll();
|
||||
uint8_t clrTopScaleAll();
|
||||
uint8_t setBottomScale(const uint8_t rdac);
|
||||
uint8_t clrBottomScale(const uint8_t rdac);
|
||||
uint8_t setBottomScaleAll();
|
||||
uint8_t clrBottomScaleAll();
|
||||
|
||||
|
||||
// page 27-28
|
||||
uint8_t setLinearMode(const uint8_t rdac);
|
||||
uint8_t setPotentiometerMode(const uint8_t rdac);
|
||||
// 0 = potentio, 1 = linear
|
||||
uint8_t getOperationalMode(const uint8_t rdac);
|
||||
|
||||
uint8_t incrementLinear(const uint8_t rdac);
|
||||
uint8_t incrementLinearAll();
|
||||
uint8_t decrementLineair(const uint8_t rdac);
|
||||
uint8_t decrementLineairAll();
|
||||
uint8_t increment6dB(const uint8_t rdac);
|
||||
uint8_t increment6dBAll();
|
||||
uint8_t decrement6dB(const uint8_t rdac);
|
||||
uint8_t decrement6dBAll();
|
||||
|
||||
|
||||
// SYNC functions
|
||||
// preload registers to change all channels synchronuous
|
||||
uint8_t preload(const uint8_t rdac, const uint8_t value);
|
||||
uint8_t preloadAll(const uint8_t value);
|
||||
// copy the preloads to the channels. The bitmask indicates which channels
|
||||
// b00001101 would indicate channel 0, 2 and 3;
|
||||
uint8_t sync(const uint8_t mask);
|
||||
|
||||
|
||||
// MISC
|
||||
uint8_t pmCount() { return _potCount; };
|
||||
uint8_t maxValue() { return _maxValue; };
|
||||
uint8_t shutDown();
|
||||
|
||||
|
||||
// returns the value from internal registers.
|
||||
uint8_t readBackINPUT(const uint8_t rdac) { return readBack(rdac, 0x00); };
|
||||
uint8_t readBackEEPROM(const uint8_t rdac) { return readBack(rdac, 0x01); };
|
||||
uint8_t readBackCONTROL(const uint8_t rdac) { return readBack(rdac, 0x02); };
|
||||
uint8_t readBackRDAC(const uint8_t rdac) { return readBack(rdac, 0x03); };
|
||||
|
||||
|
||||
// USE WITH CARE - READ DATASHEET
|
||||
// write to control register
|
||||
// value : 0 1
|
||||
// bit 0 : FREEZE RDAC's normal operation
|
||||
// bit 1 : EEPROM DISABLED normal operation
|
||||
// bit 2 : normal operation LINEAR GAIN MODE
|
||||
// bit 3 : normal operation BURST MODE
|
||||
uint8_t writeControlRegister(uint8_t mask);
|
||||
// TODO separate get set functions ?
|
||||
|
||||
|
||||
protected:
|
||||
uint8_t _potCount = 4; // unknown
|
||||
uint8_t _maxValue = 255; // unknown
|
||||
|
||||
|
||||
private:
|
||||
uint8_t send(const uint8_t cmd, const uint8_t value);
|
||||
uint8_t readBack(const uint8_t rdac, const uint8_t mask);
|
||||
|
||||
uint8_t _address;
|
||||
uint8_t _lastValue[4];
|
||||
|
||||
TwoWire* _wire;
|
||||
};
|
||||
|
||||
//////////////////////////////////////////////////////////////
|
||||
|
||||
class AD5123 : public AD51XX
|
||||
{
|
||||
AD5123(const uint8_t address, TwoWire *wire = &Wire);
|
||||
};
|
||||
|
||||
class AD5124 : public AD51XX
|
||||
{
|
||||
AD5124(const uint8_t address, TwoWire *wire = &Wire);
|
||||
};
|
||||
|
||||
class AD5143 : public AD51XX
|
||||
{
|
||||
AD5143(const uint8_t address, TwoWire *wire = &Wire);
|
||||
};
|
||||
|
||||
class AD5144 : public AD51XX
|
||||
{
|
||||
public:
|
||||
AD5144(const uint8_t address, TwoWire *wire = &Wire);
|
||||
};
|
||||
|
||||
class AD5144A : public AD51XX
|
||||
{
|
||||
public:
|
||||
AD5144A(const uint8_t address, TwoWire *wire = &Wire);
|
||||
};
|
||||
|
||||
class AD5122A : public AD51XX
|
||||
{
|
||||
AD5122A(const uint8_t address, TwoWire *wire = &Wire);
|
||||
};
|
||||
|
||||
class AD5142A : public AD51XX
|
||||
{
|
||||
public:
|
||||
AD5142A(const uint8_t address, TwoWire *wire = &Wire);
|
||||
};
|
||||
|
||||
class AD5121 : public AD51XX
|
||||
{
|
||||
public:
|
||||
AD5121(const uint8_t address, TwoWire *wire = &Wire);
|
||||
};
|
||||
|
||||
class AD5141 : public AD51XX
|
||||
{
|
||||
public:
|
||||
AD5141(const uint8_t address, TwoWire *wire = &Wire);
|
||||
};
|
||||
|
||||
|
||||
// -- END OF FILE --
|
21
libraries/AD5144A/LICENSE
Normal file
21
libraries/AD5144A/LICENSE
Normal file
@ -0,0 +1,21 @@
|
||||
MIT License
|
||||
|
||||
Copyright (c) 2021 - 2021 Rob Tillaart
|
||||
|
||||
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.
|
165
libraries/AD5144A/README.md
Normal file
165
libraries/AD5144A/README.md
Normal file
@ -0,0 +1,165 @@
|
||||
|
||||
[![Arduino CI](https://github.com/RobTillaart/AD5144A/workflows/Arduino%20CI/badge.svg)](https://github.com/marketplace/actions/arduino_ci)
|
||||
[![License: MIT](https://img.shields.io/badge/license-MIT-green.svg)](https://github.com/RobTillaart/AD5144A/blob/master/LICENSE)
|
||||
[![GitHub release](https://img.shields.io/github/release/RobTillaart/AD5144A.svg?maxAge=3600)](https://github.com/RobTillaart/AD5144A/releases)
|
||||
|
||||
|
||||
# AD5144A
|
||||
|
||||
Arduino library for **I2C AD5144A** 4 channel digital potentiometer.
|
||||
|
||||
|
||||
## Description
|
||||
|
||||
The library is an experimental library for the **I2C AD5144A** 4 channel digital potentiometer.
|
||||
- it is not tested extensively, (AD5144A partly)
|
||||
- so use at own risk, and
|
||||
- please report problems and/or success.
|
||||
|
||||
From the datasheet it is expected that the library will work more or less
|
||||
for the family of related AD devices. However as said before this is not tested.
|
||||
If there are problems, please file an issue.
|
||||
|
||||
This library uses the **I2C** interface to communicate with the device.
|
||||
It does not work for the **SPI** versions of these devices.
|
||||
See TODO.
|
||||
|
||||
|
||||
## I2C
|
||||
|
||||
For the selection of the address, see table 12 / 13 datasheet.
|
||||
|
||||
The AD5144A devices support standard 100 kHz, and fast 400 kHz, data transfer modes.
|
||||
|
||||
|
||||
## Interface
|
||||
|
||||
The library has a number of functions which are all quite straightforward.
|
||||
|
||||
As the library is experimental, function signatures might change in the future.
|
||||
|
||||
### Constructors
|
||||
|
||||
- **AD51XX(uint8_t address, TwoWire \*wire = &Wire)** base class, to set the I2C address and optional the Wire bus used.
|
||||
This class does not distinguish between the derived classes.
|
||||
The developer is responsible for handling this correctly when using the base class.
|
||||
|
||||
| device | #potmeters | # rheostats | range | tested |
|
||||
|:--------|:-----------:|:-----------:|:------:|:-------:|
|
||||
| AD5123 | 2 | 2 | 0..127 | no |
|
||||
| AD5124 | 4 | 0 | 0..127 | no |
|
||||
| AD5143 | 2 | 2 | 0..255 | no |
|
||||
| AD5144 | 4 | 0 | 0..255 | partial |
|
||||
| AD5144A | 4 | 0 | 0..255 | partial |
|
||||
| AD5122A | 2 | 0 | 0..127 | no |
|
||||
| AD5142A | 2 | 0 | 0..255 | no |
|
||||
| AD5121 | 1 | 0 | 0..127 | no |
|
||||
| AD5141 | 1 | 0 | 0..255 | no |
|
||||
|
||||
Derived classes:
|
||||
- **AD5123(uint8_t address, TwoWire \*wire = &Wire)**
|
||||
- **AD5124(uint8_t address, TwoWire \*wire = &Wire)**
|
||||
- **AD5143(uint8_t address, TwoWire \*wire = &Wire)**
|
||||
- **AD5144(uint8_t address, TwoWire \*wire = &Wire)**
|
||||
- **AD5144A(uint8_t address, TwoWire \*wire = &Wire)**
|
||||
- **AD5122A(uint8_t address, TwoWire \*wire = &Wire)**
|
||||
- **AD5142A(uint8_t address, TwoWire \*wire = &Wire)**
|
||||
- **AD5121(uint8_t address, TwoWire \*wire = &Wire)**
|
||||
- **AD5141(uint8_t address, TwoWire \*wire = &Wire)**
|
||||
|
||||
|
||||
### I2C / device initialization
|
||||
|
||||
- **bool begin(uint8_t sda, uint8_t scl)** ESP32 a.o initializing of Wire.
|
||||
Returns true if the address of the device can be found on the I2C bus.
|
||||
- **bool begin()** for UNO, returns true if the address of the device can be found on the I2C bus.
|
||||
- **bool isConnected()** returns true if the address of the device can be found on the I2C bus.
|
||||
- **uint8_t reset()** calls the built in RESET command, check datasheet for details,
|
||||
|
||||
|
||||
### Basic IO
|
||||
|
||||
Used to set one channel at the time.
|
||||
|
||||
- **uint8_t write(rdac, value)** set channel rdac 0..3 to value 0..255 (depending on type less channels and lower max value should be used)
|
||||
The value is also written into a cache of last set values for fast retrieval later.
|
||||
- **uint8_t read(rdac)** read back set value from the **cache**, not from the device.
|
||||
|
||||
|
||||
### EEPROM
|
||||
|
||||
The value stored in the EEPROM is the value the 4 potmeters will start at boot time.
|
||||
This allows to start at predefined values and makes it possibly easier to continue after
|
||||
a reboot.
|
||||
|
||||
- **uint8_t storeEEPROM(rdac)** store the current channel value in EEPROM.
|
||||
- **uint8_t storeEEPROM(rdac, value)** store a specific (new) value in EEPROM.
|
||||
- **uint8_t recallEEPROM(rdac)** get the value from EEPROM and set the channel.
|
||||
|
||||
|
||||
### Async
|
||||
|
||||
Sets values in sequence, not at exact same time
|
||||
|
||||
- **uint8_t writeAll(value)** write the same value to all channels.
|
||||
- **uint8_t zeroAll()** sets all channels to 0
|
||||
- **uint8_t midScaleAll()** sets all channels to their midpoint 128 / 64
|
||||
- **uint8_t maxAll()** sets all channels to the max 255 / 127
|
||||
- **uint8_t zero(rdac)** sets one channel to 0
|
||||
- **uint8_t midScale(rdac)** sets one channel to its midpoint = 128 / 64
|
||||
- **uint8_t maxValue(rdac)** sets one channel to the max 255 / 127
|
||||
|
||||
|
||||
### Sync
|
||||
|
||||
- **uint8_t preload(rdac, value)** prepare a rdac for a new value but only use it after **sync()** is called.
|
||||
- **uint8_t preloadAll(value)** prepape all rdacs with the same value, and wait for **sync()**
|
||||
- **uint8_t sync(mask)** will transfer the preloaded values to the (4) rdacs at the very same moment. The 4-bit mask is used to select which rdacs to sync.
|
||||
|
||||
|
||||
### ReadBack
|
||||
|
||||
These function read back from the internal registers of the actual device.
|
||||
|
||||
- **uint8_t readBackINPUT(rdac)** reads back the "preload value" in the INPUT register.
|
||||
- **uint8_t readBackEEPROM(rdac)** reads the **boot value** for the selected rdac from EEPROM.
|
||||
- **uint8_t readBackCONTROL(rdac)** read back the control register. Read the datasheet for the details of the individual bits.
|
||||
- **uint8_t readBackRDAC(rdac)** reads the value of the rdac from the device.
|
||||
|
||||
|
||||
### Write control register
|
||||
|
||||
- **uint8_t writeControlRegister(uint8_t mask)** writes to the control register.
|
||||
Read the datasheet for the details of the individual bits.
|
||||
**Warning** use with care!
|
||||
|
||||
|
||||
### Misc
|
||||
|
||||
- **uint8_t pmCount()** returns the number of potmeters / channels the device has. Useful when writing your own loops over all channels.
|
||||
- **uint8_t shutDown()** check datasheet, not tested yet, use at own risk.
|
||||
|
||||
|
||||
## Operation
|
||||
|
||||
The examples show the basic working of the functions.
|
||||
|
||||
|
||||
## TODO
|
||||
|
||||
See also open issues.
|
||||
|
||||
#### Must
|
||||
|
||||
- testing ...
|
||||
- example sketches
|
||||
|
||||
#### Could
|
||||
|
||||
- CI test code
|
||||
- SPI based version of the library ?
|
||||
- test for maxValue when writing a channel as not all derived use 0..255
|
||||
|
||||
- some functions can be performance optimized
|
||||
- writing a value is not needed is last value is the same?
|
||||
|
@ -0,0 +1,94 @@
|
||||
//
|
||||
// FILE: AD5144A_low_level.ino
|
||||
// AUTHOR: Rob Tillaart
|
||||
// VERSION: 0.1.0
|
||||
// PURPOSE: test low level IO
|
||||
// DATE: 2021-05-04
|
||||
// URL: https://github.com/RobTillaart/AD5144A
|
||||
|
||||
|
||||
// THIS IS A LOW LEVEL WRITE TEST FOR AD5144A
|
||||
// IT DOES NOT USE THE LIBRARY
|
||||
|
||||
|
||||
#include "Arduino.h"
|
||||
#include "Wire.h"
|
||||
|
||||
#define ADDRESS 0x77
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
Serial.println(__FILE__);
|
||||
|
||||
Wire.begin();
|
||||
|
||||
Serial.print("CONNECT:\t");
|
||||
Wire.beginTransmission(ADDRESS);
|
||||
int rv = Wire.endTransmission();
|
||||
Serial.println(rv);
|
||||
|
||||
Serial.println("LOOP 0..255 POTMETER 0");
|
||||
for (int val = 0; val < 256; val++)
|
||||
{
|
||||
Wire.beginTransmission(ADDRESS);
|
||||
Wire.write(0x11);
|
||||
Wire.write(val);
|
||||
int x = Wire.endTransmission();
|
||||
Serial.print(val);
|
||||
Serial.print("\t");
|
||||
Serial.println(x);
|
||||
delay(10);
|
||||
}
|
||||
|
||||
Serial.println("LOOP 0..255 POTMETER 1");
|
||||
for (int val = 0; val < 256; val++)
|
||||
{
|
||||
Wire.beginTransmission(ADDRESS);
|
||||
Wire.write(0x12);
|
||||
Wire.write(val);
|
||||
int x = Wire.endTransmission();
|
||||
Serial.print(val);
|
||||
Serial.print("\t");
|
||||
Serial.println(x);
|
||||
delay(10);
|
||||
}
|
||||
|
||||
Serial.println("LOOP 0..255 POTMETER 2");
|
||||
for (int val = 0; val < 256; val++)
|
||||
{
|
||||
Wire.beginTransmission(ADDRESS);
|
||||
Wire.write(0x14);
|
||||
Wire.write(val);
|
||||
int x = Wire.endTransmission();
|
||||
Serial.print(val);
|
||||
Serial.print("\t");
|
||||
Serial.println(x);
|
||||
delay(10);
|
||||
}
|
||||
|
||||
Serial.println("LOOP 0..255 POTMETER 3");
|
||||
for (int val = 0; val < 256; val++)
|
||||
{
|
||||
Wire.beginTransmission(ADDRESS);
|
||||
Wire.write(0x18);
|
||||
Wire.write(val);
|
||||
int x = Wire.endTransmission();
|
||||
Serial.print(val);
|
||||
Serial.print("\t");
|
||||
Serial.println(x);
|
||||
delay(10);
|
||||
}
|
||||
|
||||
Serial.println();
|
||||
Serial.println("done...");
|
||||
}
|
||||
|
||||
|
||||
void loop()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
// -- END OF FILE --
|
@ -0,0 +1,56 @@
|
||||
//
|
||||
// FILE: AD5144A_test_EEPROM.ino
|
||||
// AUTHOR: Rob Tillaart
|
||||
// VERSION: 0.1.0
|
||||
// PURPOSE: test EEPROM functions
|
||||
// DATE: 2021-05-04
|
||||
// URL: https://github.com/RobTillaart/AD5144A
|
||||
|
||||
|
||||
#include "AD5144A.h"
|
||||
|
||||
// select the right type
|
||||
// adjust address
|
||||
AD5144A AD(0x77);
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
Serial.println(__FILE__);
|
||||
|
||||
Wire.begin();
|
||||
if (AD.begin() == false)
|
||||
{
|
||||
Serial.println("device not found");
|
||||
return;
|
||||
}
|
||||
|
||||
// values should be same after start
|
||||
for (int ch = 0; ch < AD.pmCount(); ch++)
|
||||
{
|
||||
Serial.print(ch);
|
||||
Serial.print('\t');
|
||||
Serial.print(AD.recallEEPROM(ch));
|
||||
Serial.print('\t');
|
||||
Serial.print(AD.readBackRDAC(ch));
|
||||
Serial.println();
|
||||
}
|
||||
|
||||
// update values for after next (full) power up.
|
||||
for (int ch = 0; ch < AD.pmCount(); ch++)
|
||||
{
|
||||
uint8_t val = AD.recallEEPROM(ch);
|
||||
AD.storeEEPROM(ch, val + 1);
|
||||
}
|
||||
|
||||
Serial.println("done...");
|
||||
}
|
||||
|
||||
|
||||
void loop()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
// -- END OF FILE --
|
@ -0,0 +1,55 @@
|
||||
//
|
||||
// FILE: AD5144A_test_control_register.ino
|
||||
// AUTHOR: Rob Tillaart
|
||||
// VERSION: 0.1.0
|
||||
// PURPOSE: read CONTROL REGISTER functions
|
||||
// DATE: 2021-05-04
|
||||
// URL: https://github.com/RobTillaart/AD5144A
|
||||
|
||||
|
||||
#include "AD5144A.h"
|
||||
|
||||
// select the right type
|
||||
// adjust address
|
||||
AD5144A AD(0x77);
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
Serial.println(__FILE__);
|
||||
|
||||
Wire.begin();
|
||||
if (AD.begin() == false)
|
||||
{
|
||||
Serial.println("device not found");
|
||||
return;
|
||||
}
|
||||
|
||||
Serial.println("check datasheet");
|
||||
Serial.println("CH\tWP\tEE\tMODE\tBURST");
|
||||
for (uint8_t ch = 0; ch < AD.pmCount(); ch++)
|
||||
{
|
||||
uint8_t mask = AD.readBackCONTROL(ch);
|
||||
Serial.print(ch);
|
||||
Serial.print('\t');
|
||||
Serial.print(mask & 0x01);
|
||||
Serial.print('\t');
|
||||
Serial.print(mask & 0x02);
|
||||
Serial.print('\t');
|
||||
Serial.print(mask & 0x04);
|
||||
Serial.print('\t');
|
||||
Serial.print(mask & 0x08);
|
||||
Serial.println();
|
||||
}
|
||||
|
||||
Serial.println("done...");
|
||||
}
|
||||
|
||||
|
||||
void loop()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
// -- END OF FILE --
|
@ -0,0 +1,44 @@
|
||||
//
|
||||
// FILE: AD5144A_test_isConnected.ino
|
||||
// AUTHOR: Rob Tillaart
|
||||
// VERSION: 0.1.0
|
||||
// PURPOSE: check isConnected()
|
||||
// DATE: 2021-05-04
|
||||
// URL: https://github.com/RobTillaart/AD5144A
|
||||
|
||||
|
||||
#include "AD5144A.h"
|
||||
|
||||
// select the right type
|
||||
// adjust address
|
||||
AD5144A AD(0x77);
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
Serial.println(__FILE__);
|
||||
|
||||
Wire.begin();
|
||||
|
||||
Serial.println();
|
||||
Serial.print("Begin: ");
|
||||
Serial.println(AD.begin());
|
||||
Serial.print("Connected: ");
|
||||
Serial.println(AD.isConnected());
|
||||
Serial.print("CHANNELS:\t");
|
||||
Serial.println(AD.pmCount());
|
||||
Serial.print("MAXVALUE:\t");
|
||||
Serial.println(AD.maxValue());
|
||||
Serial.println();
|
||||
|
||||
Serial.println("done...");
|
||||
}
|
||||
|
||||
|
||||
void loop()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
// -- END OF FILE --
|
@ -0,0 +1,134 @@
|
||||
//
|
||||
// FILE: AD5144A_test_performance.ino
|
||||
// AUTHOR: Rob Tillaart
|
||||
// VERSION: 0.1.0
|
||||
// PURPOSE: indication performance methods of the class
|
||||
// DATE: 2021-04-30
|
||||
// URL: https://github.com/RobTillaart/AD5144A
|
||||
|
||||
|
||||
#include "AD5144A.h"
|
||||
|
||||
// select the right type
|
||||
// adjust address
|
||||
AD5144A AD(0x77);
|
||||
|
||||
uint32_t start, stop;
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
Serial.println(__FILE__);
|
||||
|
||||
Wire.begin();
|
||||
if (AD.begin() == false)
|
||||
{
|
||||
Serial.println("device not found");
|
||||
return;
|
||||
}
|
||||
|
||||
Serial.println();
|
||||
Serial.print("CHANNELS:\t");
|
||||
Serial.println(AD.pmCount());
|
||||
Serial.print("MAXVALUE:\t");
|
||||
Serial.println(AD.maxValue());
|
||||
Serial.println();
|
||||
|
||||
test_1000_writes();
|
||||
test_1000_reads();
|
||||
|
||||
Serial.println("done...");
|
||||
}
|
||||
|
||||
|
||||
void loop()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
void test_1000_writes()
|
||||
{
|
||||
Serial.println();
|
||||
Serial.println(__FUNCTION__);
|
||||
delay(10);
|
||||
|
||||
start = micros();
|
||||
for (int i = 0; i < 1000; i++)
|
||||
{
|
||||
AD.write(0, i & 0xFF);
|
||||
}
|
||||
stop = micros();
|
||||
Serial.println(stop - start);
|
||||
Serial.println();
|
||||
}
|
||||
|
||||
|
||||
void test_1000_reads()
|
||||
{
|
||||
uint32_t sum = 0;
|
||||
Serial.println();
|
||||
Serial.println(__FUNCTION__);
|
||||
delay(10);
|
||||
|
||||
start = micros();
|
||||
for (int i = 0; i < 1000; i++)
|
||||
{
|
||||
sum += AD.read(0);
|
||||
}
|
||||
stop = micros();
|
||||
Serial.println(stop - start);
|
||||
Serial.println(sum);
|
||||
Serial.println();
|
||||
}
|
||||
|
||||
|
||||
void test_midScaleAll()
|
||||
{
|
||||
Serial.println();
|
||||
Serial.println(__FUNCTION__);
|
||||
delay(10);
|
||||
|
||||
start = micros();
|
||||
AD.midScaleAll();
|
||||
stop = micros();
|
||||
Serial.println(stop - start);
|
||||
Serial.println();
|
||||
|
||||
for (int i = 0; i < AD.pmCount(); i++)
|
||||
{
|
||||
if (AD.read(i) != AD.maxValue()/2)
|
||||
{
|
||||
Serial.print("non-mid:\t");
|
||||
Serial.println(i);
|
||||
}
|
||||
}
|
||||
Serial.println();
|
||||
}
|
||||
|
||||
|
||||
void test_zeroAll() // todo test
|
||||
{
|
||||
Serial.println();
|
||||
Serial.println(__FUNCTION__);
|
||||
delay(10);
|
||||
|
||||
start = micros();
|
||||
AD.zeroAll();
|
||||
stop = micros();
|
||||
Serial.println(stop - start);
|
||||
Serial.println();
|
||||
|
||||
for (int i = 0; i < AD.pmCount(); i++)
|
||||
{
|
||||
if (AD.read(i) != 0)
|
||||
{
|
||||
Serial.print("non-zero:\t");
|
||||
Serial.println(i);
|
||||
}
|
||||
}
|
||||
Serial.println();
|
||||
}
|
||||
|
||||
|
||||
// -- END OF FILE --
|
@ -0,0 +1,79 @@
|
||||
//
|
||||
// FILE: AD5144A_test_preload_sync.ino
|
||||
// AUTHOR: Rob Tillaart
|
||||
// VERSION: 0.1.0
|
||||
// PURPOSE: demo
|
||||
// DATE: 2021-05-04
|
||||
// URL: https://github.com/RobTillaart/AD5144A
|
||||
|
||||
|
||||
// connect the AD5144A to a multichannel scope
|
||||
// to verify the potmeters change at the same time
|
||||
|
||||
|
||||
#include "AD5144A.h"
|
||||
|
||||
// select the right type
|
||||
// adjust address
|
||||
AD5144A AD(0x77);
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
Serial.println(__FILE__);
|
||||
|
||||
Wire.begin();
|
||||
if (AD.begin() == false)
|
||||
{
|
||||
Serial.println("device not found");
|
||||
return;
|
||||
}
|
||||
|
||||
test_preload();
|
||||
delay(1000);
|
||||
test_preloadAll();
|
||||
|
||||
Serial.println("done...");
|
||||
}
|
||||
|
||||
|
||||
void loop()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
void test_preload()
|
||||
{
|
||||
Serial.println();
|
||||
Serial.println(__FUNCTION__);
|
||||
|
||||
for (int val = 0; val < 256; val += 17)
|
||||
{
|
||||
for (uint8_t ch = 0; ch < AD.pmCount(); ch++) // all channels
|
||||
{
|
||||
AD.preload(ch, val);
|
||||
}
|
||||
AD.sync(0x0F);
|
||||
delay(100);
|
||||
}
|
||||
Serial.println();
|
||||
}
|
||||
|
||||
|
||||
void test_preloadAll()
|
||||
{
|
||||
Serial.println();
|
||||
Serial.println(__FUNCTION__);
|
||||
|
||||
for (int val = 0; val < 256; val += 17)
|
||||
{
|
||||
AD.preloadAll(val);
|
||||
AD.sync(0x0F);
|
||||
delay(100);
|
||||
}
|
||||
Serial.println();
|
||||
}
|
||||
|
||||
|
||||
// -- END OF FILE --
|
@ -0,0 +1,76 @@
|
||||
//
|
||||
// FILE: AD5144A_test_speed.ino
|
||||
// AUTHOR: Rob Tillaart
|
||||
// VERSION: 0.1.0
|
||||
// PURPOSE: demo
|
||||
// DATE: 2021-04-30
|
||||
// URL: https://github.com/RobTillaart/AD5144A
|
||||
|
||||
|
||||
#include "AD5144A.h"
|
||||
|
||||
// select the right type
|
||||
// adjust address
|
||||
AD5144A AD(0x77);
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
Serial.println(__FILE__);
|
||||
|
||||
Wire.begin();
|
||||
if (AD.begin() == false)
|
||||
{
|
||||
Serial.println("device not found");
|
||||
return;
|
||||
}
|
||||
|
||||
for (uint32_t speed = 50000; speed < 850000; speed += 50000)
|
||||
{
|
||||
test_i2C_clock(speed);
|
||||
}
|
||||
Serial.println("done...");
|
||||
}
|
||||
|
||||
|
||||
void loop()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
void test_i2C_clock(uint32_t clock)
|
||||
{
|
||||
Wire.setClock(clock);
|
||||
|
||||
Serial.println();
|
||||
Serial.print(__FUNCTION__);
|
||||
Serial.print(":\t");
|
||||
Serial.println(clock);
|
||||
|
||||
if (AD.isConnected() == false)
|
||||
{
|
||||
Serial.println("failed\n");
|
||||
return;
|
||||
}
|
||||
|
||||
for (int p = 0; p < AD.pmCount(); p++)
|
||||
{
|
||||
for (int val = 0; val < 256; val++)
|
||||
{
|
||||
AD.write(p, val);
|
||||
if (AD.read(p) != val)
|
||||
{
|
||||
Serial.print("error:\t");
|
||||
Serial.print(p);
|
||||
Serial.print("\t");
|
||||
Serial.print(val);
|
||||
Serial.println();
|
||||
}
|
||||
}
|
||||
}
|
||||
Serial.println("ok\n");
|
||||
}
|
||||
|
||||
|
||||
// -- END OF FILE --
|
@ -0,0 +1,56 @@
|
||||
//
|
||||
// FILE: AD5144A_test_write.ino
|
||||
// AUTHOR: Rob Tillaart
|
||||
// VERSION: 0.1.0
|
||||
// PURPOSE: demo
|
||||
// DATE: 2021-04-30
|
||||
// URL: https://github.com/RobTillaart/AD5144A
|
||||
|
||||
|
||||
#include "AD5144A.h"
|
||||
|
||||
// select the right type
|
||||
// adjust address
|
||||
AD5144A AD(0x77);
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
Serial.println(__FILE__);
|
||||
|
||||
Wire.begin();
|
||||
if (AD.begin() == false)
|
||||
{
|
||||
Serial.println("device not found");
|
||||
return;
|
||||
}
|
||||
|
||||
// will generate 20+ lines
|
||||
// decrease step 50 to 1 to test all
|
||||
for (int val = 0; val < 256; val+= 50)
|
||||
{
|
||||
for (int p = 0; p < AD.pmCount(); p++)
|
||||
{
|
||||
Serial.print(val);
|
||||
Serial.print("\t");
|
||||
Serial.print(AD.write(p, val));
|
||||
Serial.print("\t");
|
||||
Serial.print(p);
|
||||
Serial.print("\t");
|
||||
Serial.print(AD.read(p));
|
||||
Serial.print("\t");
|
||||
Serial.print(AD.readBackRDAC(p));
|
||||
Serial.println();
|
||||
}
|
||||
}
|
||||
Serial.println("done...");
|
||||
}
|
||||
|
||||
|
||||
void loop()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
// -- END OF FILE --
|
@ -0,0 +1,121 @@
|
||||
//
|
||||
// FILE: AD5144A_test_writeAll.ino
|
||||
// AUTHOR: Rob Tillaart
|
||||
// VERSION: 0.1.0
|
||||
// PURPOSE: test writeAll + wrappers
|
||||
// DATE: 2021-05-04
|
||||
// URL: https://github.com/RobTillaart/AD5144A
|
||||
|
||||
|
||||
#include "AD5144A.h"
|
||||
|
||||
// select the right type
|
||||
// adjust address
|
||||
AD5144A AD(0x77);
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
Serial.println(__FILE__);
|
||||
|
||||
Wire.begin();
|
||||
if (AD.begin() == false)
|
||||
{
|
||||
Serial.println("device not found");
|
||||
return;
|
||||
}
|
||||
|
||||
Serial.println();
|
||||
Serial.print("CHANNELS:\t");
|
||||
Serial.println(AD.pmCount());
|
||||
Serial.print("MAXVALUE:\t");
|
||||
Serial.println(AD.maxValue());
|
||||
Serial.println();
|
||||
|
||||
test_writeAll();
|
||||
test_zeroAll();
|
||||
test_midScaleAll();
|
||||
test_maxAll();
|
||||
|
||||
Serial.println("done...");
|
||||
}
|
||||
|
||||
|
||||
void loop()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
void test_writeAll()
|
||||
{
|
||||
Serial.println();
|
||||
Serial.println(__FUNCTION__);
|
||||
|
||||
for (int v = 0; v < 256; v++)
|
||||
{
|
||||
uint8_t rv = AD.writeAll(v);
|
||||
Serial.print(v);
|
||||
Serial.print('\t');
|
||||
Serial.print(AD.read(0));
|
||||
Serial.print('\t');
|
||||
Serial.println(rv);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void test_zeroAll()
|
||||
{
|
||||
Serial.println();
|
||||
Serial.println(__FUNCTION__);
|
||||
|
||||
uint8_t rv = AD.zeroAll();
|
||||
Serial.println(rv);
|
||||
|
||||
for (int i = 0; i < AD.pmCount(); i++)
|
||||
{
|
||||
Serial.print(i);
|
||||
Serial.print('\t');
|
||||
Serial.println(AD.read(i));
|
||||
}
|
||||
Serial.println();
|
||||
}
|
||||
|
||||
|
||||
void test_midScaleAll()
|
||||
{
|
||||
Serial.println();
|
||||
Serial.println(__FUNCTION__);
|
||||
|
||||
uint8_t rv = AD.midScaleAll();
|
||||
Serial.println(rv);
|
||||
|
||||
for (int i = 0; i < AD.pmCount(); i++)
|
||||
{
|
||||
Serial.print(i);
|
||||
Serial.print('\t');
|
||||
Serial.println(AD.read(i));
|
||||
}
|
||||
Serial.println();
|
||||
}
|
||||
|
||||
|
||||
void test_maxAll()
|
||||
{
|
||||
Serial.println();
|
||||
Serial.println(__FUNCTION__);
|
||||
|
||||
uint8_t rv = AD.maxAll();
|
||||
Serial.println(rv);
|
||||
|
||||
for (int i = 0; i < AD.pmCount(); i++)
|
||||
{
|
||||
Serial.print(i);
|
||||
Serial.print('\t');
|
||||
Serial.println(AD.read(i));
|
||||
}
|
||||
Serial.println();
|
||||
}
|
||||
|
||||
|
||||
// -- END OF FILE --
|
53
libraries/AD5144A/keywords.txt
Normal file
53
libraries/AD5144A/keywords.txt
Normal file
@ -0,0 +1,53 @@
|
||||
# Syntax Coloring Map For AD5144A
|
||||
|
||||
# Datatypes (KEYWORD1)
|
||||
AD51XX KEYWORD1
|
||||
AD5123 KEYWORD1
|
||||
AD5124 KEYWORD1
|
||||
AD5143 KEYWORD1
|
||||
AD5144A KEYWORD1
|
||||
AD5122A KEYWORD1
|
||||
AD5142A KEYWORD1
|
||||
AD5121 KEYWORD1
|
||||
AD5141 KEYWORD1
|
||||
|
||||
|
||||
# Methods and Functions (KEYWORD2)
|
||||
begin KEYWORD2
|
||||
isConnected KEYWORD2
|
||||
reset KEYWORD2
|
||||
|
||||
read KEYWORD2
|
||||
write KEYWORD2
|
||||
|
||||
storeEEPROM KEYWORD2
|
||||
storeEEPROM KEYWORD2
|
||||
recallEEPROM KEYWORD2
|
||||
|
||||
writeAll KEYWORD2
|
||||
zeroAll KEYWORD2
|
||||
midScaleAll KEYWORD2
|
||||
maxAll KEYWORD2
|
||||
zeroAll KEYWORD2
|
||||
mid KEYWORD2
|
||||
maxValue KEYWORD2
|
||||
|
||||
preload KEYWORD2
|
||||
preloadAll KEYWORD2
|
||||
sync KEYWORD2
|
||||
|
||||
readBackINPUT KEYWORD2
|
||||
readBackEEPROM KEYWORD2
|
||||
readBackCONTROL KEYWORD2
|
||||
readBackRDAC KEYWORD2
|
||||
|
||||
pmCount KEYWORD2
|
||||
shutDown KEYWORD2
|
||||
|
||||
|
||||
# Constants (LITERAL1)
|
||||
AD51XXA_VERSION LITERAL1
|
||||
AD51XXA_OK LITERAL1
|
||||
AD51XXA_ERROR LITERAL1
|
||||
AD51XXA_INVALID_POT LITERAL1
|
||||
|
22
libraries/AD5144A/library.json
Normal file
22
libraries/AD5144A/library.json
Normal file
@ -0,0 +1,22 @@
|
||||
{
|
||||
"name": "AD5144A",
|
||||
"keywords": "I2C,digital,PotentioMeter, AD5144A",
|
||||
"description": "Library to control 4 channel digital potentiometer AD5144A et al.",
|
||||
"authors":
|
||||
[
|
||||
{
|
||||
"name": "Rob Tillaart",
|
||||
"email": "Rob.Tillaart@gmail.com",
|
||||
"maintainer": true
|
||||
}
|
||||
],
|
||||
"repository":
|
||||
{
|
||||
"type": "git",
|
||||
"url": "https://github.com/RobTillaart/AD5144A"
|
||||
},
|
||||
"version": "0.1.2",
|
||||
"license": "MIT",
|
||||
"frameworks": "arduino",
|
||||
"platforms": "*"
|
||||
}
|
11
libraries/AD5144A/library.properties
Normal file
11
libraries/AD5144A/library.properties
Normal file
@ -0,0 +1,11 @@
|
||||
name=AD5144A
|
||||
version=0.1.2
|
||||
author=Rob Tillaart <rob.tillaart@gmail.com>
|
||||
maintainer=Rob Tillaart <rob.tillaart@gmail.com>
|
||||
sentence=Arduino Library for AD5144A
|
||||
paragraph=4 Channel digital potentiometer
|
||||
category=Signal Input/Output
|
||||
url=https://github.com/RobTillaart/AD5144A
|
||||
architectures=*
|
||||
includes=AD5144A.h
|
||||
depends=
|
49
libraries/AD5144A/test/unit_test_001.cpp
Normal file
49
libraries/AD5144A/test/unit_test_001.cpp
Normal file
@ -0,0 +1,49 @@
|
||||
//
|
||||
// FILE: unit_test_001.cpp
|
||||
// AUTHOR: Rob Tillaart
|
||||
// VERSION: 0.1.0
|
||||
// DATE: 2021-04-30
|
||||
// PURPOSE: unit tests for I2C digital PotentioMeter AD5144A
|
||||
// https://github.com/RobTillaart/AD5144A
|
||||
// https://github.com/Arduino-CI/arduino_ci/blob/master/REFERENCE.md
|
||||
//
|
||||
|
||||
// supported assertions
|
||||
// ----------------------------
|
||||
// assertEqual(expected, actual)
|
||||
// assertNotEqual(expected, actual)
|
||||
// assertLess(expected, actual)
|
||||
// assertMore(expected, actual)
|
||||
// assertLessOrEqual(expected, actual)
|
||||
// assertMoreOrEqual(expected, actual)
|
||||
// assertTrue(actual)
|
||||
// assertFalse(actual)
|
||||
// assertNull(actual)
|
||||
|
||||
#include <ArduinoUnitTests.h>
|
||||
|
||||
#include "AD5144A.h"
|
||||
|
||||
|
||||
unittest_setup()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
unittest_teardown()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
unittest(test_constructors)
|
||||
{
|
||||
Wire.begin();
|
||||
|
||||
AD5144A ADx(0x2C);
|
||||
assertEqual(1, 1);
|
||||
}
|
||||
|
||||
|
||||
unittest_main()
|
||||
|
||||
// --------
|
Loading…
x
Reference in New Issue
Block a user