Autonomous Drone: Take To The Skies With Your ODROID-XU4

This tutorial will walk you through building a Pixhawk guided autonomy-capable drone. The project consists of the following:

  • ODROID XU4 with 32GB SD Card (Flashed with Ubuntu 18.04)
  • ODROID WiFi Module #5
  • 3DR Pixhawk 1 FCU
  • Pixhawk Power Module
  • USB-TTL Module
  • Intel Realsense T265 Tracking Camera
  • Q330 UAV Frame
  • RS2203 2300KV Motors x 4
  • 25A-rated ESCs x 4
  • 5500 mAh 3S LiPo Battery
  • Spare 2.1mmx5.5mm Barrel Power Connector
  • FS-IA6B Radio Receiver
  • Flysky i6 Controller
  • PDB
  • Double Sided Mounting Tape

Wiring and Assembly

Figure 1 - All the materials used for this project prior to assembly
Figure 1 - All the materials used for this project prior to assembly

The important takeaway from our list of materials is that most of our required materials can be used to build a simple drone. The Pixhawk controller is designed to communicate with any onboard Linux capable computer and doesn't care about the peripherals, so you could potentially use any radio, battery, ESC/motor combination, and frame you want. This universality is powerful, thus you do not need to restrict yourself to the materials I listed.

Our first step would be to assemble the drone. We will assemble it in a "Quad X" configuration, which is the simplest drone configuration available in Pixhawk. Figure 2 shows how you should set up your drone connections, and also where the ESC signals should be connected to the Pixhawk outputs.

Figure 2 - Quad X with associated motor directions and numbering
Figure 2 - Quad X with associated motor directions and numbering

Figure 3 - Pixhawk Output pins (numbered). First 4 pins are colour-coded for connecting a Quad X frame
Figure 3 - Pixhawk Output pins (numbered). First 4 pins are colour-coded for connecting a Quad X frame

After assembling the frame and screwing the motors in, you can solder the ESCs to the PDB (which is part of the Q330 frame) and to the motors. Figure 4 shows the associated wiring for different sping directions.

Figure 4 - ESC to motor wire connections corresponding to different spin directions
Figure 4 - ESC to motor wire connections corresponding to different spin directions

Now connect the radio receiver to Pixhawk. Pixhawk interprets signals as SBUS, which I configured my FS-IA6B receiver to output over a single data line.

Figure 5 - FS-IA6B to Pixhawk link
Figure 5 - FS-IA6B to Pixhawk link

Now we solder the spare barrel jack connector to the Pixhawk power module, which has a 5V 3A BEC that we will use to power the onboard ODROID. The soldering is shown in Figure 6. Testing the voltage output with the voltmeter shows 5.28V, which is safe for powering our ODROID.

Figure 6 - Barrel jack connector to BEC soldering
Figure 6 - Barrel jack connector to BEC soldering

Figure 7 - Voltage output from the BEC after powering on the circuit
Figure 7 - Voltage output from the BEC after powering on the circuit

The last soldering will be the USB-TTL converter, which will be used for communication between ODROID and the Pixhawk FCU, shown in Figure 8. A schematic can be found at https://ardupilot.org/dev/_images/ODroid_Pixhawk_Wiring.jpg.

Figure 8 - USB-TTL data connection to Pixhawk
Figure 8 - USB-TTL data connection to Pixhawk

We are now done with the tedious part of the assembly, and it's time to mount everything onboard. I used soft double sided mounting tape so that the FCU and camera wouldn't be affected by the vibrations from the quadrotor. Due to the lack of space, I decided to mount the camera on the Pixhawk FCU, which was mounted on top of the ODROID. This is not the best approach, but it works well enough, though the issue could be easily mitigated by using a smaller FCU (such as the Pixracer) or by 3D printing extensions.

Figure 9 - Double sided mounting underneath the ODROID-XU4
Figure 9 - Double sided mounting underneath the ODROID-XU4

Figure 10 - The ODROID mounted on the Q330 frame
Figure 10 - The ODROID mounted on the Q330 frame

Figure 11 - The Pixhawk FCU mounted on top of ODROID. Note that the Pixhawk FCU was leveled W.R.T. the Q330 frame
Figure 11 - The Pixhawk FCU mounted on top of ODROID. Note that the Pixhawk FCU was leveled W.R.T. the Q330 frame

Figure 12 - Receiver, barrel jack, USB-TTL, WiFi adapter, and ESC outputs connected
Figure 12 - Receiver, barrel jack, USB-TTL, WiFi adapter, and ESC outputs connected

Figure 13 - Realsense T265 camera mounted on top of the Pixhawk FCU and connected to ODROID
Figure 13 - Realsense T265 camera mounted on top of the Pixhawk FCU and connected to ODROID

ODROID software setup

Our assembly is now complete, and it's time to set up the software. Luckily this is so simple it all boils down to installing packages and verifying our devices/connections:

1. Install ROS Melodic from http://wiki.ros.org/melodic/Installation/Ubuntu 2. Install [librealsense from https://github.com/IntelRealSense/librealsense/blob/master/doc/installation.md. (make sure to follow step 5) 3. install ros-melodic-ddynamic-reconfigure via apt 4. Install realsense-ros from https://github.com/IntelRealSense/realsense-ros 5. Install mavros and mavlink:

