|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <planning_scene_storage.hpp>


Public Member Functions | |
| PlanningSceneStorage (warehouse_ros::DatabaseConnection::Ptr conn) | |
| void | addPlanningScene (const moveit_msgs::msg::PlanningScene &scene) |
| void | addPlanningQuery (const moveit_msgs::msg::MotionPlanRequest &planning_query, const std::string &scene_name, const std::string &query_name="") |
| void | addPlanningResult (const moveit_msgs::msg::MotionPlanRequest &planning_query, const moveit_msgs::msg::RobotTrajectory &result, const std::string &scene_name) |
| bool | hasPlanningScene (const std::string &name) const |
| void | getPlanningSceneNames (std::vector< std::string > &names) const |
| void | getPlanningSceneNames (const std::string ®ex, std::vector< std::string > &names) const |
| bool | getPlanningScene (PlanningSceneWithMetadata &scene_m, const std::string &scene_name) const |
| Get the latest planning scene named scene_name. | |
| bool | getPlanningSceneWorld (moveit_msgs::msg::PlanningSceneWorld &world, const std::string &scene_name) const |
| bool | hasPlanningQuery (const std::string &scene_name, const std::string &query_name) const |
| bool | getPlanningQuery (MotionPlanRequestWithMetadata &query_m, const std::string &scene_name, const std::string &query_name) |
| void | getPlanningQueries (std::vector< MotionPlanRequestWithMetadata > &planning_queries, const std::string &scene_name) const |
| void | getPlanningQueriesNames (std::vector< std::string > &query_names, const std::string &scene_name) const |
| void | getPlanningQueriesNames (const std::string ®ex, std::vector< std::string > &query_names, const std::string &scene_name) const |
| void | getPlanningQueries (std::vector< MotionPlanRequestWithMetadata > &planning_queries, std::vector< std::string > &query_names, const std::string &scene_name) const |
| void | getPlanningResults (std::vector< RobotTrajectoryWithMetadata > &planning_results, const std::string &scene_name, const moveit_msgs::msg::MotionPlanRequest &planning_query) const |
| void | getPlanningResults (std::vector< RobotTrajectoryWithMetadata > &planning_results, const std::string &scene_name, const std::string &query_name) const |
| void | renamePlanningScene (const std::string &old_scene_name, const std::string &new_scene_name) |
| void | renamePlanningQuery (const std::string &scene_name, const std::string &old_query_name, const std::string &new_query_name) |
| void | removePlanningScene (const std::string &scene_name) |
| void | removePlanningQuery (const std::string &scene_name, const std::string &query_name) |
| void | removePlanningQueries (const std::string &scene_name) |
| void | removePlanningResults (const std::string &scene_name) |
| void | removePlanningResults (const std::string &scene_name, const std::string &query_name) |
| void | reset () |
Public Member Functions inherited from moveit_warehouse::MoveItMessageStorage | |
| MoveItMessageStorage (warehouse_ros::DatabaseConnection::Ptr conn) | |
| Takes a warehouse_ros DatabaseConnection. The DatabaseConnection is expected to have already been initialized. | |
| virtual | ~MoveItMessageStorage () |
Static Public Attributes | |
| static const std::string | DATABASE_NAME = "moveit_planning_scenes" |
| static const std::string | PLANNING_SCENE_ID_NAME = "planning_scene_id" |
| static const std::string | MOTION_PLAN_REQUEST_ID_NAME = "motion_request_id" |
Additional Inherited Members | |
Protected Member Functions inherited from moveit_warehouse::MoveItMessageStorage | |
| void | filterNames (const std::string ®ex, std::vector< std::string > &names) const |
| Keep only the names that match regex. | |
Protected Attributes inherited from moveit_warehouse::MoveItMessageStorage | |
| warehouse_ros::DatabaseConnection::Ptr | conn_ |
Definition at line 60 of file planning_scene_storage.hpp.
| moveit_warehouse::PlanningSceneStorage::PlanningSceneStorage | ( | warehouse_ros::DatabaseConnection::Ptr | conn | ) |
Definition at line 51 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::addPlanningQuery | ( | const moveit_msgs::msg::MotionPlanRequest & | planning_query, |
| const std::string & | scene_name, | ||
| const std::string & | query_name = "" |
||
| ) |
Definition at line 136 of file planning_scene_storage.cpp.

| void moveit_warehouse::PlanningSceneStorage::addPlanningResult | ( | const moveit_msgs::msg::MotionPlanRequest & | planning_query, |
| const moveit_msgs::msg::RobotTrajectory & | result, | ||
| const std::string & | scene_name | ||
| ) |
Definition at line 179 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::addPlanningScene | ( | const moveit_msgs::msg::PlanningScene & | scene | ) |
Definition at line 76 of file planning_scene_storage.cpp.

