46 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit.ros.warehouse.state_storage");
48 using warehouse_ros::Metadata;
49 using warehouse_ros::Query;
57 void moveit_warehouse::RobotStateStorage::createCollections()
59 state_collection_ = conn_->openCollectionPtr<moveit_msgs::msg::RobotState>(DATABASE_NAME,
"robot_states");
64 state_collection_.reset();
65 conn_->dropDatabase(DATABASE_NAME);
70 const std::string&
name,
const std::string&
robot)
78 Metadata::Ptr metadata = state_collection_->createMetadata();
79 metadata->append(STATE_NAME,
name);
80 metadata->append(ROBOT_NAME,
robot);
81 state_collection_->insert(msg, metadata);
82 RCLCPP_DEBUG(LOGGER,
"%s robot state '%s'", replace ?
"Replaced" :
"Added",
name.c_str());
87 Query::Ptr q = state_collection_->createQuery();
88 q->append(STATE_NAME,
name);
90 q->append(ROBOT_NAME,
robot);
91 std::vector<RobotStateWithMetadata> constr = state_collection_->queryList(q,
true);
92 return !constr.empty();
96 const std::string&
robot)
const
98 getKnownRobotStates(names,
robot);
99 filterNames(regex, names);
103 const std::string&
robot)
const
106 Query::Ptr q = state_collection_->createQuery();
108 q->append(ROBOT_NAME,
robot);
109 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));
116 const std::string&
robot)
const
118 Query::Ptr q = state_collection_->createQuery();
119 q->append(STATE_NAME,
name);
121 q->append(ROBOT_NAME,
robot);
122 std::vector<RobotStateWithMetadata> constr = state_collection_->queryList(q,
false);
127 msg_m = constr.front();
133 const std::string&
robot)
135 Query::Ptr q = state_collection_->createQuery();
136 q->append(STATE_NAME, old_name);
138 q->append(ROBOT_NAME,
robot);
139 Metadata::Ptr m = state_collection_->createMetadata();
140 m->append(STATE_NAME, new_name);
141 state_collection_->modifyMetadata(q, m);
142 RCLCPP_DEBUG(LOGGER,
"Renamed robot state from '%s' to '%s'", old_name.c_str(), new_name.c_str());
147 Query::Ptr q = state_collection_->createQuery();
148 q->append(STATE_NAME,
name);
150 q->append(ROBOT_NAME,
robot);
151 unsigned int rem = state_collection_->removeMessages(q);
152 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
const rclcpp::Logger LOGGER