Motion Capture
Motion capture allows for non-GPS navigation by sending pose estimation data to the flight controller's EKF. ROS makes this easy as there are drivers and packages that allow us to publish pose topics into the ROS framework. We can then relay those topics directly into MAVROS which will then send the poses to the flight controller.
Qualisys Motion Capture
This assumes that you have already set up your Qualisys motion capture system and configured a rigid body for your UAV.
QTM is only supported via Windows, so we will use another computer utilizing a Linux distro to act as our ROS pose publisher. The best practice is to connect these two machines via Ethernet to avoid latency and packet loss.
Docker
Setting up Qualisys ROS on Linux is made easy via Docker.
This tutorial will assume you are running on a Linux OS, but Docker can be used on both Mac and Windows via Docker Desktop.
First, make sure you installed Docker Engine. It is also recommend you follow the Linux Post-Installation Steps as well to manage Docker as a non-root user.
We can verify our Docker installation via:
$ docker run hello-world
We can now build our Docker mocap
image via the following commands:
$ cd ~/mavrospy/docker/mocap
$ bash run_docker.sh
This script will automatically build the mocap
image and open it in a Docker container.
CTRL+C to exit.
PX4 Parameters
If you wish to use a motion caputure system as your means for navigating without a GPS, you must configure the following PX4 parameters.
EKF2_HGT_REF = Vision
EKF2_EV_DELAY = 50.0ms
EKF2_GPS_CTRL = 0
EKF2_BARO_CTRL = Disabled
EKF2_RNG_CTRL = Disable range fusion
EKF2_REQ_NSATS = 5
MAV_USEHILGPS = Enabled
EKF2_MAG_TYPE = None
Timesync
For the pose topic to be understood properly between computers, it's important that both machines are in sync. On both systems, run:
$ timedatectl
In the output, you should see:
System clock synchronized: yes
NTP service: active
If the output indicates that the NTP service isn't active, turn it on via:
$ sudo timedatectl set-ntp on
After this, run timedatectl
again to confirm the network time status.
Motion Capture Demo
- ROS2
- ROS1
If you are following this tutorial after the GPS Navigation Tutorial please remove the outdoor MAVROSPY
container:
- RPi4
- Jetson Nano
$ docker container rm -f mavrospy2-rpi-outdoor-container
$ docker container rm -f mavrospy2-jetson-outdoor-container
Before you can start publishing pose topics, you must first modify the motion capture configuration file to specify the IP address of your QTM server. Open the file cfg.yaml
:
$ nano ~/mavrospy/docker/mocap/cfg.yaml
Find the line that reads:
hostname: "10.24.5.189"
Replace the IP address with the IP address of your QTM server. Save and exit the file.
You can now start publishing. Start by opening the mocap
Docker container:
$ cd ~/mavrospy/docker/mocap
$ ./run_docker.sh
Next, run the following command to start publishing pose topics:
$ ros2 launch motion_capture_tracking launch.py
To verify your pose topics are being published, run the following on your companion computer:
- RPi4
- Jetson Nano
$ cd ~/mavrospy/docker/rpi
$ ./run_docker.sh
$ ros2 topic echo /poses
$ cd ~/mavrospy/docker/jetson
$ ./run_docker.sh
$ ros2 topic echo /poses
You can now start our motion capture control node on our companion computer via:
- RPi4
- Jetson Nano
$ ros2 launch mavrospy mocap.py
$ ros2 launch mavrospy mocap.py fcu_url:=$FCU_URL
You can specify the flight pattern via the pattern
argument. If unspecified, it will default to square
.
- RPi4
- Jetson Nano
$ ros2 launch mavrospy mocap.py pattern:=figure8
$ ros2 launch mavrospy mocap.py fcu_url:=$FCU_URL pattern:=figure8
Available Patterns: square
, square_head
, circle
, circle_head
, figure8
, figure8_head
, spiral
, and spiral_head
. Where _head
will specify the drone to face in the direction of motion.
You can verify that your flight controller is receiving our pose topic by entering the following command on your companion computer in another terminal:
$ ros2 topic echo /mavros/vision_pose/pose
CTRL+C to exit.
If you are following this tutorial after the GPS Navigation Tutorial please remove the outdoor MAVROSPY
container:
- RPi4
- Jetson Nano
$ docker container rm -f mavrospy-rpi-outdoor-container
$ docker container rm -f mavrospy-jetson-outdoor-container
On your companion computer, make sure your running the MAVROSPY
Docker container:
- RPi4
- Jetson Nano
$ cd ~/mavrospy/docker/rpi
$ bash run_docker.sh
$ cd ~/mavrospy/docker/jetson
$ bash run_docker.sh
We must modify the mocap.launch
file to direct your rigid body name to the relay topic node. Open the file:
$ nano ~/mavrospy/launch/mocap.launch
Find this line:
<node pkg="topic_tools" type="relay" name="relay" output="screen" args="/qualisys/My_Quad/pose /mavros/vision_pose/pose"/>
Replace My_Quad
with the label of your rigid body created in QTM.
You can now start our motion capture control node on our companion computer via:
- RPi4
- Jetson Nano
$ roslaunch mavrospy mocap.launch
$ roslaunch mavrospy mocap.launch fcu_url:=$FCU_URL
You can specify the flight pattern via the pattern
argument. If unspecified, it will default to square
.
- RPi4
- Jetson Nano
$ roslaunch mavrospy mocap.launch pattern:=figure8
$ roslaunch mavrospy mocap.launch fcu_url:=$FCU_URL pattern:=figure8
Available Patterns: square
, square_head
, circle
, circle_head
, figure8
, figure8_head
, spiral
, and spiral_head
. Where _head
will specify the drone to face in the direction of motion.
In order to publish ROS pose topics from our computer to the companion computer, we must establish a ROS Master. In our case, we will choose the companion computer as the master.
On your publishing computer, start by opening the mocap
Docker container:
$ cd ~/mavrospy/docker/mocap
$ bash run_docker.sh
Next, export the ROS_MASTER_URI
environment variable. Make sure to replace master_ip_address
with the IP address of the companion computer:
$ export ROS_MASTER_URI=http://master_ip_address:11311
Now to start publishing, enter:
$ roslaunch mocap_qualisys qualisys.launch server_address:=qtm_server_address
Where qtm_server_address
is the IP address to your QTM server.
To verify your pose topics are being published, run the following on another terminal on your companion computer:
- RPi4
- Jetson Nano
$ cd ~/mavrospy/docker/rpi
$ bash run_docker.sh
$ rostopic echo /qualisys/My_Quad/pose
$ cd ~/mavrospy/docker/jetson
$ bash run_docker.sh
$ rostopic echo /qualisys/My_Quad/pose
Where My_Quad
is the label of your rigid body created in QTM. CTRL+C to exit.
You can verify that your flight controller is receiving our pose topic via:
$ rostopic echo /mavros/vision_pose/pose
CTRL+C to exit.
Additionally, you can check that the PX4 flight contoller is able to calculate a global position estimage via:
$ rostopic echo /mavros/global_position/global
CTRL+C to exit.
You can now switch to OFFBOARD mode and watch it fly!