Skip to content

Commit

Permalink
Switched to moveit's own dockerfile and fixed dependency repos (#16)
Browse files Browse the repository at this point in the history
* Fixed dockerfile and dependencies. Middlewares were added as dependencies. (rmw_fastrtps, rmw_zenoh, rmw_cyclonedds)

* Used moveit's own docker image instead of building it

* Used moveit's latest rolling docker image
* re-edited underlay workspace in dockerfile

* Changed workspace dirs in dockerfile with moveit docker's own underlay workspace alias
  • Loading branch information
CihatAltiparmak authored Aug 2, 2024
1 parent ccdcbf1 commit 6d22560
Show file tree
Hide file tree
Showing 2 changed files with 14 additions and 13 deletions.
15 changes: 6 additions & 9 deletions Dockerfile
Original file line number Diff line number Diff line change
@@ -1,25 +1,22 @@
FROM ros:rolling
FROM moveit/moveit2:rolling-source

RUN apt-get update && \
apt install wget -y

RUN mkdir ws/src -p

RUN . /opt/ros/rolling/setup.sh && \
cd ws/src && \
git clone https://github.com/CihatAltiparmak/moveit_middleware_benchmark.git -b development && \
cd ${ROS_UNDERLAY}/../src && \
git clone https://github.com/CihatAltiparmak/moveit_middleware_benchmark.git && \
vcs import < moveit_middleware_benchmark/moveit_middleware_benchmark.repos --recursive

RUN cd ws/src && \
# git clone https://github.com/ros2/rmw_zenoh.git && \
git clone https://github.com/ros2/rmw_cyclonedds.git

RUN . /opt/ros/rolling/setup.sh && \
cd ws && \
cd ${ROS_UNDERLAY}/.. && \
rosdep update --rosdistro=$ROS_DISTRO && \
apt-get update && \
apt upgrade -y && \
rosdep install --from-paths src --ignore-src -r -y

RUN . /opt/ros/rolling/setup.sh && \
cd ws && \
cd ${ROS_UNDERLAY}/.. && \
colcon build --mixin release --packages-skip test_dynmsg dynmsg_demo
12 changes: 8 additions & 4 deletions moveit_middleware_benchmark.repos
Original file line number Diff line number Diff line change
@@ -1,8 +1,4 @@
repositories:
moveit_msgs:
type: git
url: https://github.com/moveit/moveit2.git
version: main
moveit_resources:
type: git
url: https://github.com/moveit/moveit_resources.git
Expand All @@ -11,6 +7,14 @@ repositories:
type: git
url: https://github.com/ros2/rmw_zenoh.git
version: rolling
rmw_cyclonedds:
type: git
url: https://github.com/ros2/rmw_cyclonedds.git
version: rolling
rmw_fastrtps:
type: git
url: https://github.com/ros2/rmw_fastrtps.git
version: rolling
dynamic_message_introspection:
type: git
url: https://github.com/osrf/dynamic_message_introspection.git
Expand Down

0 comments on commit 6d22560

Please sign in to comment.