- Installation
- Running (in Containers)
- Updating (in Containers)
- Plan for Implementation
- Sequential Initialisation
- ROS 2 Humble Hawksbill
- PX4-Autopilot (and dependencies)
OR Just Docker
For this, we will be defining a few aliases. So do not forget to clean your
.bashrc
file later on if you want to clean your aliases.
First we need to install the autopilot firmware at the correct version.
# Clone the PX4-Autopilot Firmware
git clone --recursive -b release/1.14 https://www.github.com/PX4/PX4-Autopilot.git
cd PX4-Autopilot
# Add this directory for use later
echo "export FIRMWARE_DIR=$(pwd)" >> ~/.bashrc
source ~/.bashrc
# Confirm that the variable is stored by running
# echo $FIRMWARE_DIR
To launch the simulation environment. First run:
# Run once to ensure that any remote client (like the container)
# to connect to the X Server. Essentially allows you to run GUI
# apps launched in the container to be forwarded to your local system
xhost +
Next, we can enter the simulation docker environment:
# To launch a SITL with Gazebo-Garden GUI run this first ONCE:
docker run -it --privileged --rm \
-v ${FIRMWARE_DIR}:/Firmware:rw \
-v /tmp/.X11-unix:/tmp/.X11-unix:ro \
-e DISPLAY=${DISPLAY} \
-e LOCAL_USER_ID="$(id -u)" \
-w /Firmware \
--network=host \
--name=px4_sim px4io/px4-dev-simulation-jammy \
/bin/bash
Once we enter the simulation environment, launch the simulation by running:
# Run this once you are inside the Docker container
make px4_sitl gz_x500
To make our life easier, we can make the docker run
command into an alias:
echo 'alias px4_sim="docker run -it --privileged --rm -v ${FIRMWARE_DIR}:/Firmware:rw -v /tmp/.X11-unix:/tmp/.X11-unix:ro -e DISPLAY=${DISPLAY} -e LOCAL_USER_ID='$(id -u)' -w /Firmware --network=host --name=px4_sim px4io/px4-dev-simulation-jammy /bin/bash"' >> ~/.bashrc
Now, you can directly enter the simulation container environment by running
px4_sim
.
The DDS agent is necessary to transfer the uORB topics from within the autopilot into ROS 2 topics. This can also be deployed in container environment:
git clone https://github.com/eProsima/Micro-XRCE-DDS-Agent.git
cd Micro-XRCE-DDS-Agent
docker build -t=microxrce_agent .
The build should take some time, but once it is done, we will have the agent container available. To launch this:
docker run -it --rm --network=host microxrce_agent udp4 --port 8888
For ease of use, just copy paste the following bash command as is. There aren't any superuser commands so your system should be safe.
# First clone the repository
mkdir ~/ros_workspace && cd ~/ros_workspace
git clone --recursive https://github.com/juniorsundar-tii/px4-secure-state-reconstruction.git src
# Build the Docker image
cd src
docker build -t=ssr_ros_ws .
# Run the temp_container instance to copy out the build and install files
# This needs to be done ONCE
docker run -it --name=temp_container ssr_ros_ws /bin/bash &
cd ~/ros_workspace
rm -rf install build log
docker cp temp_container:/ros_workspace/install install
docker cp temp_container:/ros_workspace/log log
docker cp temp_container:/ros_workspace/build build
docker stop temp_container
To make it easier for us to develop the solution while testing it, we will mount the ROS 2 workspace as a volume into the container. This way, you can develop locally, but build, deploy and test into the container environment where your ROS packages are available.
Since we will be using the container environment regularly, it is HIGHLY RECOMMENDED to write this alias:
# Copy paste as it is
echo "alias ssr_ros_ws='docker run -it --network=host --ipc=host --pid=host --env UID=\$(id -u) --env GID=\$(id -g) -v /tmp/.X11-unix:/tmp/.X11-unix:ro -e DISPLAY=\${DISPLAY} -v ~/ros_workspace:/ros_workspace:rw -w /ros_workspace ssr_ros_ws'" >> ~/.bashrc
source ~/.bashrc
# Note that if you are planning to run GUI packages, preface any command in a terminal with
xhost +
We need to first build the workspace:
# You can now run all ROS 2 commands as long as you prefix it with our docker alias
ssr_ros_ws colcon build
Create a ROS 2 Workspace
mkdir ros2_ws && cd ros2_ws
Clone and build the workspace
git clone --recursive https://github.com/juniorsundar-tii/px4-secure-state-reconstruction.git src
rosdep install --from-paths src --ignore-src -r -y
colcon build
source install/local_setup.bash
To run everything we need commands in five (5) terminals:
- Running the simulation environment
- Running the MicroXRCEAgent (Run once and forget)
- Running the offboard control modules
- Run the secure state reconstruction node
- Trigger the secure state reconstruction
This will be streamlined later on, but for now please bear with it.
# in Terminal 1
px4_sim
# Once you enter the container
make px4_sitl gz_x500
# in Terminal 2
docker run -it --rm --network=host microxrce_agent udp4 --port 8888
# Can run this and forget it
# in Terminal 3
ssr_ros_ws ros2 launch px4_offboard_control module_launch.py
If successful, then the drone should be hovering in the Gazebo simulation environment.
# in Terminal 4
ssr_ros_ws ros2 launch px4_ssr ssr_launch.py # This will launch the estimator and filter
# in Terminal 5
ssr_ros_ws ros2 topic pub -1 /start_ssr std_msgs/msg/Empty "{}"
As long as the build
, install
and log
directories haven't been
tampered with, you can simply git pull
or git push
normally.
Warning
If something breaks and you are getting irreparable errors, then make sure
to commit
and push
your changes to the repository. Delete the entire
~/ros_workspace
and re-run:
# First clone the repository
mkdir ~/ros_workspace && cd ~/ros_workspace
git clone --recursive https://github.com/juniorsundar-tii/px4-secure-state-reconstruction.git src
# Build the Docker image
cd src
docker build -t=ssr_ros_ws .
# Run the temp_container instance to copy out the build and install files
# This needs to be done ONCE
docker rm temp_container
docker run -it --name=temp_container ssr_ros_ws /bin/bash &
cd ~/ros_workspace
rm -rf install build log
docker cp temp_container:/ros_workspace/install install
docker cp temp_container:/ros_workspace/log log
docker cp temp_container:/ros_workspace/build build
docker stop temp_container
graph TB
subgraph "SITL Instance"
Gazebo_Simulation[Gazebo Simulation]
PX4_Firmware_SITL[PX4 Firmware SITL]
Gazebo_Simulation --> |Sensor Outputs| PX4_Firmware_SITL
PX4_Firmware_SITL-->|Motor Inputs| Gazebo_Simulation
end
Attacker[Attacker]
Sensor_Aggregator[Sensor Aggregator]
Nominal_Controller[Nominal Controller]
Safety_Filter[Safety Filter]
Secure_State_Reconstructor[Secure State Reconstructor]
PX4_Firmware_SITL --> |EKF| Attacker
PX4_Firmware_SITL --> |EKF| Sensor_Aggregator
Attacker --> |Tampered EKF| Sensor_Aggregator
Sensor_Aggregator --> |Sensors Output| Nominal_Controller
Nominal_Controller --> |Nominal Control Inputs| Safety_Filter
Sensor_Aggregator --> |Sensors Output| Secure_State_Reconstructor
Secure_State_Reconstructor --> |Reconstructed States| Safety_Filter
Safety_Filter --> |Safe Control Inputs| PX4_Firmware_SITL
flowchart BT
subgraph "Drone"
Pixhawk_1[Pixhawk FC 1]
Pixhawk_2[Pixhawk FC 2]
Pixhawk_2 -->|EKF| Attacker
Pixhawk_1 -->|EKF| Sensor_Aggregator
Safety_Filter -->|Safe Control Inputs| Pixhawk_1
subgraph Mission_Computer[Mission Computer]
Attacker[Attacker]
Sensor_Aggregator[Sensor Aggregator]
Nominal_Controller[Nominal Controller]
Safety_Filter[Safety Filter]
Attacker -->|Tampered EKF| Sensor_Aggregator
Sensor_Aggregator --> |Sensors Output| Secure_State_Reconstructor[Secure State Reconstructor]
Sensor_Aggregator -->|Sensors Output| Nominal_Controller
Secure_State_Reconstructor -->|Reconstructed States| Safety_Filter
Nominal_Controller-->|Nominal Control Inputs| Safety_Filter
end
end
The drone will only hover until a toggle is provided:
# in Terminal 5
ssr_ros_ws ros2 topic pub -1 /start_ssr std_msgs/msg/Empty "{}"
Attacker can be toggled with this:
ssr_ros_ws ros2 topic pub -1 /safe_control std_msgs/msg/Bool "data: true" # or "data: false"
The standard controller will be used until this is initialised:
ssr_ros_ws ros2 topic pub -1 /safe_control std_msgs/msg/Bool "data: true" # or "data: false"
State reconstruction can be initialised with this:
ssr_ros_ws ros2 topic pub -1 /state_reconstruction std_msgs/msg/Bool "data: true" # or "data: false"
It is possible to query what the state of each of the above systems are by getting the appropriate parameter:
# Get state of safe controller/safety filter (boolean)
ros2 param get /offboard_control_xvel safe_control_state
# Get state of attacker (boolean)
ros2 param get /attacker attacker_state
# Get state of state reconstructor (boolean)
ros2 param get /safe_controller state_reconstruction_state