41#include <moveit_msgs/msg/robot_state.hpp>
42#include <rclcpp/logger.hpp>
44#include <moveit_warehouse_export.h>
63 void addRobotState(
const moveit_msgs::msg::RobotState& msg,
const std::string& name,
const std::string& robot =
"");
64 bool hasRobotState(
const std::string& name,
const std::string& robot =
"")
const;
65 void getKnownRobotStates(std::vector<std::string>& names,
const std::string& robot =
"")
const;
66 void getKnownRobotStates(
const std::string& regex, std::vector<std::string>& names,
67 const std::string& robot =
"")
const;
70 bool getRobotState(
RobotStateWithMetadata& msg_m,
const std::string& name,
const std::string& robot =
"")
const;
72 void renameRobotState(
const std::string& old_name,
const std::string& new_name,
const std::string& robot =
"");
74 void removeRobotState(
const std::string& name,
const std::string& robot =
"");
79 void createCollections();
82 rclcpp::Logger logger_;
#define MOVEIT_CLASS_FORWARD(C)
This class provides the mechanism to connect to a database and reads needed ROS parameters when appro...
static const std::string DATABASE_NAME
static const std::string STATE_NAME
static const std::string ROBOT_NAME
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotState >::ConstPtr RobotStateWithMetadata
warehouse_ros::MessageCollection< moveit_msgs::msg::RobotState >::Ptr RobotStateCollection