41 #include <moveit_msgs/msg/constraints.hpp>
43 #include <moveit_warehouse_export.h>
63 void addConstraints(
const moveit_msgs::msg::Constraints& msg,
const std::string&
robot =
"",
64 const std::string&
group =
"");
65 bool hasConstraints(
const std::string&
name,
const std::string&
robot =
"",
const std::string&
group =
"")
const;
66 void getKnownConstraints(std::vector<std::string>& names,
const std::string&
robot =
"",
67 const std::string&
group =
"")
const;
68 void getKnownConstraints(
const std::string& regex, std::vector<std::string>& names,
const std::string&
robot =
"",
69 const std::string&
group =
"")
const;
73 const std::string&
group =
"")
const;
75 void renameConstraints(
const std::string& old_name,
const std::string& new_name,
const std::string&
robot =
"",
76 const std::string&
group =
"");
78 void removeConstraints(
const std::string&
name,
const std::string&
robot =
"",
const std::string&
group =
"");
83 void createCollections();
static const std::string DATABASE_NAME
static const std::string CONSTRAINTS_ID_NAME
static const std::string CONSTRAINTS_GROUP_NAME
static const std::string ROBOT_NAME
This class provides the mechanism to connect to a database and reads needed ROS parameters when appro...
warehouse_ros::MessageCollection< moveit_msgs::msg::Constraints >::Ptr ConstraintsCollection
MOVEIT_CLASS_FORWARD(PlanningSceneStorage)
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::Constraints >::ConstPtr ConstraintsWithMetadata