66 const std::string& robot)
78 ROS_DEBUG(
"%s robot state '%s'", replace ?
"Replaced" :
"Added", name.c_str());
87 std::vector<RobotStateWithMetadata> constr =
state_collection_->queryList(q,
true);
88 return !constr.empty();
92 const std::string& robot)
const 99 const std::string& robot)
const 106 for (std::size_t i = 0; i < constr.size(); ++i)
108 names.push_back(constr[i]->lookupString(
STATE_NAME));
112 const std::string& robot)
const 118 std::vector<RobotStateWithMetadata> constr =
state_collection_->queryList(q,
false);
123 msg_m = constr.front();
129 const std::string& robot)
138 ROS_DEBUG(
"Renamed robot state from '%s' to '%s'", old_name.c_str(), new_name.c_str());
148 ROS_DEBUG(
"Removed %u RobotState messages (named '%s')", rem, name.c_str());
void addRobotState(const moveit_msgs::RobotState &msg, const std::string &name, const std::string &robot="")
void filterNames(const std::string ®ex, std::vector< std::string > &names) const
Keep only the names that match regex.
void getKnownRobotStates(std::vector< std::string > &names, const std::string &robot="") const
RobotStateStorage(warehouse_ros::DatabaseConnection::Ptr conn)
warehouse_ros::DatabaseConnection::Ptr conn_
This class provides the mechanism to connect to a database and reads needed ROS parameters when appro...
bool hasRobotState(const std::string &name, const std::string &robot="") const
static const std::string DATABASE_NAME
static const std::string STATE_NAME
bool getRobotState(RobotStateWithMetadata &msg_m, const std::string &name, const std::string &robot="") const
Get the constraints named name. Return false on failure.
RobotStateCollection state_collection_
void renameRobotState(const std::string &old_name, const std::string &new_name, const std::string &robot="")
void removeRobotState(const std::string &name, const std::string &robot="")
static const std::string ROBOT_NAME