Tx=20220202.

RS485 on the Raspberry Pi

This is a sad story and I am deeply disapponted by the Raspberry. But I got it to work.

Let me give you a bit of background: for a project I had to read an SMT-100 soil humidity sensor with my Raspberry Pi (Pi3B+ and Pi4B). These sensors have a version that supports MODBUS via an RS-485 differential bus. This bus is really robust and supports cable lengths up to 500m. Great! Should not be too difficult, or?

Well, the easy things always present the most difficult problems. But not so fast. I first tried to get it to work on an ESP32 chip for just a few Euros (like 5 Euros), so much cheaper than the RPI (which are basically unobtainium right now due to the chip crisis, and what you can buy is super expensive, like 60 Euros for a RPI).

RS485 on the ESP32
OK, I had to search quite a bit for such a seamingly simple task, but at least the hardware supports the special RS-485 mode. You can connect the RTS-line with the DataEnable (DE, the transmit switch line) of the level shifter, e.g., a MAX485 IC. This program code will initialize the hardware UART in the ESP32:

// we have to redefine pins, as GPIO7 and GPIO8 are not externally available.
uart_config_t uart_config = {
.baud_rate = 9600,
.data_bits = UART_DATA_8_BITS,
.parity = UART_PARITY_EVEN, // UART_PARITY_EVEN UART_PARITY_DISABLE
.stop_bits = UART_STOP_BITS_1,
.flow_ctrl = UART_HW_FLOWCTRL_DISABLE, // no UART_HW_FLOWCTRL_CTS_RTS for RS485 mode!
.rx_flow_ctrl_thresh = 122,
// .uart_sclk_t = 0 // UART source clock from APB
};

// Configure UART parameters. Has to come BEFORE installing the driver!
ESP_ERROR_CHECK(uart_param_config(uart_num, &uart_config));

// Set UART pins(TX: IO17, RX: IO16, RTS: IO23, CTS: -1).  Has to come BEFORE installing the driver!
ESP_ERROR_CHECK(uart_set_pin(uart_num, TXD2, RXD2, RTS2, CTS2));

// Install UART driver using an event queue here
ESP_ERROR_CHECK(uart_driver_install(uart_num, BUF_SIZE * 2, 0, 0, NULL, 0));

// Set RS485 half duplex mode
// UART_MODE_UART = 0x00
// UART_MODE_RS485_HALF_DUPLEX = 0x01       only works if HW flow control is disabled! This will set RTS properly!
// UART_MODE_IRDA = 0x02
// UART_MODE_RS485_COLLISION_DETECT = 0x03
// UART_MODE_RS485_APP_CTRL = 0x04          only works if HW flow control is disabled! This will set RTS properly!
ESP_ERROR_CHECK(uart_set_mode(uart_num, UART_MODE_RS485_HALF_DUPLEX));

// Timeout threshold for UART = number of symbols (~10 tics) with unchanged state on receive pin
#define ECHO_READ_TOUT          (3) // 3.5T * 8 = 28 ticks, TOUT=3 -> ~24..33 ticks
// Set read timeout of UART TOUT feature
ESP_ERROR_CHECK(uart_set_rx_timeout(uart_num, ECHO_READ_TOUT));

// here we can invert the RX and TX lines
#define UART_SIGNAL_RXD_INV  (0x1 << 2)
#define UART_SIGNAL_TXD_INV  (0x1 << 5)
// ESP_ERROR_CHECK(uart_set_line_inverse(uart_num, UART_SIGNAL_TXD_INV | UART_SIGNAL_RXD_INV)); E (24) uart: uart_set_line_inverse(236): inverse_mask error

// Serial2.begin(9600, SERIAL_8E1); // 8 data bits, even parity, 1 stop bit, RX_pin, TX_pin. Does not allow to specify the RTS pin

