ros2_control - rolling
|
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. | |
unsigned int | rw_rate |
Component's read and write rates in Hz. | |
bool | is_async |
Component is async. | |
int | thread_priority |
Async thread priority. | |
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< ComponentInfo > | joints |
std::vector< MimicJoint > | mimic_joints |
std::vector< ComponentInfo > | sensors |
std::vector< ComponentInfo > | gpios |
std::vector< TransmissionInfo > | transmissions |
std::string | original_xml |
std::unordered_map< std::string, joint_limits::JointLimits > | limits |
std::unordered_map< std::string, joint_limits::SoftJointLimits > | soft_limits |
This structure stores information about hardware defined in a robot's URDF.
std::vector<ComponentInfo> hardware_interface::HardwareInfo::gpios |
Vector of GPIOs provided by the hardware. Optional for any hardware components.
std::vector<ComponentInfo> hardware_interface::HardwareInfo::joints |
std::unordered_map<std::string, joint_limits::JointLimits> hardware_interface::HardwareInfo::limits |
The URDF parsed limits of the hardware components joint command interfaces
std::vector<MimicJoint> hardware_interface::HardwareInfo::mimic_joints |
Vector of mimic joints.
std::string hardware_interface::HardwareInfo::original_xml |
The XML contents prior to parsing
std::vector<ComponentInfo> hardware_interface::HardwareInfo::sensors |
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.
std::vector<TransmissionInfo> hardware_interface::HardwareInfo::transmissions |