This package enables the control of an autonomous aerial vehicle (UAV) that uses pixhawk hardware as a flight control unit (FCU). It has been developed with the PX4 flight stack in mind. The original purpose was for simulating insect inspired behaviours, traditional waypoints can be combined with more complex "behaviours". It is intended for use with projects that make use of a companion computer. Some key features are:
- Extends PX4 ROS/GAZEBO simulation or can be run on a companion computer.
- Built using ROS middleware - therefore provides an easy interfaces to other robotics packages.
- No need to modify code in the FCU - therefore no risk of affecting the target vehicle's stability and no need to rebuild Firmware for each update.
- Built with python
- Install ROS Melodic (desktop full version): https://wiki.ros.org/noetic
- Install the PX4 Firmware: https://dev.px4.io/master/en/setup/dev_env_linux_ubuntu.html#sim_nuttx
- Build the PX4 Firmware: https://dev.px4.io/v1.9.0/en/simulation/ros_interface.html#launching-gazebo-with-ros-wrappers
- Install catkin tools: https://catkin-tools.readthedocs.io/en/latest/installing.html#installing-on-ubuntu-with-apt-get
- Install mavros and mavros extras: https://dev.px4.io/v1.9.0/en/ros/mavros_installation.html#installation
If you want to setup a new ROS workspace for this project (recommended) then follow the steps at http://wiki.ros.org/catkin/Tutorials/create_a_workspace. An adapted example of this process is outlined in this section (change "kinetic" to your ROS installation).
First, open a terminal and (if not already done) source the main ROS installation
source /opt/ros/{{ros-version}}/setup.bash
Now create an area for your installation, for example:
$ mkdir -p ~/ros_workspaces/pyx4_ws/src
Change directories to your workspace and clone the pyx4 repo, for example:
$ cd ~/ros_workspaces/pyx4_ws/src
$ git clone https://github.com/jannsta1/pyx4
Change directories to your workspace and build.
$ cd ~/ros_workspaces/pyx4_ws/
$ catkin build
A number of environmental variables are required to enable all of the software modules to communicate with each other. The snippet below shows what is included in a typical .bashrc file or favoured way of setting environmental variables (some of these are already described in the PX4 toolchain installation so careful not to duplicate environmental variables).
# environmental variables used by pyx4 - adapt to your needs
export PX4_SRC_DIR=~/px4_myfork/Firmware # point this to where your PX4 firmware is installed
export ROBOT_VRPN_NAME="SITL" # only required if using the VRPN ROS package (Vicon)
export ROBOT_TYPE="SITL" # SITL / REAL
export ROBOT_STATE_ESTIMATION="SITL" # GPS / VICON / VISION
export FCU_URL="127.0.0.1"
export GCS_URL="127.0.0.1" # or "udp://:14570@localhost:14550"
# adds the gazebo libraries (adapt to where you installed gazebo)
export GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:~/.gazebo/models
export GAZEBO_RESOURCE_PATH=$GAZEBO_RESOURCE_PATH:~/.gazebo/worlds:/usr/share/gazebo-7 # Change to gazebo 9 if applicable
# function to set ROS/PX4 environmental variables
function setpx4() {
source /opt/ros/kinetic/setup.bash # point this to your main ROS installation
current_dir="$PWD"
build_ref=px4_sitl_default
cd ~/ros_workspaces/pixhawk_ws # point this to your ROS pyx4 project workspace
source devel/setup.bash
cd ${PX4_SRC_DIR}
# PX4
source ${PX4_SRC_DIR}/Tools/setup_gazebo.bash ${PX4_SRC_DIR} ${PX4_SRC_DIR}/build/px4_sitl_default
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:${PX4_SRC_DIR}:${PX4_SRC_DIR}/Tools/sitl_gazebo
# tidy up
cd "$current_dir"
}
setpx4 # comment out if you don't want setpx4 to run automatically
nano .ignition/fuel/config.yaml
-
Change
url: https://api.ignitionfuel.orgtourl: https://api.ignitionrobotics.org -
Run
source ~/.bashrc
- Check if
/home/user/path-to-Firmware/Firmware/Tools/sitl_gazebo/worldsexists. - If so, find the line
export GAZEBO_RESOURCE_PATHand add:~/Firmware/Tools/sitl_gazebo/worlds - Run
source ~/.bashrc
To ensure that the setup procedure has been succesful. Run the following command in a terminal that has the the ros workspace loaded:
$ roslaunch pyx4 simple_mission.launch world:=empty.world
The default aircraft should takeoff and then follow some positional setpoints before returning to the origin and landing.
There are multiple ways to specify missions in pyx4. A simple way to get up and running is to use the CSV mission loader approach. Using the templates found in pyx4_base/data/mission_specs, a sequence of position or velocity waypoints can be set for each control axis.
Once a mission has been specified in this fashion, it can be performed using the associated roslaunch file:
roslaunch pyx4 csv_mission.launch csv:=YOUR_MISSION_FILE.csv
- instruction_args can be passed. This is useful for sending unspecified parameters to a custom flight state. The arguments should be formatted like a dictionary but with semicolons to divide entries e.g. {speed:2 ; z_tgt:3.0}
The goal of the testing platform is to ensure that no bugs are introduced when the code is modified.
For that, a test mission is created, which aim is to perform the basic logic of the codebase. Then, to test, the test_mission is performed and the testing platform checks that the position of the drone at each waypoint is the same as it was before the code was modified.
Run
rostest pyx4 pyx4.test
Args
missionis, by default,pyx4_base/data/mission_specs/basic_test.csv, andcompispyx4_base/data/test/basic_test.csv
A CSV mission designed to test the basic logic of the pyx4 system.
- To test z alone in target position: take off to 3m maintaining the x and y positions at the origin.
- Test x alone in target position: advance 10m in x, maintain y and z.
- Test z alone in target position: advance 10m in x, maintain x and z.
- Test moving in x, y and z in target position: go back to the origin in x and y while increasing the altitude to 10m.
- Test x alone in target velocity: advance in x at velocity 1 for 10s, maintain y and z.
- Test y alone in target velocity: advance in y at velocity 1 for 10s, maintain x and z.
- Test x and y in target velocity while moving z in target position: advance in x and y at velocity -2 for 12s while decreasing the altitude to 5m.
- Test holding the position: maintain x, y and z for 5s.
- Test x and y in target velocity while moving z in target position and adding yaw: advance in x and y at velocity 2 for 10s while increasing the altitude to 8m and adding a target yaw of 1.
- Test landing: land at the starting point.
For each waypoint, different checks are performed to ensure correct functionality of the code base:
- waypoint position: it checks whether the position at which the drone is when a waypoint is reached is as expected.
- target type: it checks whether the target type for the xy setpoints is as expected. For example, making sure that it is target position instead of velocity.
- timeout: checks that the timeout for each waypoint is as expected.
- velocity: only for xy velocity setpoints. It checks that the velocity throughout is more or less constant and as expected.
In addition, there is a basic check that tests that the number of waypoints visited is the same as specified in the mission file.
pyx4_base/data/mission_specs/basic_test.csv: the default test missionpyx4_base/data/test/basic_test.csv: the test mission comparison file. For each waypoint, it contains the local positions the drone should be at when it reaches the waypoints.pyx4_base/test/pyx4.test: launch the Px4 and Pyx4 nodes to perform the mission. Launchpyx4_test_logic.pyto perform the test logics. Launchpyx4_test.pyto perform the unittests.pyx4_base/test_scripts/pyx4_test_logic.py: ROS node where most of the testing logic happens.pyx4_base/test_scripts/pyx4_test.py: unittest node that performs the test assertions.pyx4_base/test_scripts/get_test_data.py(optional, not recommended): to get the comparisson file for testing. Otherwise, the waypoints could be computed by hand.pyx4_base/launch/get_test_data.launch: launch file to launchget_test_data.py.
Note: This step is already done, and unless there is a change in the test mission it should not be done again.
To test a comparison file is needed. This MUST be done when the code has passed some tests or when the developer is confident the code base is working properly.
Check the test mission file to compute the final position for each waypoint and write a CSV in pyx4_base/data/test with the following columns:
- label: the waypoint number
- x: x position at the waypoint
- y: y position at the waypoint
- z: z position at the waypoint
- yaw: yaw position at the waypoint
NOT RECOMMENDED: To have it done automatically, run
roslaunch pyx4 get_test_data.launch mission:=yourmission.csv comp:=yourcomp.csv overwrite:=true/false
where
missionis the test mission. Default:pyx4_base/data/mission_specs/basic_test.csv;compis the comparison mission to write. Default:pyx4_base/data/test/basic_test.csv.overwriteis set tofalseby default. If set to true, it will overwrite the comp_file if it already exists. Iffalseand the comparison file exists, it throws an exception.
Currently, the default testing mission basic_test.csv is as described above, and the default comparison file basic_test.csv has been obtained using get_test_data.
Node to teleoperate the drone using keyboard inputs.
Uses the teleop_twist_keyboard node to take keyboard input.
To install:
sudo apt-get install ros-{{distro}}-teleop-twist-keyboard
roslaunch pyx4 teleop.launch
And to use keyboard input:
Reading from the keyboard and Publishing to Twist!
---------------------------
Moving around:
u i o
j k l
m , .
q/z : increase/decrease max speeds by 10%
w/x : increase/decrease only linear speed by 10%
e/c : increase/decrease only angular speed by 10%
anything else : stop
- Better console output
- Fix coordinate frame?
todo