Skip to content

Conversation

@Juliaj
Copy link

@Juliaj Juliaj commented Dec 19, 2025

Enables building this package in standard ROS 2 workspaces on Linux/Ubuntu, making it compatible with rolling builds from ros-controls projects. For more details, see #30.

Changes

  • Updated CMakeList.txt to handle dependency for GLFW3, mold and sccache.
  • Updated package.xml to include sccache
  • Added a section to README.md for "Development Workflow within ROS 2 Workspace" section with dependencies, build instructions, and warnings about version compatibility

Testing

Tested on Ubuntu 24.04 with:

  • System ROS 2 Jazzy packages
  • Rolling builds from ros2_control_demo and ros2_controllers
  • All dependencies properly detected and used

Also tested pixi build workflow, build succeeded.

@christophfroehlich
Copy link
Member

I tried to install the current head in a fresh Ubuntu 24.04 docker with a rolling installation and having ros2_control in the same workspace -> It worked as expected (after a clean rebuild tbh). What was the issue you had, apart from the ABI thing in #30?

@Juliaj
Copy link
Author

Juliaj commented Dec 21, 2025

@christophfroehlich thank you so much for looking into this. Comparing your setup and my env, I have example_18, a new example for ONNX runtime. Only one runtime error requires this example. If you want to set it up, here are some instructions for ONNX runtime.

My build command for ros2_ws.

colcon build --symlink-install

I have errors encountered listed below. Note some of the path below pointed to mujoco_ros2_simulation which has been changed. Example_18 from my fork has been updated with all latest changes.

  • GLFW related.

Missing libglfw3-dev dependency

CMake Error at CMakeLists.txt:13 (find_package):
  By not providing "Findglfw3.cmake" in CMAKE_MODULE_PATH this project has
  asked CMake to find a package configuration file provided by "glfw3", but
  CMake did not find one.

  Could not find a package configuration file provided by "glfw3" with any of
  the following names:

    glfw3Config.cmake
    glfw3-config.cmake

Runtime error

[ros2_control_node-2] [ERROR] [1766270839.469507630] [controller_manager]: Caught exception of type : N9pluginlib20LibraryLoadExceptionE while loading hardware: Failed to load library /home/juliaj/ros2_ws/install/mujoco_ros2_control/lib/mujoco_ros2_control/libmujoco_ros2_control.so. Make sure that you are calling the PLUGINLIB_EXPORT_CLASS macro in the library code, and that names are consistent between this macro and your XML. Error string: Could not load library dlopen error: /home/juliaj/ros2_ws/install/mujoco_ros2_control/lib/mujoco_ros2_control/libmujoco_ros2_control.so: undefined symbol: glfwGetKey, at ./src/shared_library.c:99

I looked into why this runtime error (undefined symbol: glfwGetKey) wouldn't have been caught by the test included in the repo. My hypothesis was that my example calls on_configure() which might not have been the case for the unit test.

  • sccache related
$ colcon build --symlink-install --packages-select mujoco_ros2_control
Starting >>> mujoco_ros2_control
Not searching for unused variables given on the command line.
-- The C compiler identification is GNU 13.3.0
-- The CXX compiler identification is GNU 13.3.0
-- Detecting C compiler ABI info
-- Detecting C compiler ABI info - done                 
-- Check for working C compiler: /usr/bin/cc - skipped  
-- Detecting C compile features
-- Detecting C compile features - done
-- Detecting CXX compiler ABI info
-- Detecting CXX compiler ABI info - done               
-- Check for working CXX compiler: /usr/bin/c++ - skipped
-- Detecting CXX compile features
-- Detecting CXX compile features - done
-- Found ament_cmake: 2.5.4 (/opt/ros/jazzy/share/ament_cmake/cmake)
-- Found Python3: /home/juliaj/.pyenv/shims/python3 (found version "3.12.3") found components: Interpreter 
-- Override CMake install command with custom implementation using symlinks instead of copying resources
-- Found controller_manager: 4.39.2 (/opt/ros/jazzy/share/controller_manager/cmake)
-- Found rosidl_generator_c: 4.6.6 (/opt/ros/jazzy/share/rosidl_generator_c/cmake)
-- Found rosidl_generator_cpp: 4.6.6 (/opt/ros/jazzy/share/rosidl_generator_cpp/cmake)
-- Using all available rosidl_typesupport_c: rosidl_typesupport_fastrtps_c;rosidl_typesupport_introspection_c
-- Using all available rosidl_typesupport_cpp: rosidl_typesupport_fastrtps_cpp;rosidl_typesupport_introspection_cpp
-- Found rmw_implementation_cmake: 7.3.2 (/opt/ros/jazzy/share/rmw_implementation_cmake/cmake)
-- Found rmw_fastrtps_cpp: 8.4.3 (/opt/ros/jazzy/share/rmw_fastrtps_cpp/cmake)
-- Found OpenSSL: /usr/lib/x86_64-linux-gnu/libcrypto.so (found version "3.0.13")  
-- Found FastRTPS: /opt/ros/jazzy/include (Required is at least version "2.13") 
-- Using RMW implementation 'rmw_fastrtps_cpp' as default
-- Checking for module 'glfw3'                          
--   Found glfw3, version 3.3.10
-- Found control_toolbox: 4.9.0 (/opt/ros/jazzy/share/control_toolbox/cmake)
-- Found eigen3_cmake_module: 0.3.0 (/opt/ros/jazzy/share/eigen3_cmake_module/cmake)
-- Found Eigen3: TRUE (found version "3.4.0") 
-- Ensuring Eigen3 include directory is part of orocos-kdl CMake target
-- Found Threads: TRUE                                  
-- No MuJoCo installation found. Downloading MuJoCo 3.3.4 for x86_64.
-- MuJoCo downloaded to: /home/juliaj/ros2_ws/src/mujoco_ros2_simulation/mujoco/mujoco-3.3.4
-- Installing /home/juliaj/ros2_ws/src/mujoco_ros2_simulation/mujoco/mujoco-3.3.4/lib/libmujoco.so to the install directory...
-- Found ament_cmake_gtest: 2.5.4 (/opt/ros/jazzy/share/ament_cmake_gtest/cmake)
-- Found gtest sources under '/opt/ros/jazzy/src/gtest_vendor': C++ tests using 'Google Test' will be built
-- Found launch_testing_ament_cmake: 3.4.9 (/opt/ros/jazzy/share/launch_testing_ament_cmake/cmake)
-- Found python_cmake_module: 0.11.1 (/opt/ros/jazzy/share/python_cmake_module/cmake)
-- Found PythonExtra: /home/juliaj/.pyenv/shims/python3  
-- Configuring done (7.1s)                              
-- Generating done (0.0s)
-- Build files have been written to: /home/juliaj/ros2_ws/src/mujoco_ros2_simulation/build/mujoco_ros2_control

