16#ifndef GAZEBO_ROS2_CONTROL__GAZEBO_SYSTEM_HPP_
17#define GAZEBO_ROS2_CONTROL__GAZEBO_SYSTEM_HPP_
23#include "angles/angles.h"
25#include "gazebo_ros2_control/gazebo_system_interface.hpp"
27#include "std_msgs/msg/bool.hpp"
29namespace gazebo_ros2_control
32class GazeboSystemPrivate;
51 hardware_interface::return_type
start()
override;
54 hardware_interface::return_type
stop()
override;
57 hardware_interface::return_type
read()
override;
61 const std::vector<std::string> & start_interfaces,
62 const std::vector<std::string> & stop_interfaces)
override;
65 hardware_interface::return_type
write()
override;
69 rclcpp::Node::SharedPtr & model_nh,
70 gazebo::physics::ModelPtr parent_model,
72 sdf::ElementPtr sdf)
override;
77 gazebo::physics::ModelPtr parent_model);
81 gazebo::physics::ModelPtr parent_model);
84 std::unique_ptr<GazeboSystemPrivate> dataPtr;
Definition gazebo_system_interface.hpp:62
Definition gazebo_system.hpp:38
hardware_interface::return_type read() override
Read the current state values from the actuators and sensors within the system.
Definition gazebo_system.cpp:506
hardware_interface::return_type start() override
Start exchange data with the hardware.
Definition gazebo_system.cpp:449
hardware_interface::return_type write() override
Write the current command values to the actuator within the system.
Definition gazebo_system.cpp:548
std::vector< hardware_interface::CommandInterface > export_command_interfaces() override
Exports all command interfaces for this system.
Definition gazebo_system.cpp:444
std::vector< hardware_interface::StateInterface > export_state_interfaces() override
Exports all state interfaces for this system.
Definition gazebo_system.cpp:438
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:462
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:112
hardware_interface::return_type configure(const hardware_interface::HardwareInfo &system_info) override
Configuration of the system from data parsed from the robot's URDF.
Definition gazebo_system.cpp:429
hardware_interface::return_type stop() override
Stop exchange data with the hardware.
Definition gazebo_system.cpp:455
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:103