This is all a bit ideosyncratic but it can be Google'd and, best of all, it works flawlessly! You can have this code in the setup() routine of your Arduino-like sketch and then use the UART in the loop(). Yes, the order of the above commands is important and some internet sources have the wrong order, so things don't work. Since the half-duplex switching of the DE-line on the MAX485 happens in hardware, it is totally in sync with the sending of data. No bit is lost when switching between TX and RX modes. Perfect! Since all the effort is offloaded to the hardware UART, it works while WiFi is running or a thousand other things are being done. There is a receive buffer, so no timing constraints on the receive side.

With these simple commands:

tx_len = uart_write_bytes(uart_num, (const char *)message_str, 8);
ESP_ERROR_CHECK(uart_get_buffered_data_len(uart_num, &rcv_len));
rcv_len = uart_read_bytes(uart_num, data, 20, 100);

you can implement your own MODBUS commands -- it is simple enough.

RS485 on the RPI
On this, by now (February 2022) more than 10 (!) times as expensive minicomputer, things are much more complicated and confusing. Sigh.

First: RPI-1, RPI-2, RPI-3 all only have a miesley two (!) UARTs. Only the RPI-4 has 6 UARTs. And of these UARTs one is probably taken for Bluetooth (BT), which leaves only 1 UART. So, if you want RS-232 and RS-485 you need to use a RPI-4! You can disable BT, but you still can only access one (!) UART. The other one is not accessible on the IO-pins (GPIOs) -- believe me, I tried for about a week. Sigh. With the RPI-4 you can have two UARTs on the GPIO pins.

Now, of the two standard UARTs, only one allows hardware flow control (RTS/CTS), and this one is called /dev/ttyAMA0. The other one is called /dev/ttyS0 and it is a totally castrated UART, which is close to unusable. By default this bad UART is all you get. But you can disable BT or switch the UARTs so that BT gets the bad UART (ttyS0) and you use the better one (ttyAMA0) on the GPIO pins. For this you write in /boot/config.txt:

dtoverlay=uart1
# dtoverlay=miniuart-bt
dtoverlay=disable-bt
enable_uart=1

Now you have the better UART, it even can do harware flow control (RTS/CTS), but by default RASPIAN spawns a serial Linux console (something where you can log into your RPI if you use an old terminal, like a VT100) on the only UART we have, thus making it unusable for us. But by editing /boot/cmdline.txt and removing the serial console from the boot string, we get rid of it.

Finally we can use it and enable HW flow control to get the RTS line! However, after another week of experimenting I had to realize that this UART does not support the half duplex mode needed for MODBUS on RS-485! Yes, it does switch the RTS line, but so late after the sending has finished that it is unusable for the purpose of switching between TX and RX on the MAX485. It also has the wrong polarity, so you need to invert it, e.g., with 1 transisor or a 74LS06. I did this, only to find out that it is way too slow. This way you always loose the first part of the response of your sensor. Unusable.

To initialize this UART you need some horrible setup commands:

#define RS485_PORT "/dev/ttyAMA0"

#if(WIRING == WIRINGPI)
wiringPiSetupGpio() ;  // use BCM GPIO numbering
pinMode (RTS,  OUTPUT) ; // wiringPi funktioniert nicht richtig für den RPI-4B. Setzt das gpio pin nicht!
#else
if (gpioInitialise()<0) {
return 1;
}
gpioSetMode(RTS, PI_OUTPUT);
#endif

serial_port = open(RS485_PORT, O_RDWR | O_NOCTTY | O_NONBLOCK);
if (serial_port == -1)
{
printf("[ERROR] RS485 UART open(): %s\n", strerror(errno));
return -1;
}
else
{
/*
printf("Serial port open!\n");
fflush(stdout);
*/
}

#if 0
struct serial_rs485 rs485conf;

// turns out the (better) UART ttyAMAx of the RPI 4B does NOT support the RS485 mode!

/* Enable RS485 mode: */
//rs485conf.flags |= SER_RS485_ENABLED;

/* Set logical level for RTS pin equal to 1 when sending: */
//rs485conf.flags |= SER_RS485_RTS_ON_SEND;
/* or, set logical level for RTS pin equal to 0 when sending: */
//rs485conf.flags &= ~(SER_RS485_RTS_ON_SEND);

/* Set logical level for RTS pin equal to 1 after sending: */
//rs485conf.flags |= SER_RS485_RTS_AFTER_SEND;
/* or, set logical level for RTS pin equal to 0 after sending: */
//rs485conf.flags &= ~(SER_RS485_RTS_AFTER_SEND);

/* Set rts delay before send, if needed: */
//rs485conf.delay_rts_before_send = ...;

/* Set rts delay after send, if needed: */
//rs485conf.delay_rts_after_send = ...;

/* Set this flag if you want to receive data even while sending data */
//rs485conf.flags |= SER_RS485_RX_DURING_TX;

if (ioctl(serial_port, TIOCSRS485, &rs485conf) < 0) {
/* Error handling. See errno. */
printf("RS485 config failed. %s (%d)\n", strerror(errno), errno);
exit(1);
}

#else

returncode |= tcgetattr(serial_port, &tty);
if(returncode)
{
printf("Error %s (%d) in getting UART parameters.\n", strerror(errno), errno);
exit(1);
}
else
{
/*
printf("outspeed = %d, 9600baud = %d\n", cfgetospeed(&tty), B9600);
printf("inspeed  = %d, 9600baud = %d\n", cfgetispeed(&tty), B9600);
printf("c_flag   =0x%08x\n", tty.c_cflag);
printf("  CRTSCTS=0x%08x\n", CRTSCTS);
printf("  CSIZE  =0x%08x\n", CSIZE);
printf("  CS8    =0x%08x\n", CS8);
printf("  PARENB =0x%08x\n", PARENB);
printf("  PARODD =0x%08x\n", PARODD);
printf("  CSTOPB =0x%08x\n", CSTOPB);
printf("c_iflag  =0x%08x\n", tty.c_iflag);
printf("c_lflag  =0x%08x\n", tty.c_lflag);
printf("c_oflag  =0x%08x\n", tty.c_oflag);
printf("VMIN=%d\n", tty.c_cc[VMIN]);
printf("VTIME=%d\n", tty.c_cc[VTIME]);
*/
}

returncode |= cfsetospeed (&tty, speed);
if(returncode)
{
printf("Error %s (%d) in setting UART TX speed.\n", strerror(errno), errno);
exit(1);
}

returncode |= cfsetispeed (&tty, speed);
if(returncode)
{
printf("Error %s (%d) in setting UART RX speed.\n", strerror(errno), errno);
exit(1);
}

tty.c_cflag = (tty.c_cflag & ~CSIZE) | CS8;     // 8-bit chars
tty.c_cflag |= PARENB;                          /* use parity bit */
tty.c_cflag &= ~PARODD;                         /* do not use ODD parity => parity is even */
tty.c_cflag &= ~CSTOPB;                         /* only need 1 stop bit, CSTOPB = Set two stop bits, rather than one. */
tty.c_cflag &= ~CRTSCTS;                        /* no hardware flow control -- no UART_HW_FLOWCTRL_CTS_RTS for RS485 mode needed on ESP32! */
//tty.c_cflag |= CRTSCTS;                       /* hardware flow control: is needed on RPI to set RTS to LOW if sending, must be inverted by hardware, still does not work */

// disable IGNBRK for mismatched speed tests; otherwise receive break
// as \000 chars
tty.c_iflag &= ~IGNBRK;         // disable break processing
tty.c_iflag &= ~(IXON | IXOFF | IXANY);   /* no SW flowcontrol */

tty.c_lflag = 0;                // no signaling chars, no echo,
// no canonical processing

tty.c_oflag = 0;                // no remapping, no delays

//   VMIN = 0 and VTIME = 0
//   This is a completely non-blocking read - the call is satisfied immediately directly from the driver's input queue. If data are available, it's transferred to the caller's buffer up to nbytes and returned. Otherwise zero is immediately returned to indicate "no data". We'll note that this is "polling" of the serial port, and it's almost always a bad idea. If done repeatedly, it can consume enormous amounts of processor time and is highly inefficient. Don't use this mode unless you really, really know what you're doing.
//
//   VMIN = 0 and VTIME > 0
//   This is a pure timed read. If data are available in the input queue, it's transferred to the caller's buffer up to a maximum of nbytes, and returned immediately to the caller. Otherwise the driver blocks until data arrives, or when VTIME tenths expire from the start of the call. If the timer expires without data, zero is returned. A single byte is sufficient to satisfy this read call, but if more is available in the input queue, it's returned to the caller. Note that this is an overall timer, not an intercharacter one.
//
//   VMIN > 0 and VTIME > 0
//   A read() is satisfied when either VMIN characters have been transferred to the caller's buffer, or when VTIME tenths expire between characters. Since this timer is not started until the first character arrives, this call can block indefinitely if the serial line is idle. This is the most common mode of operation, and we consider VTIME to be an intercharacter timeout, not an overall one. This call should never return zero bytes read.
//
//   VMIN > 0 and VTIME = 0
//   This is a counted read that is satisfied only when at least VMIN characters have been transferred to the caller's buffer - there is no timing component involved. This read can be satisfied from the driver's input queue (where the call could return immediately), or by waiting for new data to arrive: in this respect the call could block indefinitely. We believe that it's undefined behavior if nbytes is less then VMIN.
tty.c_cc[VMIN] = 0; // 1 = blocking read, 0 = nonblocking read
tty.c_cc[VTIME] = 0; // read timeout in 1/10 of a second

returncode |= tcflush(serial_port, TCIFLUSH);
returncode |= tcsetattr(serial_port, TCSANOW, &tty);

if(returncode)
{
printf("Error in setting UART parameters.\n");
exit(1);
}
#endif



Luckily, my sensor takes 515ms (milli seconds!) to answer to a measurement request. This is slow enough to do it by hand (meaning switching a GPIO with digitalWrite()). WiringPi is your friend -- no, not really. Turns out wiringPi is no longer supported and the last version from Gordon does not work on the RPI-4B (remember, the only RPI that allows you to have an RS-232 and RS-485 inteface at the same time, which I needed). Even though Gordon claims his latest patch makes wiringPi work on RPI-4, it does not. I tried it. Some pins work, some don't. Very frustrating. Hail open source: someone made the correct changes and hosts a forked version on GitHub and his version works! Yeah!

git clone https://github.com/WiringPi/WiringPi --branch master --single-branch wiringpi

An alternative is to use PIGPIO which has added a lot of functionallity since I last looked at it some 6 years ago. Advantage: it is still supported.

But when should we set the new RTS line high and low? Simply sandwiching the write() call

digitalWrite(RTS,LOW); // we beginn transmitting
tx_len = write(serial_port, (const void *)message_str, message_len);
digitalWrite(RTS,HIGH); // we beginn transmitting

does not work, because write() immediately returns and only writes the Bytes into a buffer. Later on the UART gets the Bytes from this buffer and clocks them out the TX line.  But when?? (Remember that I still have the 1 transistor inverter on the RTS line on this system)

What works, even for a call to which the sensor responds right away is the following:

digitalWrite(RTS,LOW); // we beginn transmitting
usleep(10000);         // and switch the MAX485 into transmit mode. Give it time to settle (not really needed)
tx_len = write(serial_port, (const void *)message_str, message_len); // transfer Bytes to transmit buffer. Returns immediately.
usleep(8900); // 10ms for sending the data: this is critical! We only have a few ms before the SMT100 starts to answer. Switch too early and the last bits are mangled. Switch too late and we miss the beginning of the transmission. Worse: the SMT100 detects this and does not change its address! I hope this usleep() does not depend on the temperature or the processor clock...
digitalWrite(RTS,HIGH); // switch to RX mode
//tcdrain(serial_port); // wait for all bytes to be sent via the line (but this too slow, takes 50ms)
usleep(25000); // this is no longer critical

