57 state_collection_ = conn_->openCollectionPtr<moveit_msgs::RobotState>(DATABASE_NAME,
"robot_states");
62 state_collection_.reset();
63 conn_->dropDatabase(DATABASE_NAME);
68 const std::string& robot)
71 if (hasRobotState(
name, robot))
73 removeRobotState(
name, robot);
76 Metadata::Ptr metadata = state_collection_->createMetadata();
77 metadata->append(STATE_NAME,
name);
78 metadata->append(ROBOT_NAME, robot);
79 state_collection_->insert(msg, metadata);
80 ROS_DEBUG(
"%s robot state '%s'", replace ?
"Replaced" :
"Added",
name.c_str());
85 Query::Ptr q = state_collection_->createQuery();
86 q->append(STATE_NAME,
name);
88 q->append(ROBOT_NAME, robot);
89 std::vector<RobotStateWithMetadata> constr = state_collection_->queryList(q,
true);
90 return !constr.empty();
94 const std::string& robot)
const
96 getKnownRobotStates(names, robot);
97 filterNames(regex, names);
101 const std::string& robot)
const
104 Query::Ptr q = state_collection_->createQuery();
106 q->append(ROBOT_NAME, robot);
107 std::vector<RobotStateWithMetadata> constr = state_collection_->queryList(q,
true, STATE_NAME,
true);
109 if (state->lookupField(STATE_NAME))
110 names.push_back(state->lookupString(STATE_NAME));
114 const std::string& robot)
const
116 Query::Ptr q = state_collection_->createQuery();
117 q->append(STATE_NAME,
name);
119 q->append(ROBOT_NAME, robot);
120 std::vector<RobotStateWithMetadata> constr = state_collection_->queryList(q,
false);
125 msg_m = constr.front();
131 const std::string& robot)
133 Query::Ptr q = state_collection_->createQuery();
134 q->append(STATE_NAME, old_name);
136 q->append(ROBOT_NAME, robot);
137 Metadata::Ptr m = state_collection_->createMetadata();
138 m->append(STATE_NAME, new_name);
139 state_collection_->modifyMetadata(q, m);
140 ROS_DEBUG(
"Renamed robot state from '%s' to '%s'", old_name.c_str(), new_name.c_str());
145 Query::Ptr q = state_collection_->createQuery();
146 q->append(STATE_NAME,
name);
148 q->append(ROBOT_NAME, robot);
149 unsigned int rem = state_collection_->removeMessages(q);
150 ROS_DEBUG(
"Removed %u RobotState messages (named '%s')", rem,
name.c_str());