#include <trajectory_constraints_storage.hpp>
|
| | 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 ®ex, 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.
|
| |
| 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 () |
| |
| | 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_ |
| |
◆ TrajectoryConstraintsStorage()
| moveit_warehouse::TrajectoryConstraintsStorage::TrajectoryConstraintsStorage |
( |
warehouse_ros::DatabaseConnection::Ptr |
conn | ) |
|
◆ addTrajectoryConstraints()
| void moveit_warehouse::TrajectoryConstraintsStorage::addTrajectoryConstraints |
( |
const moveit_msgs::msg::TrajectoryConstraints & |
msg, |
|
|
const std::string & |
name, |
|
|
const std::string & |
robot = "", |
|
|
const std::string & |
group = "" |
|
) |
| |
◆ 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 |
◆ getKnownTrajectoryConstraints() [2/2]
| void moveit_warehouse::TrajectoryConstraintsStorage::getKnownTrajectoryConstraints |
( |
std::vector< std::string > & |
names, |
|
|
const std::string & |
robot = "", |
|
|
const std::string & |
group = "" |
|
) |
| const |
◆ getTrajectoryConstraints()
| bool moveit_warehouse::TrajectoryConstraintsStorage::getTrajectoryConstraints |
( |
TrajectoryConstraintsWithMetadata & |
msg_m, |
|
|
const std::string & |
name, |
|
|
const std::string & |
robot = "", |
|
|
const std::string & |
group = "" |
|
) |
| const |
◆ hasTrajectoryConstraints()
| bool moveit_warehouse::TrajectoryConstraintsStorage::hasTrajectoryConstraints |
( |
const std::string & |
name, |
|
|
const std::string & |
robot = "", |
|
|
const std::string & |
group = "" |
|
) |
| const |
◆ removeTrajectoryConstraints()
| void moveit_warehouse::TrajectoryConstraintsStorage::removeTrajectoryConstraints |
( |
const std::string & |
name, |
|
|
const std::string & |
robot = "", |
|
|
const std::string & |
group = "" |
|
) |
| |
◆ renameTrajectoryConstraints()
| void moveit_warehouse::TrajectoryConstraintsStorage::renameTrajectoryConstraints |
( |
const std::string & |
old_name, |
|
|
const std::string & |
new_name, |
|
|
const std::string & |
robot = "", |
|
|
const std::string & |
group = "" |
|
) |
| |
◆ reset()
| void moveit_warehouse::TrajectoryConstraintsStorage::reset |
( |
| ) |
|
◆ CONSTRAINTS_GROUP_NAME
| const std::string moveit_warehouse::TrajectoryConstraintsStorage::CONSTRAINTS_GROUP_NAME = "group_id" |
|
static |
◆ CONSTRAINTS_ID_NAME
| const std::string moveit_warehouse::TrajectoryConstraintsStorage::CONSTRAINTS_ID_NAME = "constraints_id" |
|
static |
◆ DATABASE_NAME
| const std::string moveit_warehouse::TrajectoryConstraintsStorage::DATABASE_NAME = "moveit_trajectory_constraints" |
|
static |
◆ ROBOT_NAME
| const std::string moveit_warehouse::TrajectoryConstraintsStorage::ROBOT_NAME = "robot_id" |
|
static |
The documentation for this class was generated from the following files: