Skip to content

Commit

Permalink
Merge pull request moveit#589 from v4hn/pr-kinetic-rs-empty-if-no-diff
Browse files Browse the repository at this point in the history
robotStateMsgToRobotState: is_diff==true => not empty
  • Loading branch information
jrgnicho committed Aug 14, 2017
2 parents 7d36403 + 8db5eb0 commit 3499872
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion moveit_core/robot_state/src/conversions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -332,7 +332,7 @@ static bool _robotStateMsgToRobotStateHelper(const Transforms* tf, const moveit_
bool valid;
const moveit_msgs::RobotState& rs = robot_state;

if (rs.joint_state.name.empty() && rs.multi_dof_joint_state.joint_names.empty())
if (!rs.is_diff && rs.joint_state.name.empty() && rs.multi_dof_joint_state.joint_names.empty())
{
logError("Found empty JointState message");
return false;
Expand Down

0 comments on commit 3499872

Please sign in to comment.