|
| enum | ControlMethod_ { NONE = 0
, POSITION = (1 << 0)
, VELOCITY = (1 << 1)
, EFFORT = (1 << 2)
} |
| |
|
typedef SafeEnum< enum ControlMethod_ > | ControlMethod |
| |
|
| 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.
|
| |
| return_type | configure (const HardwareInfo &info) override |
| |
|
return_type | configure_default (const HardwareInfo &info) |
| |
| std::string | get_name () const final |
| |
| status | get_status () const final |
| |
| virtual std::vector< StateInterface > | export_state_interfaces ()=0 |
| | Exports all state interfaces for this system.
|
| |
| virtual std::vector< CommandInterface > | export_command_interfaces ()=0 |
| | Exports all command interfaces for this system.
|
| |
| 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 | start ()=0 |
| | Start exchange data with the hardware.
|
| |
| virtual return_type | stop ()=0 |
| | Stop exchange data with the hardware.
|
| |
| virtual return_type | read ()=0 |
| | Read the current state values from the actuators and sensors within the system.
|
| |
| virtual return_type | write ()=0 |
| | Write the current command values to the actuator within the system.
|
| |
|
|
rclcpp::Node::SharedPtr | nh_ |
| |
|
HardwareInfo | info_ |
| |
|
status | status_ |
| |
◆ initSim()
| virtual bool gazebo_ros2_control::GazeboSystemInterface::initSim |
( |
rclcpp::Node::SharedPtr & |
model_nh, |
|
|
gazebo::physics::ModelPtr |
parent_model, |
|
|
const hardware_interface::HardwareInfo & |
hardware_info, |
|
|
sdf::ElementPtr |
sdf |
|
) |
| |
|
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.
The documentation for this class was generated from the following file: