88 auto scene{ planning_scene_monitor_->getPlanningScene() };
89 moveit_msgs::msg::PlanningScene msg;
90 msg.is_diff = msg.robot_state.is_diff =
true;
91 planning_scene_monitor_->newPlanningSceneMessage(msg);
92 EXPECT_EQ(scene, planning_scene_monitor_->getPlanningScene());
93 msg.is_diff = msg.robot_state.is_diff =
false;
94 planning_scene_monitor_->newPlanningSceneMessage(msg);
95 EXPECT_EQ(scene, planning_scene_monitor_->getPlanningScene());
111 moveit_msgs::msg::PlanningScene msg;
112 msg.is_diff = msg.robot_state.is_diff =
true;
115 msg.fixed_frame_transforms.emplace_back();
116 msg.fixed_frame_transforms.back().header.frame_id =
"base_link";
117 msg.fixed_frame_transforms.back().child_frame_id =
"object";
118 msg.fixed_frame_transforms.back().transform.rotation.w = 1.0;
120 msg.fixed_frame_transforms.clear();
122 msg.robot_state.is_diff =
true;
125 msg.robot_state.is_diff =
false;
126 TRIGGERS_UPDATE(msg, UpdateType::UPDATE_STATE | UpdateType::UPDATE_GEOMETRY);
128 msg.robot_state = moveit_msgs::msg::RobotState{};
129 msg.robot_state.is_diff =
true;
130 moveit_msgs::msg::CollisionObject collision_object;
131 collision_object.header.frame_id =
"base_link";
132 collision_object.id =
"object";
133 collision_object.operation = moveit_msgs::msg::CollisionObject::ADD;
134 collision_object.pose.orientation.w = 1.0;
135 collision_object.primitives.emplace_back();
136 collision_object.primitives.back().type = shape_msgs::msg::SolidPrimitive::SPHERE;
137 collision_object.primitives.back().dimensions = { 1.0 };
138 msg.world.collision_objects.emplace_back(collision_object);
141 msg.world.collision_objects.clear();