45using warehouse_ros::Metadata;
46using warehouse_ros::Query;
50 , logger_(
moveit::getLogger(
"moveit.ros.warehouse_planning_scene_world_storage"))
55void moveit_warehouse::PlanningSceneWorldStorage::createCollections()
57 planning_scene_world_collection_ =
58 conn_->openCollectionPtr<moveit_msgs::msg::PlanningSceneWorld>(DATABASE_NAME,
"planning_scene_worlds");
63 planning_scene_world_collection_.reset();
64 conn_->dropDatabase(DATABASE_NAME);
69 const std::string& name)
72 if (hasPlanningSceneWorld(name))
74 removePlanningSceneWorld(name);
77 Metadata::Ptr metadata = planning_scene_world_collection_->createMetadata();
78 metadata->append(PLANNING_SCENE_WORLD_ID_NAME, name);
79 planning_scene_world_collection_->insert(msg, metadata);
80 RCLCPP_DEBUG(logger_,
"%s planning scene world '%s'", replace ?
"Replaced" :
"Added", name.c_str());
85 Query::Ptr q = planning_scene_world_collection_->createQuery();
86 q->append(PLANNING_SCENE_WORLD_ID_NAME, name);
87 std::vector<PlanningSceneWorldWithMetadata> psw = planning_scene_world_collection_->queryList(q,
true);
92 std::vector<std::string>& names)
const
94 getKnownPlanningSceneWorlds(names);
95 filterNames(regex, names);
101 Query::Ptr q = planning_scene_world_collection_->createQuery();
102 std::vector<PlanningSceneWorldWithMetadata> planning_scene_worlds =
103 planning_scene_world_collection_->queryList(q,
true, PLANNING_SCENE_WORLD_ID_NAME,
true);
106 if (planning_scene_world->lookupField(PLANNING_SCENE_WORLD_ID_NAME))
107 names.push_back(planning_scene_world->lookupString(PLANNING_SCENE_WORLD_ID_NAME));
112 const std::string& name)
const
114 Query::Ptr q = planning_scene_world_collection_->createQuery();
115 q->append(PLANNING_SCENE_WORLD_ID_NAME, name);
116 std::vector<PlanningSceneWorldWithMetadata> psw = planning_scene_world_collection_->queryList(q,
false);
129 const std::string& new_name)
131 Query::Ptr q = planning_scene_world_collection_->createQuery();
132 q->append(PLANNING_SCENE_WORLD_ID_NAME, old_name);
133 Metadata::Ptr m = planning_scene_world_collection_->createMetadata();
134 m->append(PLANNING_SCENE_WORLD_ID_NAME, new_name);
135 planning_scene_world_collection_->modifyMetadata(q, m);
136 RCLCPP_DEBUG(logger_,
"Renamed planning scene world from '%s' to '%s'", old_name.c_str(), new_name.c_str());
141 Query::Ptr q = planning_scene_world_collection_->createQuery();
142 q->append(PLANNING_SCENE_WORLD_ID_NAME, name);
143 unsigned int rem = planning_scene_world_collection_->removeMessages(q);
144 RCLCPP_DEBUG(logger_,
"Removed %u PlanningSceneWorld messages (named '%s')", rem, name.c_str());
This class provides the mechanism to connect to a database and reads needed ROS parameters when appro...
void getKnownPlanningSceneWorlds(std::vector< std::string > &names) const
bool hasPlanningSceneWorld(const std::string &name) const
void renamePlanningSceneWorld(const std::string &old_name, const std::string &new_name)
bool getPlanningSceneWorld(PlanningSceneWorldWithMetadata &msg_m, const std::string &name) const
Get the constraints named name. Return false on failure.
void removePlanningSceneWorld(const std::string &name)
static const std::string DATABASE_NAME
static const std::string PLANNING_SCENE_WORLD_ID_NAME
PlanningSceneWorldStorage(warehouse_ros::DatabaseConnection::Ptr conn)
void addPlanningSceneWorld(const moveit_msgs::msg::PlanningSceneWorld &msg, const std::string &name)
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::PlanningSceneWorld >::ConstPtr PlanningSceneWorldWithMetadata
Main namespace for MoveIt.