Skip to content

Commit

Permalink
Compile generate_parameter_library et.al
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Jan 23, 2024
1 parent 63fe4fa commit f3ae999
Show file tree
Hide file tree
Showing 5 changed files with 41 additions and 5 deletions.
2 changes: 1 addition & 1 deletion Dockerfile.debian11
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,7 @@ RUN colcon \
--cmake-args --no-warn-unused-cli \
--packages-up-to robot_state_publisher tf2_ros yaml_cpp_vendor tf2_geometry_msgs filters \
ros2param ros2interface ros2topic ros2action ros2lifecycle ros2launch ros2run \
xacro trajectory_msgs diagnostic_updater backward_ros && \
xacro trajectory_msgs diagnostic_updater backward_ros generate_parameter_library && \
rm -rf log src build

# set up sourcing of ros
Expand Down
2 changes: 1 addition & 1 deletion Dockerfile.debian12
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,7 @@ RUN colcon \
--cmake-args --no-warn-unused-cli \
--packages-up-to robot_state_publisher tf2_ros yaml_cpp_vendor tf2_geometry_msgs filters \
ros2param ros2interface ros2topic ros2action ros2lifecycle ros2launch ros2run \
xacro trajectory_msgs diagnostic_updater backward_ros && \
xacro trajectory_msgs diagnostic_updater backward_ros generate_parameter_library && \
rm -rf log src build

# set up sourcing of ros
Expand Down
14 changes: 13 additions & 1 deletion ros-controls.humble.repos
Original file line number Diff line number Diff line change
Expand Up @@ -14,4 +14,16 @@ repositories:
backward_ros:
type: git
url: https://github.com/ros2-gbp/backward_ros-release.git
version: debian/humble/bullseye/backward_ros
version: debian/humble/bullseye/backward_ros
cpp_polyfills:
type: git
url: https://github.com/PickNikRobotics/cpp_polyfills.git
version: main
RSL:
type: git
url: https://github.com/PickNikRobotics/RSL.git
version: main
generate_parameter_library:
type: git
url: https://github.com/PickNikRobotics/generate_parameter_library.git
version: main
14 changes: 13 additions & 1 deletion ros-controls.iron.repos
Original file line number Diff line number Diff line change
Expand Up @@ -14,4 +14,16 @@ repositories:
backward_ros:
type: git
url: https://github.com/ros2-gbp/backward_ros-release.git
version: debian/iron/bullseye/backward_ros
version: debian/iron/bullseye/backward_ros
cpp_polyfills:
type: git
url: https://github.com/PickNikRobotics/cpp_polyfills.git
version: main
RSL:
type: git
url: https://github.com/PickNikRobotics/RSL.git
version: main
generate_parameter_library:
type: git
url: https://github.com/PickNikRobotics/generate_parameter_library.git
version: main
14 changes: 13 additions & 1 deletion ros-controls.rolling.repos
Original file line number Diff line number Diff line change
Expand Up @@ -14,4 +14,16 @@ repositories:
backward_ros:
type: git
url: https://github.com/ros2-gbp/backward_ros-release.git
version: debian/rolling/bullseye/backward_ros
version: debian/rolling/bullseye/backward_ros
cpp_polyfills:
type: git
url: https://github.com/PickNikRobotics/cpp_polyfills.git
version: main
rsl:
type: git
url: https://github.com/PickNikRobotics/RSL.git
version: main
generate_parameter_library:
type: git
url: https://github.com/PickNikRobotics/generate_parameter_library.git
version: main

0 comments on commit f3ae999

Please sign in to comment.