Aerial Robotics IITK
  • Introduction
  • Danger Zone
  • Tutorials
    • Workspace Setup
      • Installing Ubuntu
      • Basic Linux Setup
      • Spruce up your space
      • ROS Setup
      • PX4 Setup
        • PX4 Toolchain Setup
      • Ardupilot Setup
      • Installing Ground Control Station
        • QGroundControl
        • Mission Planner
      • ArduPilot Setup on Docker
      • PX4 Setup on Docker
    • How to Write a ROS Package
      • ROS Package
      • Node Handles, Parameters, and Topics
      • Coding Standards
      • Custom mavros message
      • Transformations
      • Conversions
    • Cheatsheets
      • CMakeCheatsheet
      • GitCheatsheet
      • LatexCheatsheet
      • Markdown Cheatsheet
    • Miscellaneous
      • Odroid XU4 Setup
      • Simulation using Offboard Control
        • Enable Offboard Mode in PX4
      • Writing a UDev rule
      • Sensor fusion
    • Reference wiki links
  • Concepts
    • Quaternions
      • Theory
    • Kalman Filters
    • Rotations
    • Path Planning
      • Grassfire Algorithm
      • Dijkstra Algorithm
      • A* Algorithm
      • Probabilistic Roadmap
      • RRT Algorithm
      • Visibility Graph Analysis
    • Lectures
      • Aerial Robotics
      • Avionics
      • Control Systems: Introduction
      • Control Systems: Models
      • Inter IIT Tech Meet 2018
      • Kalman Filters
      • Linux and Git
      • Git Tutorial
      • ROS
      • Rotorcraft
      • Software Training
  • Control System
    • Model Predictive Control
      • System Identification
      • Sample SysId Launch Files
      • Running MPC
        • MPC with Rotors
        • MPC with PX4 Sim
        • MPC with ROS
      • References
    • PID Controller
      • Introduction
      • Basic Theory
  • Estimation
    • Visual-Inertial Odometry
      • Hardware Requirements
      • Visual-Inertial Sensing
      • DIYing a VI-Sensor
    • Setup with VICON
    • Odometry from pose data
  • Computer Vision
    • Intel RealSense D435i setup for ROS Noetic
    • IntelRealSense D435i Calibration
    • Camera Calibration
    • ArUco ROS
  • Machine Learning
    • Datasets
  • Hardware Integration
    • Configuring Radio Telemetry
    • Setting up RTK + GPS
    • Integration of Sensors with PixHawk
      • Connecting Lidar-lite through I2C
    • Connections
    • Setting up Offboard Mission
      • Setting up Companion Computer
        • Raspberry Pi 4B Setup
        • Jetson TX2 Setup
      • Communication Setup
      • Guided mode
    • Miscellaneous
  • Resources
    • Open-source algorithms and resources
    • Courses
      • State Space Modelling of a Multirotor
      • Path Planning Lecture
      • Introduction to AI in Robotics
      • RRT, RRT* and RRT*- Path Planning Algorithms
    • Useful Reading Links
      • Aerial Robotics
      • Books
      • Computer Vision and Image Processing
      • Courses on AI and Robotics
      • Deep Neural Network
      • Dynamics and Controls system
      • Motion Planning
      • Probabilistic Robotics
      • Programming
      • Robotics Hardware
      • Miscellaneous and Awesome
    • Online Purchase websites
  • Competitions
    • Inter-IIT TechMeet 8.0
    • Inter-IIT TechMeet 9.0
    • IMAV 2019, Madrid, Spain
    • Inter-IIT TechMeet 10.0
    • Inter-IIT TechMeet 11.0
Powered by GitBook
On this page
  • Building Docker Container
  • Using Docker Image

Was this helpful?

  1. Tutorials
  2. Workspace Setup

ArduPilot Setup on Docker

Building Docker Container

Pull the Docker Image

Image Used: osrf/ros:noetic-desktop-full

docker pull osrf/ros:noetic-desktop-full

Dockerfile for Building Docker Image

Make your Workspace Directory and paste the Following in the DockerFile

# Use the base image for ROS Noetic Desktop
FROM osrf/ros:noetic-desktop-full

