aboutsummaryrefslogtreecommitdiff
path: root/Tools/ros/docker
diff options
context:
space:
mode:
Diffstat (limited to 'Tools/ros/docker')
-rw-r--r--Tools/ros/docker/px4-ros-full/Dockerfile57
-rw-r--r--Tools/ros/docker/px4-ros-full/README.md12
-rw-r--r--Tools/ros/docker/px4-ros-full/scripts/setup-workspace.sh45
3 files changed, 114 insertions, 0 deletions
diff --git a/Tools/ros/docker/px4-ros-full/Dockerfile b/Tools/ros/docker/px4-ros-full/Dockerfile
new file mode 100644
index 000000000..1242b56b5
--- /dev/null
+++ b/Tools/ros/docker/px4-ros-full/Dockerfile
@@ -0,0 +1,57 @@
+#
+# PX4 full ROS container
+#
+# License: according to LICENSE.md in the root directory of the PX4 Firmware repository
+
+FROM ubuntu:14.04.1
+MAINTAINER Andreas Antener <andreas@uaventure.com>
+
+# Install basics
+## Use the "noninteractive" debconf frontend
+ENV DEBIAN_FRONTEND noninteractive
+
+RUN apt-get update \
+ && apt-get -y install wget git mercurial
+
+# Main ROS Setup
+# Following http://wiki.ros.org/indigo/Installation/Ubuntu
+# Also adding dependencies for gazebo http://gazebosim.org/tutorials?tut=drcsim_install
+
+## add ROS repositories and keys
+## install main ROS pacakges
+RUN echo "deb http://packages.ros.org/ros/ubuntu trusty main" > /etc/apt/sources.list.d/ros-latest.list \
+ && wget https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -O - | apt-key add - \
+ && apt-get update \
+ && apt-get -y install ros-indigo-desktop-full
+
+RUN rosdep init \
+ && rosdep update
+
+## setup environment variables
+RUN echo "source /opt/ros/indigo/setup.bash" >> ~/.bashrc
+
+## get rosinstall
+RUN apt-get -y install python-rosinstall
+
+## additional dependencies
+RUN apt-get -y install ros-indigo-octomap-msgs ros-indigo-joy
+
+## install drcsim
+RUN echo "deb http://packages.osrfoundation.org/drc/ubuntu trusty main" > /etc/apt/sources.list.d/drc-latest.list \
+ && wget http://packages.osrfoundation.org/drc.key -O - | apt-key add - \
+ && apt-get update \
+ && apt-get -y install drcsim
+
+# Install x11-utils to get xdpyinfo, for X11 display debugging
+# mesa-utils provides glxinfo, handy for understanding the 3D support
+RUN apt-get -y install x11-utils mesa-utils
+
+# Some QT-Apps/Gazebo don't not show controls without this
+ENV QT_X11_NO_MITSHM 1
+
+# FIXME: this doesn't work when building from vagrant
+COPY scripts/setup-workspace.sh /root/scripts/
+RUN chmod +x -R /root/scripts/*
+RUN chown -R root:root /root/scripts/*
+
+CMD ["/usr/bin/xterm"]
diff --git a/Tools/ros/docker/px4-ros-full/README.md b/Tools/ros/docker/px4-ros-full/README.md
new file mode 100644
index 000000000..af5170c70
--- /dev/null
+++ b/Tools/ros/docker/px4-ros-full/README.md
@@ -0,0 +1,12 @@
+# PX4 ROS #
+
+Full desktop ROS container.
+
+License: according to LICENSE.md in the root directory of the PX4 Firmware repository
+
+**TODO:**
+
+- use https://github.com/phusion/baseimage-docker as base
+- add user, best synced with host
+- configure ssh to work with vagrant out of the box
+
diff --git a/Tools/ros/docker/px4-ros-full/scripts/setup-workspace.sh b/Tools/ros/docker/px4-ros-full/scripts/setup-workspace.sh
new file mode 100644
index 000000000..2de5f8bec
--- /dev/null
+++ b/Tools/ros/docker/px4-ros-full/scripts/setup-workspace.sh
@@ -0,0 +1,45 @@
+#!/bin/sh
+#
+# Create workspace at current location and fetch source repositories
+#
+
+# License: according to LICENSE.md in the root directory of the PX4 Firmware repository
+
+WDIR=`pwd`
+WORKSPACE=$WDIR/catkin_ws
+
+# Setup workspace
+mkdir -p $WORKSPACE/src
+cd $WORKSPACE/src
+catkin_init_workspace
+cd $WORKSPACE
+catkin_make
+echo "source $WORKSPACE/devel/setup.bash" >> ~/.bashrc
+
+# PX4 Firmware
+cd $WORKSPACE/src
+git clone https://github.com/PX4/Firmware.git \
+ && cd Firmware \
+ && git checkout ros
+
+# euroc simulator
+cd $WORKSPACE/src
+git clone https://github.com/PX4/euroc_simulator.git \
+ && cd euroc_simulator \
+ && git checkout px4_nodes
+
+# mav comm
+cd $WORKSPACE/src
+git clone https://github.com/PX4/mav_comm.git
+
+# glog catkin
+cd $WORKSPACE/src
+git clone https://github.com/ethz-asl/glog_catkin.git
+
+# catkin simple
+cd $WORKSPACE/src
+git clone https://github.com/catkin/catkin_simple.git
+
+cd $WORKSPACE
+catkin_make
+