58 constraints_collection_ = conn_->openCollectionPtr<moveit_msgs::Constraints>(DATABASE_NAME,
"constraints");
63 constraints_collection_.reset();
64 conn_->dropDatabase(DATABASE_NAME);
69 const std::string& group)
72 if (hasConstraints(msg.name, robot, group))
74 removeConstraints(msg.name, robot, group);
77 Metadata::Ptr metadata = constraints_collection_->createMetadata();
78 metadata->append(CONSTRAINTS_ID_NAME, msg.name);
79 metadata->append(ROBOT_NAME, robot);
80 metadata->append(CONSTRAINTS_GROUP_NAME, group);
81 constraints_collection_->insert(msg, metadata);
82 ROS_DEBUG(
"%s constraints '%s'", replace ?
"Replaced" :
"Added", msg.name.c_str());
86 const std::string& group)
const
88 Query::Ptr q = constraints_collection_->createQuery();
89 q->append(CONSTRAINTS_ID_NAME,
name);
91 q->append(ROBOT_NAME, robot);
93 q->append(CONSTRAINTS_GROUP_NAME, group);
94 std::vector<ConstraintsWithMetadata> constr = constraints_collection_->queryList(q,
true);
95 return !constr.empty();
99 std::vector<std::string>& names,
100 const std::string& robot,
const std::string& group)
const
102 getKnownConstraints(names, robot, group);
103 filterNames(regex, names);
107 const std::string& robot,
const std::string& group)
const
110 Query::Ptr q = constraints_collection_->createQuery();
112 q->append(ROBOT_NAME, robot);
114 q->append(CONSTRAINTS_GROUP_NAME, group);
115 std::vector<ConstraintsWithMetadata> constr = constraints_collection_->queryList(q,
true, CONSTRAINTS_ID_NAME,
true);
117 if (it->lookupField(CONSTRAINTS_ID_NAME))
118 names.push_back(it->lookupString(CONSTRAINTS_ID_NAME));
122 const std::string& robot,
const std::string& group)
const
124 Query::Ptr q = constraints_collection_->createQuery();
125 q->append(CONSTRAINTS_ID_NAME,
name);
127 q->append(ROBOT_NAME, robot);
129 q->append(CONSTRAINTS_GROUP_NAME, group);
130 std::vector<ConstraintsWithMetadata> constr = constraints_collection_->queryList(q,
false);
135 msg_m = constr.back();
137 const_cast<moveit_msgs::Constraints*
>(
static_cast<const moveit_msgs::Constraints*
>(msg_m.get()))->name =
name;
143 const std::string& robot,
const std::string& group)
145 Query::Ptr q = constraints_collection_->createQuery();
146 q->append(CONSTRAINTS_ID_NAME, old_name);
148 q->append(ROBOT_NAME, robot);
150 q->append(CONSTRAINTS_GROUP_NAME, group);
151 Metadata::Ptr m = constraints_collection_->createMetadata();
152 m->append(CONSTRAINTS_ID_NAME, new_name);
153 constraints_collection_->modifyMetadata(q, m);
154 ROS_DEBUG(
"Renamed constraints from '%s' to '%s'", old_name.c_str(), new_name.c_str());
158 const std::string& group)
160 Query::Ptr q = constraints_collection_->createQuery();
161 q->append(CONSTRAINTS_ID_NAME,
name);
163 q->append(ROBOT_NAME, robot);
165 q->append(CONSTRAINTS_GROUP_NAME, group);
166 unsigned int rem = constraints_collection_->removeMessages(q);
167 ROS_DEBUG(
"Removed %u Constraints messages (named '%s')", rem,
name.c_str());