Class GenericSystem

Inheritance Relationships

Base Type

Class Documentation

class GenericSystem : public hardware_interface::SystemInterface

Public Functions

virtual CallbackReturn on_init(const hardware_interface::HardwareInfo &info) override

Initialization of the hardware interface from data parsed from the robot’s URDF.

Parameters:

hardware_info[in] structure with data from URDF.

Returns:

CallbackReturn::SUCCESS if required data are provided and can be parsed.

Returns:

CallbackReturn::ERROR if any error happens or data are missing.

virtual std::vector<hardware_interface::StateInterface> export_state_interfaces() override

Exports all state interfaces for this hardware interface.

The state interfaces have to be created and transferred according to the hardware info passed in for the configuration.

Note the ownership over the state interfaces is transferred to the caller.

Returns:

vector of state interfaces

virtual std::vector<hardware_interface::CommandInterface> export_command_interfaces() override

Exports all command interfaces for this hardware interface.

The command interfaces have to be created and transferred according to the hardware info passed in for the configuration.

Note the ownership over the state interfaces is transferred to the caller.

Returns:

vector of command interfaces

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.

Note

All starting and stopping interface keys are passed to all components, so the function should return return_type::OK by default when given interface keys not relevant for this component.

Parameters:
  • start_interfaces[in] vector of string identifiers for the command interfaces starting.

  • stop_interfaces[in] vector of string identifiers for the command interfacs 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.

Note

All starting and stopping interface keys are passed to all components, so the function should return return_type::OK by default when given interface keys not relevant for this component.

Parameters:
  • start_interfaces[in] vector of string identifiers for the command interfaces starting.

  • stop_interfaces[in] vector of string identifiers for the command interfacs 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 actuator.

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 actuator.

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::vector<double>> joint_commands_

The size of this vector is (standard_interfaces_.size() x nr_joints)

std::vector<std::vector<double>> joint_states_
std::vector<std::string> other_interfaces_
std::vector<std::vector<double>> other_commands_

The size of this vector is (other_interfaces_.size() x nr_joints)

std::vector<std::vector<double>> other_states_
std::vector<std::string> sensor_interfaces_
std::vector<std::vector<double>> sensor_mock_commands_

The size of this vector is (sensor_interfaces_.size() x nr_joints)

std::vector<std::vector<double>> sensor_states_
std::vector<std::string> gpio_interfaces_
std::vector<std::vector<double>> gpio_mock_commands_

The size of this vector is (gpio_interfaces_.size() x nr_joints)

std::vector<std::vector<double>> gpio_commands_
std::vector<std::vector<double>> gpio_states_