I first tried tcdrain(serial_port); but this returns so slowly, some 50ms after the last bit has been sent that it is unusable. The only way was to use absolute usleep() commands to delay the RTS line. This is all hodgepodge and a total hack destined to break.

RS485 on the RPI with a Trick
As always, there are several possible solutions to this problem.

First, the above code simply works for me most of the time. If it did not work, e.g., because some other interrupt interrupted my RTS setting, then I simply try again, and chances are that I will be lucky the second time. Or the third. You understand.

Second, there are chips (other than the MAX485) on the market which do the proper half duplex switching on their own. Great! This is probably the best and simplest solution. But I didn't have one of those chips.

Third, some people simply only send the LOW bits! They invert the TX line and use this to switch the DE line of the MAX485. This looks sketchy to me and I did not even try this. But it might work fine. I'm not sure.

Fourth, we can use the RPI itself to generate the RTS/DE signal. But to this end we need to know when the UART actually starts to send bits down the line. Well, the RPI has interrupt inputs! So we connect another GPIO pin with the TX line and have it trigger on the falling edge! (Remember: the idle level is HIGH) Then we tell a timer routine (thus independent from CPU load and other tasks) how long we want to keep the RTS pin HIGH. We do this by counting the bits (11 per Byte: start, 8 data, parity, stop) and using the baud rate (9600 in my case) we can compute the time. Once the timer expires, after this time has lapsed, it generates yet another interrupt which we use to set the RTS pin LOW. Yeahh! This is the solution I will now describe (since I did not find it on the internet, yet):

We start with some global variables:

#define RS485_PORT "/dev/ttyAMA0" // only ttyAMA* supports parity!
#define RTS 7   // GPIO07 will go HIGH to switch to TX-mode
// pin used to drive RTS, which is now DE of the RS485 IC.
#define TXIRQ 4 // GPIO04 will trigger an IRG on a falling edge
int serial_port = -1 ; // file descriptor for open serial port RS485_PORT
volatile bool arm_IRQ = false;
volatile int rts_num_char = 8, delay_RTS=0;

The advantage of doing RTS/DE ourselves is that we can choose the "right" polarity and do away with the inverter. Then we need some setup of the serial UART, similar to before:

struct termios tty;
speed_t speed = B9600; // baud, must be special symbol B9600!
int returncode = 0;
uint8_t address = 0;

#if(WIRING == WIRINGPI)
wiringPiSetupGpio() ;  // use BCM GPIO numbering
pinMode (RTS,  OUTPUT) ; // wiringPi funktioniert nicht richtig für den RPI-4B. Setzt das gpio pin nicht!
pinMode(TXIRQ, INPUT);
signal(SIGALRM, alarmWakeup); // set the routine to be called from the timer interrupt
wiringPiISR(TXIRQ, INT_EDGE_FALLING, &set_RTS); // the start bit will trigger this
#else
if (gpioInitialise()<0) {
return 1;
}
gpioSetMode(RTS, PI_OUTPUT);
#endif

serial_port = open(RS485_PORT, O_RDWR | O_NOCTTY | O_NONBLOCK);
if (serial_port == -1)
{
printf("[ERROR] RS485 UART open(): %s\n", strerror(errno));
return -1;
}
else
{
/*
printf("Serial port open!\n");
fflush(stdout);
*/
}

returncode |= tcgetattr(serial_port, &tty);
if(returncode)
{
printf("Error %s (%d) in getting UART parameters.\n", strerror(errno), errno);
exit(1);
}

returncode |= cfsetospeed (&tty, speed);
if(returncode)
{
printf("Error %s (%d) in setting UART TX speed.\n", strerror(errno), errno);
exit(1);
}

returncode |= cfsetispeed (&tty, speed);
if(returncode)
{
printf("Error %s (%d) in setting UART RX speed.\n", strerror(errno), errno);
exit(1);
}

tty.c_cflag = (tty.c_cflag & ~CSIZE) | CS8;     // 8-bit chars
tty.c_cflag |= PARENB;                          /* use parity bit */
tty.c_cflag &= ~PARODD;                         /* do not use ODD parity => parity is even */
tty.c_cflag &= ~CSTOPB;                         /* only need 1 stop bit, CSTOPB = Set two stop bits, rather than one. */
tty.c_cflag &= ~CRTSCTS;                        /* no hardware flow control -- does not work on RPI */
//tty.c_cflag |= CRTSCTS;                       /* hardware flow control: is needed on RPI to set RTS to LOW if sending, must be inverted by hardware, still does not work */

// disable IGNBRK for mismatched speed tests; otherwise receive break
// as \000 chars
tty.c_iflag &= ~IGNBRK;         // disable break processing
tty.c_iflag &= ~(IXON | IXOFF | IXANY);   /* no SW flowcontrol */

tty.c_lflag = 0;                // no signaling chars, no echo,
// no canonical processing

tty.c_oflag = 0;                // no remapping, no delays

tty.c_cc[VMIN] = 0; // 1 = blocking read, 0 = nonblocking read
tty.c_cc[VTIME] = 0; // read timeout in 1/10 of a second

returncode |= tcflush(serial_port, TCIFLUSH); // flush RX queue
returncode |= tcflush(serial_port, TCOFLUSH); // flush TX queue
returncode |= tcsetattr(serial_port, TCSANOW, &tty);

if(returncode)
{
printf("Error in setting UART parameters.\n");
exit(1);
}

Here is the interrupt routine that is called at the falling edge (the start bit of the transmission):

void set_RTS(void)
{
if(arm_IRQ)
{
arm_IRQ = false;
digitalWrite(RTS, HIGH); // switch to sending, set RTS HIGH (not really needed as earlier done outside)

// start the character timer (we only support 9600 baud)
// we have: start, 8 data, parity, stop = 11 bits per character
// 1/9600 * 11 * 1000 * 1000 = 1145 us
// we stay HIGH for as many chars as we send
ualarm(1146 * rts_num_char + delay_RTS, 0); // in usec. second argument: do not repeat
}
}

In the ualarm() call we start the timer, which will call our second routine:

void alarmWakeup(int sig_num)
{
// arm_IRQ = true; // don't do this here to avoid triggering again erroneously by the last bit
digitalWrite(RTS, LOW); // switch to RX, set RTS LOW
}

Now this is basically it! Two fine adjustments are needed:
* the IRQ is a bit too slow (sometimes) o bring the RTS line HIGH in time for the first start bit to be fully transmitted. Thus it is better to set RTS high by "hand" shortly before we start transmitting
* even though we use interrupts, some time is spent working through the IRQ routines. Thus we introduced delay_RTS which can be negative and shorten the RTS signal a bit. Just a few microseconds.

Here is a typical write() call then:

tcflush(serial_port, TCIFLUSH); // flush out possible garbage in the receive queue

digitalWrite(RTS,HIGH); // we beginn transmitting
rts_num_char = message_len;
delay_RTS = -150; // in usec. heuristic value
arm_IRQ = true;
tx_len = write(serial_port, (const void *)message_str, message_len); // transfer Bytes to transmit buffer. Returns immediately.

if(tx_len != message_len)
{
printf("Error in data sending from SMT100. Sent %d Bytes instead of %d.\n", tx_len, message_len);
fflush(stdout);
return true;
}
else
{
....
}

This finally works! But I had to use two different values for delay_RTS in two different transmit cases. No idea why. At this point I simply was happy that it worked.

We receive back every Byte that we send and this is good, as it allows us to check if our Bytes went out the door properly or  whether they were mangled. So this is a good thing and you should not remove this ability by wiring DE and RE together. Keep RE tied to GND. Of course, you now have to "read away" all the Bytes you sent. A good moment to compare them to the sent message and flag discrepancies.

There are many recipies on the i-net on how to make RS-485 work on the RPI -- only that most of them don't work. Now you know why.