File tree Expand file tree Collapse file tree 7 files changed +52
-3
lines changed Expand file tree Collapse file tree 7 files changed +52
-3
lines changed Original file line number Diff line number Diff line change @@ -24,20 +24,23 @@ RUN apt-get update -y -qq && \
2424 automake \
2525 build-essential \
2626 cmake \
27+ clang \
2728 curl \
2829 dnsutils \
2930 git \
3031 gnupg2 \
3132 intltool \
3233 libacl1-dev \
3334 libasio-dev \
35+ libassimp-dev \
3436 libblosc1 \
3537 libbondcpp-dev \
3638 libcap-dev \
3739 libcgal-dev \
3840 libeigen3-dev \
3941 libfmt-dev \
4042 liblttng-ust-dev lttng-tools python3-lttng \
43+ liboctomap-dev \
4144 libssl-dev \
4245 libtinyxml-dev \
4346 libtinyxml2-dev \
@@ -154,15 +157,23 @@ RUN vcs import --input https://raw.githubusercontent.com/ros2/ros2/$ROS_DISTRO/r
154157RUN \
155158 : "build ROS core from source" && \
156159 . "$HOME/.cargo/env" && \
157- colcon build \
160+ colcon build \
158161 --mixin release build-testing-off \
159162 --cmake-args --no-warn-unused-cli -DCMAKE_CXX_FLAGS="-Wno-maybe-uninitialized" \
160163 --packages-up-to robot_state_publisher tf2_ros tf2_eigen tf2_kdl tf2_eigen_kdl yaml_cpp_vendor filters \
161164 ros2param ros2interface ros2topic ros2action ros2lifecycle ros2launch ros2run ros_testing \
162165 xacro diagnostic_updater generate_parameter_library angles example_interfaces \
163- backward_ros pal_statistics topic_tools \
166+ backward_ros pal_statistics topic_tools ros_environment \
164167 ackermann_msgs trajectory_msgs tf2_msgs tf2_geometry_msgs sensor_msgs geometry_msgs nav_msgs \
165168 sdformat_urdf && \
169+ # build pinocchio from source with different cmake args
170+ . install/setup.sh && \
171+ colcon build \
172+ --mixin release build-testing-off \
173+ --cmake-args --no-warn-unused-cli -DBUILD_EXAMPLES=OFF -DBUILD_PYTHON_INTERFACE=OFF \
174+ -DCOAL_BACKWARD_COMPATIBILITY_WITH_HPP_FCL=TRUE \
175+ --packages-select coal pinocchio && \
176+ # cleanup
166177 rm -rf log src build
167178
168179# add default.yaml to the image
Original file line number Diff line number Diff line change @@ -67,6 +67,14 @@ repositories:
6767 type: git
6868 url: https://github.com/ros2-gbp/pal_statistics-release.git
6969 version: debian/jazzy/bookworm/pal_statistics_msgs
70+ pinocchio:
71+ type: git
72+ url: https://github.com/christophfroehlich/pinocchio.git
73+ version: patch-1
74+ coal:
75+ type: git
76+ url: https://github.com/ros2-gbp/coal-release.git
77+ version: debian/jazzy/bookworm/coal
7078 topic_tools:
7179 type: git
7280 url: https://github.com/ros2-gbp/topic_tools-release.git
Original file line number Diff line number Diff line change @@ -67,6 +67,14 @@ repositories:
6767 type: git
6868 url: https://github.com/ros2-gbp/pal_statistics-release.git
6969 version: debian/kilted/bookworm/pal_statistics_msgs
70+ pinocchio:
71+ type: git
72+ url: https://github.com/christophfroehlich/pinocchio.git
73+ version: patch-1
74+ coal:
75+ type: git
76+ url: https://github.com/ros2-gbp/coal-release.git
77+ version: debian/kilted/bookworm/coal
7078 topic_tools:
7179 type: git
7280 url: https://github.com/ros2-gbp/topic_tools-release.git
Original file line number Diff line number Diff line change @@ -67,6 +67,14 @@ repositories:
6767 type: git
6868 url: https://github.com/ros2-gbp/pal_statistics-release.git
6969 version: debian/rolling/bookworm/pal_statistics_msgs
70+ pinocchio:
71+ type: git
72+ url: https://github.com/christophfroehlich/pinocchio.git
73+ version: patch-1
74+ coal:
75+ type: git
76+ url: https://github.com/ros2-gbp/coal-release.git
77+ version: debian/rolling/bookworm/coal
7078 topic_tools:
7179 type: git
7280 url: https://github.com/ros2-gbp/topic_tools-release.git
Original file line number Diff line number Diff line change @@ -83,7 +83,13 @@ RUN vcs import src < ros-controls.$ROS_DISTRO.repos && \
8383 rosdep install -iyr --from-path src && \
8484 colcon build \
8585 --mixin release build-testing-off \
86- --cmake-args --no-warn-unused-cli && \
86+ --cmake-args --no-warn-unused-cli --packages-skip pinocchio && \
87+ # build pinocchio from source
88+ colcon build \
89+ --mixin release build-testing-off \
90+ --cmake-args --no-warn-unused-cli -DBUILD_EXAMPLES=OFF -DBUILD_PYTHON_INTERFACE=OFF \
91+ --packages-select pinocchio && \
92+ # cleanup
8793 rm -rf log src build
8894
8995# add default.yaml to the image
Original file line number Diff line number Diff line change 11repositories:
2+ pinocchio:
3+ type: git
4+ url: https://github.com/ros2-gbp/pinocchio-release.git
5+ version: rpm/kilted/9/pinocchio
Original file line number Diff line number Diff line change 11repositories:
2+ pinocchio:
3+ type: git
4+ url: https://github.com/ros2-gbp/pinocchio-release.git
5+ version: rpm/rolling/9/pinocchio
You can’t perform that action at this time.
0 commit comments