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/constraints_storage.h>
00038
00039 const std::string moveit_warehouse::ConstraintsStorage::DATABASE_NAME = "moveit_constraints";
00040
00041 const std::string moveit_warehouse::ConstraintsStorage::CONSTRAINTS_ID_NAME = "constraints_id";
00042 const std::string moveit_warehouse::ConstraintsStorage::CONSTRAINTS_GROUP_NAME = "group_id";
00043 const std::string moveit_warehouse::ConstraintsStorage::ROBOT_NAME = "robot_id";
00044
00045 using warehouse_ros::Metadata;
00046 using warehouse_ros::Query;
00047
00048 moveit_warehouse::ConstraintsStorage::ConstraintsStorage(warehouse_ros::DatabaseConnection::Ptr conn)
00049 : MoveItMessageStorage(conn)
00050 {
00051 createCollections();
00052 }
00053
00054 void moveit_warehouse::ConstraintsStorage::createCollections()
00055 {
00056 constraints_collection_ = conn_->openCollectionPtr<moveit_msgs::Constraints>(DATABASE_NAME, "constraints");
00057 }
00058
00059 void moveit_warehouse::ConstraintsStorage::reset()
00060 {
00061 constraints_collection_.reset();
00062 conn_->dropDatabase(DATABASE_NAME);
00063 createCollections();
00064 }
00065
00066 void moveit_warehouse::ConstraintsStorage::addConstraints(const moveit_msgs::Constraints& msg, const std::string& robot,
00067 const std::string& group)
00068 {
00069 bool replace = false;
00070 if (hasConstraints(msg.name, robot, group))
00071 {
00072 removeConstraints(msg.name, robot, group);
00073 replace = true;
00074 }
00075 Metadata::Ptr metadata = constraints_collection_->createMetadata();
00076 metadata->append(CONSTRAINTS_ID_NAME, msg.name);
00077 metadata->append(ROBOT_NAME, robot);
00078 metadata->append(CONSTRAINTS_GROUP_NAME, group);
00079 constraints_collection_->insert(msg, metadata);
00080 ROS_DEBUG("%s constraints '%s'", replace ? "Replaced" : "Added", msg.name.c_str());
00081 }
00082
00083 bool moveit_warehouse::ConstraintsStorage::hasConstraints(const std::string& name, const std::string& robot,
00084 const std::string& group) const
00085 {
00086 Query::Ptr q = constraints_collection_->createQuery();
00087 q->append(CONSTRAINTS_ID_NAME, name);
00088 if (!robot.empty())
00089 q->append(ROBOT_NAME, robot);
00090 if (!group.empty())
00091 q->append(CONSTRAINTS_GROUP_NAME, group);
00092 std::vector<ConstraintsWithMetadata> constr = constraints_collection_->queryList(q, true);
00093 return !constr.empty();
00094 }
00095
00096 void moveit_warehouse::ConstraintsStorage::getKnownConstraints(const std::string& regex,
00097 std::vector<std::string>& names,
00098 const std::string& robot, const std::string& group) const
00099 {
00100 getKnownConstraints(names, robot, group);
00101 filterNames(regex, names);
00102 }
00103
00104 void moveit_warehouse::ConstraintsStorage::getKnownConstraints(std::vector<std::string>& names,
00105 const std::string& robot, const std::string& group) const
00106 {
00107 names.clear();
00108 Query::Ptr q = constraints_collection_->createQuery();
00109 if (!robot.empty())
00110 q->append(ROBOT_NAME, robot);
00111 if (!group.empty())
00112 q->append(CONSTRAINTS_GROUP_NAME, group);
00113 std::vector<ConstraintsWithMetadata> constr = constraints_collection_->queryList(q, true, CONSTRAINTS_ID_NAME, true);
00114 for (std::size_t i = 0; i < constr.size(); ++i)
00115 if (constr[i]->lookupField(CONSTRAINTS_ID_NAME))
00116 names.push_back(constr[i]->lookupString(CONSTRAINTS_ID_NAME));
00117 }
00118
00119 bool moveit_warehouse::ConstraintsStorage::getConstraints(ConstraintsWithMetadata& msg_m, const std::string& name,
00120 const std::string& robot, const std::string& group) const
00121 {
00122 Query::Ptr q = constraints_collection_->createQuery();
00123 q->append(CONSTRAINTS_ID_NAME, name);
00124 if (!robot.empty())
00125 q->append(ROBOT_NAME, robot);
00126 if (!group.empty())
00127 q->append(CONSTRAINTS_GROUP_NAME, group);
00128 std::vector<ConstraintsWithMetadata> constr = constraints_collection_->queryList(q, false);
00129 if (constr.empty())
00130 return false;
00131 else
00132 {
00133 msg_m = constr.back();
00134
00135 const_cast<moveit_msgs::Constraints*>(static_cast<const moveit_msgs::Constraints*>(msg_m.get()))->name = name;
00136 return true;
00137 }
00138 }
00139
00140 void moveit_warehouse::ConstraintsStorage::renameConstraints(const std::string& old_name, const std::string& new_name,
00141 const std::string& robot, const std::string& group)
00142 {
00143 Query::Ptr q = constraints_collection_->createQuery();
00144 q->append(CONSTRAINTS_ID_NAME, old_name);
00145 if (!robot.empty())
00146 q->append(ROBOT_NAME, robot);
00147 if (!group.empty())
00148 q->append(CONSTRAINTS_GROUP_NAME, group);
00149 Metadata::Ptr m = constraints_collection_->createMetadata();
00150 m->append(CONSTRAINTS_ID_NAME, new_name);
00151 constraints_collection_->modifyMetadata(q, m);
00152 ROS_DEBUG("Renamed constraints from '%s' to '%s'", old_name.c_str(), new_name.c_str());
00153 }
00154
00155 void moveit_warehouse::ConstraintsStorage::removeConstraints(const std::string& name, const std::string& robot,
00156 const std::string& group)
00157 {
00158 Query::Ptr q = constraints_collection_->createQuery();
00159 q->append(CONSTRAINTS_ID_NAME, name);
00160 if (!robot.empty())
00161 q->append(ROBOT_NAME, robot);
00162 if (!group.empty())
00163 q->append(CONSTRAINTS_GROUP_NAME, group);
00164 unsigned int rem = constraints_collection_->removeMessages(q);
00165 ROS_DEBUG("Removed %u Constraints messages (named '%s')", rem, name.c_str());
00166 }