48using warehouse_ros::Metadata;
49using warehouse_ros::Query;
53 , logger_(
moveit::getLogger(
"moveit.ros.warehouse_trajectory_constraints_storage"))
58void moveit_warehouse::TrajectoryConstraintsStorage::createCollections()
60 constraints_collection_ =
61 conn_->openCollectionPtr<moveit_msgs::msg::TrajectoryConstraints>(DATABASE_NAME,
"trajectory_constraints");
66 constraints_collection_.reset();
67 conn_->dropDatabase(DATABASE_NAME);
72 const moveit_msgs::msg::TrajectoryConstraints& msg,
const std::string& name,
const std::string& robot,
73 const std::string& group)
76 if (hasTrajectoryConstraints(name, robot, group))
78 removeTrajectoryConstraints(name, robot, group);
81 Metadata::Ptr metadata = constraints_collection_->createMetadata();
82 metadata->append(CONSTRAINTS_ID_NAME, name);
84 metadata->append(CONSTRAINTS_GROUP_NAME, group);
85 constraints_collection_->insert(msg, metadata);
86 RCLCPP_DEBUG(logger_,
"%s constraints '%s'", replace ?
"Replaced" :
"Added", name.c_str());
90 const std::string& robot,
91 const std::string& group)
const
93 Query::Ptr q = constraints_collection_->createQuery();
94 q->append(CONSTRAINTS_ID_NAME, name);
98 q->append(CONSTRAINTS_GROUP_NAME, group);
99 std::vector<TrajectoryConstraintsWithMetadata> constr = constraints_collection_->queryList(q,
true);
100 return !constr.empty();
104 std::vector<std::string>& names,
105 const std::string& robot,
106 const std::string& group)
const
108 getKnownTrajectoryConstraints(names, robot, group);
109 filterNames(regex, names);
113 const std::string& robot,
114 const std::string& group)
const
117 Query::Ptr q = constraints_collection_->createQuery();
121 q->append(CONSTRAINTS_GROUP_NAME, group);
122 std::vector<TrajectoryConstraintsWithMetadata> constr =
123 constraints_collection_->queryList(q,
true, CONSTRAINTS_ID_NAME,
true);
126 if (traj_constraint->lookupField(CONSTRAINTS_ID_NAME))
127 names.push_back(traj_constraint->lookupString(CONSTRAINTS_ID_NAME));
132 const std::string& name,
133 const std::string& robot,
134 const std::string& group)
const
136 Query::Ptr q = constraints_collection_->createQuery();
137 q->append(CONSTRAINTS_ID_NAME, name);
141 q->append(CONSTRAINTS_GROUP_NAME, group);
142 std::vector<TrajectoryConstraintsWithMetadata> constr = constraints_collection_->queryList(q,
false);
149 msg_m = constr.back();
155 const std::string& new_name,
156 const std::string& robot,
157 const std::string& group)
159 Query::Ptr q = constraints_collection_->createQuery();
160 q->append(CONSTRAINTS_ID_NAME, old_name);
164 q->append(CONSTRAINTS_GROUP_NAME, group);
165 Metadata::Ptr m = constraints_collection_->createMetadata();
166 m->append(CONSTRAINTS_ID_NAME, new_name);
167 constraints_collection_->modifyMetadata(q, m);
168 RCLCPP_DEBUG(logger_,
"Renamed constraints from '%s' to '%s'", old_name.c_str(), new_name.c_str());
172 const std::string& robot,
173 const std::string& group)
175 Query::Ptr q = constraints_collection_->createQuery();
176 q->append(CONSTRAINTS_ID_NAME, name);
180 q->append(CONSTRAINTS_GROUP_NAME, group);
181 unsigned int rem = constraints_collection_->removeMessages(q);
182 RCLCPP_DEBUG(logger_,
"Removed %u TrajectoryConstraints messages (named '%s')", rem, name.c_str());
This class provides the mechanism to connect to a database and reads needed ROS parameters when appro...
TrajectoryConstraintsStorage(warehouse_ros::DatabaseConnection::Ptr conn)
static const std::string DATABASE_NAME
bool hasTrajectoryConstraints(const std::string &name, const std::string &robot="", const std::string &group="") const
void renameTrajectoryConstraints(const std::string &old_name, const std::string &new_name, const std::string &robot="", const std::string &group="")
void getKnownTrajectoryConstraints(std::vector< std::string > &names, const std::string &robot="", const std::string &group="") const
static const std::string CONSTRAINTS_ID_NAME
void removeTrajectoryConstraints(const std::string &name, const std::string &robot="", const std::string &group="")
static const std::string ROBOT_NAME
void addTrajectoryConstraints(const moveit_msgs::msg::TrajectoryConstraints &msg, const std::string &name, const std::string &robot="", const std::string &group="")
static const std::string CONSTRAINTS_GROUP_NAME
bool getTrajectoryConstraints(TrajectoryConstraintsWithMetadata &msg_m, const std::string &name, const std::string &robot="", const std::string &group="") const
Get the constraints named name. Return false on failure.
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::TrajectoryConstraints >::ConstPtr TrajectoryConstraintsWithMetadata
Main namespace for MoveIt.
const std::string ROBOT_NAME