#include <state_storage.h>
|
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. More...
|
|
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) |
|
| MoveItMessageStorage (warehouse_ros::DatabaseConnection::Ptr conn) |
| Takes a warehouse_ros DatabaseConnection. The DatabaseConnection is expected to have already been initialized. More...
|
|
virtual | ~MoveItMessageStorage () |
|
Definition at line 51 of file state_storage.h.
void moveit_warehouse::RobotStateStorage::addRobotState |
( |
const moveit_msgs::RobotState & |
msg, |
|
|
const std::string & |
name, |
|
|
const std::string & |
robot = "" |
|
) |
| |
void moveit_warehouse::RobotStateStorage::createCollections |
( |
| ) |
|
|
private |
void moveit_warehouse::RobotStateStorage::getKnownRobotStates |
( |
std::vector< std::string > & |
names, |
|
|
const std::string & |
robot = "" |
|
) |
| const |
void moveit_warehouse::RobotStateStorage::getKnownRobotStates |
( |
const std::string & |
regex, |
|
|
std::vector< std::string > & |
names, |
|
|
const std::string & |
robot = "" |
|
) |
| const |
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 |
void moveit_warehouse::RobotStateStorage::removeRobotState |
( |
const std::string & |
name, |
|
|
const std::string & |
robot = "" |
|
) |
| |
void moveit_warehouse::RobotStateStorage::renameRobotState |
( |
const std::string & |
old_name, |
|
|
const std::string & |
new_name, |
|
|
const std::string & |
robot = "" |
|
) |
| |
void moveit_warehouse::RobotStateStorage::reset |
( |
| ) |
|
const std::string moveit_warehouse::RobotStateStorage::DATABASE_NAME = "moveit_robot_states" |
|
static |
const std::string moveit_warehouse::RobotStateStorage::ROBOT_NAME = "robot_id" |
|
static |
const std::string moveit_warehouse::RobotStateStorage::STATE_NAME = "state_id" |
|
static |
The documentation for this class was generated from the following files: