#include <planning_scene_storage.h>

Public Member Functions | |
| void | addPlanningQuery (const moveit_msgs::MotionPlanRequest &planning_query, const std::string &scene_name, const std::string &query_name="") | 
| void | addPlanningResult (const moveit_msgs::MotionPlanRequest &planning_query, const moveit_msgs::RobotTrajectory &result, const std::string &scene_name) | 
| void | addPlanningScene (const moveit_msgs::PlanningScene &scene) | 
| void | getPlanningQueries (std::vector< MotionPlanRequestWithMetadata > &planning_queries, 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 | getPlanningQueriesNames (const std::string ®ex, std::vector< std::string > &query_names, const std::string &scene_name) const | 
| void | getPlanningQueriesNames (std::vector< std::string > &query_names, const std::string &scene_name) const | 
| bool | getPlanningQuery (MotionPlanRequestWithMetadata &query_m, const std::string &scene_name, const std::string &query_name) | 
| void | getPlanningResults (std::vector< RobotTrajectoryWithMetadata > &planning_results, const std::string &scene_name, const moveit_msgs::MotionPlanRequest &planning_query) const | 
| void | getPlanningResults (std::vector< RobotTrajectoryWithMetadata > &planning_results, const std::string &scene_name, const std::string &query_name) const | 
| bool | getPlanningScene (PlanningSceneWithMetadata &scene_m, const std::string &scene_name) const | 
| Get the latest planning scene named scene_name.  More... | |
| void | getPlanningSceneNames (const std::string ®ex, std::vector< std::string > &names) const | 
| void | getPlanningSceneNames (std::vector< std::string > &names) const | 
| bool | getPlanningSceneWorld (moveit_msgs::PlanningSceneWorld &world, const std::string &scene_name) const | 
| bool | hasPlanningQuery (const std::string &scene_name, const std::string &query_name) const | 
| bool | hasPlanningScene (const std::string &name) const | 
| PlanningSceneStorage (warehouse_ros::DatabaseConnection::Ptr conn) | |
| void | removePlanningQueries (const std::string &scene_name) | 
| void | removePlanningQuery (const std::string &scene_name, const std::string &query_name) | 
| void | removePlanningResults (const std::string &scene_name) | 
| void | removePlanningResults (const std::string &scene_name, const std::string &query_name) | 
| void | removePlanningScene (const std::string &scene_name) | 
| void | renamePlanningQuery (const std::string &scene_name, const std::string &old_query_name, const std::string &new_query_name) | 
| void | renamePlanningScene (const std::string &old_scene_name, const std::string &new_scene_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.  More... | |
| virtual | ~MoveItMessageStorage () | 
Static Public Attributes | |
| static const std::string | DATABASE_NAME = "moveit_planning_scenes" | 
| static const std::string | MOTION_PLAN_REQUEST_ID_NAME = "motion_request_id" | 
| static const std::string | PLANNING_SCENE_ID_NAME = "planning_scene_id" | 
Private Member Functions | |
| std::string | addNewPlanningRequest (const moveit_msgs::MotionPlanRequest &planning_query, const std::string &scene_name, const std::string &query_name) | 
| void | createCollections () | 
| std::string | getMotionPlanRequestName (const moveit_msgs::MotionPlanRequest &planning_query, const std::string &scene_name) const | 
Private Attributes | |
| MotionPlanRequestCollection | motion_plan_request_collection_ | 
| PlanningSceneCollection | planning_scene_collection_ | 
| RobotTrajectoryCollection | robot_trajectory_collection_ | 
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.  More... | |
  Protected Attributes inherited from moveit_warehouse::MoveItMessageStorage | |
| warehouse_ros::DatabaseConnection::Ptr | conn_ | 
Definition at line 89 of file planning_scene_storage.h.
| moveit_warehouse::PlanningSceneStorage::PlanningSceneStorage | ( | warehouse_ros::DatabaseConnection::Ptr | conn | ) | 
Definition at line 49 of file planning_scene_storage.cpp.
      
  | 
  private | 
Definition at line 146 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::addPlanningQuery | ( | const moveit_msgs::MotionPlanRequest & | planning_query, | 
| const std::string & | scene_name, | ||
| const std::string & | query_name = ""  | 
        ||
| ) | 
Definition at line 132 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::addPlanningResult | ( | const moveit_msgs::MotionPlanRequest & | planning_query, | 
| const moveit_msgs::RobotTrajectory & | result, | ||
| const std::string & | scene_name | ||
| ) | 
Definition at line 173 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::addPlanningScene | ( | const moveit_msgs::PlanningScene & | scene | ) | 
Definition at line 73 of file planning_scene_storage.cpp.
      
  | 
  private | 
Definition at line 55 of file planning_scene_storage.cpp.
      
  | 
  private | 
Definition at line 96 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 255 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 297 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 275 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 263 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 235 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::getPlanningResults | ( | std::vector< RobotTrajectoryWithMetadata > & | planning_results, | 
| const std::string & | scene_name, | ||
| const moveit_msgs::MotionPlanRequest & | planning_query | ||
| ) | const | 
Definition at line 312 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 323 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 217 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::getPlanningSceneNames | ( | const std::string & | regex, | 
| std::vector< std::string > & | names | ||
| ) | const | 
Definition at line 197 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::getPlanningSceneNames | ( | std::vector< std::string > & | names | ) | const | 
Definition at line 186 of file planning_scene_storage.cpp.
| bool moveit_warehouse::PlanningSceneStorage::getPlanningSceneWorld | ( | moveit_msgs::PlanningSceneWorld & | world, | 
| const std::string & | scene_name | ||
| ) | const | 
Definition at line 204 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 333 of file planning_scene_storage.cpp.
| bool moveit_warehouse::PlanningSceneStorage::hasPlanningScene | ( | const std::string & | name | ) | const | 
Definition at line 87 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::removePlanningQueries | ( | const std::string & | scene_name | ) | 
Definition at line 377 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::removePlanningQuery | ( | const std::string & | scene_name, | 
| const std::string & | query_name | ||
| ) | 
Definition at line 386 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::removePlanningResults | ( | const std::string & | scene_name | ) | 
Definition at line 398 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::removePlanningResults | ( | const std::string & | scene_name, | 
| const std::string & | query_name | ||
| ) | 
Definition at line 406 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::removePlanningScene | ( | const std::string & | scene_name | ) | 
Definition at line 368 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 354 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 343 of file planning_scene_storage.cpp.
| void moveit_warehouse::PlanningSceneStorage::reset | ( | ) | 
Definition at line 64 of file planning_scene_storage.cpp.
      
  | 
  static | 
Definition at line 92 of file planning_scene_storage.h.
      
  | 
  private | 
Definition at line 150 of file planning_scene_storage.h.
      
  | 
  static | 
Definition at line 95 of file planning_scene_storage.h.
      
  | 
  private | 
Definition at line 149 of file planning_scene_storage.h.
      
  | 
  static | 
Definition at line 94 of file planning_scene_storage.h.
      
  | 
  private | 
Definition at line 151 of file planning_scene_storage.h.