55 planning_scene_world_collection_ =
56 conn_->openCollectionPtr<moveit_msgs::PlanningSceneWorld>(DATABASE_NAME,
"planning_scene_worlds");
61 planning_scene_world_collection_.reset();
62 conn_->dropDatabase(DATABASE_NAME);
67 const std::string& name)
70 if (hasPlanningSceneWorld(
name))
72 removePlanningSceneWorld(
name);
75 Metadata::Ptr metadata = planning_scene_world_collection_->createMetadata();
76 metadata->append(PLANNING_SCENE_WORLD_ID_NAME,
name);
77 planning_scene_world_collection_->insert(msg, metadata);
78 ROS_DEBUG(
"%s planning scene world '%s'", replace ?
"Replaced" :
"Added",
name.c_str());
83 Query::Ptr q = planning_scene_world_collection_->createQuery();
84 q->append(PLANNING_SCENE_WORLD_ID_NAME,
name);
85 std::vector<PlanningSceneWorldWithMetadata> psw = planning_scene_world_collection_->queryList(q,
true);
90 std::vector<std::string>& names)
const
92 getKnownPlanningSceneWorlds(names);
93 filterNames(regex, names);
99 Query::Ptr q = planning_scene_world_collection_->createQuery();
100 std::vector<PlanningSceneWorldWithMetadata> planning_scene_worlds =
101 planning_scene_world_collection_->queryList(q,
true, PLANNING_SCENE_WORLD_ID_NAME,
true);
103 if (planning_scene_world->lookupField(PLANNING_SCENE_WORLD_ID_NAME))
104 names.push_back(planning_scene_world->lookupString(PLANNING_SCENE_WORLD_ID_NAME));
108 const std::string& name)
const
110 Query::Ptr q = planning_scene_world_collection_->createQuery();
111 q->append(PLANNING_SCENE_WORLD_ID_NAME,
name);
112 std::vector<PlanningSceneWorldWithMetadata> psw = planning_scene_world_collection_->queryList(q,
false);
123 const std::string& new_name)
125 Query::Ptr q = planning_scene_world_collection_->createQuery();
126 q->append(PLANNING_SCENE_WORLD_ID_NAME, old_name);
127 Metadata::Ptr m = planning_scene_world_collection_->createMetadata();
128 m->append(PLANNING_SCENE_WORLD_ID_NAME, new_name);
129 planning_scene_world_collection_->modifyMetadata(q, m);
130 ROS_DEBUG(
"Renamed planning scene world from '%s' to '%s'", old_name.c_str(), new_name.c_str());
135 Query::Ptr q = planning_scene_world_collection_->createQuery();
136 q->append(PLANNING_SCENE_WORLD_ID_NAME,
name);
137 unsigned int rem = planning_scene_world_collection_->removeMessages(q);
138 ROS_DEBUG(
"Removed %u PlanningSceneWorld messages (named '%s')", rem,
name.c_str());