16#ifndef GZ_ROS2_CONTROL_DEMOS__GZ_CUSTOM_SYSTEM_HPP_
17#define GZ_ROS2_CONTROL_DEMOS__GZ_CUSTOM_SYSTEM_HPP_
24#include "gz_ros2_control/gz_system_interface.hpp"
25#include "rclcpp_lifecycle/state.hpp"
26#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
28namespace gz_ros2_control_demos
30using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
33class GazeboSimSystemPrivate;
45 CallbackReturn on_configure(
const rclcpp_lifecycle::State & previous_state)
override;
54 CallbackReturn on_activate(
const rclcpp_lifecycle::State & previous_state)
override;
57 CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & previous_state)
override;
60 hardware_interface::return_type
read(
61 const rclcpp::Time & time,
62 const rclcpp::Duration & period)
override;
65 hardware_interface::return_type
write(
66 const rclcpp::Time & time,
67 const rclcpp::Duration & period)
override;
71 rclcpp::Node::SharedPtr & model_nh,
72 std::map<std::string, sim::Entity> & joints,
74 sim::EntityComponentManager & _ecm,
75 unsigned int update_rate)
override;
79 std::unique_ptr<GazeboSimSystemPrivate> dataPtr;
Definition gz_system_interface.hpp:77
Definition gz_custom_system.hpp:39
hardware_interface::return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) override
Read the current state values from the hardware.
Definition gz_custom_system.cpp:331
std::vector< hardware_interface::CommandInterface > export_command_interfaces() override
Exports all command interfaces for this hardware interface.
Definition gz_custom_system.cpp:314
bool initSim(rclcpp::Node::SharedPtr &model_nh, std::map< std::string, sim::Entity > &joints, const hardware_interface::HardwareInfo &hardware_info, sim::EntityComponentManager &_ecm, unsigned int update_rate) override
Initialize the system interface param[in] model_nh Pointer to the ros2 node param[in] joints Map with...
Definition gz_custom_system.cpp:106
CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams ¶ms) override
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition gz_custom_system.cpp:288
std::vector< hardware_interface::StateInterface > export_state_interfaces() override
Exports all state interfaces for this hardware interface.
Definition gz_custom_system.cpp:308
hardware_interface::return_type write(const rclcpp::Time &time, const rclcpp::Duration &period) override
Write the current command values to the hardware.
Definition gz_custom_system.cpp:375
Parameters required for the initialization of a specific hardware component plugin....
Definition hardware_component_interface_params.hpp:32
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:264