moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Static Public Attributes | List of all members
moveit_warehouse::TrajectoryConstraintsStorage Class Reference

#include <trajectory_constraints_storage.h>

Inheritance diagram for moveit_warehouse::TrajectoryConstraintsStorage:
Inheritance graph
[legend]
Collaboration diagram for moveit_warehouse::TrajectoryConstraintsStorage:
Collaboration graph
[legend]

Public Member Functions

 TrajectoryConstraintsStorage (warehouse_ros::DatabaseConnection::Ptr conn)
 
void addTrajectoryConstraints (const moveit_msgs::msg::TrajectoryConstraints &msg, const std::string &name, const std::string &robot="", const std::string &group="")
 
bool hasTrajectoryConstraints (const std::string &name, const std::string &robot="", const std::string &group="") const
 
void getKnownTrajectoryConstraints (std::vector< std::string > &names, const std::string &robot="", const std::string &group="") const
 
void getKnownTrajectoryConstraints (const std::string &regex, std::vector< std::string > &names, const std::string &robot="", const std::string &group="") const
 
bool getTrajectoryConstraints (TrajectoryConstraintsWithMetadata &msg_m, const std::string &name, const std::string &robot="", const std::string &group="") const
 Get the constraints named name. Return false on failure. More...
 
void renameTrajectoryConstraints (const std::string &old_name, const std::string &new_name, const std::string &robot="", const std::string &group="")
 
void removeTrajectoryConstraints (const std::string &name, const std::string &robot="", const std::string &group="")
 
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_trajectory_constraints"
 
static const std::string CONSTRAINTS_ID_NAME = "constraints_id"
 
static const std::string CONSTRAINTS_GROUP_NAME = "group_id"
 
static const std::string ROBOT_NAME = "robot_id"
 

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 51 of file trajectory_constraints_storage.h.

Constructor & Destructor Documentation

◆ TrajectoryConstraintsStorage()

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

Definition at line 52 of file trajectory_constraints_storage.cpp.

Member Function Documentation

◆ addTrajectoryConstraints()

void moveit_warehouse::TrajectoryConstraintsStorage::addTrajectoryConstraints ( const moveit_msgs::msg::TrajectoryConstraints &  msg,
const std::string &  name,
const std::string &  robot = "",
const std::string &  group = "" 
)

Definition at line 71 of file trajectory_constraints_storage.cpp.

◆ getKnownTrajectoryConstraints() [1/2]

void moveit_warehouse::TrajectoryConstraintsStorage::getKnownTrajectoryConstraints ( const std::string &  regex,
std::vector< std::string > &  names,
const std::string &  robot = "",
const std::string &  group = "" 
) const

Definition at line 103 of file trajectory_constraints_storage.cpp.

◆ getKnownTrajectoryConstraints() [2/2]

void moveit_warehouse::TrajectoryConstraintsStorage::getKnownTrajectoryConstraints ( std::vector< std::string > &  names,
const std::string &  robot = "",
const std::string &  group = "" 
) const

Definition at line 112 of file trajectory_constraints_storage.cpp.

Here is the caller graph for this function:

◆ getTrajectoryConstraints()

bool moveit_warehouse::TrajectoryConstraintsStorage::getTrajectoryConstraints ( TrajectoryConstraintsWithMetadata msg_m,
const std::string &  name,
const std::string &  robot = "",
const std::string &  group = "" 
) const

Get the constraints named name. Return false on failure.

Definition at line 129 of file trajectory_constraints_storage.cpp.

Here is the caller graph for this function:

◆ hasTrajectoryConstraints()

bool moveit_warehouse::TrajectoryConstraintsStorage::hasTrajectoryConstraints ( const std::string &  name,
const std::string &  robot = "",
const std::string &  group = "" 
) const

Definition at line 89 of file trajectory_constraints_storage.cpp.

◆ removeTrajectoryConstraints()

void moveit_warehouse::TrajectoryConstraintsStorage::removeTrajectoryConstraints ( const std::string &  name,
const std::string &  robot = "",
const std::string &  group = "" 
)

Definition at line 167 of file trajectory_constraints_storage.cpp.

◆ renameTrajectoryConstraints()

void moveit_warehouse::TrajectoryConstraintsStorage::renameTrajectoryConstraints ( const std::string &  old_name,
const std::string &  new_name,
const std::string &  robot = "",
const std::string &  group = "" 
)

Definition at line 150 of file trajectory_constraints_storage.cpp.

◆ reset()

void moveit_warehouse::TrajectoryConstraintsStorage::reset ( )

Definition at line 64 of file trajectory_constraints_storage.cpp.

Member Data Documentation

◆ CONSTRAINTS_GROUP_NAME

const std::string moveit_warehouse::TrajectoryConstraintsStorage::CONSTRAINTS_GROUP_NAME = "group_id"
static

Definition at line 57 of file trajectory_constraints_storage.h.

◆ CONSTRAINTS_ID_NAME

const std::string moveit_warehouse::TrajectoryConstraintsStorage::CONSTRAINTS_ID_NAME = "constraints_id"
static

Definition at line 56 of file trajectory_constraints_storage.h.

◆ DATABASE_NAME

const std::string moveit_warehouse::TrajectoryConstraintsStorage::DATABASE_NAME = "moveit_trajectory_constraints"
static

Definition at line 54 of file trajectory_constraints_storage.h.

◆ ROBOT_NAME

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

Definition at line 58 of file trajectory_constraints_storage.h.


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