aboutsummaryrefslogtreecommitdiff
path: root/Tools/ros/docker/px4-ros/Dockerfile
diff options
context:
space:
mode:
Diffstat (limited to 'Tools/ros/docker/px4-ros/Dockerfile')
-rw-r--r--Tools/ros/docker/px4-ros/Dockerfile16
1 files changed, 14 insertions, 2 deletions
diff --git a/Tools/ros/docker/px4-ros/Dockerfile b/Tools/ros/docker/px4-ros/Dockerfile
index 532a9af8b..668d50799 100644
--- a/Tools/ros/docker/px4-ros/Dockerfile
+++ b/Tools/ros/docker/px4-ros/Dockerfile
@@ -6,8 +6,11 @@ FROM ubuntu:14.04.1
MAINTAINER Andreas Antener "andreas@antener.name"
# Install basics
+## Use the "noninteractive" debconf frontend
+ENV DEBIAN_FRONTEND noninteractive
+
RUN apt-get update \
- && apt-get -y install wget git mercurial
+ && apt-get -y install wget git mercurial openssh-server
# Main ROS Setup
# Following http://wiki.ros.org/indigo/Installation/Ubuntu
@@ -39,4 +42,13 @@ RUN apt-get -y install ros-indigo-octomap-msgs
# && apt-get update \
# && apt-get -y install drcsim
-CMD /bin/bash
+# some QT-Apps/Gazebo don't not show controls without this
+ENV QT_X11_NO_MITSHM 1
+
+#RUN apt-get install -y openssh-server
+# 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
+#RUN apt-get -y install mesa-utils
+
+#CMD ["/bin/sbin/sshd", "-D"]