$ sudo apt-get install ros-kinetic-mavros ros-kinetic-mavros-extras
$ wget https://raw.githubusercontent.com/mavlink/mavros/master/mavros/scripts/install_geographiclib_datasets.sh && ./install_geographiclib_datasets.sh
6. Test that the T265 camera works (connect ODROID to a screen and execute `realsense-viewer` from terminal) 7. Verify T265 camera also works in ROS:
$ roslaunch realsense2_camera rs_t265.launch
You should see odometry messages coming in at a rate of ~200 Hz from this topic
$ rostopic hz /camera/odom/sample
subscribed to [/camera/odom/sample]
average rate: 199.868
min: 0.001s max: 0.012s std dev: 0.00130s window: 189
average rate: 199.845
min: 0.000s max: 0.044s std dev: 0.00947s window: 389
average rate: 199.574
min: 0.000s max: 0.044s std dev: 0.01103s window: 585
8. Install a conversion package from https://github.com/thien94/vision_to_mavros so that the coordinate frames from the camera to the FCU will be correct.

9. Create access point from ODROID's WiFi module and reboot to enable it:

$ git clone https://github.com/oblique/create_ap
$ cd create_ap
$ sudo make install
$ systemctl start create_ap
$ systemctl enable create_ap
$ create_ap wlan0 eth0 odroid_drone --mkconfig /etc/create_ap.conf

Pixhawk FCU setup

At this point our ODROID setup is complete and we need to configure the Pixhawk FCU with QGroundControl. You may download the AppImage to your own computer, and after connecting to the FCU follow these steps to completely set up Pixhawk for accept vision positioning data:

1. Install latest firmware 2. Choose the airframe type (for my case i will choose Quadrotor X - DJI Flame Wheel F330 as it's similar enough to the Q330) 3. Calibrate the FCU sensors 4. Calibrate your radio controller after binding it to the receiver 5. Calibrate LiPo battery and ESCs. Set the correct values in Number of Cells 6. Assign radio channels in Flight Modes. I set mine as in Figure 14 7. We now go to the Parameters section:

  • I changed `CBRK_IO_SAFETY` to disable safety checking, but this is optional
  • Change `PWM_MIN` to a reasonable value (I set it to 1050 us)
  • Set `MAV_0_CONFIG` to "TELEM 2", `MAV_0_MODE` to "Onboard"
  • Uncheck "use GPS" in `EKF2_AID_MASK` and check "vision position fusion" and "vision yaw fusion"
  • Change `EKF2_HGT_MODE` to "Vision"
  • Set the `EKF2_EV_POS_X`, `EKF2_EV_POS_Y`, `EKF2_EV_POS_Z` parameters accordingly
  • For safety, change `COM_OBL_ACT` to "Terminate" and `COM_OBL_RC_ACT` to "Terminate" in case there is some sort of error in the ODROID-Pixhawk data link

Figure 14: My radio controller channel configuration
Figure 14: My radio controller channel configuration

I assigned a manual kill switch for emergencies as well. The Manual, Position, and Offboard mode switches have been assigned for a smooth transition to autonomy.

Taking flight

Now we will send our own data for flying. We clone a custom package called my_autonomous_drone from https://github.com/yehonathanlitman/my_autonomous_drone and rebuild our ROS space. You should execute the following to find your USB-TTL converter:

$ ls /dev/tty* | grep USB
Then, change launch/px4.launch to follow this format:
<launch >
        <arg name="fcu_url" default="/dev/ttyUSB0:921600" />
        <arg name="tgt_system" default="1" />
        <arg name="tgt_component" default="1" />
        <arg name="log_output" default="log" />

        <include file="$(find mavros)/launch/node.launch" >
                <arg name="pluginlists_yaml" value="$(find my_autonomous_drone)/launch/px4_plugins.yaml" />
                <arg name="config_yaml" value="$(find my_autonomous_drone)/launch/px4_config.yaml" />

                <arg name="fcu_url" value="$(arg fcu_url)" />
                <arg name="gcs_url" value=" " />
                <arg name="tgt_system" value="$(arg tgt_system)" />
                <arg name="tgt_component" value="$(arg tgt_component)" />
                <arg name="log_output" value="$(arg log_output)" />
        </include >
</launch >
Now make a src directory in the my_autonomous_drone package and add a offb_node.cpp (https://dev.px4.io/v1.9.0/en/ros/mavros_offboard.html) to it. Make sure to add the file to the package build so it can be compiled. After powering up the drone from the battery, SSH into the access point you created and follow these commands:

1. Run “roslaunch my_autonomous_drone px4.launch” to begin data transmission 2. Verify the FCU is connected with “rostopic echo /mavros/state” 3. Launch the Realsense node with “roslaunch realsense2_camera rs_t265.launch” 4. Run “roslaunch vision_to_mavros t265_tf_to_mavros.launch” for coordinate frame conversion 5. The last step is to run “rosrun my_autonomous_drone offb_node” to begin sending the position waypoint to Pixhawk. The drone flies are shown in Figure 15.

Figure 15 - Our ODROID drone hovering at 1 meter above the ground!
Figure 15 - Our ODROID drone hovering at 1 meter above the ground!

If you want the drone to do something more impressive, you can play around with the x and y coordinates in offb_node.cpp. For example, an eight-figure can be done using parametric equations (https://mathworld.wolfram.com/EightCurve.html). Inside the while loop we can do this, where the variable “i” is initialized to 0 before the while loop begins:

double t = i * 0.02;
x = a * sin(t);
y = a * sin(t) * cos(t);
i++;

Conclusion

In this guide, I have shown you how to assemble a drone, connect its flight controller to ODROID, and send it simple guidance commands in ROS. This is just the tip of the iceberg of a super interesting field, but with a bit of hard work you can start doing some really amazing things. If you want more, you can check out my YouTube channel (youtube.com/c/SimpleKernel) where I have uploaded some more in depth instructional videos on autonomy using Pixhawk and setting up your own visual guidance from scratch.

Be the first to comment

Leave a Reply