Skip to content

Commit

Permalink
downgrade undeserved error log for empty JointState.position
Browse files Browse the repository at this point in the history
As per the JointState message doc, the ``position`` member must be
either empty OR have the same size as the ``name`` member.

In case it is empty, the message is valid, but we will still warn
we won't use it.
  • Loading branch information
sbarthelemy authored and Sébastien Barthélémy committed Nov 7, 2016
1 parent c49985f commit e476ac7
Showing 1 changed file with 10 additions and 1 deletion.
11 changes: 10 additions & 1 deletion src/joint_state_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,16 @@ void JointStateListener::callbackFixedJoint(const ros::TimerEvent& e)
void JointStateListener::callbackJointState(const JointStateConstPtr& state)
{
if (state->name.size() != state->position.size()){
ROS_ERROR("Robot state publisher received an invalid joint state vector");
if (state->position.empty()){
const int throttleSeconds = 300;
ROS_WARN_THROTTLE(throttleSeconds,
"Robot state publisher ignored a JointState message about joint(s) "
"\"%s\"(,...) whose position member was empty. This message will "
"not reappear for %d seconds.", state->name[0].c_str(),
throttleSeconds);
} else {
ROS_ERROR("Robot state publisher ignored an invalid JointState message");
}
return;
}

Expand Down

0 comments on commit e476ac7

Please sign in to comment.