Skip to content

Commit

Permalink
Use urdf/model.hpp for rolling (#1476)
Browse files Browse the repository at this point in the history
  • Loading branch information
nakul-py authored Jan 9, 2025
1 parent 7ddaf83 commit 6299094
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand Down
7 changes: 0 additions & 7 deletions joint_state_broadcaster/src/joint_state_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,13 +26,6 @@
#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
{
class State;
Expand Down

0 comments on commit 6299094

Please sign in to comment.