| void moveit_warehouse::PlanningSceneStorage::getPlanningQueries | ( | std::vector< MotionPlanRequestWithMetadata > & | planning_queries, |
| const std::string & | scene_name | ||
| ) | const |
Definition at line 263 of file planning_scene_storage.cpp.

| void moveit_warehouse::PlanningSceneStorage::getPlanningQueries | ( | std::vector< MotionPlanRequestWithMetadata > & | planning_queries, |
| std::vector< std::string > & | query_names, | ||
| const std::string & | scene_name | ||
| ) | const |
Definition at line 307 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::getPlanningQueriesNames | ( | const std::string & | regex, |
| std::vector< std::string > & | query_names, | ||
| const std::string & | scene_name | ||
| ) | const |
Definition at line 285 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::getPlanningQueriesNames | ( | std::vector< std::string > & | query_names, |
| const std::string & | scene_name | ||
| ) | const |
Definition at line 271 of file planning_scene_storage.cpp.
| bool moveit_warehouse::PlanningSceneStorage::getPlanningQuery | ( | MotionPlanRequestWithMetadata & | query_m, |
| const std::string & | scene_name, | ||
| const std::string & | query_name | ||
| ) |
Definition at line 243 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::getPlanningResults | ( | std::vector< RobotTrajectoryWithMetadata > & | planning_results, |
| const std::string & | scene_name, | ||
| const moveit_msgs::msg::MotionPlanRequest & | planning_query | ||
| ) | const |
Definition at line 328 of file planning_scene_storage.cpp.

| void moveit_warehouse::PlanningSceneStorage::getPlanningResults | ( | std::vector< RobotTrajectoryWithMetadata > & | planning_results, |
| const std::string & | scene_name, | ||
| const std::string & | query_name | ||
| ) | const |
Definition at line 343 of file planning_scene_storage.cpp.
| bool moveit_warehouse::PlanningSceneStorage::getPlanningScene | ( | PlanningSceneWithMetadata & | scene_m, |
| const std::string & | scene_name | ||
| ) | const |
Get the latest planning scene named scene_name.
Definition at line 225 of file planning_scene_storage.cpp.

| void moveit_warehouse::PlanningSceneStorage::getPlanningSceneNames | ( | const std::string & | regex, |
| std::vector< std::string > & | names | ||
| ) | const |
Definition at line 205 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::getPlanningSceneNames | ( | std::vector< std::string > & | names | ) | const |
Definition at line 192 of file planning_scene_storage.cpp.

| bool moveit_warehouse::PlanningSceneStorage::getPlanningSceneWorld | ( | moveit_msgs::msg::PlanningSceneWorld & | world, |
| const std::string & | scene_name | ||
| ) | const |
Definition at line 212 of file planning_scene_storage.cpp.
| bool moveit_warehouse::PlanningSceneStorage::hasPlanningQuery | ( | const std::string & | scene_name, |
| const std::string & | query_name | ||
| ) | const |
Definition at line 353 of file planning_scene_storage.cpp.
| bool moveit_warehouse::PlanningSceneStorage::hasPlanningScene | ( | const std::string & | name | ) | const |
Definition at line 90 of file planning_scene_storage.cpp.

| void moveit_warehouse::PlanningSceneStorage::removePlanningQueries | ( | const std::string & | scene_name | ) |
Definition at line 397 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::removePlanningQuery | ( | const std::string & | scene_name, |
| const std::string & | query_name | ||
| ) |
Definition at line 406 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::removePlanningResults | ( | const std::string & | scene_name | ) |
Definition at line 418 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::removePlanningResults | ( | const std::string & | scene_name, |
| const std::string & | query_name | ||
| ) |
Definition at line 426 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::removePlanningScene | ( | const std::string & | scene_name | ) |
Definition at line 388 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::renamePlanningQuery | ( | const std::string & | scene_name, |
| const std::string & | old_query_name, | ||
| const std::string & | new_query_name | ||
| ) |
Definition at line 374 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::renamePlanningScene | ( | const std::string & | old_scene_name, |
| const std::string & | new_scene_name | ||
| ) |
Definition at line 363 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::reset | ( | ) |
Definition at line 67 of file planning_scene_storage.cpp.

|
static |
Definition at line 63 of file planning_scene_storage.hpp.
|
static |
Definition at line 66 of file planning_scene_storage.hpp.
|
static |
Definition at line 65 of file planning_scene_storage.hpp.