Class for loading transmissions from a URDF description into ros_control interfaces. More...
#include <transmission_interface_loader.h>
Public Member Functions | |
TransmissionLoaderData * | getData () |
bool | load (const std::string &urdf) |
Load all transmissions in a URDF. More... | |
bool | load (const std::vector< TransmissionInfo > &transmission_info_vec) |
Load all transmissions contained in a vector of TransmissionInfo instances. More... | |
bool | load (const TransmissionInfo &transmission_info) |
Load a single transmission. More... | |
TransmissionInterfaceLoader (hardware_interface::RobotHW *robot_hw, RobotTransmissions *robot_transmissions) | |
Private Types | |
typedef pluginlib::ClassLoader< RequisiteProvider > | RequisiteProviderClassLoader |
typedef std::shared_ptr< RequisiteProviderClassLoader > | RequisiteProviderClassLoaderPtr |
typedef std::shared_ptr< RequisiteProvider > | RequisiteProviderPtr |
typedef pluginlib::ClassLoader< TransmissionLoader > | TransmissionClassLoader |
typedef std::shared_ptr< TransmissionClassLoader > | TransmissionClassLoaderPtr |
Class for loading transmissions from a URDF description into ros_control interfaces.
This is the entry point for automatic transmission parsing. An instance of this class is initialized with pointers to hardware and transmission abstraction interfaces, and calling the load()
methods populates these interfaces.
The input information needed for automatically loading transmissions are:
load()
methods, e.g., a URDF description).RobotHW
instance (provided in the constructor) already populated with the robot's actuator interfaces.The output after successful transmission loading is:
RobotHW
instance (provided in the constructor) to which joint interfaces have been added.RobotTransmissions
instance (provided in the constructor) to which transmission interfaces have been added.Important note: This class is stateful, and stores internally the raw data of the generated joint interfaces, so keep instances alive as long as these interfaces are used.
Definition at line 317 of file transmission_interface_loader.h.
|
private |
Definition at line 362 of file transmission_interface_loader.h.
|
private |
Definition at line 363 of file transmission_interface_loader.h.
|
private |
Definition at line 365 of file transmission_interface_loader.h.
|
private |
Definition at line 360 of file transmission_interface_loader.h.
|
private |
Definition at line 361 of file transmission_interface_loader.h.
transmission_interface::TransmissionInterfaceLoader::TransmissionInterfaceLoader | ( | hardware_interface::RobotHW * | robot_hw, |
RobotTransmissions * | robot_transmissions | ||
) |
robot_hw | Robot hardware abstraction already populated with actuator interfaces. |
robot_transmissions | Robot transmissions abstraction. |
Definition at line 89 of file transmission_interface_loader.cpp.
|
inline |
Definition at line 357 of file transmission_interface_loader.h.
bool transmission_interface::TransmissionInterfaceLoader::load | ( | const std::string & | urdf | ) |
Load all transmissions in a URDF.
This method adds new joint and transmission interfaces to the RobotHW
and RobotTransmissions
instances passed in the constructor, respectively.
urdf | Robot description containing a transmission specification. |
Definition at line 110 of file transmission_interface_loader.cpp.
bool transmission_interface::TransmissionInterfaceLoader::load | ( | const std::vector< TransmissionInfo > & | transmission_info_vec | ) |
Load all transmissions contained in a vector of TransmissionInfo
instances.
This method adds new joint and transmission interfaces to the RobotHW
and RobotTransmissions
instances passed in the constructor, respectively.
transmission_info_vec | Vector of TransmissionInfo instances. |
Definition at line 125 of file transmission_interface_loader.cpp.
bool transmission_interface::TransmissionInterfaceLoader::load | ( | const TransmissionInfo & | transmission_info | ) |
Load a single transmission.
This method adds new joint and transmission interfaces to the RobotHW
and RobotTransmissions
instances passed in the constructor, respectively.
transmission_info | Specification of a single transmission. |
Definition at line 134 of file transmission_interface_loader.cpp.
|
private |
Definition at line 374 of file transmission_interface_loader.h.
|
private |
Definition at line 368 of file transmission_interface_loader.h.
|
private |
Definition at line 371 of file transmission_interface_loader.h.
|
private |
Definition at line 372 of file transmission_interface_loader.h.
|
private |
Definition at line 367 of file transmission_interface_loader.h.