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/Dockerfile42
-rw-r--r--Tools/ros/docker/px4-ros/px4-ros-sitl/Dockerfile22
-rw-r--r--Tools/ros/docker/px4-ros/px4-ros-sitl/get-sources.sh28
3 files changed, 92 insertions, 0 deletions
diff --git a/Tools/ros/docker/px4-ros/Dockerfile b/Tools/ros/docker/px4-ros/Dockerfile
new file mode 100644
index 000000000..532a9af8b
--- /dev/null
+++ b/Tools/ros/docker/px4-ros/Dockerfile
@@ -0,0 +1,42 @@
+#
+# Base ROS Indigo
+#
+
+FROM ubuntu:14.04.1
+MAINTAINER Andreas Antener "andreas@antener.name"
+
+# Install basics
+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
+
+
+## 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
+
+CMD /bin/bash
diff --git a/Tools/ros/docker/px4-ros/px4-ros-sitl/Dockerfile b/Tools/ros/docker/px4-ros/px4-ros-sitl/Dockerfile
new file mode 100644
index 000000000..4c47295a8
--- /dev/null
+++ b/Tools/ros/docker/px4-ros/px4-ros-sitl/Dockerfile
@@ -0,0 +1,22 @@
+#
+# PX4 ROS SITL
+#
+
+FROM px4ros/ros-base:no-drcsim
+MAINTAINER Andreas Antener "andreas@antener.name"
+
+# TODO
+#USER px4
+
+RUN . /opt/ros/indigo/setup.sh \
+ && mkdir -p /catkin_ws/src \
+ && cd /catkin_ws/src \
+ && catkin_init_workspace \
+ && cd /catkin_ws \
+ && catkin_make \
+ && echo "source /catkin_ws/devel/setup.bash" >> ~/.bashrc
+
+COPY get-sources.sh /catkin_ws/src/
+RUN chmod +x /catkin_ws/src/get-sources.sh
+
+CMD /bin/bash
diff --git a/Tools/ros/docker/px4-ros/px4-ros-sitl/get-sources.sh b/Tools/ros/docker/px4-ros/px4-ros-sitl/get-sources.sh
new file mode 100644
index 000000000..237ae7500
--- /dev/null
+++ b/Tools/ros/docker/px4-ros/px4-ros-sitl/get-sources.sh
@@ -0,0 +1,28 @@
+#!/bin/sh
+#
+# Fetch source repositories
+#
+
+# PX4 Firmware
+git clone https://github.com/PX4/Firmware.git \
+ && cd Firmware \
+ && git checkout ros \
+ && cd ..
+
+# euroc simulator
+git clone https://github.com/PX4/euroc_simulator.git \
+ && cd euroc_simulator \
+ && git checkout px4_nodes \
+ && cd ..
+
+# mav comm
+git clone https://github.com/PX4/mav_comm.git
+
+# glog catkin
+git clone https://github.com/ethz-asl/glog_catkin.git
+
+# catkin simple
+git clone https://github.com/catkin/catkin_simple.git
+
+echo "Execute catkin_make to compile all the sources."
+