#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 (const std::string &host="", const unsigned int port=0, double wait_seconds=5.0) | |
| Initialize the state storage to connect to a specified host and port for the MongoDB. If defaults are used for the parameters (empty host name, 0 port), the constructor looks for ROS params specifying which host/port to use. NodeHandle::searchParam() is used starting from ~ to look for warehouse_port and warehouse_host. If no values are found, the defaults are left to be the ones MongoDB uses. If wait_seconds is above 0, then a maximum number of seconds can elapse until connection is successful, or a runtime exception is thrown. | |
| 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 49 of file state_storage.h.
| moveit_warehouse::RobotStateStorage::RobotStateStorage | ( | const std::string & | host = "", | 
| const unsigned int | port = 0, | ||
| double | wait_seconds = 5.0 | ||
| ) | 
Initialize the state storage to connect to a specified host and port for the MongoDB. If defaults are used for the parameters (empty host name, 0 port), the constructor looks for ROS params specifying which host/port to use. NodeHandle::searchParam() is used starting from ~ to look for warehouse_port and warehouse_host. If no values are found, the defaults are left to be the ones MongoDB uses. If wait_seconds is above 0, then a maximum number of seconds can elapse until connection is successful, or a runtime exception is thrown.
Definition at line 44 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 63 of file state_storage.cpp.
| void moveit_warehouse::RobotStateStorage::createCollections | ( | ) |  [private] | 
Definition at line 51 of file state_storage.cpp.
| void moveit_warehouse::RobotStateStorage::getKnownRobotStates | ( | std::vector< std::string > & | names, | 
| const std::string & | robot = "" | ||
| ) | const | 
Definition at line 92 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 86 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 104 of file state_storage.cpp.
| bool moveit_warehouse::RobotStateStorage::hasRobotState | ( | const std::string & | name, | 
| const std::string & | robot = "" | ||
| ) | const | 
Definition at line 77 of file state_storage.cpp.
| void moveit_warehouse::RobotStateStorage::removeRobotState | ( | const std::string & | name, | 
| const std::string & | robot = "" | ||
| ) | 
Definition at line 129 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 119 of file state_storage.cpp.
Definition at line 56 of file state_storage.cpp.
| const std::string moveit_warehouse::RobotStateStorage::DATABASE_NAME = "moveit_robot_states"  [static] | 
Definition at line 53 of file state_storage.h.
| const std::string moveit_warehouse::RobotStateStorage::ROBOT_NAME = "robot_id"  [static] | 
Definition at line 56 of file state_storage.h.
Definition at line 83 of file state_storage.h.
| const std::string moveit_warehouse::RobotStateStorage::STATE_NAME = "state_id"  [static] | 
Definition at line 55 of file state_storage.h.