ros2_control - rolling
|
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. More... | |
SystemInterface (SystemInterface &&other)=default | |
CallbackReturn | init (const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface) |
virtual CallbackReturn | on_init (const HardwareInfo &hardware_info) |
Initialization of the hardware interface from data parsed from the robot's URDF. More... | |
virtual std::vector< StateInterface > | export_state_interfaces () |
Exports all state interfaces for this hardware interface. More... | |
virtual std::vector< hardware_interface::InterfaceDescription > | export_unlisted_state_interface_descriptions () |
virtual std::vector< StateInterface::ConstSharedPtr > | on_export_state_interfaces () |
virtual std::vector< CommandInterface > | export_command_interfaces () |
Exports all command interfaces for this hardware interface. More... | |
virtual std::vector< hardware_interface::InterfaceDescription > | export_unlisted_command_interface_descriptions () |
virtual std::vector< CommandInterface::SharedPtr > | on_export_command_interfaces () |
virtual return_type | prepare_command_mode_switch (const std::vector< std::string > &, const std::vector< std::string > &) |
Prepare for a new command interface switch. More... | |
virtual return_type | perform_command_mode_switch (const std::vector< std::string > &, const std::vector< std::string > &) |
return_type | trigger_read (const rclcpp::Time &time, const rclcpp::Duration &period) |
Triggers the read method synchronously or asynchronously depending on the HardwareInfo. More... | |
virtual return_type | read (const rclcpp::Time &time, const rclcpp::Duration &period)=0 |
Read the current state values from the actuator. More... | |
return_type | trigger_write (const rclcpp::Time &time, const rclcpp::Duration &period) |
Triggers the write method synchronously or asynchronously depending on the HardwareInfo. More... | |
virtual return_type | write (const rclcpp::Time &time, const rclcpp::Duration &period)=0 |
Write the current command values to the actuator. More... | |
virtual std::string | get_name () const |
Get name of the actuator hardware. More... | |
virtual std::string | get_group_name () const |
Get name of the actuator hardware group to which it belongs to. More... | |
const rclcpp_lifecycle::State & | get_lifecycle_state () const |
Get life-cycle state of the actuator hardware. More... | |
void | set_lifecycle_state (const rclcpp_lifecycle::State &new_state) |
Set life-cycle state of the actuator hardware. More... | |
void | set_state (const std::string &interface_name, const double &value) |
double | get_state (const std::string &interface_name) const |
void | set_command (const std::string &interface_name, const double &value) |
double | get_command (const std::string &interface_name) const |
rclcpp::Logger | get_logger () const |
Get the logger of the SystemInterface. More... | |
rclcpp::Clock::SharedPtr | get_clock () const |
Get the clock of the SystemInterface. More... | |
const HardwareInfo & | get_hardware_info () const |
Get the hardware info of the SystemInterface. More... | |
Protected Attributes | |
rclcpp::Node::SharedPtr | nh_ |
Protected Attributes inherited from hardware_interface::SystemInterface | |
HardwareInfo | info_ |
std::unordered_map< std::string, InterfaceDescription > | joint_state_interfaces_ |
std::unordered_map< std::string, InterfaceDescription > | joint_command_interfaces_ |
std::unordered_map< std::string, InterfaceDescription > | sensor_state_interfaces_ |
std::unordered_map< std::string, InterfaceDescription > | gpio_state_interfaces_ |
std::unordered_map< std::string, InterfaceDescription > | gpio_command_interfaces_ |
std::unordered_map< std::string, InterfaceDescription > | unlisted_state_interfaces_ |
std::unordered_map< std::string, InterfaceDescription > | unlisted_command_interfaces_ |
rclcpp_lifecycle::State | lifecycle_state_ |
std::unique_ptr< realtime_tools::AsyncFunctionHandler< return_type > > | async_handler_ |
std::vector< StateInterface::SharedPtr > | joint_states_ |
std::vector< CommandInterface::SharedPtr > | joint_commands_ |
std::vector< StateInterface::SharedPtr > | sensor_states_ |
std::vector< StateInterface::SharedPtr > | gpio_states_ |
std::vector< CommandInterface::SharedPtr > | gpio_commands_ |
std::vector< StateInterface::SharedPtr > | unlisted_states_ |
std::vector< CommandInterface::SharedPtr > | unlisted_commands_ |