#include <planning_scene_world_storage.h>
Public Member Functions | |
void | addPlanningSceneWorld (const moveit_msgs::PlanningSceneWorld &msg, const std::string &name) |
void | getKnownPlanningSceneWorlds (std::vector< std::string > &names) const |
void | getKnownPlanningSceneWorlds (const std::string ®ex, std::vector< std::string > &names) const |
bool | getPlanningSceneWorld (PlanningSceneWorldWithMetadata &msg_m, const std::string &name) const |
Get the constraints named name. Return false on failure. More... | |
bool | hasPlanningSceneWorld (const std::string &name) const |
PlanningSceneWorldStorage (warehouse_ros::DatabaseConnection::Ptr conn) | |
void | removePlanningSceneWorld (const std::string &name) |
void | renamePlanningSceneWorld (const std::string &old_name, const std::string &new_name) |
void | reset () |
Public Member Functions inherited from moveit_warehouse::MoveItMessageStorage | |
MoveItMessageStorage (warehouse_ros::DatabaseConnection::Ptr conn) | |
Takes a warehouse_ros DatabaseConnection. The DatabaseConnection is expected to have already been initialized. More... | |
virtual | ~MoveItMessageStorage () |
Static Public Attributes | |
static const std::string | DATABASE_NAME = "moveit_planning_scene_worlds" |
static const std::string | PLANNING_SCENE_WORLD_ID_NAME = "world_id" |
Private Member Functions | |
void | createCollections () |
Private Attributes | |
PlanningSceneWorldCollection | planning_scene_world_collection_ |
Additional Inherited Members | |
Protected Member Functions inherited from moveit_warehouse::MoveItMessageStorage | |
void | filterNames (const std::string ®ex, std::vector< std::string > &names) const |
Keep only the names that match regex. More... | |
Protected Attributes inherited from moveit_warehouse::MoveItMessageStorage | |
warehouse_ros::DatabaseConnection::Ptr | conn_ |
Definition at line 48 of file planning_scene_world_storage.h.
moveit_warehouse::PlanningSceneWorldStorage::PlanningSceneWorldStorage | ( | warehouse_ros::DatabaseConnection::Ptr | conn | ) |
Definition at line 45 of file planning_scene_world_storage.cpp.
void moveit_warehouse::PlanningSceneWorldStorage::addPlanningSceneWorld | ( | const moveit_msgs::PlanningSceneWorld & | msg, |
const std::string & | name | ||
) |
Definition at line 64 of file planning_scene_world_storage.cpp.
|
private |
Definition at line 51 of file planning_scene_world_storage.cpp.
void moveit_warehouse::PlanningSceneWorldStorage::getKnownPlanningSceneWorlds | ( | std::vector< std::string > & | names | ) | const |
Definition at line 94 of file planning_scene_world_storage.cpp.
void moveit_warehouse::PlanningSceneWorldStorage::getKnownPlanningSceneWorlds | ( | const std::string & | regex, |
std::vector< std::string > & | names | ||
) | const |
Definition at line 87 of file planning_scene_world_storage.cpp.
bool moveit_warehouse::PlanningSceneWorldStorage::getPlanningSceneWorld | ( | PlanningSceneWorldWithMetadata & | msg_m, |
const std::string & | name | ||
) | const |
Get the constraints named name. Return false on failure.
Definition at line 105 of file planning_scene_world_storage.cpp.
bool moveit_warehouse::PlanningSceneWorldStorage::hasPlanningSceneWorld | ( | const std::string & | name | ) | const |
Definition at line 79 of file planning_scene_world_storage.cpp.
void moveit_warehouse::PlanningSceneWorldStorage::removePlanningSceneWorld | ( | const std::string & | name | ) |
Definition at line 131 of file planning_scene_world_storage.cpp.
void moveit_warehouse::PlanningSceneWorldStorage::renamePlanningSceneWorld | ( | const std::string & | old_name, |
const std::string & | new_name | ||
) |
Definition at line 120 of file planning_scene_world_storage.cpp.
void moveit_warehouse::PlanningSceneWorldStorage::reset | ( | ) |
Definition at line 57 of file planning_scene_world_storage.cpp.
|
static |
Definition at line 51 of file planning_scene_world_storage.h.
|
private |
Definition at line 73 of file planning_scene_world_storage.h.
|
static |
Definition at line 52 of file planning_scene_world_storage.h.