Class DockDatabase

Class Documentation

class DockDatabase

An object to contain docks and docking plugins.

Public Functions

DockDatabase()

A constructor for opennav_docking::DockDatabase.

bool initialize(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::shared_ptr<tf2_ros::Buffer> tf)

A setup function to populate database.

Parameters:
  • parent – Weakptr to the node to use to get interances and parameters

  • tf – TF buffer

Returns:

If successful

~DockDatabase()

A destructor for opennav_docking::DockDatabase.

void activate()

An activation method.

void deactivate()

An deactivation method.

Dock *findDock(const std::string &dock_id)

Find a dock instance & plugin in the databases from ID.

Parameters:

dock_id – Id of dock to find

Returns:

Dock pointer

ChargingDock::Ptr findDockPlugin(const std::string &type)

Find a dock plugin to use for a given type.

Parameters:

typeDock type to find plugin for

Returns:

Dock plugin pointer

unsigned int instance_size() const

Get the number of docks in the database.

Returns:

unsigned int Number of dock instances in the database

unsigned int plugin_size() const

Get the number of dock types in the database.

Returns:

unsigned int Number of dock types in the database

Protected Functions

bool getDockPlugins(const rclcpp_lifecycle::LifecycleNode::SharedPtr &node, std::shared_ptr<tf2_ros::Buffer> tf)

Populate database of dock type plugins.

Parameters:
  • Node – Node to get values from

  • tf – TF buffer

Returns:

bool If successful

bool getDockInstances(const rclcpp_lifecycle::LifecycleNode::SharedPtr &node)

Populate database of dock instances.

Parameters:

Node – Node to get values from

Dock *findDockInstance(const std::string &dock_id)

Find a dock instance in the database from ID.

Parameters:

dock_id – Id of dock to find

Returns:

Dock pointer

void reloadDbCb(const std::shared_ptr<opennav_docking_msgs::srv::ReloadDatabase::Request> request, std::shared_ptr<opennav_docking_msgs::srv::ReloadDatabase::Response> response)

Service request to reload database of docks.

Parameters:
  • request – Service request

  • response – Service response

Protected Attributes

rclcpp_lifecycle::LifecycleNode::WeakPtr node_
DockPluginMap dock_plugins_
DockMap dock_instances_
pluginlib::ClassLoader<opennav_docking_core::ChargingDock> dock_loader_
rclcpp::Service<opennav_docking_msgs::srv::ReloadDatabase>::SharedPtr reload_db_service_