Skip to content

Conversation

@idesign0
Copy link
Contributor

Fix macOS compilation issues in Navigation2 packages

Summary

  • This PR fixes compilation issues on macOS for couple of Navigation2 packages. The changes include:
  • Correct use of template keyword in dependent template calls
  • Pass-by-value instead of non-const reference for optional structs

Package-wise Changes

1. nav2_behavior_tree

File: bt_action_server_impl.hpp

before:

// Put items on the blackboard
blackboard_->set<rclcpp::Node::SharedPtr>("node", client_node_);  // NOLINT
blackboard_->set<std::chrono::milliseconds>("server_timeout", default_server_timeout_);  // NOLINT
blackboard_->set<std::chrono::milliseconds>("bt_loop_duration", bt_loop_duration_);  // NOLINT
blackboard_->set<std::chrono::milliseconds>(
  "wait_for_service_timeout",
  wait_for_service_timeout_);

after:

// Put items on the blackboard
blackboard_->template set<rclcpp::Node::SharedPtr>("node", client_node_);  // NOLINT
blackboard_->template set<std::chrono::milliseconds>("server_timeout", default_server_timeout_);  // NOLINT
blackboard_->template set<std::chrono::milliseconds>("bt_loop_duration", bt_loop_duration_);  // NOLINT
blackboard_->template set<std::chrono::milliseconds>(
  "wait_for_service_timeout",
  wait_for_service_timeout_);

Explanation: The template keyword is required in dependent template contexts on Apple Clang.

2. nav2_route

a) File: route_server.hpp

before:

ReroutingState & rerouting_info = ReroutingState());

after:

ReroutingState rerouting_info = ReroutingState());

b) File: route_server.cpp

before:

template<typename GoalT>
Route RouteServer::findRoute(
  const std::shared_ptr<const GoalT> goal,
  ReroutingState & rerouting_info)
{
  // ...
}

after:

template<typename GoalT>
Route RouteServer::findRoute(
  const std::shared_ptr<const GoalT> goal,
  ReroutingState rerouting_info)
{
  // ...
}

Explanation: Non-const lvalue references cannot bind to temporaries in C++. Changing to pass-by-value fixes the compilation error while preserving optional behavior.

Testing

  • Full Navigation2 build on macOS: ✅ success
  • Verified no compilation warnings or runtime errors during compile-time checks
Signed-off-by: Dhruv Patel <dhruvpatel2991998@gmail.com>
Signed-off-by: Dhruv Patel <dhruvpatel2991998@gmail.com>
@SteveMacenski
Copy link
Member

SteveMacenski commented Nov 26, 2025

Please fill out the PR template in the future :-)

This also doesn't appear to build. How did you test this?

@idesign0
Copy link
Contributor Author

Please fill out the PR template in the future :-)

This also doesn't appear to build. How did you test this?

Thanks for the feedback! I’ll make sure to fill out the PR template properly next time.
Regarding the build: I tested these changes on macOS 26.1 (25B78) using the kilted branch. The workspace built successfully with the following command:

colcon build \                                          
  --symlink-install \
  --base-paths src/ros-planning/navigation2  \
  --executor parallel \
  --parallel-workers $(sysctl -n hw.ncpu) \
  --cmake-args -DCMAKE_TOOLCHAIN_FILE=$MY_TOOLCHAIN_FILE

Below is the Toolchain i use for the all the ros2 package builds.

message(WARN " Toolchain.cmake is being used.")

# Set C++ standard
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_CXX_EXTENSIONS OFF)
set(CMAKE_BUILD_TYPE "Release" CACHE STRING "Build type" FORCE)

# Setting all the Build Tests Off
set(BUILD_TESTING OFF CACHE BOOL "Disable building tests" FORCE)
set(BUILD_UNIT_TESTS OFF CACHE BOOL "Disable building tests" FORCE)
set(BUILD_TESTS OFF CACHE BOOL "Disable building tests" FORCE)

# Make sure all workspace-installed packages are visible
set(ROS_WORKSPACE_INSTALL "$ENV{HOME}/kilted-ros2/install")
list(APPEND CMAKE_PREFIX_PATH "${ROS_WORKSPACE_INSTALL}")

# Ceres
set(BUILD_BENCHMARKS OFF CACHE BOOL "Disable building benchmarks" FORCE) 
set(BUILD_EXAMPLES OFF CACHE BOOL "Disable building examples" FORCE)

# --- yaml-cpp from ROS 2 kilted install ---
set(YAML_CPP_INCLUDE_DIRS
    "$ENV{HOME}/kilted-ros2/install/yaml_cpp_vendor/opt/yaml_cpp_vendor/include"
    CACHE PATH "yaml-cpp include dir")

set(YAML_CPP_LIBRARIES
    "$ENV{HOME}/kilted-ros2/install/yaml_cpp_vendor/opt/yaml_cpp_vendor/lib/libyaml-cpp.dylib"
    CACHE FILEPATH "yaml-cpp library")

# Use the paths
include_directories(${YAML_CPP_INCLUDE_DIRS})

# Backward ROS
# On macOS, do NOT add Linux-only flags
set(CMAKE_EXE_LINKER_FLAGS "${backward_ros_full_path_LIBRARIES} ${CMAKE_EXE_LINKER_FLAGS}" CACHE STRING "Linker flags" FORCE)

# Optimization flags
if(CMAKE_BUILD_TYPE STREQUAL "Release")
  add_compile_options(-O3 -march=native)
endif()


# Suppress treating warnings as errors
string(REPLACE "-Werror" "" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}")
string(REPLACE "-Werror" "" CMAKE_C_FLAGS "${CMAKE_C_FLAGS}")

# 2. Force the new, modified flags into the CMake cache
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}" CACHE STRING "Modified CXX flags without -Werror" FORCE)
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS}" CACHE STRING "Modified C flags without -Werror" FORCE)

# Suppress warning as errors
add_compile_options(
        -Wno-error=unused-command-line-argument
        -Wno-error=pessimizing-move
        -Wno-error=unused-variable
        -Wno-error=unused-parameter
        -Wno-error=unused-but-set-variable
        -Wno-error=shadow 
        -Wno-error=shadow-field
        -Wno-error=deprecated-dynamic-exception-spec
        -Wno-error=inconsistent-missing-override
        -Wno-error=format-security
        -Wno-error=overloaded-virtual
        -Wno-error=deprecated-builtins
        -Wno-error=deprecated-copy-with-dtor
        -Wno-error=deprecated-copy-with-user-provided-dtor
        -Wno-error=unused-lambda-capture
 )

 if (CMAKE_CXX_COMPILER_ID MATCHES "Clang")
    # This specifically suppresses the dynamic exception warning
    string(APPEND CMAKE_CXX_FLAGS " -Wno-deprecated-dynamic-exception-spec")
    
    # Optional: If you want to disable ALL warnings-as-errors globally,
    # ensure this is done after any package might have tried to enable it.
    string(REPLACE "-Werror" "" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}")
endif()

# macOS specific linker
set(CMAKE_MACOSX_RPATH ON)

# Thread config
set(CMAKE_THREAD_LIBS_INIT "-lpthread")
set(CMAKE_HAVE_THREADS_LIBRARY 1)
set(CMAKE_USE_WIN32_THREADS_INIT 0)
set(CMAKE_USE_PTHREADS_INIT 1)
set(THREADS_PREFER_PTHREAD_FLAG ON)

# # OpenMP for Apple Clang
# set(OpenMP_INCLUDE_DIR "/opt/homebrew/opt/libomp/include")
# set(OpenMP_LIB_DIR "/opt/homebrew/opt/libomp/lib")

# include_directories(SYSTEM "${OpenMP_INCLUDE_DIR}")

# set(CMAKE_C_FLAGS   "${CMAKE_C_FLAGS} -Xclang -fopenmp")
# set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Xclang -fopenmp")

# set(CMAKE_EXE_LINKER_FLAGS    "${CMAKE_EXE_LINKER_FLAGS} -L${OpenMP_LIB_DIR} -lomp")
# set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} -L${OpenMP_LIB_DIR} -lomp")
# set(CMAKE_MODULE_LINKER_FLAGS "${CMAKE_MODULE_LINKER_FLAGS} -L${OpenMP_LIB_DIR} -lomp")

# # Create the imported target so downstream packages can use it
# if (NOT TARGET OpenMP::OpenMP_CXX)
#     add_library(OpenMP::OpenMP_CXX INTERFACE IMPORTED)
#     set_target_properties(OpenMP::OpenMP_CXX PROPERTIES
#         INTERFACE_INCLUDE_DIRECTORIES "${OpenMP_INCLUDE_DIR}"
#         INTERFACE_LINK_LIBRARIES "-L${OpenMP_LIB_DIR} -lomp"
#     )
# endif()

# macOS provides LAPACK and BLAS inside Accelerate framework
set(BLAS_LIBRARIES "-framework Accelerate" CACHE STRING "BLAS libraries")
set(LAPACK_LIBRARIES "-framework Accelerate" CACHE STRING "LAPACK libraries")

# Paths related to dependencies used at build time (absolute or relative)

# Boost
# Path to your custom Boost installation
set(BOOST_ROOT "$ENV{HOME}/kilted-ros2/src/ros-commondep/boost-1.89" CACHE PATH "Boost root")
set(BOOST_INCLUDEDIR "${BOOST_ROOT}/include" CACHE PATH "Boost include")
set(BOOST_LIBRARYDIR "${BOOST_ROOT}/lib" CACHE PATH "Boost lib")

# Asio from Boost
set(THIRDPARTY_Asio ON CACHE BOOL "Allow Thirdparty Asio" FORCE)

# Ensure Boost can be found without searching system paths first
set(CMAKE_PREFIX_PATH "${BOOST_ROOT};${CMAKE_PREFIX_PATH}")

# Force modern CMake Boost behavior
set(Boost_NO_SYSTEM_PATHS ON CACHE BOOL "Don't search system paths for Boost")
set(Boost_NO_BOOST_CMAKE OFF CACHE BOOL "Allow BoostConfig.cmake if present")
find_package(Boost REQUIRED)

# Make sure CMake uses your Boost include & lib paths
set(Boost_INCLUDE_DIRS "${BOOST_INCLUDEDIR}" CACHE PATH "Boost include dirs" FORCE)
set(Boost_LIBRARY_DIRS "${BOOST_LIBRARYDIR}" CACHE PATH "Boost library dir" FORCE)

# Force include + lib dirs globally
include_directories(SYSTEM ${BOOST_INCLUDEDIR})
link_directories(${BOOST_LIBRARYDIR})

# Globally enable deprecated Boost Timer API
add_definitions(-DBOOST_TIMER_ENABLE_DEPRECATED)

# Python-specific paths
set(Boost_PYTHON_LIBRARY "${BOOST_LIBRARYDIR}/libboost_python311.dylib" CACHE FILEPATH "Boost Python library")
set(Boost_PYTHON_INCLUDE_DIR "${BOOST_INCLUDEDIR}" CACHE PATH "Boost Python include dir")

# Optional: force CMake to find Boost in these directories
set(CMAKE_PREFIX_PATH "${BOOST_ROOT}/lib/cmake/Boost-1.89.0;${CMAKE_PREFIX_PATH}" CACHE PATH "Boost CMake path")

# Google Benchmark paths (Homebrew)
set(CMAKE_PREFIX_PATH "/opt/homebrew/opt/google-benchmark;${CMAKE_PREFIX_PATH}")

#CLI
set(CLI11_INCLUDE_DIRS "/opt/homebrew/include" CACHE PATH "CLI11 include path" FORCE)
include_directories(SYSTEM ${CLI11_INCLUDE_DIRS})

# CSparse paths (Homebrew)
set(CSPARSE_INCLUDE_DIR "/opt/homebrew/include/suitesparse")
set(CSPARSE_LIBRARY "/opt/homebrew/lib/libsuitesparse.dylib")

# Ceres
set(Ceres_DIR "$ENV{HOME}/kilted-ros2/install/ceres-solver/lib/cmake/Ceres" CACHE PATH "")

# ProtoBuf
set(PROTOBUF_INSTALL_PATH 
    "$ENV{HOME}/kilted-ros2/install/protobuf" 
    CACHE PATH "Installation path for source-built Protobuf" FORCE)

# Set the CMAKE_PREFIX_PATH to prioritize the source install over Homebrew
set(CMAKE_PREFIX_PATH 
    "${PROTOBUF_INSTALL_PATH};${CMAKE_PREFIX_PATH}")

# Explicitly add the include directory to the system path
include_directories(SYSTEM "${PROTOBUF_INSTALL_PATH}/include")

# Explicitly set the variables that packages like gz-msgs will search for
set(PROTOBUF_INCLUDE_DIR "${PROTOBUF_INSTALL_PATH}/include" CACHE PATH "Protobuf Include Dir" FORCE)
set(PROTOBUF_LIBRARY "${PROTOBUF_INSTALL_PATH}/lib/libprotobuf.dylib" CACHE FILEPATH "Protobuf Library" FORCE)

# 1. Set the GDAL_CONFIG variable (often found in /opt/homebrew/bin)
set(GDAL_CONFIG_BIN "/opt/homebrew/bin/gdal-config" CACHE FILEPATH "Path to Homebrew gdal-config utility." FORCE)

# 2. Add it as an environment variable (often required by CMake's FindGDAL)
set(ENV{GDAL_CONFIG} ${GDAL_CONFIG_BIN})

# 3. Add the Homebrew prefix for general finding (if not already there)
set(CMAKE_PREFIX_PATH 
    "/opt/homebrew/opt/gdal;${CMAKE_PREFIX_PATH}" CACHE STRING "Prefix paths" FORCE)
    
#livox_ros_driver2
set(PCL_ALL_IN_ONE_INSTALLER OFF CACHE BOOL "Disable bundled Boost" FORCE)
set(ROS_EDITION "ROS2" CACHE STRING "ROS edition")
set(ROS_VERSION "2" CACHE STRING "ROS Version")
set(KILTED_ROS "kilted" CACHE STRING "ROS 2 kilted")
set(ROS_DISTRO "kilted" CACHE STRING "ROS 2 Distro")

# Qt5 path (for ROS packages)
set(Qt5_DIR "/opt/homebrew/opt/qt@5/lib/cmake/Qt5" CACHE PATH "Qt5 CMake path")
set(QT5_PREFIX "/opt/homebrew/opt/qt@5" CACHE PATH "Qt5 prefix path")

# Qt6 path (for Ignition Gazebo)
set(Qt6_DIR "/opt/homebrew/opt/qt/lib/cmake/Qt6" CACHE PATH "Qt6 CMake path")
set(QT6_PREFIX "/opt/homebrew/opt/qt" CACHE PATH "Qt6 prefix path")

# Add both Qt5 and Qt6 CMake modules to CMAKE_PREFIX_PATH
set(CMAKE_PREFIX_PATH "${QT6_PREFIX}/lib/cmake;${QT5_PREFIX}/lib/cmake;${CMAKE_PREFIX_PATH}" CACHE PATH "Qt CMake paths" FORCE)

# Add Qt5 and Qt6 binaries to PATH (for moc, uic, rcc)
set(ENV{PATH} "${QT6_PREFIX}/bin:${QT5_PREFIX}/bin:$ENV{PATH}")

# Tell CMake to look for frameworks last (helps prevent conflicts)
set(CMAKE_FIND_FRAMEWORK LAST)

# OpenGL (for Qt5Gui)
set(_GL_INCDIRS "/opt/homebrew/include" CACHE STRING "")
set(_qt5gui_OPENGL_INCLUDE_DIR "/opt/homebrew/include/GL" CACHE PATH "")
set(Qt5Gui_OPENGL_IMPLEMENTATION GL CACHE STRING "")
set(Qt5Gui_OPENGL_LIBRARIES "/opt/homebrew/lib/libGL.dylib" CACHE FILEPATH "")

# moveit_ros_perception
# Toolchain for macOS Homebrew OpenGL dependencies
set(GLEW_INCLUDE_DIR "/opt/homebrew/opt/glew/include" CACHE PATH "GLEW include directory")
set(GLEW_LIBRARY "/opt/homebrew/opt/glew/lib/libGLEW.dylib" CACHE FILEPATH "GLEW library")

set(GLUT_INCLUDE_DIR "/opt/homebrew/opt/freeglut/include" CACHE PATH "GLUT/FreeGLUT include directory")
set(GLUT_LIBRARY "/opt/homebrew/lib/libglut.dylib" CACHE FILEPATH "GLUT/FreeGLUT library")

set(GLEW_INCLUDE_DIRS ${GLEW_INCLUDE_DIR} CACHE INTERNAL "")
set(GLEW_LIBRARIES ${GLEW_LIBRARY} CACHE INTERNAL "")
set(GLUT_INCLUDE_DIRS ${GLUT_INCLUDE_DIR} CACHE INTERNAL "")
set(GLUT_LIBRARIES ${GLUT_LIBRARY} CACHE INTERNAL "")

set(SYSTEM_GL_INCLUDE_DIR ${GLEW_INCLUDE_DIRS} ${GLUT_INCLUDE_DIRS} CACHE INTERNAL "")
set(SYSTEM_GL_LIBRARIES ${GLEW_LIBRARIES} ${GLUT_LIBRARIES} CACHE INTERNAL "")

# macOS: link system OpenGL framework for Ogre
set(OGRE_FRAMEWORKS "-framework OpenGL")
# Pass to global linker flags for executables & shared libs
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${OGRE_FRAMEWORKS}" CACHE STRING "Link OpenGL framework for Ogre" FORCE)
set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} ${OGRE_FRAMEWORKS}" CACHE STRING "Link OpenGL framework for Ogre" FORCE)

# --- Force TinyXML2 targets for Gazebo vendors (Mac/Homebrew fix) ---
if (NOT TARGET tinyxml2::tinyxml2)
    add_library(tinyxml2::tinyxml2 INTERFACE IMPORTED)
    set_target_properties(tinyxml2::tinyxml2 PROPERTIES
        INTERFACE_INCLUDE_DIRECTORIES "/opt/homebrew/include"
        INTERFACE_LINK_LIBRARIES "/opt/homebrew/lib/libtinyxml2.dylib"
    )
endif()

if (NOT TARGET TINYXML2::TINYXML2)
    add_library(TINYXML2::TINYXML2 INTERFACE IMPORTED)
    set_target_properties(TINYXML2::TINYXML2 PROPERTIES
        INTERFACE_INCLUDE_DIRECTORIES "/opt/homebrew/include"
        INTERFACE_LINK_LIBRARIES "/opt/homebrew/lib/libtinyxml2.dylib"
    )
endif()

# --- Eigen (Homebrew) ---
# Ensure CMake can find Eigen headers
set(EIGEN3_INCLUDE_DIR "/opt/homebrew/include/eigen3" CACHE PATH "Eigen3 include directory" FORCE)
include_directories(SYSTEM ${EIGEN3_INCLUDE_DIR})

# Optional: add Eigen to CMAKE_PREFIX_PATH so find_package(Eigen3) works
set(CMAKE_PREFIX_PATH "/opt/homebrew/include/eigen3;${CMAKE_PREFIX_PATH}" CACHE STRING "CMake prefix path" FORCE)

# If a package uses find_package(Eigen3)
find_package(Eigen3 REQUIRED)

# --- Google glog (Homebrew) ---
set(GLOG_INCLUDE_DIR "/opt/homebrew/include" CACHE PATH "glog include path" FORCE)
set(GLOG_LIBRARY "/opt/homebrew/lib/libglog.dylib" CACHE FILEPATH "glog library" FORCE)

# Add include directory globally
include_directories(SYSTEM ${GLOG_INCLUDE_DIR})

# Append glog library to all targets' linker flags
# This ensures Ceres symbols (used in nav2_constrained_smoother) are found
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${GLOG_LIBRARY}")
set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} ${GLOG_LIBRARY}")
set(CMAKE_MODULE_LINKER_FLAGS "${CMAKE_MODULE_LINKER_FLAGS} ${GLOG_LIBRARY}")

# --- PCL Conversions ---
set(PCL_CONVERSIONS_INCLUDE_DIR "$ENV{HOME}/kilted-ros2/src/ros-perception/perception_pcl/pcl_conversions/include")
# Export for downstream packages
set(pcl_conversions_INCLUDE_DIRS "${PCL_CONVERSIONS_INCLUDE_DIR}" CACHE PATH "PCL Conversions include dirs" FORCE)
@idesign0
Copy link
Contributor Author

Please fill out the PR template in the future :-)

This also doesn't appear to build. How did you test this?

Build failure is simply related to nav2::LifecycleNode i think. My bad 🙃. Will fix and push it soon.

@mini-1235
Copy link
Collaborator

This seems to be related to #5660, @traversaro can you take a look here?

@traversaro
Copy link
Contributor

This seems to be related to #5660, @traversaro can you take a look here?

Yes, that indeed includes a fix for that issue, but I think it introduces a subtle bug, I commented inline.

> reverting to nav2::LifecycleNode rather using rclcpp::Node

Signed-off-by: Dhruv Patel <dhruvpatel2991998@gmail.com>
@codecov
Copy link

codecov bot commented Nov 27, 2025

Codecov Report

✅ All modified and coverable lines are covered by tests.

Files with missing lines Coverage Δ
...clude/nav2_behavior_tree/bt_action_server_impl.hpp 88.65% <100.00%> (-2.54%) ⬇️
...lude/nav2_route/plugins/route_operation_client.hpp 95.00% <ø> (ø)
nav2_route/include/nav2_route/route_server.hpp 100.00% <ø> (ø)
nav2_route/src/route_server.cpp 97.86% <ø> (+1.60%) ⬆️

... and 10 files with indirect coverage changes

🚀 New features to boost your workflow:
  • ❄️ Test Analytics: Detect flaky tests, report on failures, and find test suite problems.
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

4 participants