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 #include <moveit/warehouse/state_storage.h>
00038
00039 const std::string moveit_warehouse::RobotStateStorage::DATABASE_NAME = "moveit_robot_states";
00040
00041 const std::string moveit_warehouse::RobotStateStorage::STATE_NAME = "state_id";
00042 const std::string moveit_warehouse::RobotStateStorage::ROBOT_NAME = "robot_id";
00043
00044 using warehouse_ros::Metadata;
00045 using warehouse_ros::Query;
00046
00047 moveit_warehouse::RobotStateStorage::RobotStateStorage(warehouse_ros::DatabaseConnection::Ptr conn)
00048 : MoveItMessageStorage(conn)
00049 {
00050 createCollections();
00051 }
00052
00053 void moveit_warehouse::RobotStateStorage::createCollections()
00054 {
00055 state_collection_ = conn_->openCollectionPtr<moveit_msgs::RobotState>(DATABASE_NAME, "robot_states");
00056 }
00057
00058 void moveit_warehouse::RobotStateStorage::reset()
00059 {
00060 state_collection_.reset();
00061 conn_->dropDatabase(DATABASE_NAME);
00062 createCollections();
00063 }
00064
00065 void moveit_warehouse::RobotStateStorage::addRobotState(const moveit_msgs::RobotState& msg, const std::string& name,
00066 const std::string& robot)
00067 {
00068 bool replace = false;
00069 if (hasRobotState(name, robot))
00070 {
00071 removeRobotState(name, robot);
00072 replace = true;
00073 }
00074 Metadata::Ptr metadata = state_collection_->createMetadata();
00075 metadata->append(STATE_NAME, name);
00076 metadata->append(ROBOT_NAME, robot);
00077 state_collection_->insert(msg, metadata);
00078 ROS_DEBUG("%s robot state '%s'", replace ? "Replaced" : "Added", name.c_str());
00079 }
00080
00081 bool moveit_warehouse::RobotStateStorage::hasRobotState(const std::string& name, const std::string& robot) const
00082 {
00083 Query::Ptr q = state_collection_->createQuery();
00084 q->append(STATE_NAME, name);
00085 if (!robot.empty())
00086 q->append(ROBOT_NAME, robot);
00087 std::vector<RobotStateWithMetadata> constr = state_collection_->queryList(q, true);
00088 return !constr.empty();
00089 }
00090
00091 void moveit_warehouse::RobotStateStorage::getKnownRobotStates(const std::string& regex, std::vector<std::string>& names,
00092 const std::string& robot) const
00093 {
00094 getKnownRobotStates(names, robot);
00095 filterNames(regex, names);
00096 }
00097
00098 void moveit_warehouse::RobotStateStorage::getKnownRobotStates(std::vector<std::string>& names,
00099 const std::string& robot) const
00100 {
00101 names.clear();
00102 Query::Ptr q = state_collection_->createQuery();
00103 if (!robot.empty())
00104 q->append(ROBOT_NAME, robot);
00105 std::vector<RobotStateWithMetadata> constr = state_collection_->queryList(q, true, STATE_NAME, true);
00106 for (std::size_t i = 0; i < constr.size(); ++i)
00107 if (constr[i]->lookupField(STATE_NAME))
00108 names.push_back(constr[i]->lookupString(STATE_NAME));
00109 }
00110
00111 bool moveit_warehouse::RobotStateStorage::getRobotState(RobotStateWithMetadata& msg_m, const std::string& name,
00112 const std::string& robot) const
00113 {
00114 Query::Ptr q = state_collection_->createQuery();
00115 q->append(STATE_NAME, name);
00116 if (!robot.empty())
00117 q->append(ROBOT_NAME, robot);
00118 std::vector<RobotStateWithMetadata> constr = state_collection_->queryList(q, false);
00119 if (constr.empty())
00120 return false;
00121 else
00122 {
00123 msg_m = constr.front();
00124 return true;
00125 }
00126 }
00127
00128 void moveit_warehouse::RobotStateStorage::renameRobotState(const std::string& old_name, const std::string& new_name,
00129 const std::string& robot)
00130 {
00131 Query::Ptr q = state_collection_->createQuery();
00132 q->append(STATE_NAME, old_name);
00133 if (!robot.empty())
00134 q->append(ROBOT_NAME, robot);
00135 Metadata::Ptr m = state_collection_->createMetadata();
00136 m->append(STATE_NAME, new_name);
00137 state_collection_->modifyMetadata(q, m);
00138 ROS_DEBUG("Renamed robot state from '%s' to '%s'", old_name.c_str(), new_name.c_str());
00139 }
00140
00141 void moveit_warehouse::RobotStateStorage::removeRobotState(const std::string& name, const std::string& robot)
00142 {
00143 Query::Ptr q = state_collection_->createQuery();
00144 q->append(STATE_NAME, name);
00145 if (!robot.empty())
00146 q->append(ROBOT_NAME, robot);
00147 unsigned int rem = state_collection_->removeMessages(q);
00148 ROS_DEBUG("Removed %u RobotState messages (named '%s')", rem, name.c_str());
00149 }