Class Ros2SensorPlugin
Defined in File Ros2SensorPlugin.hpp
Inheritance Relationships
Base Type
public webots_ros2_driver::PluginInterface
(Class PluginInterface)
Derived Types
public webots_ros2_driver::Ros2Camera
(Class Ros2Camera)public webots_ros2_driver::Ros2Compass
(Class Ros2Compass)public webots_ros2_driver::Ros2DistanceSensor
(Class Ros2DistanceSensor)public webots_ros2_driver::Ros2Emitter
(Class Ros2Emitter)public webots_ros2_driver::Ros2GPS
(Class Ros2GPS)public webots_ros2_driver::Ros2IMU
(Class Ros2IMU)public webots_ros2_driver::Ros2Lidar
(Class Ros2Lidar)public webots_ros2_driver::Ros2LightSensor
(Class Ros2LightSensor)public webots_ros2_driver::Ros2RGBD
(Class Ros2RGBD)public webots_ros2_driver::Ros2RangeFinder
(Class Ros2RangeFinder)public webots_ros2_driver::Ros2Receiver
(Class Ros2Receiver)public webots_ros2_driver::Ros2VacuumGripper
(Class Ros2VacuumGripper)
Class Documentation
-
class Ros2SensorPlugin : public webots_ros2_driver::PluginInterface
Utility class for common Webots sensors.
Subclassed by webots_ros2_driver::Ros2Camera, webots_ros2_driver::Ros2Compass, webots_ros2_driver::Ros2DistanceSensor, webots_ros2_driver::Ros2Emitter, webots_ros2_driver::Ros2GPS, webots_ros2_driver::Ros2IMU, webots_ros2_driver::Ros2Lidar, webots_ros2_driver::Ros2LightSensor, webots_ros2_driver::Ros2RGBD, webots_ros2_driver::Ros2RangeFinder, webots_ros2_driver::Ros2Receiver, webots_ros2_driver::Ros2VacuumGripper
Public Functions
-
virtual void init(webots_ros2_driver::WebotsNode *node, std::unordered_map<std::string, std::string> ¶meters) override
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 relatedparameters – [in] Parameters (key-value pairs) located under a <plugin> (dynamically loaded plugins) or <ros> (statically loaded plugins).
Protected Functions
-
bool preStep()
Checks if a sensor has data ready and updates the last update time.
- Returns:
Should publishing from the sensor be considered
-
virtual void init(webots_ros2_driver::WebotsNode *node, std::unordered_map<std::string, std::string> ¶meters) override