40#include <moveit_msgs/msg/planning_scene_world.hpp>
41#include <rclcpp/logger.hpp>
71 void createCollections();
74 rclcpp::Logger logger_;
This class provides the mechanism to connect to a database and reads needed ROS parameters when appro...
void getKnownPlanningSceneWorlds(std::vector< std::string > &names) const
bool hasPlanningSceneWorld(const std::string &name) const
void renamePlanningSceneWorld(const std::string &old_name, const std::string &new_name)
bool getPlanningSceneWorld(PlanningSceneWorldWithMetadata &msg_m, const std::string &name) const
Get the constraints named name. Return false on failure.
void removePlanningSceneWorld(const std::string &name)
static const std::string DATABASE_NAME
static const std::string PLANNING_SCENE_WORLD_ID_NAME
void addPlanningSceneWorld(const moveit_msgs::msg::PlanningSceneWorld &msg, const std::string &name)
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::PlanningSceneWorld >::ConstPtr PlanningSceneWorldWithMetadata
warehouse_ros::MessageCollection< moveit_msgs::msg::PlanningSceneWorld >::Ptr PlanningSceneWorldCollection