16#ifndef GZ_ROS2_CONTROL__GZ_SYSTEM_HPP_
17#define GZ_ROS2_CONTROL__GZ_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
30using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
33class GazeboSimSystemPrivate;
43 "Replaced by GazeboSimSystem::on_init(const "
44 "hardware_interface::HardwareComponentInterfaceParams & params).")]]
51 CallbackReturn on_configure(
const rclcpp_lifecycle::State & previous_state)
override;
60 CallbackReturn on_activate(
const rclcpp_lifecycle::State & previous_state)
override;
63 CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & previous_state)
override;
67 const std::vector<std::string> & start_interfaces,
68 const std::vector<std::string> & stop_interfaces)
override;
71 hardware_interface::return_type
read(
72 const rclcpp::Time & time,
73 const rclcpp::Duration & period)
override;
76 hardware_interface::return_type
write(
77 const rclcpp::Time & time,
78 const rclcpp::Duration & period)
override;
82 rclcpp::Node::SharedPtr & model_nh,
83 std::map<std::string, sim::Entity> & joints,
85 sim::EntityComponentManager & _ecm,
86 unsigned int update_rate)
override;
96 std::unique_ptr<GazeboSimSystemPrivate> dataPtr;
Definition gz_system_interface.hpp:77
Definition gz_system.hpp:39
std::vector< hardware_interface::CommandInterface > export_command_interfaces() override
Exports all command interfaces for this hardware interface.
Definition gz_system.cpp:616
std::vector< hardware_interface::StateInterface > export_state_interfaces() override
Exports all state interfaces for this hardware interface.
Definition gz_system.cpp:610
hardware_interface::return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) override
Read the current state values from the hardware.
Definition gz_system.cpp:633
hardware_interface::return_type write(const rclcpp::Time &time, const rclcpp::Duration &period) override
Write the current command values to the hardware.
Definition gz_system.cpp:758
CallbackReturn on_init(const hardware_interface::HardwareInfo &info) override
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition gz_system.cpp:579
hardware_interface::return_type perform_command_mode_switch(const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces) override
Definition gz_system.cpp:712
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_system.cpp:203
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:252