Skip to content

Commit

Permalink
Fixed dockerfile and dependencies. Middlewares were added as dependen…
Browse files Browse the repository at this point in the history
…cies. (rmw_fastrtps, rmw_zenoh, rmw_cyclonedds)
  • Loading branch information
CihatAltiparmak committed Jul 24, 2024
1 parent 563d83b commit 001df83
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 6 deletions.
7 changes: 2 additions & 5 deletions Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -7,17 +7,14 @@ 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 && \
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 && \
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 && \
Expand Down
10 changes: 9 additions & 1 deletion moveit_middleware_benchmark.repos
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
repositories:
moveit_msgs:
moveit2:
type: git
url: https://github.com/moveit/moveit2.git
version: main
Expand All @@ -11,6 +11,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 001df83

Please sign in to comment.