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"
28 namespace gz_ros2_control
30 using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
33 class 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;
61 const std::vector<std::string> & start_interfaces,
62 const std::vector<std::string> & stop_interfaces)
override;
65 hardware_interface::return_type
read(
66 const rclcpp::Time & time,
67 const rclcpp::Duration & period)
override;
70 hardware_interface::return_type
write(
71 const rclcpp::Time & time,
72 const rclcpp::Duration & period)
override;
76 rclcpp::Node::SharedPtr & model_nh,
77 std::map<std::string, sim::Entity> & joints,
79 sim::EntityComponentManager & _ecm,
80 unsigned int update_rate)
override;
90 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:518
std::vector< hardware_interface::StateInterface > export_state_interfaces() override
Exports all state interfaces for this hardware interface.
Definition: gz_system.cpp:512
CallbackReturn on_init(const hardware_interface::HardwareInfo &system_info) override
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition: gz_system.cpp:494
hardware_interface::return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) override
Read the current state values from the actuator.
Definition: gz_system.cpp:535
hardware_interface::return_type write(const rclcpp::Time &time, const rclcpp::Duration &period) override
Write the current command values to the actuator.
Definition: gz_system.cpp:642
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:596
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:167
This structure stores information about hardware defined in a robot's URDF.
Definition: hardware_info.hpp:170