Cubieboard and Arduino via UART

In my last post, we saw how flexible and powerful the Cubieboard can be, with the correct knowledge of the pin multiplexing and choosing the pin functionality for your application. Given that you have 7 UART ports, and around 3 SPI ports at your disposal, you can only imagine the power that this gives you.

The company that produces the SoC on which the Cubieboard is based on, AllWinner, primarily wanted to develop this chip as a cheap alternative to Android enabled device manufacturers, such as phones, tablets and what not! And hence, the chipset and subsequently the development boards, are powerful, flexible and have ports designed for external device interfacing, including 2 camera interfaces. (However, only one can be active at one time, like front cam and back cam) But, what it makes for in these interfaces, it lacks in the number of ADC’s (Only one, for accelerometer. People argue that it has the ADC’s for the LCD screen, but involves hacking the driver files, interesting project if someone is willing me to pay for it) and PWM channels. Basically, you cannot collect data or move motors by just using the Cubieboard.

So, if you are planning to use the Cubieboard in your Embedded Design Project, you will sooner or later have the need to communicate with a daughter board, either for getting a bunch of sensor data, or performing some actuation. This post comes as a result of a similar need I had, where I had to trigger a bunch of OpenCV codes which depended on certain sensor values.

Since I could not interface my sensors on the Cubieboard, I decided to use an Arduino for measuring the sensor data and communicate the processed values to the Cubieboard via UART.

The Cubieboard has 8 UART ports in all, including the 4-pin TTL port. However, this 4 pin TTL by default is used in the following ways:

  1. Console Messages (including bootup messages)
  2. A getty so you can login via serial

So, I would suggest that you avoid using the TTL pins, since you would need to edit the boot and initab files in order to use them. Plus, this port comes in very handy for debugging purposes. So instead, we will configure the other GPIO pins for UART.

On the Arduino side, instead of connected pins 0 and 1 (The default UART pins) , I decided to use the SoftSerial library instead. Why? Because I wanted to hook up my Arduino to my PC via USB, whilst it communicates with the Cubieboard, for debugging purposes.

Now I will show the codes on the Arduino and the Cubieboard side respectively, after which you can safely wire up the proper pins on both sides and communicate seamlessly.

Arduino side:

As mentioned before, I won’t be using the default serial pins for interfacing and instead use the SoftSerial library to configure pins 2 and 3 instead. However, the SoftSerial library does not support baudrates above 9600. We will see how that is actually a good thing for us later. Following code snippet sends a character to both serial ports if the ADC value is above a threshold, and prints whatever value it gets from CubieBoard to the PC:

/*

 Connects Arduino to Cubieboard
 Arduino: SoftSerial
 Raspberry Pi: GPIO UART

 Based on Arduino SoftSerial example

 */
#include

SoftwareSerial mySerial(2, 3); // RX, TX
int pressure;
int THRESHOLD = 500;

void setup()
{
 // Open serial communications to PC and wait for port to open:
  Serial.begin(57600);

  // set the data rate for the SoftwareSerial port to Cubieboard
  mySerial.begin(9600);

  // Set A1 as input sensor
  pinMode(A1,INPUT);
}

void loop() // run over and over
{
  // Measure the sensor value
  pressure = analogRead(A1);

  // If pressure crosses the threshold, send character to both ports
  if(pressure>THRESHOLD) {
    Serial.write("Y");
    mySerial.write("Y");
  }

  // If data is available on Cubieboard, print it to PC
  if (mySerial.available())
    Serial.write(mySerial.read());
}

Cubieboard side:

First order of business would be to configure a UART port  of our choice on the Cubieboard. For this case, UART5 is an optimal choice, it has only the Rx and Tx ports, just like the Arduino side, thus not wasting any GPIOs unnecessarily.

Now we make changes in the fex file like mentioned in my previous post and note down the pins:

[uart_para5]
uart_used = 1
uart_port = 5
uart_type = 2
uart_tx = port:PH06
uart_rx = port:PH07

The pins are : Tx (Port H, pin 6) and Rx (Porn H, pin 7)

Make sure to compile the fex file to an appropriate bin file, otherwise the changes will not be seen.

Just to check all the UART ports that you have, you can just list by the following command:

ls /dev/tty*

OR

dmesg|grep tty 

Now for the communication part, hackers tend to use Python due to the ease with which you can perform serial communication, thanks to the PySerial library. But in my case, since I had to trigger some OpenCV based codes, I decided to go the C++ way, since I could just include a header file in the main file and save a lot of unwanted mess.

Serial Initialization function

Although you can just open the Serial Port on any linux box as a file, you need to define some flow control and flag options for the desired communication terminal since this is an asynchronous communication and follows a proper handshaking protocol(If you need more clarification on this, please mention on the comments). So we will need some standard libraries for this purpose, you can add them like this:

#include
#include <sys/ioctl.h>

Now we initialize the serial port terminal options :

/*Init function, takes serialport address and baudrate as input */
int serialport_init(const char* serialport, int baud)
{
struct termios toptions;     //from the termios lib
int fd;                      //file descriptor

Next step would be to open the port with the proper flags and initialize the input and output data speed equal to the input baudrate:

//Open the port as a file
//O_RDWR = Open as read and write
//O_NOCTTY = TTY file not to be used for control purposes
fd = open(serialport, O_RDWR | O_NOCTTY)
//set the baudrate
speed_t brate = baud
//setting the input and output speed
cfsetispeed(&toptions, brate);
cfsetospeed(&toptions, brate);

Now that the serial port has been initialized with the correct options, you can just read it as a file and accordingly write the functions for them. For the complete code with the read and write functions, please refer to this link.

Now you can include this library in your main file and initialize the port like this:

 serialport_init("/dev/ttyS5", 9600); 

Final Connections:

Now that we have configured the UART pins and written the appropriate code on both ends, time to hook them up. Following are the pin outs:

Cubieboard Arduino
Rx – Port H, pin 7 Rx – pin 2
Tx – Port H, pin 6 Tx – Pin 3

The possibilities from here are endless, you can send commands from the Board to the Arduino and use them to control motors or actuators. In case you need further clarifications on any of these, feel free to drop a comment here!

NOTE: I mentioned before that the 9600 baudrate on the Arduino is actually a blessing in disguise for us, that is because Arduino supports only 2 pin UART, which is actually not at all ideal for a full duplex communication. Imagine this scenario, the Arduino sends some data and triggers a code on the Cubieboard, now any data that the Arduino sends while the Cubieboard is still executing the code will be lost because of the lack of proper data control pins. A quick fix around this would be to run a thread which accumulates the sensor data in a buffer on the board, or to time your code properly so that it finishes executing before the next data comes in

Happy Tinkering!

32 comments
  1. nth said:

    hi
    i use cubieboard A10
    i received data from uart5_rx (pin 37, PH7), but i can’t send data from uart5_tx (i don’t find PH6 in cubieboard document)

    I configure test is
    uart_tx=port:PH06
    uart_rx=port:PH07
    and change to
    uart_tx=port:PI10
    uart_rx=port:PH07

    can you help me?
    How to send data from uart5 (uart6) ? i don’t know set pin uart_tx !

  2. abhinavgupta said:

    Hey!

    I just checked the available pin out on the Cubieboard and I completely missed that the PH06 is actually muxed and used up in the Cubieboard’s SATA pin out. So I’d suggest that you use the UART 2 or 3, those pin out are still available

  3. Roop said:

    any tips getting this working with usb connected directly to the cubie?

    it gets detected:
    Bus 005 Device 002: ID 0403:6001 Future Technology Devices International, Ltd FT232 USB-Serial (UART) IC

    but no /dev/tty* instance appears.

    • abhinavgupta said:

      Well, is this the message you got from dmesg? If yes and there was no mention of where it can be accessed, then you might have to re compile the kernel again on changing the config file. In any case can you tell me what device is this?

  4. thomasf said:

    You have to modprobe the driver of your USB-Serial IC, after that it will appear as ttyUSB

    • abhinavgupta said:

      Exactly! But in case its a USB camera, you need to install appropriate drivers for v4l without which you wont be able to run modprobe in the first place.

  5. Roop said:

    Thanks for the help. I wound up following your steps and could get (sporadic) use of serial output from the Arduino to the cubieboard.

    would you be able to share the full C serial sample? I’ve been through many iterations of ones online but am yet to see consistent behavior from the cubiearduino connection.

    • abhinavgupta said:

      Can you elaborate on the sporadic part? Are you receiving garbage values? Or is the Rx-Tx on both sides not that robust?

      If it is the second one, then that is because Arduino doesn’t follow the 6 pin UART format, maybe you can write a software routine to emulate these pins?

  6. Roop said:

    the value is certainly the correct values. sometimes i receive them as i like, eg

    20
    20
    21

    but other times I receive wierd carriage return/space/tab sequences (underscore for spaces):

    20
    [newline]
    _______20
    [newline]
    _____________21

    others yet, nothing. i can’t get this working reliably enough to use it. it’s one of the three behaviors and to cycle through them, i restart minicom.

    • abhinavgupta said:

      I will test out the code soon, I am guessing this is mostly due to baudrate or some issue with software handling of the data buffer.

  7. Dimi Henri said:

    hi , i use a cubieboard 2
    i have configurate my UART5 on the pin PH15 and PH14
    when i lanch dmesg|grep tty i have the UART5 on ttyS2
    but i don’t know how can i send and receive data, i have checked your C code but with my oscilloscope i have neither signal, can you help me please?

    • abhinavgupta said:

      Try sending some normal characters with minicom? Install minicom on both your board and your machine and test it.

      • Dimi Henri said:

        thank you for your reply.
        I have install minicom and connect my pin PH15, PH14 GND and 5V with a FTDI for check data on the terminal on the PC but i have nothing. With the oscilloscope also i have nothing.

      • abhinavgupta said:

        You do not have to connect 5V anywhere! You just need to connect the RX TX and GND line. In fact attaching the 5V lines might damage the board!

  8. Dimi Henri said:

    OK thank you i have find the problem, i have not the juste MUX for the UART now i have change that and its good. thank you for your help

  9. Afiqah said:

    hi.,
    where i get library –> ioctl.h ?
    thank for your help..

    • abhinavgupta said:

      The library is a standard one that comes with the native gcc distribution, you need not get it per se.

  10. Benny said:

    Hello,
    I am trying to get the UART working on my Cubietruck with CubianOS but without luck.

    My script.fex looks like this:

    [uart_para7]
    uart_used = 1
    uart_port = 7
    uart_type = 2
    uart_tx = port:PI20
    uart_rx = port:PI21

    I have no other declaration of these pins in the script.fex file. The pins are on the extension header CN8
    PIN15 PI20 (FMIN-L/PS2SCLK0/UART7-TX/HSCL)
    PIN17 PI21 (FMIN-R/PS2SDA0/UART7-RX/HSDA)

    Do you have any idea what can be the problem?

    • abhinavgupta said:

      Hey sorry for the late reply!

      What you are amissing is the pin muxes in your fex file which has made me realized a very big blunder in my post which is an incomplete fex file. Please wait till I fix the post.

      Apologies to everyone here for the misleading post/

      • Benny said:

        Hi,

        Thanks for your help. I have now fixed the missing muxes and it is working for me now.
        Meanwile I am running in another problem which costs me a lot of time to discover it.
        In the default config of minicom there is the hardware flow enabled and when you are not disable it it will not work.
        My problem was that I have not realized that I have forgotten to save the minicom config.
        So all the time there was the hardware flow enabled and a have not connected it in hardware.
        After disabling the hardware flow in minicom the UARTs are working very well for me.

  11. Willy said:

    Hello,

    I am trying to use UART connection between arduino and cubieboard 2 . I have changed the uart_para5 on script.bin as stated above, but there is no pin ph6. I have seen the cubieboard pin defintion and there is no matching pin between the on on script.bin and the one from cubieboard pin definition.

    For example on the script.bin:
    [uart_para5]
    uart_tx = port:PH06
    uart_rx = port:PH07

    on the cubieboard2 pin definition:
    there is no ph6. but on the table explanation on the definition table uart5_tx is on pin 45 PI10.

    on the scipt.bin all uart_para pin are not available on the gpio pin.

    Could you please explain me how to resolve this issue? thanks in advance.

    • abhinavgupta said:

      You are right, the ports defined by the default fex file has PH06, and as you pointed out correctly, the mux table shows PI10 as a pin with UART5-TX. To enable the UART 5 for your case, I suggest making the UART 5 para something like this:

      [uart_para5]
      uart_used = 0
      uart_port = 5
      uart_type = 2
      uart_tx = port: PI10
      uart_rx = port: PI11

      The three is because, UART5 TX and RX are on the mux 3 of PI10 and PI11 respectively.

      • Willy said:

        Thank you for your clear answer. I am trying to create the main program now. could you give me example to receive and send serial to arduino? In your program you have already stated command to receive and send: int serialport_read_until(int fd, char* buf, char until) and int serialport_write(int fd, const char* str). but I don’t know what to insert on the fd, buf, and until (or str).

      • Lilian said:

        I would be interested by an example of using too. I can’t read anything but the writing works well.
        Thank You for your sharing.

  12. milton ortiz said:

    any schematic on how to find the pins to be used in cb2? i cannot find ph6 in the docs, i can’t even find port h. your help would be appreciated

    • milton ortiz said:

      sorry, i had a cache version of the page and didn’t see you already answered, thanks

  13. Fransiscus Richard said:

    Hello, I’m using cubie2. I want to make the cubie to receive gps data given by arduino via serial5 in cubie and print it out using cout(I’m using Qt Creator for the programming). but as I tried your coding, it returns an error that says the serial port cannot be opened, permission denied. could you help me please? Thanks before.

  14. milton ortiz said:

    hello, i need help.
    i did all your steps, edited script.bin, i used pi10 and pi11 for cubie2, reboot but when “dmesg|grep tty” just uart0:ttys0 is enabled, do i missed something? anything left to enable uart5? i am newbie in this.
    thanks in advance

    • abhinavgupta said:

      Which distribution are you using? It could be because your .config file in the linux must not be allowing multiple instances of the serial driver file. Were you able to resolve the issue or still stuck?

      Sorry for the late reply.

      • milton ortiz said:

        thanks for answering, i already switched procedures for my requirement, now i am connecting rf24l01 directly to cubie. thanks again

  15. Razor said:

    Great! Thanks a lot!

  16. Eder Navarro said:

    Hi, great tutorial. one thing, I put all the functions on one file with a main and tested but didn’t seem to work, it only worked when I manually opened the port with cutecom.

    I fixed the problem adding a “B” to the baud settings on serialport_init function like this:

    serialport_init(“/dev/ttyS1”, B115200);

Leave a comment