Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes | List of all members
moveit_warehouse::RobotStateStorage Class Reference

#include <state_storage.h>

Inheritance diagram for moveit_warehouse::RobotStateStorage:
Inheritance graph
[legend]

Public Member Functions

void addRobotState (const moveit_msgs::RobotState &msg, const std::string &name, const std::string &robot="")
 
void getKnownRobotStates (const std::string &regex, std::vector< std::string > &names, const std::string &robot="") const
 
void getKnownRobotStates (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)
 
- 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_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_
 

Additional Inherited Members

- Protected Member Functions inherited from moveit_warehouse::MoveItMessageStorage
void filterNames (const std::string &regex, 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_
 

Detailed Description

Definition at line 82 of file state_storage.h.

Constructor & Destructor Documentation

◆ RobotStateStorage()

moveit_warehouse::RobotStateStorage::RobotStateStorage ( warehouse_ros::DatabaseConnection::Ptr  conn)

Definition at line 49 of file state_storage.cpp.

Member Function Documentation

◆ addRobotState()

void moveit_warehouse::RobotStateStorage::addRobotState ( const moveit_msgs::RobotState &  msg,
const std::string &  name,
const std::string &  robot = "" 
)

Definition at line 67 of file state_storage.cpp.

◆ createCollections()

void moveit_warehouse::RobotStateStorage::createCollections ( )
private

Definition at line 55 of file state_storage.cpp.

◆ getKnownRobotStates() [1/2]

void moveit_warehouse::RobotStateStorage::getKnownRobotStates ( const std::string &  regex,
std::vector< std::string > &  names,
const std::string &  robot = "" 
) const

Definition at line 93 of file state_storage.cpp.

◆ getKnownRobotStates() [2/2]

void moveit_warehouse::RobotStateStorage::getKnownRobotStates ( std::vector< std::string > &  names,
const std::string &  robot = "" 
) const

Definition at line 100 of file state_storage.cpp.

◆ 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 113 of file state_storage.cpp.

◆ hasRobotState()

bool moveit_warehouse::RobotStateStorage::hasRobotState ( const std::string &  name,
const std::string &  robot = "" 
) const

Definition at line 83 of file state_storage.cpp.

◆ removeRobotState()

void moveit_warehouse::RobotStateStorage::removeRobotState ( const std::string &  name,
const std::string &  robot = "" 
)

Definition at line 143 of file state_storage.cpp.

◆ renameRobotState()

void moveit_warehouse::RobotStateStorage::renameRobotState ( const std::string &  old_name,
const std::string &  new_name,
const std::string &  robot = "" 
)

Definition at line 130 of file state_storage.cpp.

◆ reset()

void moveit_warehouse::RobotStateStorage::reset ( )

Definition at line 60 of file state_storage.cpp.

Member Data Documentation

◆ DATABASE_NAME

const std::string moveit_warehouse::RobotStateStorage::DATABASE_NAME = "moveit_robot_states"
static

Definition at line 85 of file state_storage.h.

◆ ROBOT_NAME

const std::string moveit_warehouse::RobotStateStorage::ROBOT_NAME = "robot_id"
static

Definition at line 88 of file state_storage.h.

◆ state_collection_

RobotStateCollection moveit_warehouse::RobotStateStorage::state_collection_
private

Definition at line 110 of file state_storage.h.

◆ STATE_NAME

const std::string moveit_warehouse::RobotStateStorage::STATE_NAME = "state_id"
static

Definition at line 87 of file state_storage.h.


The documentation for this class was generated from the following files:


warehouse
Author(s): Ioan Sucan
autogenerated on Thu Apr 18 2024 02:25:06