ros2_control - humble
Classes | Typedefs | Enumerations | Functions | Variables
hardware_interface Namespace Reference

Classes

class  Actuator
 
class  ActuatorInterface
 
struct  ControllerInfo
 Controller Information. More...
 
class  ReadOnlyHandle
 A handle used to get and set a value on a given interface. More...
 
class  ReadWriteHandle
 
class  StateInterface
 
class  CommandInterface
 
struct  HardwareComponentInfo
 Hardware Component Information. More...
 
struct  InterfaceInfo
 
struct  ComponentInfo
 
struct  JointInfo
 Contains semantic info about a given joint loaded from URDF for a transmission. More...
 
struct  ActuatorInfo
 Contains semantic info about a given actuator loaded from URDF for a transmission. More...
 
struct  TransmissionInfo
 Contains semantic info about a given transmission loaded from URDF. More...
 
struct  HardwareInfo
 This structure stores information about hardware defined in a robot's URDF. More...
 
class  LoanedCommandInterface
 
class  LoanedStateInterface
 
struct  HardwareReadWriteStatus
 
class  ResourceManager
 
class  Sensor
 
class  SensorInterface
 
class  System
 
class  SystemInterface
 
class  ResourceStorage
 

Typedefs

using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
 Virtual Class to implement when integrating a 1 DoF actuator into ros2_control. More...
 

Enumerations

enum class  return_type : std::uint8_t { OK = 0 , ERROR = 1 }
 

Functions

HARDWARE_INTERFACE_PUBLIC std::vector< HardwareInfoparse_control_resources_from_urdf (const std::string &urdf)
 Search XML snippet from URDF for information about a control component. More...
 
double stod (const std::string &s)
 Helper function to convert a std::string to double in a locale-independent way. More...
 
bool parse_bool (const std::string &bool_string)
 

Variables

constexpr char HW_IF_POSITION [] = "position"
 Constant defining position interface.
 
constexpr char HW_IF_VELOCITY [] = "velocity"
 Constant defining velocity interface.
 
constexpr char HW_IF_ACCELERATION [] = "acceleration"
 Constant defining acceleration interface.
 
constexpr char HW_IF_EFFORT [] = "effort"
 Constant defining effort interface.
 
auto trigger_and_print_hardware_state_transition
 

Detailed Description

Author
: Denis Stogl

Typedef Documentation

◆ CallbackReturn

typedef rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn hardware_interface::CallbackReturn

Virtual Class to implement when integrating a 1 DoF actuator into ros2_control.

Virtual Class to implement when integrating a complex system into ros2_control.

Virtual Class to implement when integrating a stand-alone sensor into ros2_control.

The typical examples are conveyors or motors.

Methods return values have type rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn with the following meaning:

Returns
CallbackReturn::SUCCESS method execution was successful.
CallbackReturn::FAILURE method execution has failed and and can be called again.
CallbackReturn::ERROR critical error has happened that should be managed in "on_error" method.

The hardware ends after each method in a state with the following meaning:

UNCONFIGURED (on_init, on_cleanup): Hardware is initialized but communication is not started and therefore no interface is available.

INACTIVE (on_configure, on_deactivate): Communication with the hardware is started and it is configured. States can be read and non-movement hardware interfaces commanded. Hardware interfaces for movement will NOT be available. Those interfaces are: HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_ACCELERATION, and HW_IF_EFFORT.

FINALIZED (on_shutdown): Hardware interface is ready for unloading/destruction. Allocated memory is cleaned up.

ACTIVE (on_activate): Power circuits of hardware are active and hardware can be moved, e.g., brakes are disabled. Command interfaces for movement are available and have to be accepted. Those interfaces are: HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_ACCELERATION, and HW_IF_EFFORT.

The typical examples are Force-Torque Sensor (FTS), Interial Measurement Unit (IMU).

Methods return values have type rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn with the following meaning:

Returns
CallbackReturn::SUCCESS method execution was successful.
CallbackReturn::FAILURE method execution has failed and and can be called again.
CallbackReturn::ERROR critical error has happened that should be managed in "on_error" method.

The hardware ends after each method in a state with the following meaning:

UNCONFIGURED (on_init, on_cleanup): Hardware is initialized but communication is not started and therefore no interface is available.

INACTIVE (on_configure, on_deactivate): Communication with the hardware is started and it is configured. States can be read and non-movement hardware interfaces commanded. Hardware interfaces for movement will NOT be available. Those interfaces are: HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_ACCELERATION, and HW_IF_EFFORT.

FINALIZED (on_shutdown): Hardware interface is ready for unloading/destruction. Allocated memory is cleaned up.

ACTIVE (on_activate): Power circuits of hardware are active and hardware can be moved, e.g., brakes are disabled. Command interfaces for movement are available and have to be accepted. Those interfaces are: HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_ACCELERATION, and HW_IF_EFFORT.

The common examples for these types of hardware are multi-joint systems with or without sensors such as industrial or humanoid robots.

Methods return values have type rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn with the following meaning:

Returns
CallbackReturn::SUCCESS method execution was successful.
CallbackReturn::FAILURE method execution has failed and and can be called again.
CallbackReturn::ERROR critical error has happened that should be managed in "on_error" method.

The hardware ends after each method in a state with the following meaning:

UNCONFIGURED (on_init, on_cleanup): Hardware is initialized but communication is not started and therefore no interface is available.

INACTIVE (on_configure, on_deactivate): Communication with the hardware is started and it is configured. States can be read and non-movement hardware interfaces commanded. Hardware interfaces for movement will NOT be available. Those interfaces are: HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_ACCELERATION, and HW_IF_EFFORT.

FINALIZED (on_shutdown): Hardware interface is ready for unloading/destruction. Allocated memory is cleaned up.

ACTIVE (on_activate): Power circuits of hardware are active and hardware can be moved, e.g., brakes are disabled. Command interfaces for movement are available and have to be accepted. Those interfaces are: HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_ACCELERATION, and HW_IF_EFFORT.

Function Documentation

◆ parse_control_resources_from_urdf()

std::vector< HardwareInfo > hardware_interface::parse_control_resources_from_urdf ( const std::string &  urdf)

Search XML snippet from URDF for information about a control component.

Parameters
[in]urdfstring with robot's URDF
Returns
vector filled with information about robot's control resources
Exceptions
std::runtime_errorif a robot attribute or tag is not found

◆ stod()

double hardware_interface::stod ( const std::string &  s)

Helper function to convert a std::string to double in a locale-independent way.

Exceptions
std::invalid_argumentif not a valid number from https://github.com/ros-planning/srdfdom/blob/ad17b8d25812f752c397a6011cec64aeff090c46/src/model.cpp#L53

Variable Documentation

◆ trigger_and_print_hardware_state_transition

auto hardware_interface::trigger_and_print_hardware_state_transition
Initial value:
=
[](
auto transition, const std::string transition_name, const std::string & hardware_name,
const lifecycle_msgs::msg::State::_id_type & target_state)
{
RCUTILS_LOG_INFO_NAMED(
"resource_manager", "'%s' hardware '%s' ", transition_name.c_str(), hardware_name.c_str());
const rclcpp_lifecycle::State new_state = transition();
bool result = new_state.id() == target_state;
if (result)
{
RCUTILS_LOG_INFO_NAMED(
"resource_manager", "Successful '%s' of hardware '%s'", transition_name.c_str(),
hardware_name.c_str());
}
else
{
RCUTILS_LOG_INFO_NAMED(
"resource_manager", "Failed to '%s' hardware '%s'", transition_name.c_str(),
hardware_name.c_str());
}
return result;
}