[0/19] Building CXX object CMakeFiles/lodepng.dir/_deps/lodepng-src/lodepng.cpp.o
[0/19] Building CXX object CMakeFiles/platform_ui_adapter.dir/mujoco/mujoco-3.3.4/simulate/glfw_adapter.cc.o
[0/19] Building CXX object CMakeFiles/platform_ui_adapter.dir/mujoco/mujoco-3.3.4/simulate/glfw_dispatch.cc.o
[0/19] Building CXX object CMakeFiles/platform_ui_adapter.dir/mujoco/mujoco-3.3.4/simulate/platform_ui_adapter.cc.o
[0/19] Building CXX object CMakeFiles/libsimulate.dir/mujoco/mujoco-3.3.4/simulate/simulate.cc.o
[0/19] Building CXX object CMakeFiles/mujoco_ros2_control.dir/src/mujoco_system_interface.cpp.o
[0/19] Building CXX object CMakeFiles/mujoco_ros2_control.dir/src/mujoco_cameras.cpp.o
[0/19] Building CXX object CMakeFiles/mujoco_ros2_control.dir/src/mujoco_lidar.cpp.o
[0/19] Building CXX object CMakeFiles/ros2_control_node.dir/src/mujoco_ros2_control_node.cpp.o
[0/19] Building CXX object test/CMakeFiles/test_plugin.dir/test_plugin.cpp.o
[0/19] Building CXX object gtest/CMakeFiles/gtest.dir/src/gtest-all.cc.o
[0/19] Building CXX object gtest/CMakeFiles/gtest_main.dir/src/gtest_main.cc.o
[1/19] Building CXX object CMakeFiles/lodepng.dir/_deps/lodepng-src/lodepng.cpp.o
FAILED: CMakeFiles/lodepng.dir/_deps/lodepng-src/lodepng.cpp.o 
sccache /usr/bin/c++  -I/home/juliaj/ros2_ws/src/mujoco_ros2_simulation/build/mujoco_ros2_control/_deps/lodepng-src -O2 -g -DNDEBUG -fPIC -Wall -Wextra -Wpedantic -MD -MT CMakeFiles/lodepng.dir/_deps/lodepng-src/lodepng.cpp.o -MF CMakeFiles/lodepng.dir/_deps/lodepng-src/lodepng.cpp.o.d -o CMakeFiles/lodepng.dir/_deps/lodepng-src/lodepng.cpp.o -c /home/juliaj/ros2_ws/src/mujoco_ros2_simulation/build/mujoco_ros2_control/_deps/lodepng-src/lodepng.cpp
/bin/sh: 1: sccache: not found
  • Trouble with -fuse-ld=mold which appears to be set with pixi, i had a hard time to remove it. After poking around, I believed that this was caused by CXXFLAGS = "-fuse-ld=mold" in pixi.toml, but when building outside pixi, if CXXFLAGS contains this flag and mold isn't installed, the build fails with "cannot find 'ld'".
colcon build --symlink-install
Starting >>> mujoco_ros2_control
Not searching for unused variables given on the command line.
-- The C compiler identification is GNU 13.3.0
-- The CXX compiler identification is GNU 13.3.0        
-- Detecting C compiler ABI info
-- Detecting C compiler ABI info - failed               
-- Check for working C compiler: /usr/bin/cc
CMake Error at /usr/share/cmake-3.28/Modules/CMakeTestCCompiler.cmake:67 (message):
  The C compiler

    "/usr/bin/cc"

  is not able to compile a simple test program.

  It fails with the following output:

    Change Dir: '/home/juliaj/ros2_ws/src/mujoco_ros2_simulation/build/mujoco_ros2_control/CMakeFiles/CMakeScratch/TryCompile-TeHSaA'
    
    Run Build Command(s): /usr/bin/ninja -v cmTC_bd939
    [1/2] /usr/bin/cc    -o CMakeFiles/cmTC_bd939.dir/testCCompiler.c.o -c /home/juliaj/ros2_ws/src/mujoco_ros2_simulation/build/mujoco_ros2_control/CMakeFiles/CMakeScratch/TryCompile-TeHSaA/testCCompiler.c
    [2/2] : && /usr/bin/cc  -fuse-ld=mold CMakeFiles/cmTC_bd939.dir/testCCompiler.c.o -o cmTC_bd939   && :
    FAILED: cmTC_bd939 
    : && /usr/bin/cc  -fuse-ld=mold CMakeFiles/cmTC_bd939.dir/testCCompiler.c.o -o cmTC_bd939   && :
    collect2: fatal error: cannot find ‘ld’
    compilation terminated.
    ninja: build stopped: subcommand failed.
    
    ```

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants