![]() |
ros2_control - humble
|


Public Types | |
| enum | ControlMethod_ { NONE = 0 , POSITION = (1 << 0) , VELOCITY = (1 << 1) , EFFORT = (1 << 2) , VELOCITY_PID = (1 << 3) , POSITION_PID = (1 << 4) } |
| typedef SafeEnum< enum ControlMethod_ > | ControlMethod |
Public Member Functions | |
| virtual bool | initSim (rclcpp::Node::SharedPtr &model_nh, gazebo::physics::ModelPtr parent_model, const hardware_interface::HardwareInfo &hardware_info, sdf::ElementPtr sdf)=0 |
| Initialize the system interface param[in] model_nh pointer to the ros2 node param[in] parent_model pointer to the model param[in] control_hardware vector filled with information about robot's control resources param[in] sdf pointer to the SDF. | |
Public Member Functions inherited from hardware_interface::SystemInterface | |
| SystemInterface (const SystemInterface &other)=delete | |
| SystemInterface copy constructor is actively deleted. | |
| SystemInterface (SystemInterface &&other)=default | |
| virtual CallbackReturn | on_init (const HardwareInfo &hardware_info) |
| Initialization of the hardware interface from data parsed from the robot's URDF. | |
| virtual std::vector< StateInterface > | export_state_interfaces ()=0 |
| Exports all state interfaces for this hardware interface. | |
| virtual std::vector< CommandInterface > | export_command_interfaces ()=0 |
| Exports all command interfaces for this hardware interface. | |
| virtual return_type | prepare_command_mode_switch (const std::vector< std::string > &, const std::vector< std::string > &) |
| Prepare for a new command interface switch. | |
| virtual return_type | perform_command_mode_switch (const std::vector< std::string > &, const std::vector< std::string > &) |
| virtual return_type | read (const rclcpp::Time &time, const rclcpp::Duration &period)=0 |
| Read the current state values from the actuator. | |
| virtual return_type | write (const rclcpp::Time &time, const rclcpp::Duration &period)=0 |
| Write the current command values to the actuator. | |
| virtual std::string | get_name () const |
| Get name of the actuator hardware. | |
| const rclcpp_lifecycle::State & | get_state () const |
| Get life-cycle state of the actuator hardware. | |
| void | set_state (const rclcpp_lifecycle::State &new_state) |
| Set life-cycle state of the actuator hardware. | |
Protected Attributes | |
| rclcpp::Node::SharedPtr | nh_ |
Protected Attributes inherited from hardware_interface::SystemInterface | |
| HardwareInfo | info_ |
| rclcpp_lifecycle::State | lifecycle_state_ |
|
pure virtual |
Initialize the system interface param[in] model_nh pointer to the ros2 node param[in] parent_model pointer to the model param[in] control_hardware vector filled with information about robot's control resources param[in] sdf pointer to the SDF.
Implemented in gazebo_ros2_control::GazeboSystem.