Class PluginInterface

Inheritance Relationships

Derived Types

Class Documentation

class PluginInterface

Subclassed by webots_ros2_driver::PythonPlugin, webots_ros2_driver::Ros2LED, webots_ros2_driver::Ros2Pen, webots_ros2_driver::Ros2SensorPlugin

Public Functions

virtual void init(WebotsNode *node, std::unordered_map<std::string, std::string> &parameters) = 0

Prepare your plugin in this method. Fired before the node is spinned. Parameters are passed from the WebotsNode and/or from URDF.

Parameters:
  • node[in] WebotsNode inherited from rclcpp::Node with a few extra methods related

  • parameters[in] Parameters (key-value pairs) located under a <plugin> (dynamically loaded plugins) or <ros> (statically loaded plugins).

virtual void step() = 0

This method is called on each timestep. You should not call robot.step() in this method as it is automatically called.