Can't open I2C device

I want to connect the SC16IS752 chip [here] via the I2C A or I2C B port on the PixHawk 4. The goal is to connect multiple (at least 2) independent UART devices.

To do so, I wrote a driver, based on the [pca9685] driver. Based on the [datasheet of the chip] and this [example code], I modified the code as shown below.

Now the problem is, I cannot connect to the board, all I get is the return code -125. I tried with the original I2C address of the chip (0x90) as well as the right shifted (0x48) adress, as some sources suggest. The chip/board itself is working, I verified it with a spare Raspberry Pi.

Is there anything I missed to get the connection working? Do I have to specifiy the I2C port on the PixHawk? If so, how would I do this? Or do I have to add some information about the chip somewhere else for the I2C connection to work?

Any help is appreciated!

/****************************************************************************
 *
 *   Copyright (c) 2012-2017 PX4 Development Team. All rights reserved.
 *
 * Redistribution and use in source and binary forms, with or without
 * modification, are permitted provided that the following conditions
 * are met:
 *
 * 1. Redistributions of source code must retain the above copyright
 *    notice, this list of conditions and the following disclaimer.
 * 2. Redistributions in binary form must reproduce the above copyright
 *    notice, this list of conditions and the following disclaimer in
 *    the documentation and/or other materials provided with the
 *    distribution.
 * 3. Neither the name PX4 nor the names of its contributors may be
 *    used to endorse or promote products derived from this software
 *    without specific prior written permission.
 *
 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
 * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 * POSSIBILITY OF SUCH DAMAGE.
 *
 ****************************************************************************/

/**
 * @file sc16is752.cpp
 *
 * Driver for the SC16IS752 I2C PWM module
 * The chip is used on the Adafruit I2C/PWM converter https://www.adafruit.com/product/815
 *
 * Parts of the code are adapted from the arduino library for the board
 * https://github.com/adafruit/Adafruit-PWM-Servo-Driver-Library
 * for the license of these parts see the
 * arduino_Adafruit_PWM_Servo_Driver_Library_license.txt file
 * see https://github.com/adafruit/Adafruit-PWM-Servo-Driver-Library for contributors
 *
 * @author Thomas Gubler <thomasgubler@gmail.com>
 */

#include <px4_config.h>
#include <px4_defines.h>

#include <drivers/device/i2c.h>

#include <sys/types.h>
#include <stdint.h>
#include <string.h>
#include <stdlib.h>
#include <stdbool.h>
#include <fcntl.h>
#include <unistd.h>
#include <stdio.h>
#include <ctype.h>
#include <math.h>
#include <px4_getopt.h>

#include <nuttx/wqueue.h>
#include <nuttx/clock.h>

#include <perf/perf_counter.h>
#include <systemlib/err.h>

#include <uORB/uORB.h>
#include <uORB/topics/i2c_readout.h>

#include <board_config.h>
#include <drivers/drv_io_expander.h>

#define ADDR 0x90	// I2C adress

#define SC16IS752_DEVICE_PATH "/dev/sc16is752"
#define SC16IS752_BUS         PX4_I2C_BUS_EXPANSION

#define RHR		0x00 // Recv Holding Register is 0x00 in READ Mode
#define THR		0x00 // Xmit Holding Register is 0x00 in WRITE Mode

#define IER		0x01 // Interrupt Enable Register

#define IIR		0x02 // Interrupt Identification Register in READ Mode
#define FCR		0x02 // FIFO Control Register in WRITE Mode

#define LCR		0x03 // Line Control Register
#define MCR		0x04 // Modem Control Register
#define LSR		0x05 // Line status Register
#define MSR		0x06 // Modem Status Register
#define SPR		0x07 // ScratchPad Register
#define TCR		0x06 // Transmission Control Register
#define TLR		0x07 // Trigger Level Register
#define TXLVL		0x08 // Xmit FIFO Level Register
#define RXLVL		0x09 // Recv FIFO Level Register
#define IODir		0x0A // I/O Pins Direction Register
#define IOState		0x0B // I/O Pins State Register
#define IOIntEna	0x0C // I/O Interrupt Enable Register
#define IOControl	0x0E // I/O Pins Control Register
#define EFCR		0x0F // Extra Features Control Register

#define DLL		0x00 // Divisor Latch LSB  0x00
#define DLH		0x01 // Divisor Latch MSB  0x01

#define EFR		0x02 // Enhanced Function Register

#define I2CWRITE	0x00
#define I2CREAD		0x01

#define CHANA		0
#define CHANB		1

/* interface ioctls */
#define IOCTL_RESET         1
#define IOCTL_MEASURE       2

