#include <constraints_storage.h>
Public Member Functions | |
void | addConstraints (const moveit_msgs::Constraints &msg, const std::string &robot="", const std::string &group="") |
ConstraintsStorage (warehouse_ros::DatabaseConnection::Ptr conn) | |
bool | getConstraints (ConstraintsWithMetadata &msg_m, const std::string &name, const std::string &robot="", const std::string &group="") const |
Get the constraints named name. Return false on failure. | |
void | getKnownConstraints (std::vector< std::string > &names, const std::string &robot="", const std::string &group="") const |
void | getKnownConstraints (const std::string ®ex, std::vector< std::string > &names, const std::string &robot="", const std::string &group="") const |
bool | hasConstraints (const std::string &name, const std::string &robot="", const std::string &group="") const |
void | removeConstraints (const std::string &name, const std::string &robot="", const std::string &group="") |
void | renameConstraints (const std::string &old_name, const std::string &new_name, const std::string &robot="", const std::string &group="") |
void | reset () |
Static Public Attributes | |
static const std::string | CONSTRAINTS_GROUP_NAME = "group_id" |
static const std::string | CONSTRAINTS_ID_NAME = "constraints_id" |
static const std::string | DATABASE_NAME = "moveit_constraints" |
static const std::string | ROBOT_NAME = "robot_id" |
Private Member Functions | |
void | createCollections () |
Private Attributes | |
ConstraintsCollection | constraints_collection_ |
Definition at line 51 of file constraints_storage.h.
moveit_warehouse::ConstraintsStorage::ConstraintsStorage | ( | warehouse_ros::DatabaseConnection::Ptr | conn | ) |
Definition at line 48 of file constraints_storage.cpp.
void moveit_warehouse::ConstraintsStorage::addConstraints | ( | const moveit_msgs::Constraints & | msg, |
const std::string & | robot = "" , |
||
const std::string & | group = "" |
||
) |
Definition at line 66 of file constraints_storage.cpp.
void moveit_warehouse::ConstraintsStorage::createCollections | ( | ) | [private] |
Definition at line 54 of file constraints_storage.cpp.
bool moveit_warehouse::ConstraintsStorage::getConstraints | ( | ConstraintsWithMetadata & | msg_m, |
const std::string & | name, | ||
const std::string & | robot = "" , |
||
const std::string & | group = "" |
||
) | const |
Get the constraints named name. Return false on failure.
Definition at line 119 of file constraints_storage.cpp.
void moveit_warehouse::ConstraintsStorage::getKnownConstraints | ( | std::vector< std::string > & | names, |
const std::string & | robot = "" , |
||
const std::string & | group = "" |
||
) | const |
Definition at line 104 of file constraints_storage.cpp.
void moveit_warehouse::ConstraintsStorage::getKnownConstraints | ( | const std::string & | regex, |
std::vector< std::string > & | names, | ||
const std::string & | robot = "" , |
||
const std::string & | group = "" |
||
) | const |
Definition at line 96 of file constraints_storage.cpp.
bool moveit_warehouse::ConstraintsStorage::hasConstraints | ( | const std::string & | name, |
const std::string & | robot = "" , |
||
const std::string & | group = "" |
||
) | const |
Definition at line 83 of file constraints_storage.cpp.
void moveit_warehouse::ConstraintsStorage::removeConstraints | ( | const std::string & | name, |
const std::string & | robot = "" , |
||
const std::string & | group = "" |
||
) |
Definition at line 155 of file constraints_storage.cpp.
void moveit_warehouse::ConstraintsStorage::renameConstraints | ( | const std::string & | old_name, |
const std::string & | new_name, | ||
const std::string & | robot = "" , |
||
const std::string & | group = "" |
||
) |
Definition at line 140 of file constraints_storage.cpp.
Definition at line 59 of file constraints_storage.cpp.
Definition at line 84 of file constraints_storage.h.
const std::string moveit_warehouse::ConstraintsStorage::CONSTRAINTS_GROUP_NAME = "group_id" [static] |
Definition at line 57 of file constraints_storage.h.
const std::string moveit_warehouse::ConstraintsStorage::CONSTRAINTS_ID_NAME = "constraints_id" [static] |
Definition at line 56 of file constraints_storage.h.
const std::string moveit_warehouse::ConstraintsStorage::DATABASE_NAME = "moveit_constraints" [static] |
Definition at line 54 of file constraints_storage.h.
const std::string moveit_warehouse::ConstraintsStorage::ROBOT_NAME = "robot_id" [static] |
Definition at line 58 of file constraints_storage.h.