|
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.
|
|
| SystemInterface (const SystemInterface &other)=delete |
| SensorInterface 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 ()=0 |
| Read the current state values from the actuator.
|
|
virtual return_type | write ()=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.
|
|
|
rclcpp::Node::SharedPtr | nh_ |
|
HardwareInfo | info_ |
|
rclcpp_lifecycle::State | lifecycle_state_ |
|
◆ 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: