Use 8-bit i2c address on LPC platform

Fix #9799 — hopefully not a unicorn
2.0.x
Scott Lahteine 6 years ago
parent 631d867dc9
commit a43e892fb5

@ -87,7 +87,7 @@ void eeprom_write_byte(uint8_t *pos, unsigned char value) {
eeprom_init();
Wire.beginTransmission(eeprom_device_address);
Wire.beginTransmission(I2C_ADDRESS(eeprom_device_address));
Wire.write((int)(eeprom_address >> 8)); // MSB
Wire.write((int)(eeprom_address & 0xFF)); // LSB
Wire.write(value);
@ -103,7 +103,7 @@ void eeprom_write_byte(uint8_t *pos, unsigned char value) {
void eeprom_update_block(const void *pos, void* eeprom_address, size_t n) {
eeprom_init();
Wire.beginTransmission(eeprom_device_address);
Wire.beginTransmission(I2C_ADDRESS(eeprom_device_address));
Wire.write((int)((unsigned)eeprom_address >> 8)); // MSB
Wire.write((int)((unsigned)eeprom_address & 0xFF)); // LSB
Wire.endTransmission();
@ -115,7 +115,7 @@ void eeprom_update_block(const void *pos, void* eeprom_address, size_t n) {
flag |= Wire.read() ^ ptr[c];
if (flag) {
Wire.beginTransmission(eeprom_device_address);
Wire.beginTransmission(I2C_ADDRESS(eeprom_device_address));
Wire.write((int)((unsigned)eeprom_address >> 8)); // MSB
Wire.write((int)((unsigned)eeprom_address & 0xFF)); // LSB
Wire.write((uint8_t*)pos, n);
@ -133,7 +133,7 @@ uint8_t eeprom_read_byte(uint8_t *pos) {
eeprom_init();
Wire.beginTransmission(eeprom_device_address);
Wire.beginTransmission(I2C_ADDRESS(eeprom_device_address));
Wire.write((int)(eeprom_address >> 8)); // MSB
Wire.write((int)(eeprom_address & 0xFF)); // LSB
Wire.endTransmission();
@ -145,7 +145,7 @@ uint8_t eeprom_read_byte(uint8_t *pos) {
void eeprom_read_block(void* pos, const void* eeprom_address, size_t n) {
eeprom_init();
Wire.beginTransmission(eeprom_device_address);
Wire.beginTransmission(I2C_ADDRESS(eeprom_device_address));
Wire.write((int)((unsigned)eeprom_address >> 8)); // MSB
Wire.write((int)((unsigned)eeprom_address & 0xFF)); // LSB
Wire.endTransmission();

@ -229,3 +229,9 @@
#define LROUND(x) lroundf(x)
#define FMOD(x, y) fmodf(x, y)
#define HYPOT(x,y) SQRT(HYPOT2(x,y))
#ifdef TARGET_LPC1768
#define I2C_ADDRESS(A) ((A) << 1)
#else
#define I2C_ADDRESS(A) A
#endif

@ -473,7 +473,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) {
}
void I2CPositionEncoder::reset() {
Wire.beginTransmission(i2cAddress);
Wire.beginTransmission(I2C_ADDRESS(i2cAddress));
Wire.write(I2CPE_RESET_COUNT);
Wire.endTransmission();
@ -703,7 +703,7 @@ void I2CPositionEncodersMgr::report_position(const int8_t idx, const bool units,
void I2CPositionEncodersMgr::change_module_address(const uint8_t oldaddr, const uint8_t newaddr) {
// First check 'new' address is not in use
Wire.beginTransmission(newaddr);
Wire.beginTransmission(I2C_ADDRESS(newaddr));
if (!Wire.endTransmission()) {
SERIAL_ECHOPAIR("?There is already a device with that address on the I2C bus! (", newaddr);
SERIAL_ECHOLNPGM(")");
@ -711,7 +711,7 @@ void I2CPositionEncodersMgr::change_module_address(const uint8_t oldaddr, const
}
// Now check that we can find the module on the oldaddr address
Wire.beginTransmission(oldaddr);
Wire.beginTransmission(I2C_ADDRESS(oldaddr));
if (Wire.endTransmission()) {
SERIAL_ECHOPAIR("?No module detected at this address! (", oldaddr);
SERIAL_ECHOLNPGM(")");
@ -722,7 +722,7 @@ void I2CPositionEncodersMgr::change_module_address(const uint8_t oldaddr, const
SERIAL_ECHOLNPAIR(", changing address to ", newaddr);
// Change the modules address
Wire.beginTransmission(oldaddr);
Wire.beginTransmission(I2C_ADDRESS(oldaddr));
Wire.write(I2CPE_SET_ADDR);
Wire.write(newaddr);
Wire.endTransmission();
@ -733,7 +733,7 @@ void I2CPositionEncodersMgr::change_module_address(const uint8_t oldaddr, const
safe_delay(I2CPE_REBOOT_TIME);
// Look for the module at the new address.
Wire.beginTransmission(newaddr);
Wire.beginTransmission(I2C_ADDRESS(newaddr));
if (Wire.endTransmission()) {
SERIAL_ECHOLNPGM("Address change failed! Check encoder module.");
return;
@ -753,7 +753,7 @@ void I2CPositionEncodersMgr::change_module_address(const uint8_t oldaddr, const
void I2CPositionEncodersMgr::report_module_firmware(const uint8_t address) {
// First check there is a module
Wire.beginTransmission(address);
Wire.beginTransmission(I2C_ADDRESS(address));
if (Wire.endTransmission()) {
SERIAL_ECHOPAIR("?No module detected at this address! (", address);
SERIAL_ECHOLNPGM(")");
@ -763,7 +763,7 @@ void I2CPositionEncodersMgr::report_module_firmware(const uint8_t address) {
SERIAL_ECHOPAIR("Requesting version info from module at address ", address);
SERIAL_ECHOLNPGM(":");
Wire.beginTransmission(address);
Wire.beginTransmission(I2C_ADDRESS(address));
Wire.write(I2CPE_SET_REPORT_MODE);
Wire.write(I2CPE_REPORT_VERSION);
Wire.endTransmission();
@ -777,7 +777,7 @@ void I2CPositionEncodersMgr::report_module_firmware(const uint8_t address) {
}
// Set module back to normal (distance) mode
Wire.beginTransmission(address);
Wire.beginTransmission(I2C_ADDRESS(address));
Wire.write(I2CPE_SET_REPORT_MODE);
Wire.write(I2CPE_REPORT_DISTANCE);
Wire.endTransmission();

@ -69,7 +69,7 @@ uint8_t mcp4728_analogWrite(uint8_t channel, uint16_t value) {
* This will also write current Vref, PowerDown, Gain settings to EEPROM
*/
uint8_t mcp4728_eepromWrite() {
Wire.beginTransmission(DAC_DEV_ADDRESS);
Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS));
Wire.write(SEQWRITE);
LOOP_XYZE(i) {
Wire.write(DAC_STEPPER_VREF << 7 | DAC_STEPPER_GAIN << 4 | highByte(mcp4728_values[i]));
@ -82,7 +82,7 @@ uint8_t mcp4728_eepromWrite() {
* Write Voltage reference setting to all input regiters
*/
uint8_t mcp4728_setVref_all(uint8_t value) {
Wire.beginTransmission(DAC_DEV_ADDRESS);
Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS));
Wire.write(VREFWRITE | (value ? 0x0F : 0x00));
return Wire.endTransmission();
}
@ -90,7 +90,7 @@ uint8_t mcp4728_setVref_all(uint8_t value) {
* Write Gain setting to all input regiters
*/
uint8_t mcp4728_setGain_all(uint8_t value) {
Wire.beginTransmission(DAC_DEV_ADDRESS);
Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS));
Wire.write(GAINWRITE | (value ? 0x0F : 0x00));
return Wire.endTransmission();
}
@ -133,7 +133,7 @@ void mcp4728_setDrvPct(uint8_t pct[XYZE]) {
* No EEPROM update
*/
uint8_t mcp4728_fastWrite() {
Wire.beginTransmission(DAC_DEV_ADDRESS);
Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS));
LOOP_XYZE(i) {
Wire.write(highByte(mcp4728_values[i]));
Wire.write(lowByte(mcp4728_values[i]));
@ -145,7 +145,7 @@ uint8_t mcp4728_fastWrite() {
* Common function for simple general commands
*/
uint8_t mcp4728_simpleCommand(byte simpleCommand) {
Wire.beginTransmission(GENERALCALL);
Wire.beginTransmission(I2C_ADDRESS(GENERALCALL));
Wire.write(simpleCommand);
return Wire.endTransmission();
}

@ -50,7 +50,7 @@ static void i2c_send(const byte addr, const byte a, const byte b) {
digipot_mcp4451_send_byte(a);
digipot_mcp4451_send_byte(b);
#else
Wire.beginTransmission(addr);
Wire.beginTransmission(I2C_ADDRESS(addr));
Wire.write(a);
Wire.write(b);
Wire.endTransmission();

@ -34,7 +34,7 @@
void blinkm_set_led_color(const LEDColor &color) {
Wire.begin();
Wire.beginTransmission(0x09);
Wire.beginTransmission(I2C_ADDRESS(0x09));
Wire.write('o'); //to disable ongoing script, only needs to be used once
Wire.write('n');
Wire.write(color.r);

@ -74,14 +74,14 @@
byte PCA_init = 0;
static void PCA9632_WriteRegister(const byte addr, const byte regadd, const byte value) {
Wire.beginTransmission(addr);
Wire.beginTransmission(I2C_ADDRESS(addr));
Wire.write(regadd);
Wire.write(value);
Wire.endTransmission();
}
static void PCA9632_WriteAllRegisters(const byte addr, const byte regadd, const byte value1, const byte value2, const byte value3) {
Wire.beginTransmission(addr);
Wire.beginTransmission(I2C_ADDRESS(addr));
Wire.write(PCA9632_AUTO_IND | regadd);
Wire.write(value1);
Wire.write(value2);
@ -91,7 +91,7 @@ static void PCA9632_WriteAllRegisters(const byte addr, const byte regadd, const
#if 0
static byte PCA9632_ReadRegister(const byte addr, const byte regadd) {
Wire.beginTransmission(addr);
Wire.beginTransmission(I2C_ADDRESS(addr));
Wire.write(regadd);
const byte value = Wire.read();
Wire.endTransmission();

@ -81,7 +81,7 @@ void TWIBus::send() {
debug(PSTR("send"), this->addr);
#endif
Wire.beginTransmission(this->addr);
Wire.beginTransmission(I2C_ADDRESS(this->addr));
Wire.write(this->buffer, this->buffer_s);
Wire.endTransmission();

Loading…
Cancel
Save