Class GenericSystem
Defined in File generic_system.hpp
Inheritance Relationships
Base Type
public hardware_interface::SystemInterface
(Class SystemInterface)
Class Documentation
-
class GenericSystem : public hardware_interface::SystemInterface
Public Functions
-
virtual CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams ¶ms) override
Initialization of the hardware interface from data parsed from the robot’s URDF.
Warning
The parsed executor should not be used to call
cancel()
or use blocking callbacks such asspin()
.- Parameters:
params – [in] A struct of type hardware_interface::HardwareComponentInterfaceParams containing all necessary parameters for initializing this specific hardware component, specifically its HardwareInfo, and a weak_ptr to the executor.
- Returns:
CallbackReturn::SUCCESS if required data are provided and can be parsed.
- Returns:
CallbackReturn::ERROR if any error happens or data are missing.
-
hardware_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State &previous_state) override
-
virtual std::vector<hardware_interface::InterfaceDescription> export_unlisted_command_interface_descriptions() override
Override this method to export custom CommandInterfaces which are not defined in the URDF file. Those interfaces will be added to the unlisted_command_interfaces_ map.
- Returns:
vector of descriptions to the unlisted CommandInterfaces
-
virtual return_type prepare_command_mode_switch(const std::vector<std::string> &start_interfaces, const std::vector<std::string> &stop_interfaces) override
Prepare for a new command interface switch.
Prepare for any mode-switching required by the new command interface combination.
Note
This is a non-realtime evaluation of whether a set of command interface claims are possible, and call to start preparing data structures for the upcoming switch that will occur.
- Parameters:
start_interfaces – [in] vector of string identifiers for the command interfaces starting.
stop_interfaces – [in] vector of string identifiers for the command interfaces stopping.
- Returns:
return_type::OK if the new command interface combination can be prepared (or) if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.
-
virtual return_type perform_command_mode_switch(const std::vector<std::string> &start_interfaces, const std::vector<std::string> &stop_interfaces) override
Perform the mode-switching for the new command interface combination.
Note
This is part of the realtime update loop, and should be fast.
- Parameters:
start_interfaces – [in] vector of string identifiers for the command interfaces starting.
stop_interfaces – [in] vector of string identifiers for the command interfaces stopping.
- Returns:
return_type::OK if the new command interface combination can be switched to (or) if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.
-
virtual return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) override
Read the current state values from the hardware.
The data readings from the physical hardware has to be updated and reflected accordingly in the exported state interfaces. That is, the data pointed by the interfaces shall be updated.
- Parameters:
time – [in] The time at the start of this control loop iteration
period – [in] The measured time taken by the last control loop iteration
- Returns:
return_type::OK if the read was successful, return_type::ERROR otherwise.
-
inline virtual return_type write(const rclcpp::Time&, const rclcpp::Duration&) override
Write the current command values to the hardware.
The physical hardware shall be updated with the latest value from the exported command interfaces.
- Parameters:
time – [in] The time at the start of this control loop iteration
period – [in] The measured time taken by the last control loop iteration
- Returns:
return_type::OK if the read was successful, return_type::ERROR otherwise.
Protected Attributes
-
const std::vector<std::string> standard_interfaces_ = {hardware_interface::HW_IF_POSITION, hardware_interface::HW_IF_VELOCITY, hardware_interface::HW_IF_ACCELERATION, hardware_interface::HW_IF_EFFORT}
Use standard interfaces for joints because they are relevant for dynamic behavior.
By splitting the standard interfaces from other type, the users are able to inherit this class and simply create small “simulation” with desired dynamic behavior. The advantage over using Gazebo is that enables “quick & dirty” tests of robot’s URDF and controllers.
-
std::vector<std::string> skip_interfaces_
-
std::vector<std::string> other_interfaces_
-
std::vector<std::string> sensor_interfaces_
-
std::vector<std::string> gpio_mock_interfaces_
-
virtual CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams ¶ms) override