Skip to content

Commit

Permalink
Using urdf/model.hpp for rolling.
Browse files Browse the repository at this point in the history
  • Loading branch information
nakul-py committed Jan 7, 2025
1 parent d86b9d7 commit 88c800a
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 0 deletions.
6 changes: 6 additions & 0 deletions joint_state_broadcaster/src/joint_state_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,13 @@
#include "rclcpp/qos.hpp"
#include "rclcpp/time.hpp"
#include "std_msgs/msg/header.hpp"

#include "rclcpp/version.h"
#if RCLCPP_VERSION_GTE(29, 0, 0)
#include "urdf/model.hpp"
#else
#include "urdf/model.h"
#endif

namespace rclcpp_lifecycle
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,13 @@
#include "rclcpp_action/create_server.hpp"
#include "rclcpp_action/server_goal_handle.hpp"
#include "rclcpp_lifecycle/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_trajectory_controller
{
Expand Down

0 comments on commit 88c800a

Please sign in to comment.