Skip to content

Commit 4536d3f

Browse files
Use RCL_ROS_TIME
Co-authored-by: Sai Kishor Kothakota <[email protected]>
1 parent 54aefe1 commit 4536d3f

File tree

1 file changed

+1
-1
lines changed

1 file changed

+1
-1
lines changed

control_toolbox/include/control_filters/gravity_compensation.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -93,7 +93,7 @@ GravityCompensation<T>::~GravityCompensation()
9393
template <typename T>
9494
bool GravityCompensation<T>::configure()
9595
{
96-
clock_ = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
96+
clock_ = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
9797
p_tf_Buffer_.reset(new tf2_ros::Buffer(clock_));
9898
p_tf_Listener_.reset(new tf2_ros::TransformListener(*p_tf_Buffer_.get(), true));
9999

0 commit comments

Comments
 (0)