diff --git a/src/robot_state_publisher.cpp b/src/robot_state_publisher.cpp index 4863c94..94fcec7 100644 --- a/src/robot_state_publisher.cpp +++ b/src/robot_state_publisher.cpp @@ -345,7 +345,12 @@ void RobotStatePublisher::callbackJointState( } } - publishTransforms(joint_positions, state->header.stamp); + rclcpp::Parameter sim_p = this->get_parameter("use_sim_time"); + if (sim_p.as_bool()) { + publishTransforms(joint_positions, now); + } else { + publishTransforms(joint_positions, state->header.stamp); + } // store publish time in joint map for (size_t i = 0; i < state->name.size(); i++) {