Skip to content

Commit

Permalink
Silent error "Found empty JointState message"
Browse files Browse the repository at this point in the history
  • Loading branch information
rhaschke committed Jul 18, 2024
1 parent 7631486 commit 4f69a22
Showing 1 changed file with 2 additions and 0 deletions.
2 changes: 2 additions & 0 deletions capabilities/src/execute_task_solution_capability.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,8 +170,10 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
exec_traj.effect_on_success_ = [this,
&scene_diff = const_cast<::moveit_msgs::PlanningScene&>(sub_traj.scene_diff),
description](const plan_execution::ExecutableMotionPlan* /*plan*/) {
// Never modify joint state directly (only via robot trajectories)
scene_diff.robot_state.joint_state = sensor_msgs::JointState();
scene_diff.robot_state.multi_dof_joint_state = sensor_msgs::MultiDOFJointState();
scene_diff.robot_state.is_diff = true; // silent empty JointState msg error

if (!moveit::core::isEmpty(scene_diff)) {
ROS_DEBUG_STREAM_NAMED("ExecuteTaskSolution", "apply effect of " << description);
Expand Down

0 comments on commit 4f69a22

Please sign in to comment.