Public Member Functions | Private Types | Private Attributes
transmission_interface::TransmissionInterfaceLoader Class Reference

Class for loading transmissions from a URDF description into ros_control interfaces. More...

#include <transmission_interface_loader.h>

List of all members.

Public Member Functions

TransmissionLoaderDatagetData ()
bool load (const std::string &urdf)
 Load all transmissions in a URDF.
bool load (const std::vector< TransmissionInfo > &transmission_info_vec)
 Load all transmissions contained in a vector of TransmissionInfo instances.
bool load (const TransmissionInfo &transmission_info)
 Load a single transmission.
 TransmissionInterfaceLoader (hardware_interface::RobotHW *robot_hw, RobotTransmissions *robot_transmissions)

Private Types

typedef pluginlib::ClassLoader
< RequisiteProvider
RequisiteProviderClassLoader
typedef boost::shared_ptr
< RequisiteProviderClassLoader
RequisiteProviderClassLoaderPtr
typedef boost::shared_ptr
< RequisiteProvider
RequisiteProviderPtr
typedef pluginlib::ClassLoader
< TransmissionLoader
TransmissionClassLoader
typedef boost::shared_ptr
< TransmissionClassLoader
TransmissionClassLoaderPtr

Private Attributes

TransmissionLoaderData loader_data_
RequisiteProviderClassLoaderPtr req_provider_loader_
hardware_interface::RobotHWrobot_hw_ptr_
RobotTransmissionsrobot_transmissions_ptr_
TransmissionClassLoaderPtr transmission_class_loader_

Detailed Description

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:

The output after successful transmission loading is:

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.

 class FooRobot : public hardware_interface::RobotHW
 {
 public:
   void read(ros::Time time, ros::Duration period);
   void write(ros::Time time, ros::Duration period);

   bool init()
   {
     // Populate robot_hw with actuator interfaces (e.g., EffortActuatorInterface)
     // This is hardware-specific, and not detailed here
     // ...

     // Initialize transmission loader
     try
     {
       transmission_loader_.reset(new TransmissionInterfaceLoader(this, &robot_transmissions));
     }
     catch(const std::invalid_argument& ex)
     {
       ROS_ERROR_STREAM("Failed to create transmission interface loader. " << ex.what());
       return false;
     }
     catch(const pluginlib::LibraryLoadException& ex)
     {
       ROS_ERROR_STREAM("Failed to create transmission interface loader. " << ex.what());
       return false;
     }
     catch(...)
     {
       ROS_ERROR_STREAM("Failed to create transmission interface loader. ");
       return false;
     }

     std::string robot_description;
     // ...load URDF from parameter server or file

     // Perform actual transmission loading
     if (!transmission_loader_->load(robot_description)) {return false;}

    // We can now query for any of the created interfaces, for example:
    // robot_transmissions_.get<ActuatorToJointStateInterface>();
    // this->get<JointStateInterface>();

    return true;
  }

 private:
   RobotTransmissions robot_transmissions_;
   boost::scoped_ptr<TransmissionInterfaceLoader> transmission_loader_;

 };

Definition at line 355 of file transmission_interface_loader.h.


Member Typedef Documentation

Definition at line 400 of file transmission_interface_loader.h.

Definition at line 401 of file transmission_interface_loader.h.

Definition at line 403 of file transmission_interface_loader.h.

Definition at line 398 of file transmission_interface_loader.h.

Definition at line 399 of file transmission_interface_loader.h.


Constructor & Destructor Documentation

Parameters:
robot_hwRobot hardware abstraction already populated with actuator interfaces.
robot_transmissionsRobot transmissions abstraction.

Definition at line 88 of file transmission_interface_loader.cpp.


Member Function Documentation

Definition at line 395 of file transmission_interface_loader.h.

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.

Parameters:
urdfRobot description containing a transmission specification.
Returns:
True if successful.

Definition at line 109 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.

Parameters:
transmission_info_vecVector of TransmissionInfo instances.
Returns:
True if successful.

Definition at line 124 of file transmission_interface_loader.cpp.

Load a single transmission.

This method adds new joint and transmission interfaces to the RobotHW and RobotTransmissions instances passed in the constructor, respectively.

Parameters:
transmission_infoSpecification of a single transmission.
Returns:
True if successful.

Definition at line 133 of file transmission_interface_loader.cpp.


Member Data Documentation

Definition at line 412 of file transmission_interface_loader.h.

Definition at line 406 of file transmission_interface_loader.h.

Definition at line 409 of file transmission_interface_loader.h.

Definition at line 410 of file transmission_interface_loader.h.

Definition at line 405 of file transmission_interface_loader.h.


The documentation for this class was generated from the following files:


transmission_interface
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Sat Jun 8 2019 20:09:32