Skip to content

Commit

Permalink
robotStateMsgToRobotState: is_diff==true => not empty
Browse files Browse the repository at this point in the history
In case the incoming RobotStateMsg is a diff,
the joint fields are allowed to be empty.
This is used to change attached objects.
  • Loading branch information
v4hn committed Aug 9, 2017
1 parent 7d36403 commit 8db5eb0
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 8db5eb0

Please sign in to comment.