#include <state_storage.h>

Public Member Functions | |
| 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 |
| void | getKnownRobotStates (const std::string ®ex, std::vector< std::string > &names, const std::string &robot="") const |
| bool | getRobotState (RobotStateWithMetadata &msg_m, const std::string &name, const std::string &robot="") const |
| Get the constraints named name. Return false on failure. | |
| bool | hasRobotState (const std::string &name, const std::string &robot="") const |
| void | removeRobotState (const std::string &name, const std::string &robot="") |
| void | renameRobotState (const std::string &old_name, const std::string &new_name, const std::string &robot="") |
| void | reset () |
| RobotStateStorage (warehouse_ros::DatabaseConnection::Ptr conn) | |
Static Public Attributes | |
| static const std::string | DATABASE_NAME = "moveit_robot_states" |
| static const std::string | ROBOT_NAME = "robot_id" |
| static const std::string | STATE_NAME = "state_id" |
Private Member Functions | |
| void | createCollections () |
Private Attributes | |
| RobotStateCollection | state_collection_ |
Definition at line 51 of file state_storage.h.
| moveit_warehouse::RobotStateStorage::RobotStateStorage | ( | warehouse_ros::DatabaseConnection::Ptr | conn | ) |
Definition at line 47 of file state_storage.cpp.
| void moveit_warehouse::RobotStateStorage::addRobotState | ( | const moveit_msgs::RobotState & | msg, |
| const std::string & | name, | ||
| const std::string & | robot = "" |
||
| ) |
Definition at line 65 of file state_storage.cpp.
| void moveit_warehouse::RobotStateStorage::createCollections | ( | ) | [private] |
Definition at line 53 of file state_storage.cpp.
| void moveit_warehouse::RobotStateStorage::getKnownRobotStates | ( | std::vector< std::string > & | names, |
| const std::string & | robot = "" |
||
| ) | const |
Definition at line 98 of file state_storage.cpp.
| void moveit_warehouse::RobotStateStorage::getKnownRobotStates | ( | const std::string & | regex, |
| std::vector< std::string > & | names, | ||
| const std::string & | robot = "" |
||
| ) | const |
Definition at line 91 of file state_storage.cpp.
| bool moveit_warehouse::RobotStateStorage::getRobotState | ( | RobotStateWithMetadata & | msg_m, |
| const std::string & | name, | ||
| const std::string & | robot = "" |
||
| ) | const |
Get the constraints named name. Return false on failure.
Definition at line 111 of file state_storage.cpp.
| bool moveit_warehouse::RobotStateStorage::hasRobotState | ( | const std::string & | name, |
| const std::string & | robot = "" |
||
| ) | const |
Definition at line 81 of file state_storage.cpp.
| void moveit_warehouse::RobotStateStorage::removeRobotState | ( | const std::string & | name, |
| const std::string & | robot = "" |
||
| ) |
Definition at line 141 of file state_storage.cpp.
| void moveit_warehouse::RobotStateStorage::renameRobotState | ( | const std::string & | old_name, |
| const std::string & | new_name, | ||
| const std::string & | robot = "" |
||
| ) |
Definition at line 128 of file state_storage.cpp.
Definition at line 58 of file state_storage.cpp.
const std::string moveit_warehouse::RobotStateStorage::DATABASE_NAME = "moveit_robot_states" [static] |
Definition at line 54 of file state_storage.h.
const std::string moveit_warehouse::RobotStateStorage::ROBOT_NAME = "robot_id" [static] |
Definition at line 57 of file state_storage.h.
Definition at line 79 of file state_storage.h.
const std::string moveit_warehouse::RobotStateStorage::STATE_NAME = "state_id" [static] |
Definition at line 56 of file state_storage.h.