#include <state_storage.h>
|
| RobotStateStorage (warehouse_ros::DatabaseConnection::Ptr conn) |
|
void | addRobotState (const moveit_msgs::msg::RobotState &msg, const std::string &name, const std::string &robot="") |
|
bool | hasRobotState (const std::string &name, const std::string &robot="") const |
|
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.
|
|
void | renameRobotState (const std::string &old_name, const std::string &new_name, const std::string &robot="") |
|
void | removeRobotState (const std::string &name, const std::string &robot="") |
|
void | reset () |
|
| MoveItMessageStorage (warehouse_ros::DatabaseConnection::Ptr conn) |
| Takes a warehouse_ros DatabaseConnection. The DatabaseConnection is expected to have already been initialized.
|
|
virtual | ~MoveItMessageStorage () |
|
|
void | filterNames (const std::string ®ex, std::vector< std::string > &names) const |
| Keep only the names that match regex.
|
|
warehouse_ros::DatabaseConnection::Ptr | conn_ |
|
Definition at line 53 of file state_storage.h.
◆ RobotStateStorage()
moveit_warehouse::RobotStateStorage::RobotStateStorage |
( |
warehouse_ros::DatabaseConnection::Ptr |
conn | ) |
|
◆ addRobotState()
void moveit_warehouse::RobotStateStorage::addRobotState |
( |
const moveit_msgs::msg::RobotState & |
msg, |
|
|
const std::string & |
name, |
|
|
const std::string & |
robot = "" |
|
) |
| |
◆ getKnownRobotStates() [1/2]
void moveit_warehouse::RobotStateStorage::getKnownRobotStates |
( |
const std::string & |
regex, |
|
|
std::vector< std::string > & |
names, |
|
|
const std::string & |
robot = "" |
|
) |
| const |
◆ getKnownRobotStates() [2/2]
void moveit_warehouse::RobotStateStorage::getKnownRobotStates |
( |
std::vector< std::string > & |
names, |
|
|
const std::string & |
robot = "" |
|
) |
| const |
◆ getRobotState()
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 116 of file state_storage.cpp.
◆ hasRobotState()
bool moveit_warehouse::RobotStateStorage::hasRobotState |
( |
const std::string & |
name, |
|
|
const std::string & |
robot = "" |
|
) |
| const |
◆ removeRobotState()
void moveit_warehouse::RobotStateStorage::removeRobotState |
( |
const std::string & |
name, |
|
|
const std::string & |
robot = "" |
|
) |
| |
◆ renameRobotState()
void moveit_warehouse::RobotStateStorage::renameRobotState |
( |
const std::string & |
old_name, |
|
|
const std::string & |
new_name, |
|
|
const std::string & |
robot = "" |
|
) |
| |
◆ reset()
void moveit_warehouse::RobotStateStorage::reset |
( |
| ) |
|
◆ DATABASE_NAME
const std::string moveit_warehouse::RobotStateStorage::DATABASE_NAME = "moveit_robot_states" |
|
static |
◆ ROBOT_NAME
const std::string moveit_warehouse::RobotStateStorage::ROBOT_NAME = "robot_id" |
|
static |
◆ STATE_NAME
const std::string moveit_warehouse::RobotStateStorage::STATE_NAME = "state_id" |
|
static |
The documentation for this class was generated from the following files: