37 #ifndef MOVEIT_MOVEIT_WAREHOUSE_STATE_STORAGE_ 38 #define MOVEIT_MOVEIT_WAREHOUSE_STATE_STORAGE_ 42 #include <moveit_msgs/RobotState.h> 61 void addRobotState(
const moveit_msgs::RobotState& msg,
const std::string& name,
const std::string& robot =
"");
62 bool hasRobotState(
const std::string& name,
const std::string& robot =
"")
const;
63 void getKnownRobotStates(std::vector<std::string>& names,
const std::string& robot =
"")
const;
65 const std::string& robot =
"")
const;
68 bool getRobotState(RobotStateWithMetadata& msg_m,
const std::string& name,
const std::string& robot =
"")
const;
70 void renameRobotState(
const std::string& old_name,
const std::string& new_name,
const std::string& robot =
"");
72 void removeRobotState(
const std::string& name,
const std::string& robot =
"");
void addRobotState(const moveit_msgs::RobotState &msg, const std::string &name, const std::string &robot="")
void getKnownRobotStates(std::vector< std::string > &names, const std::string &robot="") const
RobotStateStorage(warehouse_ros::DatabaseConnection::Ptr conn)
warehouse_ros::MessageWithMetadata< moveit_msgs::RobotState >::ConstPtr RobotStateWithMetadata
This class provides the mechanism to connect to a database and reads needed ROS parameters when appro...
MOVEIT_CLASS_FORWARD(ConstraintsStorage)
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="")
warehouse_ros::MessageCollection< moveit_msgs::RobotState >::Ptr RobotStateCollection
static const std::string ROBOT_NAME