47using warehouse_ros::Metadata;
48using warehouse_ros::Query;
56void moveit_warehouse::RobotStateStorage::createCollections()
58 state_collection_ = conn_->openCollectionPtr<moveit_msgs::msg::RobotState>(DATABASE_NAME,
"robot_states");
63 state_collection_.reset();
64 conn_->dropDatabase(DATABASE_NAME);
69 const std::string& name,
const std::string& robot)
72 if (hasRobotState(name, robot))
74 removeRobotState(name, robot);
77 Metadata::Ptr metadata = state_collection_->createMetadata();
78 metadata->append(STATE_NAME, name);
80 state_collection_->insert(msg, metadata);
81 RCLCPP_DEBUG(logger_,
"%s robot state '%s'", replace ?
"Replaced" :
"Added", name.c_str());
86 Query::Ptr q = state_collection_->createQuery();
87 q->append(STATE_NAME, name);
90 std::vector<RobotStateWithMetadata> constr = state_collection_->queryList(q,
true);
91 return !constr.empty();
95 const std::string& robot)
const
97 getKnownRobotStates(names, robot);
98 filterNames(regex, names);
102 const std::string& robot)
const
105 Query::Ptr q = state_collection_->createQuery();
108 std::vector<RobotStateWithMetadata> constr = state_collection_->queryList(q,
true, STATE_NAME,
true);
111 if (state->lookupField(STATE_NAME))
112 names.push_back(state->lookupString(STATE_NAME));
117 const std::string& robot)
const
119 Query::Ptr q = state_collection_->createQuery();
120 q->append(STATE_NAME, name);
123 std::vector<RobotStateWithMetadata> constr = state_collection_->queryList(q,
false);
130 msg_m = constr.front();
136 const std::string& robot)
138 Query::Ptr q = state_collection_->createQuery();
139 q->append(STATE_NAME, old_name);
142 Metadata::Ptr m = state_collection_->createMetadata();
143 m->append(STATE_NAME, new_name);
144 state_collection_->modifyMetadata(q, m);
145 RCLCPP_DEBUG(logger_,
"Renamed robot state from '%s' to '%s'", old_name.c_str(), new_name.c_str());
150 Query::Ptr q = state_collection_->createQuery();
151 q->append(STATE_NAME, name);
154 unsigned int rem = state_collection_->removeMessages(q);
155 RCLCPP_DEBUG(logger_,
"Removed %u RobotState messages (named '%s')", rem, name.c_str());
This class provides the mechanism to connect to a database and reads needed ROS parameters when appro...
void renameRobotState(const std::string &old_name, const std::string &new_name, const std::string &robot="")
bool hasRobotState(const std::string &name, const std::string &robot="") const
static const std::string DATABASE_NAME
void getKnownRobotStates(std::vector< std::string > &names, const std::string &robot="") const
bool getRobotState(RobotStateWithMetadata &msg_m, const std::string &name, const std::string &robot="") const
Get the constraints named name. Return false on failure.
void removeRobotState(const std::string &name, const std::string &robot="")
static const std::string STATE_NAME
RobotStateStorage(warehouse_ros::DatabaseConnection::Ptr conn)
void addRobotState(const moveit_msgs::msg::RobotState &msg, const std::string &name, const std::string &robot="")
static const std::string ROBOT_NAME
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotState >::ConstPtr RobotStateWithMetadata
Main namespace for MoveIt.
const std::string ROBOT_NAME