# Set build arguments
ARG USER=ariitk
ARG DEBIAN_FRONTEND=noninteractive

RUN groupadd -r ${USER} && useradd -r -g ${USER} ${USER} && \
    mkdir -p /home/${USER} && \
    chown -R ${USER}:${USER} /home/${USER} && \
    echo ${USER}' ALL=(ALL) NOPASSWD: ALL' >> /etc/sudoers && \
    chmod 0440 /etc/sudoers

# Set the working directory
WORKDIR /home/${USER}

# Update package lists and install required ROS packages and tools
RUN apt-get update && \
    apt-get install -y \
    ros-noetic-moveit \
    ros-noetic-ros-controllers \
    ros-noetic-gazebo-ros-control \
    ros-noetic-rosserial \
    ros-noetic-rosserial-arduino \
    ros-noetic-roboticsgroup-upatras-gazebo-plugins \
    ros-noetic-actionlib-tools \
    ros-noetic-rqt \
    ros-noetic-rqt-common-plugins \
    ros-noetic-rqt-robot-plugins \
    terminator \
    python \
    python3 \
    python3-pip \
    python3-rosdep \
    python3-rosinstall \
    python3-rosinstall-generator \
    python3-wstool \
    python3-catkin-tools \
    build-essential \
    libgstreamer-plugins-base1.0-dev \
    gstreamer1.0-plugins-bad \
    gstreamer1.0-plugins-base \
    gstreamer1.0-plugins-good \
    gstreamer1.0-plugins-ugly \
    libprotobuf-dev \
    libprotoc-dev \
    protobuf-compiler \
    libeigen3-dev \
    libxml2-utils \
    python3-rospkg \
    python3-jinja2 \
    ros-noetic-mavros \
    ros-noetic-mavros-extras \
    ros-noetic-mavlink \
    nano \
    git \
    vim && \
    rm -rf /var/lib/apt/lists/*
# Install Gazebo & Meshlab
RUN curl -sSL http://get.gazebosim.org | sh && \
    apt-get install -y gazebo11 \
    meshlab
# PX4 Install Script
RUN wget https://raw.githubusercontent.com/PX4/PX4-Autopilot/refs/heads/main/Tools/setup/ubuntu.sh && \
    wget https://raw.githubusercontent.com/PX4/PX4-Autopilot/refs/heads/main/Tools/setup/requirements.txt && \
    chmod +x ubuntu.sh && \
    ./ubuntu.sh && \
    rm ubuntu.sh && \
    rm requirements.txt
# Install MAVROS
RUN apt-get install -y ros-noetic-mavros \
    ros-noetic-mavros-extras && \
    wget https://raw.githubusercontent.com/mavlink/mavros/master/mavros/scripts/install_geographiclib_datasets.sh && \
    chmod +x install_geographiclib_datasets.sh && \
    ./install_geographiclib_datasets.sh && \
    rm install_geographiclib_datasets.sh
# Ardupilot Setup
RUN git clone --recurse-submodules https://github.com/ArduPilot/ardupilot.git /home/${USER}/ardupilot && \
    chmod +x /home/${USER}/ardupilot/Tools/environment_install/install-prereqs-ubuntu.sh && \
    sed -i "s/sudo //g" /home/${USER}/ardupilot/Tools/environment_install/install-prereqs-ubuntu.sh && \
    sed -i "s/exit 1//g" /home/${USER}/ardupilot/Tools/environment_install/install-prereqs-ubuntu.sh && \
    /home/${USER}/ardupilot/Tools/environment_install/install-prereqs-ubuntu.sh -y

# Install Python packages
RUN apt-get install -y --reinstall libssl-dev && \
    rm -rf /usr/lib/python3/dist-packages/OpenSSL /usr/lib/python3/pyOpenSSL-19.0.0.egg-info && \
    pip install flask flask-ask-sdk ask-sdk && \
    pip install --upgrade pymavlink MAVProxy && \
    pip3 install kconfiglib pyserial && \
    pip3 install --user empy && \
    pip3 install --user toml && \
    pip3 install --user numpy && \
    pip3 install --user pandas && \
    pip3 install --user jinja2 && \
    pip3 install --user pyyaml pyros-genmsg packaging

# Edit .bashrc
RUN echo '#! /bin/bash' >> /home/${USER}/.bashrc && \
    echo 'source /opt/ros/noetic/setup.bash' >> /home/${USER}/.bashrc && \
    echo 'source /usr/share/gazebo/setup.sh' >> /home/${USER}/.bashrc && \
    echo 'export GAZEBO_MODEL_PATH=~/ardupilot_gazebo/models' >> /home/${USER}/.bashrc && \
    echo 'export GAZEBO_RESOURCE_PATH=~/ardupilot_gazebo/worlds:${GAZEBO_RESOURCE_PATH}' >> /home/${USER}/.bashrc && \
    echo 'export PATH=/usr/lib/ccache:$PATH' >> /home/${USER}/.bashrc && \
    echo 'export GAZEBO_PLUGIN_PATH=/usr/lib/x86_64-linux-gnu/gazebo-11/plugins:$GAZEBO_PLUGIN_PATH ' && \
    echo 'export GAZEBO_PLUGIN_PATH=/opt/ros/noetic/lib:$GAZEBO_PLUGIN_PATH'

# Switch to the specified user
USER ${USER}

Build Docker Image

Docker Image name: ariitk

docker build -t ariitk .

Make a Shared Directory between Host & Docker Container

Shared Directory Path: ~/Docker/Shared-Volumes/ariitk-Container

mkdir -p ~/Docker/Shared-Volumes/ariitk-Container

Note: You can use any of your directory for this

Running the Docker Container

Container Name: ariitk

sudo docker run -d -it --rm -v ~/Docker/Shared-Volumes/ariitk-Container:/home/Shared-Volume/ -v /tmp/.X11-unix/:/tmp/.X11-unix --net host --env="$(env | grep DISPLAY)" --name ariitk ariitk

Provide Permission to DISPLAY for Docker

xhost +local:docker

If you've problem in running the GUI Applications in the Container try the following methods:

  • Make sure that output of env | grep DISPLAY should contain 1 line and should look like this: DISPLAY=:1. If not then, manually feed the DISPLAY value in the run command. For example sudo docker run -d -it --rm -v ~/Docker/Shared-Volumes/ariitk-Container:/home/Shared-Volume/ -v /tmp/.X11-unix/:/tmp/.X11-unix --net host --env="DISPLAY=:1" --name ariitk <image_name/image_id>

  • If error = libGL error: MESA-LOADER: failed to retrieve device information. Add this parameter this in docker run : -e LIBGL_ALWAYS_SOFTWARE=1 and install the required libraries.

Note: We've provided --rm argument, so do all the work in the shared directory. Because all the data outside shared directory would be deleted as soon as the container is stopped. And in order to save any changes in the docker container, use docker commit to create a new version for the changes

Attach to Docker Container

Shell used: bash

docker exec -it ariitk /bin/bash

Initial Setup Inside the Container

  • Copy .bashrc of root user to ariitk user

  • Copy /root/.ardupilot_env to /user/ariitk/.ardupilot_env

  • Append export PATH=$PATH:/root/.local/bin/ to root user's .bashrc

  • MAVROS Setup

mkdir -p ardupilot_ws/src
cd ardupilot_ws/
catkin init 
cd src/
mkdir launch
roscp mavros apm.launch apm.launch

After this, edit apm.launch such that it uses a Network Port instead of Physical Port

<arg name="fcu_url" default="tcp://127.0.0.1:2626" />

Full File should look something like this

<launch>
	<!-- vim: set ft=xml noet : -->
	<!-- example launch script for ArduPilot based FCU's -->

	<arg name="fcu_url" default="tcp://127.0.0.1:2626" />
	<arg name="gcs_url" default="" />
	<arg name="tgt_system" default="1" />
	<arg name="tgt_component" default="1" />
	<arg name="log_output" default="screen" />
	<arg name="fcu_protocol" default="v2.0" />
	<arg name="respawn_mavros" default="false" />

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

		<arg name="fcu_url" value="$(arg fcu_url)" />
		<arg name="gcs_url" value="$(arg gcs_url)" />
		<arg name="tgt_system" value="$(arg tgt_system)" />
		<arg name="tgt_component" value="$(arg tgt_component)" />
		<arg name="log_output" value="$(arg log_output)" />
		<arg name="fcu_protocol" value="$(arg fcu_protocol)" />
		<arg name="respawn_mavros" value="$(arg respawn_mavros)" />
	</include>
</launch>
  • Setup ArduPilot Gazebo

cd ~
git clone https://github.com/khancyr/ardupilot_gazebo.git 
cd ardupilot_gazebo/
mkdir build 
cd build/
cmake ..
make -j4
sudo make install

Note: You've to run ArduPilot as root User At the end, the .bashrc file of ariitk user should Look something like this:

source /opt/ros/noetic/setup.bash
source /usr/share/gazebo/setup.sh
export GAZEBO_MODEL_PATH=~/ardupilot_gazebo/models
export GAZEBO_RESOURCE_PATH=~/ardupilot_gazebo/worlds:${GAZEBO_RESOURCE_PATH}
export PATH=/usr/lib/ccache:$PATH
source /home/ariitk/ardupilot/Tools/completion/completion.bash
source ~/.ardupilot_env
source /usr/share/gazebo/setup.sh

And .ardupilot.env like

export PATH=/opt/gcc-arm-none-eabi-10-2020-q4-major/bin:$PATH
export PATH=/home/ariitk/ardupilot/Tools/autotest:$PATH
export PATH=/usr/lib/ccache:$PATH

Test the Docker Container

To test the Successful Setup of Docker Container, run the following commands in different Terminals (in order)

roscore
gazebo --verbose ~/ardupilot_gazebo/worlds/iris_arducopter_runway.world
sim_vehicle.py -v ArduCopter -f gazebo-iris --console --map --out=tcpin:127.0.0.1:2626 # It should be run as root and the Network Address in --out should be the same that was edited in apm.launch
roslaunch apm.launch

You should see a Drone in the Middle of a Runway. To Test MAVROS and MAVPROXY. You can ARM the drone. List the ROS Topics and Services with the following commands.

rostopic list
rosservice list

ARM the Drone with the Following Service Call

rosservice call /mavros/cmd/arming true

Save the Initial Changes

To save the Initial Changes make an image of the container

docker commit ariitk ariitk/ardupilot

Export Docker Image

To export a docker Image, type the following command

docker save -o <filename>.tar ariitk/ardupilot

Using Docker Image

Import Docker Image

To import a docker image, type the following command

docker load -i <filename>.tar

You can then tag the import image with the following command

docker tag <image_id> my_custom_image:latest

You can find the image_id with the following command

docker image list

Make a Shared Directory between Host & Docker Container

Shared Directory Path: ~/Docker/Shared-Volumes/ariitk-Container

mkdir -p ~/Docker/Shared-Volumes/ariitk-Container

Run Docker Image

Container Name: ariitk

sudo docker run -d -it --rm -v ~/Docker/Shared-Volumes/ariitk-Container:/home/Shared-Volume/ -v /tmp/.X11-unix/:/tmp/.X11-unix --net host --env="$(env | grep DISPLAY)" --name ariitk <image_name/image_id>

Provide Permission to DISPLAY for Docker

xhost +local:docker

If you've problem in running the GUI Applications in the Container try the following methods:

  • Make sure that output of env | grep DISPLAY should contain 1 line and should look like this: DISPLAY=:1. If not then, manually feed the DISPLAY value in the run command. For example sudo docker run -d -it --rm -v ~/Docker/Shared-Volumes/ariitk-Container:/home/Shared-Volume/ -v /tmp/.X11-unix/:/tmp/.X11-unix --net host --env="DISPLAY=:1" --name ariitk <image_name/image_id>

  • If error = libGL error: MESA-LOADER: failed to retrieve device information. Add this parameter this in docker run : -e LIBGL_ALWAYS_SOFTWARE=1 and install the required libraries.

Note: We've provided --rm argument, so do all the work in the shared directory. Because all the data outside shared directory would be deleted as soon as the container is stopped. And in order to save any changes in the docker container, use docker commit to create a new version for the changes

Attach to Docker Container

Shell used: bash

docker exec -it ariitk /bin/bash
PreviousMission PlannerNextPX4 Setup on Docker

Last updated 3 months ago

Was this helpful?