Serialx - Support for half duplex...

Status
Not open for further replies.

KurtE

Senior Member+
As I have been testing several Serial port related issues associated with the new beta board which now adds Serial4 and Serial5. Right now I am needing to update some of my own code/libraries to support them, and I was wondering if it makes sense to add some of the support for Half duplex directly into the HardwareSerial code.

Example Setup code for my Bioloid (Robotis AX12) support.
Code:
void ax12Init(long baud, Stream* pstream, int direction_pin ){
    // Need to enable the PU resistor on the TX pin
    s_paxStream = pstream;
    s_direction_pin = direction_pin;    // save away.

    // Lets do some init here
    if (s_paxStream == &Serial) {
        Serial.begin(baud);
    }

    if (s_paxStream == (Stream*)&Serial1) {
        Serial1.begin(baud);
#if defined(KINETISK) || defined(__MKL26Z64__)
        if (s_direction_pin == -1) {
            UART0_C1 |= UART_C1_LOOPS | UART_C1_RSRC;
            CORE_PIN1_CONFIG = PORT_PCR_DSE | PORT_PCR_SRE | PORT_PCR_MUX(3) | PORT_PCR_PE | PORT_PCR_PS; // pullup on output pin;
        } else {
            Serial1.transmitterEnable(s_direction_pin);
        }
#elif defined(TEENSYDUINO)
        // Handle on Teensy2...
        if (s_direction_pin != -1) {
            Serial1.transmitterEnable(s_direction_pin);
        }
#endif
    }
#ifdef SERIAL_PORT_HARDWARE1
    if (s_paxStream == &Serial2) {
        Serial2.begin(baud);
#if defined(KINETISK)  || defined(__MKL26Z64__)
        if (s_direction_pin == -1) {
            UART1_C1 |= UART_C1_LOOPS | UART_C1_RSRC;
            CORE_PIN10_CONFIG = PORT_PCR_DSE | PORT_PCR_SRE | PORT_PCR_MUX(3) | PORT_PCR_PE | PORT_PCR_PS; // pullup on output pin;
        } else {
            Serial2.transmitterEnable(s_direction_pin);
        }

#endif
    }
#endif
...
Current code also supports Serial3... Now to add 4/5. More question for other thread, but figure out what #ifdef to use to know if I have Serial4 and Serial5...

But it would be great if instead, I could use a different, MODE on Serial1.begin(1000000, SERIAL_8N1_HALFDUPLEX);

And it would handle the changing of the UARTS c1 register and currently I then enable PU on the ports TX register. Could use bit 6 for this.

Currently my own code is not as complete as it should be as I don't currently have any support for handling the non default TX pin for the UART, and there are no calls to query what the TX pin currently is...

Also when I am doing the half duplex, I need to set/clear the UART_C3_TXDIR to set the TX pin as input or output. Current code to setRX looks like:
Code:
#if defined(KINETISK)  || defined(__MKL26Z64__)
    // Teensy 3.1
    if (s_paxStream == (Stream*)&Serial1) {
        UART0_C3 &= ~UART_C3_TXDIR;
    }
    if (s_paxStream == (Stream*)&Serial2) {
        UART1_C3 &= ~UART_C3_TXDIR;
    }
    if (s_paxStream == (Stream*)&Serial3) {
        UART2_C3 &= ~UART_C3_TXDIR;
    }
I can probably clean this up in my own code to hold onto pointer of the UARTx_C3 register, but would be nice if I could add a method to do this internal to serial class. Something like: setHalfDuplexDirection(bool output=true);

If this makes sense, I would obviously be willing to do the work and issue Pull request.

Thoughts?
Kurt
 
Any idea how much code and performance cost this adds to the serial code?

I guess this question could really be better answered if we had some decent ways to benchmark the serial overhead.....
 
Hi Paul,

Not much code, I have not done the complete set yet, can and put it into it's own branch if you would like to take a look.
Along the line of:
HardwareSerial.h
Add:
Code:
#define SERIAL_8_N1_HALFDUPLEX 0x40
Then for each of the Serial1-5 add new function prototype:
Code:
void serial_set_tx_dir(uint8_t tx_output);

For each of the Serial classes add method:
Code:
	virtual void setTXPinDirection (uint8_t tx_output) { serial_set_tx_dir(tx_output); }

Then in each of the Serialx.c files, make change to serial_format: Something like:
Code:
void serial_format(uint32_t format)
{
	uint8_t c;

	c = UART0_C1;
	c = (c & ~0x13) | (format & 0x03);	// configure parity
	if (format & 0x04) c |= 0x10;		// 9 bits (might include parity)
	UART0_C1 = c;
	if ((format & 0x0F) == 0x04) UART0_C3 |= 0x40; // 8N2 is 9 bit with 9th bit always 1
	c = UART0_S2 & ~0x10;
	if (format & 0x10) c |= 0x10;		// rx invert
	UART0_S2 = c;
	c = UART0_C3 & ~0x10;
	if (format & 0x20) c |= 0x10;		// tx invert
	UART0_C3 = c;
#ifdef SERIAL_9BIT_SUPPORT
	c = UART0_C4 & 0x1F;
	if (format & 0x08) c |= 0x20;		// 9 bit mode with parity (requires 10 bits)
	UART0_C4 = c;
	use9Bits = format & 0x80;
#endif
	if (format & 0x40) {
            UART0_C1 |= UART_C1_LOOPS | UART_C1_RSRC;  // Half duplex
        }
}
Which added the last lines which turned on loops mode...
Note: optionally here, I often also turn on Pull up resistor, other times use external PU. But if added might look like:
CORE_PIN1_CONFIG = PORT_PCR_DSE | PORT_PCR_SRE | PORT_PCR_MUX(3) | PORT_PCR_PE | PORT_PCR_PS; // pullup on output pin;
But if I did it, would also need to check which IO pin is assigned to TX

Then for the set_tx_dir, function is pretty simple:
Code:
void serial_set_tx_dir(uint8_t tx_output)
{
	if (tx_output)
    	UART0_C3 |= UART_C3_TXDIR;
    else
		UART0_C3 &= ~UART_C3_TXDIR;
}
Again optionally in here I also typically in setting to RX mode do a Serial.flush(), as you typically need to wait until the last bit is output before switching the direction of the TX pin...

Hope that makes sense.

Edit: As per overhead, not much as the only code most apps would ever see is simply the extra test in the format function

Edit 2: Alternative to adding a new API would be to overload: transmitterEnable and it's functionality.
For example maybe allow special pin (0xff?), when set, would work same way as the direction pin, that is
Example in serial_putchar(c), we have:
if (transmit_pin) transmit_assert();

Where transmit_assert is macro, which on KINETISK: #define transmit_assert() *transmit_pin = 1;
So could could add code here... (if transmit_pin == (char*)-1) UART0_C3 |= UART_C3_TXDIR; else *transmit_pin = 1;

Likewise for transmit deassert()... This actually would be pretty nice as then my code could work the same for both with external buffer chip or using half duplex...
 
Last edited:
Status
Not open for further replies.
Back
Top