Holybro CM4 + Pixhawk 5X setup troubleshoot thread

About

While setting up the Holybro’s new, to be released CM4 baseboard Pixhawk5X, I found that although I can flash the firmware, the HDMI output doesn’t show anything, and I neither can SSH into the Raspberry Pi via USB connection.

Therefore I am starting this thread to track any previous successes on getting this board running, so that we can also prepare for the documentation in parallel.

image

If anyone has succeeded in setting it up, please leave a comment!

What I’ve tried / done so far

This is the main tutorial that I’ve followed to get the RPi CM4 flahsed & working.

Suspected Issue

Power supply (is USB-C enough?) → Apparently low voltage on SD card lines? can cause reboot (mentioned in the reboot Github issue I believe)?

Related Resources

Other Comments

@ryanjAA it seems like you have the CM4 baseboard version yourself. Were you able to flash the Raspberry Pi successfully & have it communicating with PX4?

Updates

Flashing image as described here: Full Compute Module 4 (Raspberry Pi) Setup / Imaging Guide

First, I set the CM4 into eMMC mode, and plugged in via USB to the CM4 Slave port.

image

image

But then the flashing took too long, so I aborted it.

I then downloaded the image: Operating system images – Raspberry Pi

I don’t have one (as you now know). Hope the integration is going well :slight_smile:

eMMC Flashing again

Following this nice eMMC flashing tutorial as well: How to flash Raspberry Pi OS onto the Compute Module 4 eMMC with usbboot | Jeff Geerling

First, I set the Dip-Switch to ‘RPI’, to enter eMMC mode :thinking:

It seems like “CM4 Slave” needs to be connected, in order for sudo ./rpiboot command to work and flash the RPi.

Having the flash image downloaded seems to speed up flashing process considerably!

It took ~5 minutes for the last 99% flashing
 stage to end, but then the ‘Verifying’ stage is proceeding now.

Another nice documentation on eMMC flashing: Usage | CM4 Sensing

Finally!! Then I unmounted the boot partition to make sure I don’t mess up while unplugging the cable :wink:

It boots!

After connecting HDMI, the CM4 indeed showed the screen output for the first time, yay!

Flashing PX4

Then I flashed PX4 by connecting USB cable from desktop to the “FC” USB connector port and doing make px4_fmu-v6x in the latest upstream PX4-Autopilot repo.

SSH-ing into it

Although I already configured Wifi settings in Raspberry Pi imager, it seems like without a dongle it won’t work.

Therefore I am using the ethernet connector and using an external Ethernet switch to route it & connect to my laptop.

However, I was getting error like this:

The authenticity of host 'raspberrypi.local (192.168.34.49)' can't be established.
ECDSA key fingerprint is ASDF ASDF
Are you sure you want to continue connecting (yes/no/[fingerprint])? yes
Warning: Permanently added 'raspberrypi.local,192.168.34.49' (ECDSA) to the list of known hosts.
pi@raspberrypi.local's password: 
Permission denied, please try again.
pi@raspberrypi.local's password: 
Permission denied, please try again.
pi@raspberrypi.local's password: 
pi@raspberrypi.local: Permission denied (publickey,password).

So I had to uncomment the lien that said PasswordAuthentication yes, in order to allow password authentication through SSH.

SSH related resources

In the end, I switched from DHCP to “share to other computers” option for Wired network settings on desktop. Then, I could detect the raspberypi.local via network (the IP address output when executing hostname -I in Raspberry Pi changed as well!)

Then the SSH worked!

There was a nerror popping up regarding env variable (-bash: warning: setlocale: LC_ALL: cannot change locale (en_US.UTF-8)) but solved via this: Problem with locales on remote server via ssh - Jerris Blog - Jerris Welt

CM4 Host / Slave connections

image

image

Notes from Vince

CM4 UART(GPIO14–TXD , GPIO15–RXD , GPIO16–CTS , GPIO17–RTS) is connect to Tel2 on the CM4 Base.

I got the CM4 + Pixhawk 6X combo to work.

Below are the steps taken to flash the CM4 part, boot it, and connect it to PX4.

Notes

  • The fan does not indicate if the CM4 is powered/running or not. It seems to always be running.
  • The power module plugged into Power1/2 does not power the Rpi part. You can use the additional cable from the power module to the CM4 Slave USB-C port.
  • The Micro-HDMI port is an output port.
  • Some CM4 might not have wifi device and therefore won’t connect automatically, unless you plug in a compatible wifi dongle into the CM4 Host ports.

Flash EMMC

We need to flash a RPi image onto EMMC.

  1. Switch Dip-Switch to RPI.
  2. Connect computer to USB-C CM4 Slave port used to flash and power the RPi.
  3. Get usbboot, build it and run it.
sudo apt install libusb-1.0-0-dev
git clone --depth=1 https://github.com/raspberrypi/usbboot,
cd usbboot
make
sudo ./rpiboot
  1. You can now install your favorite Linux distro, e.g. Raspberry Pi OS 64bit, using The rpi-imager. Make sure to add wifi and ssh settings (hidden behind the gear/advanced symbol).
sudo apt install rpi-imager
rpi-imager
  1. Once done, unmount the volumes, and power off the CM4 by unpluggin USB-C CM4 Slave.
  2. Switch Dip-Switch back to EMMC.
  3. Power on CM4 by providing power to USB-C CM4 Slave port.
  4. To check if it’s booting/working, either check HDMI output, or connect via ssh (if set up in rpi-imager, and wifi is available).

Connect PX4 to CM4 via serial

