Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
109 changes: 106 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,49 @@ cmake_minimum_required(VERSION 3.16)

project(mujoco_ros2_control)

# Find mold linker (required dependency, Linux only)
# mold is Linux-specific and not available on macOS/Windows
if(CMAKE_SYSTEM_NAME STREQUAL "Linux")
find_program(MOLD_LINKER
NAMES mold
PATHS /usr/bin /usr/local/bin /opt/conda/bin ${CONDA_PREFIX}/bin
NO_DEFAULT_PATH
)
if(NOT MOLD_LINKER)
find_program(MOLD_LINKER mold)
endif()

if(NOT MOLD_LINKER)
message(FATAL_ERROR "mold linker not found. Please install mold: sudo apt-get install mold")
endif()
message(STATUS "Found mold linker: ${MOLD_LINKER}")

# Set mold as the linker if not already set via environment
if(NOT DEFINED ENV{CXXFLAGS} OR NOT "$ENV{CXXFLAGS}" MATCHES "-fuse-ld=mold")
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -fuse-ld=mold")
set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} -fuse-ld=mold")
message(STATUS "Using mold linker for faster builds")
endif()
else()
message(STATUS "mold linker skipped (not available on ${CMAKE_SYSTEM_NAME})")
endif()

# Find sccache (required dependency for compiler caching)
# Try multiple methods: standard PATH, common install locations
find_program(SCCACHE_PROGRAM
NAMES sccache
PATHS /usr/bin /usr/local/bin /opt/conda/bin ${CONDA_PREFIX}/bin
NO_DEFAULT_PATH
)
if(NOT SCCACHE_PROGRAM)
find_program(SCCACHE_PROGRAM sccache)
endif()

if(NOT SCCACHE_PROGRAM)
message(FATAL_ERROR "sccache not found. Please install sccache: sudo apt-get install sccache (or via cargo: cargo install sccache)")
endif()
message(STATUS "Found sccache: ${SCCACHE_PROGRAM}")

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
Expand All @@ -10,7 +53,67 @@ endif()
find_package(ament_cmake REQUIRED)
find_package(controller_manager REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(glfw3 REQUIRED)

# Find GLFW
# Standard approach: use pkg-config for system packages (libglfw3-dev provides .pc file)
# Fallback to CMake config for conda/pixi environments, then manual find
find_package(PkgConfig QUIET)
if(PkgConfig_FOUND)
pkg_check_modules(GLFW3 glfw3)
endif()

if(GLFW3_FOUND)
# Create glfw target from pkg-config (standard for system packages)
# Use find_library to get actual library path for proper linking
find_library(GLFW3_LIBRARY_FILE
NAMES glfw glfw3
PATHS ${GLFW3_LIBRARY_DIRS} /usr/lib /usr/local/lib /usr/lib/x86_64-linux-gnu
NO_DEFAULT_PATH
)
if(NOT GLFW3_LIBRARY_FILE)
find_library(GLFW3_LIBRARY_FILE NAMES glfw glfw3)
endif()
if(GLFW3_LIBRARY_FILE)
add_library(glfw INTERFACE)
target_include_directories(glfw INTERFACE ${GLFW3_INCLUDE_DIRS})
target_link_libraries(glfw INTERFACE ${GLFW3_LIBRARY_FILE})
target_compile_options(glfw INTERFACE ${GLFW3_CFLAGS_OTHER})
else()
# Fallback to pkg-config libraries if find_library fails
add_library(glfw INTERFACE)
target_include_directories(glfw INTERFACE ${GLFW3_INCLUDE_DIRS})
target_link_libraries(glfw INTERFACE ${GLFW3_LIBRARIES})
target_compile_options(glfw INTERFACE ${GLFW3_CFLAGS_OTHER})
endif()
else()
# Fallback: try CMake config (for conda/pixi environments)
find_package(glfw3 QUIET)
if(glfw3_FOUND)
if(TARGET glfw3::glfw3 AND NOT TARGET glfw)
add_library(glfw ALIAS glfw3::glfw3)
elseif(TARGET glfw3 AND NOT TARGET glfw)
add_library(glfw ALIAS glfw3)
endif()
else()
# Last resort: manual find (shouldn't be needed if libglfw3-dev is installed)
find_library(GLFW3_LIBRARY
NAMES glfw glfw3
PATHS /usr/lib /usr/local/lib /usr/lib/x86_64-linux-gnu
)
find_path(GLFW3_INCLUDE_DIR
NAMES GLFW/glfw3.h
PATHS /usr/include /usr/local/include
)
if(GLFW3_LIBRARY AND GLFW3_INCLUDE_DIR)
add_library(glfw INTERFACE)
target_include_directories(glfw INTERFACE ${GLFW3_INCLUDE_DIR})
target_link_libraries(glfw INTERFACE ${GLFW3_LIBRARY})
else()
message(FATAL_ERROR "GLFW3 not found. Please install libglfw3-dev: sudo apt-get install libglfw3-dev")
endif()
endif()
endif()

find_package(control_toolbox REQUIRED)
find_package(hardware_interface REQUIRED)
find_package(pluginlib REQUIRED)
Expand Down Expand Up @@ -129,7 +232,7 @@ target_include_directories(
platform_ui_adapter PUBLIC ${MUJOCO_SIMULATE_DIR} ${MUJOCO_INCLUDE_DIR}
$<TARGET_PROPERTY:glfw,INTERFACE_INCLUDE_DIRECTORIES>
)
target_link_libraries(platform_ui_adapter PUBLIC ${MUJOCO_LIB})
target_link_libraries(platform_ui_adapter PUBLIC ${MUJOCO_LIB} glfw)
target_compile_options(platform_ui_adapter PRIVATE ${MUJOCO_SILENCE_COMPILER_WARNINGS})
add_library(mujoco::platform_ui_adapter ALIAS platform_ui_adapter)

Expand All @@ -145,7 +248,7 @@ target_sources(
PRIVATE ${MUJOCO_SIMULATE_DIR}/simulate.cc ${MUJOCO_SIMULATE_DIR}/array_safety.h
)
target_include_directories(libsimulate PUBLIC ${MUJOCO_SIMULATE_DIR} ${MUJOCO_INCLUDE_DIR})
target_link_libraries(libsimulate PUBLIC lodepng mujoco::platform_ui_adapter ${MUJOCO_LIB})
target_link_libraries(libsimulate PUBLIC lodepng mujoco::platform_ui_adapter ${MUJOCO_LIB} glfw)
target_compile_options(libsimulate PRIVATE ${MUJOCO_SILENCE_COMPILER_WARNINGS})

# Mujoco ROS 2 control system interface (this package)
Expand Down
45 changes: 45 additions & 0 deletions docs/DEVELOPMENT.md
Original file line number Diff line number Diff line change
Expand Up @@ -79,3 +79,48 @@ ros2 launch mujoco_ros2_control test_robot.launch.py

Users may need to tweak the compose file to support their specific host OS or GPUs.
For more information refer to the comments in the compose file.

## Development Workflow within ROS 2 Workspace

This package can be built in a standard ROS 2 workspace on Linux/Ubuntu. This workflow is recommended for integrating with existing ROS 2 workspaces or for developers working with rolling builds from `ros2_control` or `ros2_controllers` projects. For isolated development environments, consider using the [Docker Development Workflow](#docker-development-workflow) or [Pixi Development Workflow](#pixi-development-workflow) instead.

> [!WARNING]
> Special care is needed when building in a ROS 2 workspace because ROS 2 packages from system installations or rolling builds may not be compatible with the versions pinned in `pixi.lock`. Version mismatches can cause ABI incompatibilities leading to segmentation faults (SIGSEGV) during runtime, such as `ros2_control_node` crashing with exit code -11 during hardware initialization. Ensure that your ROS 2 workspace uses compatible package versions to avoid build conflicts and runtime crashes. See [issue #30](https://github.com/ros-controls/mujoco_ros2_control/issues/30) for more details.

### Dependencies

Install required system dependencies:

```bash
# Install ROS 2 dependencies via rosdep
rosdep update --rosdistro $ROS_DISTRO
rosdep install --from-paths src --ignore-src -r -y

# Install additional build dependencies
sudo apt-get install libglfw3-dev sccache mold
```

**Note:** `mold` is a Linux-only linker optimization. On macOS/Windows, it will be automatically skipped during the build.

### Build

From your ROS 2 workspace root:

```bash
# Source ROS 2 installation
source /opt/ros/$ROS_DISTRO/setup.bash

# Build the package
colcon build --symlink-install --packages-select mujoco_ros2_control

# Source the workspace
source install/setup.bash
```

The build system will:
- Automatically download MuJoCo 3.3.4 if not found locally
- Use `pkg-config` to find GLFW (system package) or fall back to CMake config (conda/pixi environments)
- Require `sccache` for compiler caching (cross-platform)
- Require `mold` linker on Linux for faster linking (skipped on other platforms)

If any required dependency is missing, CMake will provide clear error messages with installation instructions.
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
<depend>controller_manager</depend>
<depend>hardware_interface</depend>
<depend>libglfw3-dev</depend>
<depend>sccache</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>rclcpp_lifecycle</depend>
Expand Down
Loading