From b8fea5691d5228d9e1b65891af8bdcbbf0adf53b Mon Sep 17 00:00:00 2001 From: Mike Lautman Date: Thu, 14 Mar 2019 19:13:27 -0600 Subject: [PATCH 1/3] update rosinstall --- moveit.rosinstall | 66 +++++++++++++++++++++++++++++++---------------- 1 file changed, 44 insertions(+), 22 deletions(-) diff --git a/moveit.rosinstall b/moveit.rosinstall index 012eba1015..171bd86eb2 100644 --- a/moveit.rosinstall +++ b/moveit.rosinstall @@ -1,34 +1,56 @@ # This file is intended for users who want to build MoveIt! from source. # Used with wstool, users can download source of all packages of MoveIt!. + - git: - local-name: moveit - uri: https://github.com/ros-planning/moveit.git - version: master + local-name: moveit2 + uri: https://github.com/ros-planning/moveit2.git + version: moveit2-ci + - git: local-name: moveit_msgs - uri: https://github.com/ros-planning/moveit_msgs.git - version: melodic-devel + # TODO(mlautman): update to ros-planning once the package has been merged back in + uri: https://github.com/AcutronicRobotics/moveit_msgs + version: ros2 - git: - local-name: moveit_resources - uri: https://github.com/ros-planning/moveit_resources.git - version: master + local-name: geometric_shapes + # TODO(mlautman): update to ros-planning once the package has been ported + uri: https://github.com/AcutronicRobotics/geometric_shapes + version: ros2 - git: - local-name: moveit_visual_tools - uri: https://github.com/ros-planning/moveit_visual_tools.git - version: melodic-devel + local-name: object_recognition_msgs + # TODO(mlautman): update to ros-planning once the package has been ported + uri: https://github.com/AcutronicRobotics/object_recognition_msgs + version: master - git: - local-name: rviz_visual_tools - uri: https://github.com/PickNikRobotics/rviz_visual_tools - version: melodic-devel + local-name: octomap_msgs + # TODO(mlautman): update to ros-planning once the package has been ported + uri: https://github.com/AcutronicRobotics/octomap_msgs + version: ros2 - git: - local-name: geometric_shapes - uri: https://github.com/ros-planning/geometric_shapes.git - version: melodic-devel + local-name: random_numbers + # TODO(mlautman): update to ros-planning once the package has been ported + uri: https://github.com/AcutronicRobotics/random_numbers + version: ros2 - git: local-name: srdfdom - uri: https://github.com/ros-planning/srdfdom.git - version: melodic-devel + # TODO(mlautman): update to ros-planning once the package has been ported + uri: https://github.com/mlautman/srdfdom + version: ros2 +- git: + local-name: urdf_parser_py + # TODO(mlautman): update to ros-planning once the package has been ported + uri: https://github.com/AcutronicRobotics/urdf_parser_py + version: ros2 +- git: + local-name: octomap + uri: https://github.com/AcutronicRobotics/octomap + version: ros2 +- git: + local-name: moveit_resources + # TODO(mlautman): update to ros-planning once the package has been ported + uri: https://github.com/AcutronicRobotics/moveit_resources + version: master - git: - local-name: moveit_tutorials - uri: https://github.com/ros-planning/moveit_tutorials.git - version: melodic-devel + local-name: joint_state_publisher + uri: https://github.com/ros/joint_state_publisher.git + version: ros2-devel From 7e0fc1c5c0d5ff1fcea70a705a8cb72b4e0f44d9 Mon Sep 17 00:00:00 2001 From: Michael Lautman Date: Tue, 12 Mar 2019 14:21:00 -0600 Subject: [PATCH 2/3] porting dockerfile in preparation for moveit2-ci --- .docker/ci-shadow-fixed/Dockerfile | 15 ----- .docker/ci/Dockerfile | 97 +++++++++++++++++++++--------- .docker/experimental/Dockerfile | 28 --------- .docker/release/Dockerfile | 5 +- .docker/source/Dockerfile | 28 ++++----- 5 files changed, 82 insertions(+), 91 deletions(-) delete mode 100644 .docker/ci-shadow-fixed/Dockerfile delete mode 100644 .docker/experimental/Dockerfile diff --git a/.docker/ci-shadow-fixed/Dockerfile b/.docker/ci-shadow-fixed/Dockerfile deleted file mode 100644 index bc9107c99e..0000000000 --- a/.docker/ci-shadow-fixed/Dockerfile +++ /dev/null @@ -1,15 +0,0 @@ -# moveit/moveit:melodic-ci-shadow-fixed -# Sets up a base image to use for running Continuous Integration on Travis - -FROM moveit/moveit:melodic-ci -MAINTAINER Dave Coleman dave@picknik.ai - -# Switch to ros-shadow-fixed -RUN echo "deb http://packages.ros.org/ros-shadow-fixed/ubuntu `lsb_release -cs` main" | tee /etc/apt/sources.list.d/ros-latest.list - -# Upgrade packages to ros-shadow-fixed and clean apt-cache within one RUN command -RUN apt-get -qq update && \ - apt-get -qq dist-upgrade && \ - # - # Clear apt-cache to reduce image size - rm -rf /var/lib/apt/lists/* diff --git a/.docker/ci/Dockerfile b/.docker/ci/Dockerfile index de2a963dc3..0050d8ee60 100644 --- a/.docker/ci/Dockerfile +++ b/.docker/ci/Dockerfile @@ -1,50 +1,89 @@ -# moveit/moveit:melodic-ci +# moveit/moveit2:crystal-ci # Sets up a base image to use for running Continuous Integration on Travis +FROM ros:crystal-ros-base-bionic -FROM ros:melodic-ros-base -MAINTAINER Dave Coleman dave@picknik.ai +LABEL maintainer="mike@picknik.ai" ENV TERM xterm # Setup catkin workspace -ENV CATKIN_WS=/root/ws_moveit -WORKDIR $CATKIN_WS +ENV ROS_WS=/opt/ws_moveit -# Commands are combined in single RUN statement with "apt/lists" folder removal to reduce image size -# https://docs.docker.com/develop/develop-images/dockerfile_best-practices/#minimize-the-number-of-layers -RUN \ - mkdir src && \ - cd src && \ - # - # Download moveit source, so that we can get necessary dependencies - wstool init --shallow . https://raw.githubusercontent.com/ros-planning/moveit/${ROS_DISTRO}-devel/moveit.rosinstall && \ - # - # Update apt package list as previous containers clear the cache - apt-get -qq update && \ - apt-get -qq dist-upgrade && \ +WORKDIR $ROS_WS + +# Update apt package list as previous containers clear the cache +RUN apt-get -qq update && \ + apt-get -qq dist-upgrade -y && \ # # Install some base dependencies apt-get -qq install -y \ - # Some source builds require a package.xml be downloaded via wget from an external location wget \ # Required for rosdep command sudo \ - # Preferred build tools - python-catkin-tools \ clang clang-format-3.9 clang-tidy clang-tools \ - ccache && \ - # - # Download all dependencies of MoveIt! + ccache \ + curl gnupg2 lsb-release \ + # Some python dependencies for working with ROS2 + python3-colcon-common-extensions \ + python3-pip \ + python-rosdep \ + python3-wstool \ + python3-rospkg-modules \ + python3-rosdistro-modules \ + && \ + # Clear apt-cache to reduce image size + rm -rf /var/lib/apt/lists/* + +# Upgrade Pip and install some packages needed for testing +# NOTE(mlautman): These pip installs are from the ros2 source install instructions. Seeing as not all of them +# are installed in the base image I added them here. I have not been able to verify that they are needed +# and if they aren't necessary they should be removed. +RUN python3 -m pip install --upgrade pip && \ + python3 -m pip install -U \ + argcomplete \ + flake8 \ + flake8-blind-except \ + flake8-builtins \ + flake8-class-newline \ + flake8-comprehensions \ + flake8-deprecated \ + flake8-docstrings \ + flake8-import-order \ + flake8-quotes \ + pytest-repeat \ + pytest-rerunfailures \ + pytest \ + pytest-cov \ + pytest-runner \ + setuptools + +# Install Fast-RTPS dependencies +RUN apt-get -qq update && \ + apt-get install -qq --no-install-recommends -y \ + libasio-dev \ + libtinyxml2-dev \ + && \ + # Clear apt-cache to reduce image size + rm -rf /var/lib/apt/lists/* + +# Download moveit source, so that we can get necessary dependencies +RUN mkdir src && \ + cd $ROS_WS/src && \ + # TODO(mlautman): This should be changed to use vcs in the future + wstool init --shallow . https://raw.githubusercontent.com/ros-planning/moveit2/moveit2-ci/moveit.rosinstall + +# Download all MoveIt dependencies +RUN \ + apt-get -qq update && \ rosdep update && \ rosdep install -y --from-paths . --ignore-src --rosdistro ${ROS_DISTRO} --as-root=apt:false && \ - # - # Remove the source code from this container - # TODO: in the future we may want to keep this here for further optimization of later containers - cd .. && \ - rm -rf src/ && \ - # # Clear apt-cache to reduce image size rm -rf /var/lib/apt/lists/* +# Remove the source code from this container +# TODO: in the future we may want to keep this here for further optimization of later containers +RUN cd $ROS_WS && \ + rm -rf src/ && \ + # Continous Integration Setting ENV IN_DOCKER 1 diff --git a/.docker/experimental/Dockerfile b/.docker/experimental/Dockerfile deleted file mode 100644 index 36b1de3b7d..0000000000 --- a/.docker/experimental/Dockerfile +++ /dev/null @@ -1,28 +0,0 @@ -# moveit/moveit:melodic-experimental -# Based on a moveit source install, adds the mongo driver and the warehouse packages - -FROM moveit/moveit:melodic-source - -ENV CATKIN_WS=/root/ws_moveit -RUN mkdir -p $CATKIN_WS/src -WORKDIR $CATKIN_WS/src - -# installing mongocxx driver for the warehouse -RUN git clone -b 26compat https://github.com/mongodb/mongo-cxx-driver.git && \ - apt-get update -qq && \ - apt-get -qq install -y scons mongodb && \ - cd mongo-cxx-driver && \ - scons --use-system-boost --prefix=/usr/local/ --full --disable-warnings-as-errors && \ - ls /usr/local/lib && \ - # scons install && \ - rm -rf /var/lib/apt/lists/* - -# Download warehouse source -RUN wstool set -yu warehouse_ros_mongo --git https://github.com/ros-planning/warehouse_ros_mongo.git -v jade-devel && \ - wstool set -yu warehouse_ros --git https://github.com/ros-planning/warehouse_ros.git -v jade-devel - -# build the workspace -RUN cd $CATKIN_WS && \ - source /root/ws_moveit/devel/setup.bash && \ - catkin init && \ - catkin build diff --git a/.docker/release/Dockerfile b/.docker/release/Dockerfile index e06998b1a2..f7900b3ead 100644 --- a/.docker/release/Dockerfile +++ b/.docker/release/Dockerfile @@ -1,7 +1,8 @@ -# moveit/moveit:melodic-release +# moveit/moveit2:crystal-release # Full debian-based install of MoveIt! using apt-get +# TODO(mlautman): Add this Dockerfile to DockerHub once the moveit2 debians are released -FROM ros:melodic-ros-base +FROM ros:crystal-ros-base-bionic MAINTAINER Dave Coleman dave@picknik.ai # Commands are combined in single RUN statement with "apt/lists" folder removal to reduce image size diff --git a/.docker/source/Dockerfile b/.docker/source/Dockerfile index b7f0086fe3..17a8d273b0 100644 --- a/.docker/source/Dockerfile +++ b/.docker/source/Dockerfile @@ -1,30 +1,24 @@ -# moveit/moveit:melodic-source +# moveit/moveit2:crystal-source # Downloads the moveit source code and install remaining debian dependencies -FROM moveit/moveit:melodic-ci-shadow-fixed -MAINTAINER Dave Coleman dave@picknik.ai +FROM moveit/moveit2:crystal-ci +LABEL maintainer="mike@picknik.ai" # Commands are combined in single RUN statement with "apt/lists" folder removal to reduce image size # https://docs.docker.com/develop/develop-images/dockerfile_best-practices/#minimize-the-number-of-layers -RUN \ - mkdir src && \ +RUN mkdir src && \ cd src && \ # # Download moveit source so that we can get necessary dependencies - wstool init . https://raw.githubusercontent.com/ros-planning/moveit/${ROS_DISTRO}-devel/moveit.rosinstall && \ - # - # Update apt package list as cache is cleared in previous container - # Usually upgrading involves a few packages only (if container builds became out-of-sync) - apt-get -qq update && \ + wstool init . https://raw.githubusercontent.com/ros-planning/moveit2/moveit2-ci/moveit.rosinstall + +# Update apt package list as cache is cleared in previous container +# Usually upgrading involves a few packages only (if container builds became out-of-sync) +RUN apt-get -qq update && \ apt-get -qq dist-upgrade && \ - # rosdep update && \ rosdep install -y --from-paths . --ignore-src --rosdistro ${ROS_DISTRO} --as-root=apt:false && \ rm -rf /var/lib/apt/lists/* -# Configure catkin workspace, but do not build because Docker times out -ENV PYTHONIOENCODING UTF-8 -RUN catkin config --extend /opt/ros/$ROS_DISTRO --install --cmake-args -DCMAKE_BUILD_TYPE=Release - # Status rate is limited so that just enough info is shown to keep Docker from timing out, - # but not too much such that the Docker log gets too long (another form of timeout) - # catkin build --limit-status-rate 0.001 --no-notify + # Build the workspace +RUN colcon build --symlink-install --event-handlers console_direct+ From 0ab2a549c675dea9ddd5a36ae91441af122a5a96 Mon Sep 17 00:00:00 2001 From: Mike Lautman Date: Mon, 25 Mar 2019 13:47:43 -0600 Subject: [PATCH 3/3] changing branch from moveit2-ci to master in prep for merge --- .docker/ci/Dockerfile | 2 +- .docker/source/Dockerfile | 2 +- moveit.rosinstall | 3 +-- 3 files changed, 3 insertions(+), 4 deletions(-) diff --git a/.docker/ci/Dockerfile b/.docker/ci/Dockerfile index 0050d8ee60..8d8f663224 100644 --- a/.docker/ci/Dockerfile +++ b/.docker/ci/Dockerfile @@ -70,7 +70,7 @@ RUN apt-get -qq update && \ RUN mkdir src && \ cd $ROS_WS/src && \ # TODO(mlautman): This should be changed to use vcs in the future - wstool init --shallow . https://raw.githubusercontent.com/ros-planning/moveit2/moveit2-ci/moveit.rosinstall + wstool init --shallow . https://raw.githubusercontent.com/ros-planning/moveit2/master/moveit.rosinstall # Download all MoveIt dependencies RUN \ diff --git a/.docker/source/Dockerfile b/.docker/source/Dockerfile index 17a8d273b0..56fbc23675 100644 --- a/.docker/source/Dockerfile +++ b/.docker/source/Dockerfile @@ -10,7 +10,7 @@ RUN mkdir src && \ cd src && \ # # Download moveit source so that we can get necessary dependencies - wstool init . https://raw.githubusercontent.com/ros-planning/moveit2/moveit2-ci/moveit.rosinstall + wstool init . https://raw.githubusercontent.com/ros-planning/moveit2/master/moveit.rosinstall # Update apt package list as cache is cleared in previous container # Usually upgrading involves a few packages only (if container builds became out-of-sync) diff --git a/moveit.rosinstall b/moveit.rosinstall index 171bd86eb2..86e77ad2e1 100644 --- a/moveit.rosinstall +++ b/moveit.rosinstall @@ -4,8 +4,7 @@ - git: local-name: moveit2 uri: https://github.com/ros-planning/moveit2.git - version: moveit2-ci - + version: master - git: local-name: moveit_msgs # TODO(mlautman): update to ros-planning once the package has been merged back in