Pixhawk 6X talks to CM4 using Telem2 (/dev/ttyS4).

  1. To enable this MAVLink instance, set the params:
  • MAV_1_CONFIG: 102
  • MAV_1_MODE: 2
  • SER_TEL2_BAUD: 921600
  1. reboot the FMU

  2. On the RPi side, I would connect it to Wifi using a Wifi Dongle.

  3. Enable serial port to FMU by using raspi-config: Go to 3 Interface Options, then I6 Serial Port.
    Choose

  • login shell accessible over serial → No
  • serial port hardware enabled → Yes
    Finish, and reboot.
    (This will add enable_uart=1 to /boot/config.txt, and remove console=serial0,115200 from /boot/cmdline.txt
  1. Now MAVLink traffic should be available on /dev/serial0 at a baudrate of 921600.

Try out MAVSDK-Python

  1. Make sure the CM4 is connected to the internet, e.g. using a wifi, or ethernet.
  2. Install MAVSDK Python:
python3 -m pip install mavsdk
  1. Copy an example from the MAVSDK-Python examples.
  2. Change the system_address="udp://:14540" to system_address="serial:///dev/serial0:921600"
  3. Try out the example. Permission for the serial port should already be available through the dialout group.
2 Likes

Next I tried to connect the to ethernet ports and try out local link:

Link-local networking setup between CM4 and FC

Local cable

To set up a local ethernet connection between CM4 and the flight computer, the two ethernet ports need to be connected using a 8 pin to 4 pin connector.

The pinout of the cable is:

8 pin:
1 A
2 B
3 C
4 D
5 (not connected)
6 (not connected)
7 (not connected)
8 (not connected)

to 4 pin:
1 B
2 A
3 D
4 C

IP setup on CM4

Since there is no DHCP server active in this configuration, the IPs have to be set manually:

First, connect to the CM4 via ssh by connecting to the CM4’s wifi (or use a Wifi dongle).

Once the ethernet cables are plugged in, the eth0 network interface seems to switch from DOWN to UP.

You can check the status using:

ip address show eth0

You can also try to enable it manually:

sudo ip link set dev eth0 up

It then seems to automatically set a link-local address, for me it looks like this:

ip address show eth0

2: eth0: <BROADCAST,MULTICAST,UP,LOWER_UP> mtu 1500 qdisc mq state UP group default qlen 1000
    link/ether xx:xx:xx:xx:xx:xx brd ff:ff:ff:ff:ff:ff
    inet 169.254.21.183/16 brd 169.254.255.255 scope global noprefixroute eth0
       valid_lft forever preferred_lft forever
    inet6 fe80::yyyy:yyyy:yyyy:yyyy/64 scope link 
       valid_lft forever preferred_lft forever

This means the CM4’s ethernet IP is 169.254.21.183.

IP setup on FC

Now connect to the NuttX shell (using a console, or the MAVLink shell), and check the status of the link:

ifconfig

eth0    Link encap:Ethernet HWaddr xx:xx:xx:xx:xx:xx at DOWN
        inet addr:0.0.0.0 DRaddr:192.168.0.254 Mask:255.255.255.0

For me it is DOWN at first.

To set it to UP:

ifup eth0

ifup eth0...OK

Now check the config again:

ifconfig

eth0    Link encap:Ethernet HWaddr xx:xx:xx:xx:xx:xx at UP
        inet addr:0.0.0.0 DRaddr:192.168.0.254 Mask:255.255.255.0

However, it doesn’t have an IP yet. I’m going to set one similar to the one of CM4:

ifconfig eth0 169.254.21.184

And check it:

ifconfig

eth0    Link encap:Ethernet HWaddr xx:xx:xx:xx:xx:xx at UP
        inet addr:169.254.21.184 DRaddr:169.254.21.1 Mask:255.255.255.0

Now the devices should be able to ping each other.

Note that this configuration is ephemeral and will be lost after a reboot, so we’ll need to find a way to configure it statically.

Ping test

First from the CM4:

ping 169.254.21.184

PING 169.254.21.184 (169.254.21.184) 56(84) bytes of data.
64 bytes from 169.254.21.184: icmp_seq=1 ttl=64 time=0.188 ms
64 bytes from 169.254.21.184: icmp_seq=2 ttl=64 time=0.131 ms
64 bytes from 169.254.21.184: icmp_seq=3 ttl=64 time=0.190 ms
64 bytes from 169.254.21.184: icmp_seq=4 ttl=64 time=0.112 ms
^C
--- 169.254.21.184 ping statistics ---
4 packets transmitted, 4 received, 0% packet loss, time 3077ms
rtt min/avg/max/mdev = 0.112/0.155/0.190/0.034 ms

And from the FC in NuttShell:

ping 169.254.21.183

PING 169.254.21.183 56 bytes of data
56 bytes from 169.254.21.183: icmp_seq=0 time=0 ms
56 bytes from 169.254.21.183: icmp_seq=1 time=0 ms
56 bytes from 169.254.21.183: icmp_seq=2 time=0 ms
56 bytes from 169.254.21.183: icmp_seq=3 time=0 ms
56 bytes from 169.254.21.183: icmp_seq=4 time=0 ms
56 bytes from 169.254.21.183: icmp_seq=5 time=0 ms
56 bytes from 169.254.21.183: icmp_seq=6 time=0 ms
56 bytes from 169.254.21.183: icmp_seq=7 time=0 ms
56 bytes from 169.254.21.183: icmp_seq=8 time=0 ms
56 bytes from 169.254.21.183: icmp_seq=9 time=0 ms
10 packets transmitted, 10 received, 0% packet loss, time 10010 ms

MAVLink/MAVSDK test

For this, we need to set the mavlink instance to send traffic to the CM4’s IP:

For an initial test we can do:

mavlink start -o 14540 -t 169.254.21.183

This will send MAVLink traffic on UDP to port 14540 (the MAVSDK/MAVROS port) to that IP which means MAVSDK can just listen to any UDP arriving at that default port.

To run a MAVSDK example, install mavsdk via pip, and try out an example from MAVSDK-Python/examples.

For instance:

python3 -m pip install mavsdk

wget https://raw.githubusercontent.com/mavlink/MAVSDK-Python/main/examples/tune.py
chmod +x tune.py
./tune.py
1 Like

Hi JulianOes, glad that you got the Rpi CMP4 + Pixhawk FMuv6U working fine.

I am trying to flash the Pixhawk FMUv6U using the USB port of Pixhawk in DFU mode using STM32CubeProgrammer.

I am first trying to upload the bootloader file which was available in PX4 repo

At device memory adress 0x0000:0000

And later lost DFU access, but through JTAG, I had access to the STM32 where I could see that bootloader was uploaded. Later, I even tried to flash the firmware file from here

All i did is to convert px4_fmu-v6u_rtps.px4 file to px4_fmu-v6u_rtps.bin to upload the firmware through STMCubeIDE. Tried updating QGC to the latest version, neither the device manager nor QGC did not show up the device.
Also, quick note,

There is no SD card access to the custom board. Is the SD card really essential for the bootup of the pixhawk or will it even be detectable without SD card is the question

What do you suggest, we can collaborate and try solving this issue. I need real help here. Cheers!

I’m confused what you’re trying to do, and I have no experience with STMCubeIDE.

Why don’t you use the normal px4 uploader?

Actually, I built a board around FMUv6U architecture,
STM32H753IIT6

There is not much information provided neither in the PX4 GitHub Repo nor there is no other implementation i see apart from this,

so I tried to upload their firmware from what they were using.

No luck, I am able to upload the bootloader from STM32CubeProgrammer in DFU mode, neither does Device manager or QGC detect the device nor Mission Planner

Kinda stuck in a limbo

And I dont see any support from Ardupilot too

Any help would be appreciated

Also since, its a bare STM32 that we have put on the board, there is no bootloader installed.
SD card access is provided now, fixed it. Is there any way I can bootup PX4 from SD card?

You need to do a board bring up. Look at copying one of the existing boards closest to yours and editing all the config files for your pinout. it won’t work otherwise.

The pinout is tried and tested by Gumstix already, we have not altered it in the first prototype board. So assuming that, it’s just the process of flashing a bare Pixhawk for the first time,
For the FMUv6U architecture.

From DFU to connecting to QCG/Mission Planner for the first time after DFU flashing
So assuming that, could you run me through with the first time flashing a Pixhawk fmuv6u board, target device is STM32H753IIT6

I get this when flashing the bootloader file

I am trying to flash the board from the direct USB port from STM32H753IIT6

This thread has been helpful.
However I currently need help with a message from rpiboot “Waiting for BCM2835/6/7/2711
”
I know this indicates that the USB port has been opened, and my computer is waiting to see a Raspberry Pi on the opened port.
I have verified in device manager that two ports are opened (from the fm and cm4 slave connections),
Has anyone troubleshot this?
I’ve tried different cables.
Did PC reboots and multiple rpiboot restarts as administrator.
I do have the rpi-emmc switched to rpi.

Are you on Windows or Linux? What command are you trying to run? Have you tried to run it as administrator (or sudo on Linux)?

I am opening rpiboot in Windows as the administrator. I confirm that the CM4 and Flight Controller are connected (ports open). RPI boot responds with a message:
Waiting for BCM2835/6/7/2711
 which I think means rpiboot is waiting to connect to CM4. So since the board is not recognized by RPIboot, I don’t get to the point where I can enter a command.

(upload://scGbrmc3ltbwKRaNvfcmiaH0JbG.png)

I’d try what they suggest here: Raspberry Pi Compute Module 4 8GB Flashing Issue! - Raspberry Pi Forums

One of the things would be to check whether the CM4 is correctly connected in the IO, so open up the case and take the CM4 out and put it back in maybe?

Hi Julian,
Your suggestion hit the mark.

I had ordered a controller with the CM4, but the unit that was sent to me did not have one installed. Just an empty space with two rails.

Thanks,
Tom