From 3d8e951cd59db4dba7461557c520b05ed458f0cd Mon Sep 17 00:00:00 2001 From: nakul-py Date: Wed, 8 Jan 2025 17:10:33 +0530 Subject: [PATCH] Using urdf/model.hpp for rolling and urdf/model.h for jazzy or humble --- .../joint_state_broadcaster/joint_state_broadcaster.hpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/joint_state_broadcaster/include/joint_state_broadcaster/joint_state_broadcaster.hpp b/joint_state_broadcaster/include/joint_state_broadcaster/joint_state_broadcaster.hpp index da02c5feb8..f0f100d6d0 100644 --- a/joint_state_broadcaster/include/joint_state_broadcaster/joint_state_broadcaster.hpp +++ b/joint_state_broadcaster/include/joint_state_broadcaster/joint_state_broadcaster.hpp @@ -26,7 +26,13 @@ #include "joint_state_broadcaster_parameters.hpp" #include "realtime_tools/realtime_publisher.hpp" #include "sensor_msgs/msg/joint_state.hpp" + +#include "rclcpp/version.h" +#if RCLCPP_VERSION_GTE(29, 0, 0) +#include "urdf/model.hpp" +#else #include "urdf/model.h" +#endif namespace joint_state_broadcaster {