How to Run MAVROS on VOXL with PX4
Table of contents
- Overview
- Prerequisites
- mavros_test example ROS node
- Setup and Configuration
- Test mavros_test offboard-mode flight pattern
- Running mavros automatically on boot
- Troubleshooting:
Overview
This tutorial demonstrates how to fly a VOXL-based drone autonomously in a figure 8, using MAVROS.
For this setup, MAVROS is installed and runs on VOXL inside the roskinetic-xenial docker image. Additionally, the voxl-vision-px4
background service should be running in Yocto and is automatically started on boot once configured. This provides Visual Inertial Odometry (VIO) for PX4 and manages the mavlink telemetry over UART to the PX4 Flight Core.
WARNING: At the end of this tutorial, your drone will be flying autonomously. Please only run this in a safe location away from people and wear protective eyewear!!
Prerequisites
- Make sure voxl-vision-px4 is installed and configured.
- Make sure your drone flies reliably in position mode with VIO.
- Make sure you have the roskinetic-xenial docker image installed.
mavros_test example ROS node
mavros_test
is available at https://gitlab.com/voxl-public/mavros_test which provides helper scripts for starting the mavros node as well as the source code for a “mavros_test” node which demonstrates how to use offboard mode to make px4 fly a pattern autonomously.
The following scripts should help you run mavros in the roskinetic-xenial docker image even if you don’t use the mavros_test node itself.
ros_environment.sh
This configures the ROS IP environment variables and is used by run_mavros.sh
and run_mavros_test.sh
. This is much like the ~/my_ros_env.sh
script in the Yocto base image. You don’t have to run this script yourself as it is called by run_mavros.sh
and run_mavros_test.sh
, but this is where you would make changes to match your network configuration.
Note: if you using the docker image without but not the run_mavros_*
scripts, run the following to configure ROS
cd /root/yoctohome/mavros_test
source ros_environment.sh
run_mavros.sh
This will start the mavros node configured to listen for UDP packets from voxl-vision-px4 and relay them back to qGroundControl.
run_mavros_test.sh
This will start two ROS nodes: mavros and mavros_test. You don’t need to call run_mavros.sh
first. mavros_test.sh
waits for a connection to PX4 through mavros then arms the drone and flies a 1m square before landing.
build.sh and clean.sh
These build and clean the catkin_ws and mavros_test node. Make sure to build INSIDE the roskinetic-xenial docker so it links to the roskinetic libraries and builds for arm64.
Setup and Configuration
configure voxl-vision-px4
voxl-vision-px4
must be configured to pipe px4’s mavlink messages from UART to UDP at localhost. This can be done simply by enabling the en_localhost_mavlink_udp
feature in the voxl-vision-px4 config file (/etc/modalai/voxl-vision-px4.conf
). Note that this opens a socket at port 14551 just for local communication with mavros. Communication with QGC is over port 14550 to prevent conflicts.
yocto:/home/root# cat /etc/modalai/voxl-vision-px4.conf
{
"qgc_ip": "192.168.8.60",
"en_localhost_mavlink_udp": true,
.
.
.
After updaing the config file, restart the voxl-vision-px4 service for the changes to take effect.
yocto:/home/root# systemctl restart voxl-vision-px4
While it is possible to have MAVROS handle the communication with QGC, we do not recommend this since QGC could initiate communication with voxl-vision-px4
at any time which would cause redundant links. The mavros_test demo does not create a link to QGC. Also note that if you are writing your own mavros scripts you will need to specify port 14551 for communication with voxl-vision-px4
.
Build and configure mavros_test node
Clone and copy the mavros_test repo to the home directory on VOXL. Current source code available at https://gitlab.com/voxl-public/mavros_test
me@mylaptop:~/git$ adb push mavros_test/ /home/root/mavros_test/
Start the roskinetic-xenial docker image and make sure the mavros_test directory you copied over is visible inside the docker. If you are using the voxl-docker utility then this should work.
yocto:/home/root# voxl-docker -i roskinetic-xenial:v1.0
roskinetic:~$ ls
ros_catkin_ws yoctohome
roskinetic:~$ cd yoctohome/mavros_test/
roskinetic:mavros_test$
Now you can build the mavros_test ROS node.
roskinetic:mavros_test$ ./clean.sh
roskinetic:mavros_test$ ./build.sh
Edit the scripts/ros_environment.sh script to match your network configuration. By default it is set up with the 192.168.8.1 address that VOXL takes when running in softAP wifi mode. If your VOXL is on a wifi network you will need to change this to VOXL’s new IP address.
Mavros also needs to be told what sysid PX4 has. The default is 1 but if you’ve changed the MAV_SYS_ID
parameter in PX4 this will need to match.
roskinetic:mavros_test$ nano ros_environment.sh
# configure ROS IPs here
export ROS_MASTER_IP=127.0.0.1
export ROS_IP=192.168.8.1
export ROS_MASTER_URI=http://${ROS_MASTER_IP}:11311/
# mavros needs to know what PX4's system id is
export PX4_SYS_ID=1
Note: the new mavros_test binary you just built and the changes you made to ros_environment.sh will not be lost when you exit the docker image since the mavros_test directory is in yocto’s home directory and is mounted inside the docker image.
Test Mavros
While still in the docker, you should now be able to start mavros and qGroundControl should connect. Don’t run run_mavros_test.sh yet or your drone will try to arm and takeoff!!
roskinetic:mavros_test$ ./run_mavros.sh
Test mavros_test offboard-mode flight pattern
Power on your drone in a safe flight location. Wherever the system powers on will be x,y,z = 0,0,0 in visual odometry frame and where the system will fly the pattern. You can alternative restart the voxl-vision-px4 systemd process to restart VIO if you’ve moved the drone since power on.
SSH into VOXL, launch the roskinetic docker, and run run_mavros_test.sh
yocto:/home/root# voxl-docker -i roskinetic-xenial:v1.0
roskinetic:~$ cd yoctohome/mavros_test/
roskinetic:mavros_test$ ./run_mavros_test.sh
Running mavros automatically on boot
As per the running docker on VOXL instructions, you can place the following in the /etc/modalai/docker-autorun.sh script and make sure the docker-autorun systyemd service is enabled.
voxl-docker -n -i roskinetic-xenial:v1.0 -w /root/yoctohome/mavros_test/ -e "/bin/bash run_mavros.sh"
systemctl enable docker-autorun
Troubleshooting:
It’s very possible that you hear QGC warn “high accelerometer bias” if the system has sat still too long before arming. This is a known issue with PX4’s EKF2. To quickly continue reset the PX4 software from QGC. Our preffered method is in the parameters page in QGC click tools>restart vehicle. This will only reset the PX4, not VOXL, mavros, or VIO.
references
https://wiki.ros.org/mavros https://dev.px4.io/v1.9.0/en/ros/mavros_offboard.html