43 bool isEmpty(
const moveit_msgs::PlanningScene& msg)
45 return msg.name.empty() && msg.fixed_frame_transforms.empty() && msg.allowed_collision_matrix.entry_names.empty() &&
46 msg.link_padding.empty() && msg.link_scale.empty() &&
isEmpty(msg.robot_state) &&
isEmpty(msg.world);
49 bool isEmpty(
const moveit_msgs::PlanningSceneWorld& msg)
51 return msg.collision_objects.empty() && msg.octomap.octomap.data.empty();
54 bool isEmpty(
const moveit_msgs::RobotState& msg)
59 return static_cast<bool>(msg.is_diff) && msg.multi_dof_joint_state.joint_names.empty() &&
60 msg.joint_state.name.empty() && msg.attached_collision_objects.empty() && msg.joint_state.position.empty() &&
61 msg.joint_state.velocity.empty() && msg.joint_state.effort.empty() &&
62 msg.multi_dof_joint_state.transforms.empty() && msg.multi_dof_joint_state.twist.empty() &&
63 msg.multi_dof_joint_state.wrench.empty();
66 bool isEmpty(
const moveit_msgs::Constraints& constr)
68 return constr.position_constraints.empty() && constr.orientation_constraints.empty() &&
69 constr.visibility_constraints.empty() && constr.joint_constraints.empty();
72 bool isEmpty(
const geometry_msgs::Quaternion& msg)
74 return msg.x == 0.0 && msg.y == 0.0 && msg.z == 0.0 && msg.w == 0.0;
77 bool isEmpty(
const geometry_msgs::Pose& msg)
79 return msg.position.x == 0.0 && msg.position.y == 0.0 && msg.position.z == 0.0 &&
isEmpty(msg.orientation);