Class for loading transmissions from a URDF description into ros_control interfaces. More...
#include <transmission_interface_loader.h>
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.
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.
typedef pluginlib::ClassLoader<RequisiteProvider> transmission_interface::TransmissionInterfaceLoader::RequisiteProviderClassLoader [private] |
Definition at line 400 of file transmission_interface_loader.h.
typedef boost::shared_ptr<RequisiteProviderClassLoader> transmission_interface::TransmissionInterfaceLoader::RequisiteProviderClassLoaderPtr [private] |
Definition at line 401 of file transmission_interface_loader.h.
typedef boost::shared_ptr<RequisiteProvider> transmission_interface::TransmissionInterfaceLoader::RequisiteProviderPtr [private] |
Definition at line 403 of file transmission_interface_loader.h.
typedef pluginlib::ClassLoader<TransmissionLoader> transmission_interface::TransmissionInterfaceLoader::TransmissionClassLoader [private] |
Definition at line 398 of file transmission_interface_loader.h.
typedef boost::shared_ptr<TransmissionClassLoader> transmission_interface::TransmissionInterfaceLoader::TransmissionClassLoaderPtr [private] |
Definition at line 399 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 88 of file transmission_interface_loader.cpp.
Definition at line 395 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 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.
transmission_info_vec | Vector of TransmissionInfo instances. |
Definition at line 124 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 133 of file transmission_interface_loader.cpp.
Definition at line 412 of file transmission_interface_loader.h.
RequisiteProviderClassLoaderPtr transmission_interface::TransmissionInterfaceLoader::req_provider_loader_ [private] |
Definition at line 406 of file transmission_interface_loader.h.
hardware_interface::RobotHW* transmission_interface::TransmissionInterfaceLoader::robot_hw_ptr_ [private] |
Definition at line 409 of file transmission_interface_loader.h.
RobotTransmissions* transmission_interface::TransmissionInterfaceLoader::robot_transmissions_ptr_ [private] |
Definition at line 410 of file transmission_interface_loader.h.
TransmissionClassLoaderPtr transmission_interface::TransmissionInterfaceLoader::transmission_class_loader_ [private] |
Definition at line 405 of file transmission_interface_loader.h.