Fixing bug with timestamps when there are only fixed joints
This commit is contained in:
parent
750f7a5b94
commit
dacb572019
|
@ -57,8 +57,8 @@ JointStateListener::JointStateListener(const KDL::Tree& tree)
|
||||||
|
|
||||||
if (tree.getNrOfJoints() == 0){
|
if (tree.getNrOfJoints() == 0){
|
||||||
boost::shared_ptr<sensor_msgs::JointState> empty_state(new sensor_msgs::JointState);
|
boost::shared_ptr<sensor_msgs::JointState> empty_state(new sensor_msgs::JointState);
|
||||||
empty_state->header.stamp = ros::Time::now();
|
|
||||||
while (ros::ok()){
|
while (ros::ok()){
|
||||||
|
empty_state->header.stamp = ros::Time::now();
|
||||||
this->callbackJointState(empty_state);
|
this->callbackJointState(empty_state);
|
||||||
publish_rate_.sleep();
|
publish_rate_.sleep();
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue