16 #ifndef GAZEBO_ROS2_CONTROL__GAZEBO_SYSTEM_HPP_
17 #define GAZEBO_ROS2_CONTROL__GAZEBO_SYSTEM_HPP_
19 #define VELOCITY_PID_PARAMS_PREFIX "vel_"
20 #define POSITION_PID_PARAMS_PREFIX "pos_"
26 #include "angles/angles.h"
28 #include "control_toolbox/pid.hpp"
29 #include "gazebo_ros2_control/gazebo_system_interface.hpp"
31 #include "std_msgs/msg/bool.hpp"
33 namespace gazebo_ros2_control
35 using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
38 class GazeboSystemPrivate;
57 CallbackReturn on_activate(
const rclcpp_lifecycle::State & previous_state)
override;
60 CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & previous_state)
override;
64 const std::vector<std::string> & start_interfaces,
65 const std::vector<std::string> & stop_interfaces)
override;
68 hardware_interface::return_type
read(
69 const rclcpp::Time & time,
70 const rclcpp::Duration & period)
override;
73 hardware_interface::return_type
write(
74 const rclcpp::Time & time,
75 const rclcpp::Duration & period)
override;
79 rclcpp::Node::SharedPtr & model_nh,
80 gazebo::physics::ModelPtr parent_model,
82 sdf::ElementPtr sdf)
override;
87 gazebo::physics::ModelPtr parent_model);
91 gazebo::physics::ModelPtr parent_model);
94 const std::string & prefix,
97 bool extractPIDFromParameters(
101 std::unique_ptr<GazeboSystemPrivate> dataPtr;
Definition: gazebo_system_interface.hpp:62
Definition: gazebo_system.hpp:44
std::vector< hardware_interface::CommandInterface > export_command_interfaces() override
Exports all command interfaces for this hardware interface.
Definition: gazebo_system.cpp:690
CallbackReturn on_init(const hardware_interface::HardwareInfo &system_info) override
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition: gazebo_system.cpp:675
hardware_interface::return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) override
Read the current state values from the actuator.
Definition: gazebo_system.cpp:761
std::vector< hardware_interface::StateInterface > export_state_interfaces() override
Exports all state interfaces for this hardware interface.
Definition: gazebo_system.cpp:684
hardware_interface::return_type perform_command_mode_switch(const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces) override
Definition: gazebo_system.cpp:706
bool initSim(rclcpp::Node::SharedPtr &model_nh, gazebo::physics::ModelPtr parent_model, const hardware_interface::HardwareInfo &hardware_info, sdf::ElementPtr sdf) override
Initialize the system interface param[in] model_nh pointer to the ros2 node param[in] parent_model po...
Definition: gazebo_system.cpp:125
hardware_interface::return_type write(const rclcpp::Time &time, const rclcpp::Duration &period) override
Write the current command values to the actuator.
Definition: gazebo_system.cpp:802
Definition: hardware_info.hpp:77
This structure stores information about hardware defined in a robot's URDF.
Definition: hardware_info.hpp:170