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