ros2_control - rolling
Public Attributes | List of all members
hardware_interface::HardwareInfo Struct Reference

This structure stores information about hardware defined in a robot's URDF. More...

#include <hardware_info.hpp>

Public Attributes

std::string name
 Name of the hardware.
 
std::string type
 Type of the hardware: actuator, sensor or system.
 
std::string group
 Hardware group to which the hardware belongs.
 
bool is_async
 Component is async.
 
std::string hardware_plugin_name
 Name of the pluginlib plugin of the hardware that will be loaded.
 
std::unordered_map< std::string, std::string > hardware_parameters
 (Optional) Key-value pairs for hardware parameters.
 
std::vector< ComponentInfojoints
 
std::vector< MimicJointmimic_joints
 
std::vector< ComponentInfosensors
 
std::vector< ComponentInfogpios
 
std::vector< TransmissionInfotransmissions
 
std::string original_xml
 
std::unordered_map< std::string, joint_limits::JointLimitslimits
 
std::unordered_map< std::string, joint_limits::SoftJointLimitssoft_limits
 

Detailed Description

This structure stores information about hardware defined in a robot's URDF.

Member Data Documentation

◆ gpios

std::vector<ComponentInfo> hardware_interface::HardwareInfo::gpios

Vector of GPIOs provided by the hardware. Optional for any hardware components.

◆ joints

std::vector<ComponentInfo> hardware_interface::HardwareInfo::joints

Vector of joints provided by the hardware. Required for Actuator and System Hardware.

◆ limits

std::unordered_map<std::string, joint_limits::JointLimits> hardware_interface::HardwareInfo::limits

The URDF parsed limits of the hardware components joint command interfaces

◆ mimic_joints

std::vector<MimicJoint> hardware_interface::HardwareInfo::mimic_joints

Vector of mimic joints.

◆ original_xml

std::string hardware_interface::HardwareInfo::original_xml

The XML contents prior to parsing

◆ sensors

std::vector<ComponentInfo> hardware_interface::HardwareInfo::sensors

Vector of sensors provided by the hardware. Required for Sensor and optional for System Hardware.

◆ soft_limits

std::unordered_map<std::string, joint_limits::SoftJointLimits> hardware_interface::HardwareInfo::soft_limits

Map of software joint limits used for clamping the command where the key is the joint name. Optional If not specified or less restrictive than the JointLimits uses the previous JointLimits.

◆ transmissions

std::vector<TransmissionInfo> hardware_interface::HardwareInfo::transmissions

Vector of transmissions to calculate ratio between joints and physical actuators. Optional for Actuator and System Hardware.


The documentation for this struct was generated from the following file: