From dacb572019e010bc1bb16bd9e4b31848efdb4eca Mon Sep 17 00:00:00 2001 From: eitan Date: Wed, 1 Dec 2010 19:02:17 +0000 Subject: [PATCH] Fixing bug with timestamps when there are only fixed joints --- robot_state_publisher/src/joint_state_listener.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/robot_state_publisher/src/joint_state_listener.cpp b/robot_state_publisher/src/joint_state_listener.cpp index e7b2eee..84f4875 100644 --- a/robot_state_publisher/src/joint_state_listener.cpp +++ b/robot_state_publisher/src/joint_state_listener.cpp @@ -57,8 +57,8 @@ JointStateListener::JointStateListener(const KDL::Tree& tree) if (tree.getNrOfJoints() == 0){ boost::shared_ptr empty_state(new sensor_msgs::JointState); - empty_state->header.stamp = ros::Time::now(); while (ros::ok()){ + empty_state->header.stamp = ros::Time::now(); this->callbackJointState(empty_state); publish_rate_.sleep(); }