39#include <warehouse_ros/database_connection.h>
60 void filterNames(
const std::string& regex, std::vector<std::string>& names)
const;
62 warehouse_ros::DatabaseConnection::Ptr
conn_;
66typename warehouse_ros::DatabaseConnection::Ptr
loadDatabase(
const rclcpp::Node::SharedPtr& node);
This class provides the mechanism to connect to a database and reads needed ROS parameters when appro...
virtual ~MoveItMessageStorage()
warehouse_ros::DatabaseConnection::Ptr conn_
void filterNames(const std::string ®ex, std::vector< std::string > &names) const
Keep only the names that match regex.
warehouse_ros::DatabaseConnection::Ptr loadDatabase(const rclcpp::Node::SharedPtr &node)
Load a database connection.