typedef begin_packed_struct struct SC16IS752_data_t {
	union {
		uint8_t  chan_a;
		uint8_t  chan_b;
	} uart;
} end_packed_struct SC16IS752_data_t;

class SC16IS752 : public device::I2C
{
public:
	SC16IS752(int bus = SC16IS752_BUS, uint8_t address = ADDR);
	virtual ~SC16IS752() = default;


	virtual int		init();
	virtual int		ioctl(struct file *filp, int cmd, unsigned long arg);
	virtual int		info();
	virtual int		reset();
	bool			is_running() { return _running; }

private:
	work_s			_work;


	enum IOX_MODE		_mode;
	bool			_running;
	int			_i2ciox_interval;
	bool			_should_run;
	perf_counter_t		_comms_errors;

	uint8_t			_msg[3];

	orb_advert_t		_i2c_readout_topic;
	int			_orb_class_instance;
	struct i2c_readout_s  	_i2c_readout;

	SC16IS752_data_t reading;

	bool _mode_on_initialized;  /** Set to true after the first call of i2ciox in mode IOX_MODE_ON */

	static void		i2ciox_trampoline(void *arg);
	void			i2ciox();

	/* Wrapper to read a byte from addr */
	int _read(uint8_t reg, uint8_t chan, uint8_t &value);

	/* Wrapper to wite a byte to addr */
	int _write(uint8_t reg, uint8_t chan, uint8_t value);

};

/* for now, we only support one board */
namespace
{
SC16IS752 *g_sc16is752;
}

void sc16is752_usage();

extern "C" __EXPORT int sc16is752_main(int argc, char *argv[]);

SC16IS752::SC16IS752(int bus, uint8_t address) :
	I2C("sc16is752", SC16IS752_DEVICE_PATH, bus, address, 100000),
	_mode(IOX_MODE_OFF),
	_running(false),
	_i2ciox_interval(SEC2TICK(1.0f / 60.0f)),
	_should_run(false),
	_comms_errors(perf_alloc(PC_COUNT, "sc16is752_com_err")),
	_i2c_readout_topic(nullptr),
	_orb_class_instance(-1),
	_mode_on_initialized(false)
{
	memset(&_work, 0, sizeof(_work));
	memset(_msg, 0, sizeof(_msg));
}

int
SC16IS752::init()
{
	int ret;
	I2C::init();

	/**
	 * This routine initializes Channels A and B
	 * Copyright (c) 2008 Dave Yeatman
	 * https://www.ccsinfo.com/forum/viewtopic.php?t=36523
	 */
	// Channel A Setups
	//Prescaler in MCR defaults on MCU reset to the value of 1
	_write(LCR, CHANA, 0x80); // 0x80 to program baud rate divisor
	_write(DLL, CHANA, 0x18); // 0x18=9600K, 0x06 =38,42K with X1=3.6864MHz
	_write(DLH, CHANA, 0x00); //

	_write(LCR, CHANA, 0xBF); // access EFR register
	_write(EFR, CHANA, 0X10); // enable enhanced registers
	//
	_write(LCR, CHANA, 0x03); // 8 data bits, 1 stop bit, no parity
	_write(FCR, CHANA, 0x07); // reset TXFIFO, reset RXFIFO, enable FIFO mode

	// Channel B Setups
	//Prescaler in MCR defaults on MCU reset to the value of 1
	_write(LCR, CHANB, 0x80); // 0x80 to program baud rate divisor
	_write(DLL, CHANB, 0x18); // 0x18=9600K, 0x06 =38,42K with X1=3.6864MHz
	_write(DLH, CHANB, 0x00); //

	_write(LCR, CHANB, 0xBF); // access EFR register
	_write(EFR, CHANB, 0X10); // enable enhanced registers
	//
	_write(LCR, CHANB, 0x03); // 8 data bits, 1 stop bit, no parity
	_write(FCR, CHANB, 0x07); // reset TXFIFO, reset RXFIFO, enable FIFO mode

	// Test connection
	uint8_t test_buf = 0x00;
	ret = _read(RHR, CHANA, test_buf);

	if (ret != OK) {
		return ret;
	}

	ret = reset();

	if (ret != OK) {
		return ret;
	}

	return ret;
}

int
SC16IS752::ioctl(struct file *filp, int cmd, unsigned long arg)
{
	int ret = -EINVAL;

	switch (cmd) {

	case IOX_SET_MODE:

		if (_mode != (IOX_MODE)arg) {

			switch ((IOX_MODE)arg) {
			case IOX_MODE_OFF:
				warnx("shutting down");
				break;

			case IOX_MODE_ON:
				warnx("starting");
				break;

			case IOX_MODE_TEST_OUT:
				warnx("test starting");
				break;

			default:
				return -1;
			}

			_mode = (IOX_MODE)arg;
		}

		// if not active, kick it
		if (!_running) {
			_running = true;
			work_queue(LPWORK, &_work, (worker_t)&SC16IS752::i2ciox_trampoline, this, 1);
		}


		return OK;

	default:
		// see if the parent class can make any use of it
		ret = CDev::ioctl(filp, cmd, arg);
		break;
	}

	return ret;
}

int
SC16IS752::info()
{
	int ret = OK;

	if (is_running()) {
		warnx("Driver is running, mode: %u", _mode);

	} else {
		warnx("Driver started but not running");
	}

	return ret;
}

void
SC16IS752::i2ciox_trampoline(void *arg)
{
	SC16IS752 *i2ciox = reinterpret_cast<SC16IS752 *>(arg);

	i2ciox->i2ciox();
}

/**
 * Main loop function
 */
void
SC16IS752::i2ciox()
{
	PX4_INFO("I'M ALIVE!");

	if (_mode == IOX_MODE_TEST_OUT) {
		_should_run = true;

	} else if (_mode == IOX_MODE_OFF) {
		_should_run = false;

	} else {
		if (!_mode_on_initialized) {
			/* Subscribe to actuator control 2 (payload group for gimbal) */
			_i2c_readout_topic = orb_advertise(ORB_ID(i2c_readout), &_i2c_readout);

			_mode_on_initialized = true;

			uint8_t buf;
			uint8_t status;

			/**
			* Read from Channel A
			*/
			buf = 0x00;

			status = 0;
			status = _read(LSR, CHANA, buf);
			PX4_INFO("Chan A status: %u", status);
			PX4_INFO("Chan A buf: %u", buf);

			if ((status > 0)) { // && (buf & 0x01)) { // is data waiting?
				// data present in receiver FIFO
				status = _read(RHR, CHANA, buf);
				reading.uart.chan_a = buf;
				PX4_INFO("Buf: %u, Status: %u", buf, status);
			}

			/**
			 * Read from Channel B
			 */
			buf = 0x00;

			status = 0;
			status = _read(LSR, CHANB, buf);
			PX4_INFO("Chan B status: %u", status);
			PX4_INFO("Chan B buf: %u", buf);

			if ((status > 0)) { // && (buf & 0x01)) { // is data waiting?
				// data present in receiver FIFO
				status = _read(RHR, CHANB, buf);
				reading.uart.chan_b = buf;
				PX4_INFO("Buf: %u, Status: %u", buf, status);
			}

			_i2c_readout.channel_a = reading.uart.chan_a;
			_i2c_readout.channel_b = reading.uart.chan_b;

			/* publish it */
			if (_i2c_readout_topic != nullptr) {
				/* publish it */
				orb_publish(ORB_ID(i2c_readout), _i2c_readout_topic, &_i2c_readout);
			}
		}

		_should_run = true;
	}

	// check if any activity remains, else stop
	if (!_should_run) {
		_running = false;
		return;
	}

	// re-queue ourselves to run again later
	_running = true;
	work_queue(LPWORK, &_work, (worker_t)&SC16IS752::i2ciox_trampoline, this, _i2ciox_interval);
}

int SC16IS752::reset(void)
{
	warnx("resetting");
	return (_write(FCR, CHANA, 0x07) + _write(FCR, CHANB, 0x07));
}

/* Wrapper to read a byte from addr */
int
SC16IS752::_read(uint8_t reg, uint8_t chan, uint8_t &value)
{
	int ret = OK;

	_msg[0] = ADDR;
	_msg[1] = (reg << 3) | (chan << 1);
	_msg[2] = ADDR;

	/* get value */
	ret = transfer(_msg, 3, &value, 1);

	if (ret != OK) {
		goto fail_read;
	}

	return ret;

fail_read:
	perf_count(_comms_errors);
	DEVICE_LOG("I2C::transfer (read) returned: %d; value: %d", ret, value);

	return ret;
}

/* Wrapper to wite a byte to addr */
int
SC16IS752::_write(uint8_t reg, uint8_t chan, uint8_t value)
{
	int ret = OK;
	_msg[0] = ADDR;
	_msg[1] = (reg << 3) | (chan << 1);
	_msg[2] = value;
	/* send addr and value */
	ret = transfer(_msg, 3, nullptr, 0);

	if (ret != OK) {
		perf_count(_comms_errors);
		DEVICE_LOG("I2C::transfer (write) returned: %d", ret);
	}

	return ret;
}

void
sc16is752_usage()
{
	warnx("missing command: try 'start', 'test', 'stop', 'info'");
	warnx("options:");
	warnx("    -b i2cbus (%d)", PX4_I2C_BUS_EXPANSION);
	warnx("    -a addr (0x%x)", ADDR);
}

int
sc16is752_main(int argc, char *argv[])
{
	int i2cdevice = -1;
	int i2caddr = ADDR; // 7bit

	int myoptind = 1;
	int ch;
	const char *myoptarg = nullptr;


	// jump over start/off/etc and look at options first
	while ((ch = px4_getopt(argc, argv, "a:b:", &myoptind, &myoptarg)) != EOF) {
		switch (ch) {
		case 'a':
			i2caddr = strtol(myoptarg, NULL, 0);
			break;

		case 'b':
			i2cdevice = strtol(myoptarg, NULL, 0);
			break;

		default:
			sc16is752_usage();
			exit(0);
		}
	}

	if (myoptind >= argc) {
		sc16is752_usage();
		exit(0);
	}

	const char *verb = argv[myoptind];

	int fd;
	int ret;

	if (!strcmp(verb, "start")) {
		if (g_sc16is752 != nullptr) {
			errx(1, "already started");
		}

		if (i2cdevice == -1) {
			// try the external bus first
			i2cdevice = PX4_I2C_BUS_EXPANSION;
			g_sc16is752 = new SC16IS752(PX4_I2C_BUS_EXPANSION, i2caddr);

			if (g_sc16is752 != nullptr && OK != g_sc16is752->init()) {
				delete g_sc16is752;
				g_sc16is752 = nullptr;
			}

			if (g_sc16is752 == nullptr) {
				errx(1, "init failed");
			}
		}

		if (g_sc16is752 == nullptr) {
			g_sc16is752 = new SC16IS752(i2cdevice, i2caddr);

			if (g_sc16is752 == nullptr) {
				errx(1, "new failed");
			}

			if (OK != g_sc16is752->init()) {
				delete g_sc16is752;
				g_sc16is752 = nullptr;
				errx(1, "init failed");
			}
		}

		fd = open(SC16IS752_DEVICE_PATH, 0);

		if (fd == -1) {
			errx(1, "Unable to open " SC16IS752_DEVICE_PATH);
		}

		ret = ioctl(fd, IOX_SET_MODE, (unsigned long)IOX_MODE_ON);
		close(fd);


		exit(0);
	}

	// need the driver past this point
	if (g_sc16is752 == nullptr) {
		warnx("not started, run sc16is752 start");
		exit(1);
	}

	if (!strcmp(verb, "info")) {
		g_sc16is752->info();
		exit(0);
	}

	if (!strcmp(verb, "reset")) {
		g_sc16is752->reset();
		exit(0);
	}


	if (!strcmp(verb, "test")) {
		fd = open(SC16IS752_DEVICE_PATH, 0);

		if (fd == -1) {
			errx(1, "Unable to open " SC16IS752_DEVICE_PATH);
		}

		ret = ioctl(fd, IOX_SET_MODE, (unsigned long)IOX_MODE_TEST_OUT);

		close(fd);
		exit(ret);
	}

	if (!strcmp(verb, "stop")) {
		fd = open(SC16IS752_DEVICE_PATH, 0);

		if (fd == -1) {
			errx(1, "Unable to open " SC16IS752_DEVICE_PATH);
		}

		ret = ioctl(fd, IOX_SET_MODE, (unsigned long)IOX_MODE_OFF);
		close(fd);

		// wait until we're not running any more
		for (unsigned i = 0; i < 15; i++) {
			if (!g_sc16is752->is_running()) {
				break;
			}

			usleep(50000);
			printf(".");
			fflush(stdout);
		}

		printf("\n");
		fflush(stdout);

		if (!g_sc16is752->is_running()) {
			delete g_sc16is752;
			g_sc16is752 = nullptr;
			warnx("stopped, exiting");
			exit(0);

		} else {
			warnx("stop failed.");
			exit(1);
		}
	}

	sc16is752_usage();
	exit(0);
}

Do you have a logic analyzer? It helps to see what is being sent on the i2c line when you start your driver and what the chip is responding with.

Sadly no, but I’ll try to get my hands on one.

Any idea what the return code -125 means? I can’t seem to find any references to it and the default PX4 error codes end at something around 40 to 50.

I got myself a Logic Analyzer and was able to figure some things out:

  • The I2C A corresponds to port number 4; I’d suspect I2C B would correspond to port number 5 but I didn’t actually test that.
  • The code -125 is returned whenever there is no device detected on the bus.

Thus, starting my code via sc16is752 start -a 0x48 -b 4 will successfully initialize the I2C connection. However, the code itself does not loop (yet). This will be the next step but is probably better suited for another discussion thread.

PS: for anyone wondering why the I2C address suddenly is 0x48 instead of 0x90, that is because one has to right-shift the address by one bit.