15 #include "opennav_docking/dock_database.hpp"
17 namespace opennav_docking
22 dock_loader_(
"opennav_docking_core",
"opennav_docking_core::ChargingDock")
27 dock_instances_.clear();
28 dock_plugins_.clear();
32 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
33 std::shared_ptr<tf2_ros::Buffer> tf)
36 auto node = node_.lock();
41 "An error occurred while getting the dock plugins!");
48 "An error occurred while getting the dock instances!");
54 "Docking Server has %u dock types and %u dock instances available.",
55 this->plugin_size(), this->instance_size());
57 reload_db_service_ = node->create_service<nav2_msgs::srv::ReloadDockDatabase>(
61 std::placeholders::_1, std::placeholders::_2));
68 DockPluginMap::iterator it;
69 for (it = dock_plugins_.begin(); it != dock_plugins_.end(); ++it) {
70 it->second->activate();
76 DockPluginMap::iterator it;
77 for (it = dock_plugins_.begin(); it != dock_plugins_.end(); ++it) {
78 it->second->deactivate();
83 const std::shared_ptr<nav2_msgs::srv::ReloadDockDatabase::Request> request,
84 std::shared_ptr<nav2_msgs::srv::ReloadDockDatabase::Response> response)
86 if (!mutex_->try_lock()) {
87 RCLCPP_ERROR(node_.lock()->get_logger(),
"Cannot reload database while docking!");
88 response->success =
false;
92 auto node = node_.lock();
93 DockMap dock_instances;
94 if (utils::parseDockFile(request->filepath, node, dock_instances)) {
95 dock_instances_ = dock_instances;
96 response->success =
true;
99 "Dock database reloaded from file %s.", request->filepath.c_str());
103 response->success =
false;
110 ChargingDock::Ptr dock_plugin{
nullptr};
116 dock_instance->plugin = dock_plugin;
117 return dock_instance;
126 auto it = dock_instances_.find(dock_id);
127 if (it != dock_instances_.end()) {
128 return &(it->second);
136 if (type.empty() && dock_plugins_.size() == 1) {
137 return dock_plugins_.begin()->second;
140 auto it = dock_plugins_.find(type);
141 if (it != dock_plugins_.end()) {
148 const rclcpp_lifecycle::LifecycleNode::SharedPtr & node,
149 std::shared_ptr<tf2_ros::Buffer> tf)
151 std::vector<std::string> docks_plugins;
152 if (!node->has_parameter(
"dock_plugins")) {
153 node->declare_parameter(
"dock_plugins", rclcpp::ParameterType::PARAMETER_STRING_ARRAY);
155 if (!node->get_parameter(
"dock_plugins", docks_plugins)) {
156 RCLCPP_ERROR(node->get_logger(),
"Charging dock plugins not given!");
160 if (docks_plugins.size() < 1u) {
161 RCLCPP_ERROR(node->get_logger(),
"Charging dock plugins empty! Must provide 1.");
165 for (
size_t i = 0; i != docks_plugins.size(); i++) {
167 std::string plugin_type = nav2_util::get_plugin_type_param(
168 node, docks_plugins[i]);
169 opennav_docking_core::ChargingDock::Ptr dock =
170 dock_loader_.createUniqueInstance(plugin_type);
172 node->get_logger(),
"Created charging dock plugin %s of type %s",
173 docks_plugins[i].c_str(), plugin_type.c_str());
174 dock->configure(node, docks_plugins[i], tf);
175 dock_plugins_.insert({docks_plugins[i], dock});
176 }
catch (
const std::exception & ex) {
178 node->get_logger(),
"Failed to create Charging Dock plugin. Exception: %s",
189 using rclcpp::ParameterType::PARAMETER_STRING;
190 using rclcpp::ParameterType::PARAMETER_STRING_ARRAY;
193 std::string dock_filepath;
194 if (!node->has_parameter(
"dock_database")) {
195 node->declare_parameter(
"dock_database", PARAMETER_STRING);
197 if (node->get_parameter(
"dock_database", dock_filepath)) {
199 node->get_logger(),
"Loading dock from database file %s.", dock_filepath.c_str());
201 return utils::parseDockFile(dock_filepath, node, dock_instances_);
202 }
catch (YAML::ParserException & e) {
205 "Dock database (%s) is malformed: %s.", dock_filepath.c_str(), e.what());
212 std::vector<std::string> docks_param;
213 if (!node->has_parameter(
"docks")) {
214 node->declare_parameter(
"docks", PARAMETER_STRING_ARRAY);
216 if (node->get_parameter(
"docks", docks_param)) {
217 RCLCPP_INFO(node->get_logger(),
"Loading docks from parameter file.");
218 return utils::parseDockParams(docks_param, node, dock_instances_);
223 "Dock database filepath nor dock parameters set. "
224 "Docking actions can only be executed specifying the dock pose via the action request. "
225 "Or update the dock database via the reload_database service.");
231 return dock_plugins_.size();
236 return dock_instances_.size();
Dock * findDock(const std::string &dock_id)
Find a dock instance & plugin in the databases from ID.
void reloadDbCb(const std::shared_ptr< nav2_msgs::srv::ReloadDockDatabase::Request > request, std::shared_ptr< nav2_msgs::srv::ReloadDockDatabase::Response > response)
Service request to reload database of docks.
bool getDockInstances(const rclcpp_lifecycle::LifecycleNode::SharedPtr &node)
Populate database of dock instances.
Dock * findDockInstance(const std::string &dock_id)
Find a dock instance in the database from ID.
bool initialize(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::shared_ptr< tf2_ros::Buffer > tf)
A setup function to populate database.
ChargingDock::Ptr findDockPlugin(const std::string &type)
Find a dock plugin to use for a given type.
void deactivate()
An deactivation method.
unsigned int plugin_size() const
Get the number of dock types in the database.
~DockDatabase()
A destructor for opennav_docking::DockDatabase.
unsigned int instance_size() const
Get the number of docks in the database.
DockDatabase(std::shared_ptr< std::mutex > mutex=std::make_shared< std::mutex >())
A constructor for opennav_docking::DockDatabase.
void activate()
An activation method.
bool getDockPlugins(const rclcpp_lifecycle::LifecycleNode::SharedPtr &node, std::shared_ptr< tf2_ros::Buffer > tf)
Populate database of dock type plugins.
Dock was not found in the provided dock database.
Dock plugin provided in the database or action was invalid.