Skip to content

Tutorial Creating a Custom Python Plugin

Darko Lukić edited this page Aug 13, 2021 · 6 revisions

Since webots_ros2 1.1.1 one can create Python plugins with webots_ros2_driver package.

See the Creating a Custom C++ Plugin tutorial for C++ plugins.

Before going further, please check the webots_ros2_driver architecture to better understand the plugin system.

The following example assumes you have a ROS 2 Python package created. On how to create a ROS 2 Python package please visit the official tutorial.

A simple plugin publishing time can be implemented as follows:

# Compared to the typical `from controller import Node` we added parent modules.
from webots_ros2_driver.webots.controller import Node
from std_msgs.msg import Float32
import rclpy
import rclpy.node


class PluginClassNameExample:
    # The `init` method is called only once the driver is initialized.
    # You will always get two arguments in the `init` method.
    # - The `webots_node` contains a reference on a Supervisor instance.
    # - The `properties` is a dictionary created from the XML tags.
    def init(self, webots_node, properties):
        # This will print the parameter from the URDF file.
        #
        #     `{ 'parameterExample': 'someValue' }`
        #
        print('properties:', properties)

        # The robot property is a reference to a Supervisor instance.
        # It allows you to access the standard Webots API.
        # See: https://cyberbotics.com/doc/reference/supervisor
        print('basic timestep:', int(webots_node.robot.getBasicTimeStep()))
        print('robot name:', webots_node.robot.getName())
        print('is robot?', webots_node.robot.getType() == Node.ROBOT)

        self.__robot = webots_node.robot

        # Unfortunately, we cannot get an instance of the parent ROS node.
        # However, we can create a new one.
        rclpy.init(args=None)
        self.__node = rclpy.node.Node('plugin_node_example')
        self.__publisher = self.__node.create_publisher(Float32, 'custom_time', 1)

    # The `step` method is called at every step.
    def step(self):
        self.__publisher.publish(Float32(data=self.__robot.getTime()))

The plugin should be saved under the Python module of your package. For example:

.
├── package_name_example
│   └── plugin_file_name_example.py (our plugin for above)
├── setup.py
├── resource
|   ├── your_robot_description.urdf
│   └── package_name_example
└── package.xml

Then, in the robot description file (e.g. your_robot_description.urdf), under the <webots>, you should include the plugin as following:

<?xml version="1.0" ?>
<robot name="Your Robot">
    <webots>
        <plugin type="package_name_example.plugin_file_name_example.PluginClassNameExample">
            <parameterExample>someValue</parameterExample>
        </plugin>
    </webots>
</robot>
Clone this wiki locally