Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef MOVEIT_MOVEIT_WAREHOUSE_PLANNING_SCENE_STORAGE_
00038 #define MOVEIT_MOVEIT_WAREHOUSE_PLANNING_SCENE_STORAGE_
00039
00040 #include "moveit/warehouse/moveit_message_storage.h"
00041 #include <moveit/macros/class_forward.h>
00042 #include <moveit_msgs/PlanningScene.h>
00043 #include <moveit_msgs/MotionPlanRequest.h>
00044 #include <moveit_msgs/RobotTrajectory.h>
00045
00046 namespace moveit_warehouse
00047 {
00048 typedef mongo_ros::MessageWithMetadata<moveit_msgs::PlanningScene>::ConstPtr PlanningSceneWithMetadata;
00049 typedef mongo_ros::MessageWithMetadata<moveit_msgs::MotionPlanRequest>::ConstPtr MotionPlanRequestWithMetadata;
00050 typedef mongo_ros::MessageWithMetadata<moveit_msgs::RobotTrajectory>::ConstPtr RobotTrajectoryWithMetadata;
00051
00052 typedef boost::shared_ptr<mongo_ros::MessageCollection<moveit_msgs::PlanningScene> > PlanningSceneCollection;
00053 typedef boost::shared_ptr<mongo_ros::MessageCollection<moveit_msgs::MotionPlanRequest> > MotionPlanRequestCollection;
00054 typedef boost::shared_ptr<mongo_ros::MessageCollection<moveit_msgs::RobotTrajectory> > RobotTrajectoryCollection;
00055
00056 MOVEIT_CLASS_FORWARD(PlanningSceneStorage);
00057
00058 class PlanningSceneStorage : public MoveItMessageStorage
00059 {
00060 public:
00061 static const std::string DATABASE_NAME;
00062
00063 static const std::string PLANNING_SCENE_ID_NAME;
00064 static const std::string MOTION_PLAN_REQUEST_ID_NAME;
00065
00073 PlanningSceneStorage(const std::string& host = "", const unsigned int port = 0, double wait_seconds = 5.0);
00074
00075 void addPlanningScene(const moveit_msgs::PlanningScene& scene);
00076 void addPlanningQuery(const moveit_msgs::MotionPlanRequest& planning_query, const std::string& scene_name,
00077 const std::string& query_name = "");
00078 void addPlanningResult(const moveit_msgs::MotionPlanRequest& planning_query,
00079 const moveit_msgs::RobotTrajectory& result, const std::string& scene_name);
00080
00081 bool hasPlanningScene(const std::string& name) const;
00082 void getPlanningSceneNames(std::vector<std::string>& names) const;
00083 void getPlanningSceneNames(const std::string& regex, std::vector<std::string>& names) const;
00084
00086 bool getPlanningScene(PlanningSceneWithMetadata& scene_m, const std::string& scene_name) const;
00087 bool getPlanningSceneWorld(moveit_msgs::PlanningSceneWorld& world, const std::string& scene_name) const;
00088
00089 bool hasPlanningQuery(const std::string& scene_name, const std::string& query_name) const;
00090 bool getPlanningQuery(MotionPlanRequestWithMetadata& query_m, const std::string& scene_name,
00091 const std::string& query_name);
00092 void getPlanningQueries(std::vector<MotionPlanRequestWithMetadata>& planning_queries,
00093 const std::string& scene_name) const;
00094 void getPlanningQueriesNames(std::vector<std::string>& query_names, const std::string& scene_name) const;
00095 void getPlanningQueriesNames(const std::string& regex, std::vector<std::string>& query_names,
00096 const std::string& scene_name) const;
00097 void getPlanningQueries(std::vector<MotionPlanRequestWithMetadata>& planning_queries,
00098 std::vector<std::string>& query_names, const std::string& scene_name) const;
00099
00100 void getPlanningResults(std::vector<RobotTrajectoryWithMetadata>& planning_results, const std::string& scene_name,
00101 const moveit_msgs::MotionPlanRequest& planning_query) const;
00102 void getPlanningResults(std::vector<RobotTrajectoryWithMetadata>& planning_results, const std::string& scene_name,
00103 const std::string& query_name) const;
00104
00105 void renamePlanningScene(const std::string& old_scene_name, const std::string& new_scene_name);
00106 void renamePlanningQuery(const std::string& scene_name, const std::string& old_query_name,
00107 const std::string& new_query_name);
00108
00109 void removePlanningScene(const std::string& scene_name);
00110 void removePlanningQuery(const std::string& scene_name, const std::string& query_name);
00111 void removePlanningQueries(const std::string& scene_name);
00112 void removePlanningResults(const std::string& scene_name);
00113 void removePlanningResults(const std::string& scene_name, const std::string& query_name);
00114
00115 void reset();
00116
00117 private:
00118 void createCollections();
00119
00120 std::string getMotionPlanRequestName(const moveit_msgs::MotionPlanRequest& planning_query,
00121 const std::string& scene_name) const;
00122 std::string addNewPlanningRequest(const moveit_msgs::MotionPlanRequest& planning_query, const std::string& scene_name,
00123 const std::string& query_name);
00124
00125 PlanningSceneCollection planning_scene_collection_;
00126 MotionPlanRequestCollection motion_plan_request_collection_;
00127 RobotTrajectoryCollection robot_trajectory_collection_;
00128 };
00129 }
00130
00131 #endif