39 #include <rclcpp/serialization.hpp>
47 using warehouse_ros::Metadata;
48 using warehouse_ros::Query;
50 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit.ros.warehouse.planning_scene_storage");
58 void moveit_warehouse::PlanningSceneStorage::createCollections()
60 planning_scene_collection_ =
61 conn_->openCollectionPtr<moveit_msgs::msg::PlanningScene>(DATABASE_NAME,
"planning_scene");
62 motion_plan_request_collection_ =
64 robot_trajectory_collection_ =
65 conn_->openCollectionPtr<moveit_msgs::msg::RobotTrajectory>(DATABASE_NAME,
"robot_trajectory");
70 planning_scene_collection_.reset();
71 motion_plan_request_collection_.reset();
72 robot_trajectory_collection_.reset();
73 conn_->dropDatabase(DATABASE_NAME);
80 if (hasPlanningScene(
scene.name))
82 removePlanningScene(
scene.name);
85 Metadata::Ptr metadata = planning_scene_collection_->createMetadata();
86 metadata->append(PLANNING_SCENE_ID_NAME,
scene.name);
87 planning_scene_collection_->insert(
scene, metadata);
88 RCLCPP_DEBUG(LOGGER,
"%s scene '%s'", replace ?
"Replaced" :
"Added",
scene.name.c_str());
93 Query::Ptr q = planning_scene_collection_->createQuery();
94 q->append(PLANNING_SCENE_ID_NAME,
name);
95 std::vector<PlanningSceneWithMetadata> planning_scenes = planning_scene_collection_->queryList(q,
true);
96 return !planning_scenes.empty();
99 std::string moveit_warehouse::PlanningSceneStorage::getMotionPlanRequestName(
103 Query::Ptr q = motion_plan_request_collection_->createQuery();
104 q->append(PLANNING_SCENE_ID_NAME, scene_name);
105 std::vector<MotionPlanRequestWithMetadata> existing_requests = motion_plan_request_collection_->queryList(q,
false);
108 if (existing_requests.empty())
112 rclcpp::Serialization<moveit_msgs::msg::MotionPlanRequest> serializer;
113 rclcpp::SerializedMessage serialized_msg_arg;
114 serializer.serialize_message(&planning_query, &serialized_msg_arg);
115 const size_t serial_size_arg = serialized_msg_arg.size();
116 const void* data_arg = serialized_msg_arg.get_rcl_serialized_message().buffer;
121 rclcpp::SerializedMessage serialized_msg;
122 serializer.serialize_message(&msg, &serialized_msg);
123 const size_t serial_size = serialized_msg.size();
124 const void* data = serialized_msg.get_rcl_serialized_message().buffer;
126 if (serial_size != serial_size_arg)
128 if (memcmp(data_arg, data, serial_size) == 0)
130 return existing_request->lookupString(MOTION_PLAN_REQUEST_ID_NAME);
136 const std::string& scene_name,
137 const std::string& query_name)
139 std::string
id = getMotionPlanRequestName(planning_query, scene_name);
142 if (!query_name.empty() &&
id.empty())
143 removePlanningQuery(scene_name, query_name);
145 if (
id != query_name ||
id.empty())
146 addNewPlanningRequest(planning_query, scene_name, query_name);
151 const std::string& scene_name,
152 const std::string& query_name)
154 std::string
id = query_name;
157 std::set<std::string> used;
158 Query::Ptr q = motion_plan_request_collection_->createQuery();
159 q->append(PLANNING_SCENE_ID_NAME, scene_name);
160 std::vector<MotionPlanRequestWithMetadata> existing_requests = motion_plan_request_collection_->queryList(q,
true);
162 used.insert(existing_request->lookupString(MOTION_PLAN_REQUEST_ID_NAME));
163 std::size_t index = existing_requests.size();
166 id =
"Motion Plan Request " + std::to_string(index);
168 }
while (used.find(
id) != used.end());
170 Metadata::Ptr metadata = motion_plan_request_collection_->createMetadata();
171 metadata->append(PLANNING_SCENE_ID_NAME, scene_name);
172 metadata->append(MOTION_PLAN_REQUEST_ID_NAME,
id);
173 motion_plan_request_collection_->insert(planning_query, metadata);
174 RCLCPP_DEBUG(LOGGER,
"Saved planning query '%s' for scene '%s'",
id.c_str(), scene_name.c_str());
179 const moveit_msgs::msg::RobotTrajectory& result,
180 const std::string& scene_name)
182 std::string
id = getMotionPlanRequestName(planning_query, scene_name);
184 id = addNewPlanningRequest(planning_query, scene_name,
"");
185 Metadata::Ptr metadata = robot_trajectory_collection_->createMetadata();
186 metadata->append(PLANNING_SCENE_ID_NAME, scene_name);
187 metadata->append(MOTION_PLAN_REQUEST_ID_NAME,
id);
188 robot_trajectory_collection_->insert(result, metadata);
194 Query::Ptr q = planning_scene_collection_->createQuery();
195 std::vector<PlanningSceneWithMetadata> planning_scenes =
196 planning_scene_collection_->queryList(q,
true, PLANNING_SCENE_ID_NAME,
true);
199 names.push_back(
planning_scene->lookupString(PLANNING_SCENE_ID_NAME));
203 std::vector<std::string>& names)
const
205 getPlanningSceneNames(names);
206 filterNames(regex, names);
210 const std::string& scene_name)
const
213 if (getPlanningScene(scene_m, scene_name))
215 world = scene_m->world;
223 const std::string& scene_name)
const
225 Query::Ptr q = planning_scene_collection_->createQuery();
226 q->append(PLANNING_SCENE_ID_NAME, scene_name);
227 std::vector<PlanningSceneWithMetadata> planning_scenes = planning_scene_collection_->queryList(q,
false);
228 if (planning_scenes.empty())
230 RCLCPP_WARN(LOGGER,
"Planning scene '%s' was not found in the database", scene_name.c_str());
233 scene_m = planning_scenes.back();
235 const_cast<moveit_msgs::msg::PlanningScene*
>(
static_cast<const moveit_msgs::msg::PlanningScene*
>(scene_m.get()))->name =
241 const std::string& scene_name,
242 const std::string& query_name)
244 Query::Ptr q = motion_plan_request_collection_->createQuery();
245 q->append(PLANNING_SCENE_ID_NAME, scene_name);
246 q->append(MOTION_PLAN_REQUEST_ID_NAME, query_name);
247 std::vector<MotionPlanRequestWithMetadata> planning_queries = motion_plan_request_collection_->queryList(q,
false);
248 if (planning_queries.empty())
250 RCLCPP_ERROR(LOGGER,
"Planning query '%s' not found for scene '%s'", query_name.c_str(), scene_name.c_str());
255 query_m = planning_queries.front();
261 std::vector<MotionPlanRequestWithMetadata>& planning_queries,
const std::string& scene_name)
const
263 Query::Ptr q = motion_plan_request_collection_->createQuery();
264 q->append(PLANNING_SCENE_ID_NAME, scene_name);
265 planning_queries = motion_plan_request_collection_->queryList(q,
false);
269 const std::string& scene_name)
const
271 Query::Ptr q = motion_plan_request_collection_->createQuery();
272 q->append(PLANNING_SCENE_ID_NAME, scene_name);
273 std::vector<MotionPlanRequestWithMetadata> planning_queries = motion_plan_request_collection_->queryList(q,
true);
276 if (planning_query->lookupField(MOTION_PLAN_REQUEST_ID_NAME))
277 query_names.push_back(planning_query->lookupString(MOTION_PLAN_REQUEST_ID_NAME));
281 std::vector<std::string>& query_names,
282 const std::string& scene_name)
const
284 getPlanningQueriesNames(query_names, scene_name);
288 std::vector<std::string> fnames;
290 for (
const std::string& query_name : query_names)
293 if (std::regex_match(query_name, match,
r))
295 fnames.push_back(query_name);
298 query_names.swap(fnames);
303 std::vector<MotionPlanRequestWithMetadata>& planning_queries, std::vector<std::string>& query_names,
304 const std::string& scene_name)
const
306 Query::Ptr q = motion_plan_request_collection_->createQuery();
307 q->append(PLANNING_SCENE_ID_NAME, scene_name);
308 planning_queries = motion_plan_request_collection_->queryList(q,
false);
309 query_names.resize(planning_queries.size());
310 for (std::size_t i = 0; i < planning_queries.size(); ++i)
311 if (planning_queries[i]->lookupField(MOTION_PLAN_REQUEST_ID_NAME))
312 query_names[i] = planning_queries[i]->lookupString(MOTION_PLAN_REQUEST_ID_NAME);
314 query_names[i].clear();
318 std::vector<RobotTrajectoryWithMetadata>& planning_results,
const std::string& scene_name,
321 std::string
id = getMotionPlanRequestName(planning_query, scene_name);
323 planning_results.clear();
325 getPlanningResults(planning_results,
id, scene_name);
329 std::vector<RobotTrajectoryWithMetadata>& planning_results,
const std::string& scene_name,
330 const std::string& planning_query)
const
332 Query::Ptr q = robot_trajectory_collection_->createQuery();
333 q->append(PLANNING_SCENE_ID_NAME, scene_name);
334 q->append(MOTION_PLAN_REQUEST_ID_NAME, planning_query);
335 planning_results = robot_trajectory_collection_->queryList(q,
false);
339 const std::string& query_name)
const
341 Query::Ptr q = motion_plan_request_collection_->createQuery();
342 q->append(PLANNING_SCENE_ID_NAME, scene_name);
343 q->append(MOTION_PLAN_REQUEST_ID_NAME, query_name);
344 std::vector<MotionPlanRequestWithMetadata> queries = motion_plan_request_collection_->queryList(q,
true);
345 return !queries.empty();
349 const std::string& new_scene_name)
351 Query::Ptr q = planning_scene_collection_->createQuery();
352 q->append(PLANNING_SCENE_ID_NAME, old_scene_name);
353 Metadata::Ptr m = planning_scene_collection_->createMetadata();
354 m->append(PLANNING_SCENE_ID_NAME, new_scene_name);
355 planning_scene_collection_->modifyMetadata(q, m);
356 RCLCPP_DEBUG(LOGGER,
"Renamed planning scene from '%s' to '%s'", old_scene_name.c_str(), new_scene_name.c_str());
360 const std::string& old_query_name,
361 const std::string& new_query_name)
363 Query::Ptr q = motion_plan_request_collection_->createQuery();
364 q->append(PLANNING_SCENE_ID_NAME, scene_name);
365 q->append(MOTION_PLAN_REQUEST_ID_NAME, old_query_name);
366 Metadata::Ptr m = motion_plan_request_collection_->createMetadata();
367 m->append(MOTION_PLAN_REQUEST_ID_NAME, new_query_name);
368 motion_plan_request_collection_->modifyMetadata(q, m);
369 RCLCPP_DEBUG(LOGGER,
"Renamed planning query for scene '%s' from '%s' to '%s'", scene_name.c_str(),
370 old_query_name.c_str(), new_query_name.c_str());
375 removePlanningQueries(scene_name);
376 Query::Ptr q = planning_scene_collection_->createQuery();
377 q->append(PLANNING_SCENE_ID_NAME, scene_name);
378 unsigned int rem = planning_scene_collection_->removeMessages(q);
379 RCLCPP_DEBUG(LOGGER,
"Removed %u PlanningScene messages (named '%s')", rem, scene_name.c_str());
384 removePlanningResults(scene_name);
385 Query::Ptr q = motion_plan_request_collection_->createQuery();
386 q->append(PLANNING_SCENE_ID_NAME, scene_name);
387 unsigned int rem = motion_plan_request_collection_->removeMessages(q);
388 RCLCPP_DEBUG(LOGGER,
"Removed %u MotionPlanRequest messages for scene '%s'", rem, scene_name.c_str());
392 const std::string& query_name)
394 removePlanningResults(scene_name, query_name);
395 Query::Ptr q = motion_plan_request_collection_->createQuery();
396 q->append(PLANNING_SCENE_ID_NAME, scene_name);
397 q->append(MOTION_PLAN_REQUEST_ID_NAME, query_name);
398 unsigned int rem = motion_plan_request_collection_->removeMessages(q);
399 RCLCPP_DEBUG(LOGGER,
"Removed %u MotionPlanRequest messages for scene '%s', query '%s'", rem, scene_name.c_str(),
405 Query::Ptr q = robot_trajectory_collection_->createQuery();
406 q->append(PLANNING_SCENE_ID_NAME, scene_name);
407 unsigned int rem = robot_trajectory_collection_->removeMessages(q);
408 RCLCPP_DEBUG(LOGGER,
"Removed %u RobotTrajectory messages for scene '%s'", rem, scene_name.c_str());
412 const std::string& query_name)
414 Query::Ptr q = robot_trajectory_collection_->createQuery();
415 q->append(PLANNING_SCENE_ID_NAME, scene_name);
416 q->append(MOTION_PLAN_REQUEST_ID_NAME, query_name);
417 unsigned int rem = robot_trajectory_collection_->removeMessages(q);
418 RCLCPP_DEBUG(LOGGER,
"Removed %u RobotTrajectory messages for scene '%s', query '%s'", rem, scene_name.c_str(),
This class provides the mechanism to connect to a database and reads needed ROS parameters when appro...
bool getPlanningSceneWorld(moveit_msgs::msg::PlanningSceneWorld &world, const std::string &scene_name) const
void removePlanningScene(const std::string &scene_name)
void addPlanningQuery(const moveit_msgs::msg::MotionPlanRequest &planning_query, const std::string &scene_name, const std::string &query_name="")
void removePlanningQuery(const std::string &scene_name, const std::string &query_name)
static const std::string PLANNING_SCENE_ID_NAME
void getPlanningResults(std::vector< RobotTrajectoryWithMetadata > &planning_results, const std::string &scene_name, const moveit_msgs::msg::MotionPlanRequest &planning_query) const
void removePlanningQueries(const std::string &scene_name)
PlanningSceneStorage(warehouse_ros::DatabaseConnection::Ptr conn)
void addPlanningResult(const moveit_msgs::msg::MotionPlanRequest &planning_query, const moveit_msgs::msg::RobotTrajectory &result, const std::string &scene_name)
void renamePlanningQuery(const std::string &scene_name, const std::string &old_query_name, const std::string &new_query_name)
static const std::string DATABASE_NAME
bool hasPlanningQuery(const std::string &scene_name, const std::string &query_name) const
void getPlanningQueries(std::vector< MotionPlanRequestWithMetadata > &planning_queries, const std::string &scene_name) const
void removePlanningResults(const std::string &scene_name)
void addPlanningScene(const moveit_msgs::msg::PlanningScene &scene)
bool getPlanningQuery(MotionPlanRequestWithMetadata &query_m, const std::string &scene_name, const std::string &query_name)
void renamePlanningScene(const std::string &old_scene_name, const std::string &new_scene_name)
void getPlanningSceneNames(std::vector< std::string > &names) const
void getPlanningQueriesNames(std::vector< std::string > &query_names, const std::string &scene_name) const
bool hasPlanningScene(const std::string &name) const
static const std::string MOTION_PLAN_REQUEST_ID_NAME
bool getPlanningScene(PlanningSceneWithMetadata &scene_m, const std::string &scene_name) const
Get the latest planning scene named scene_name.
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::PlanningScene >::ConstPtr PlanningSceneWithMetadata
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::MotionPlanRequest >::ConstPtr MotionPlanRequestWithMetadata
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
const rclcpp::Logger LOGGER