Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00027
00028
00029 #include <ros/console.h>
00030
00031
00032 #include <pluginlib/class_list_macros.h>
00033
00034
00035 #include <hardware_interface/internal/demangle_symbol.h>
00036 #include <transmission_interface/simple_transmission.h>
00037 #include <transmission_interface/simple_transmission_loader.h>
00038
00039 namespace transmission_interface
00040 {
00041
00042 TransmissionSharedPtr SimpleTransmissionLoader::load(const TransmissionInfo& transmission_info)
00043 {
00044
00045 if (!checkActuatorDimension(transmission_info, 1)) {return TransmissionSharedPtr();}
00046 if (!checkJointDimension(transmission_info, 1)) {return TransmissionSharedPtr();}
00047
00048
00049 TiXmlElement actuator_el = loadXmlElement(transmission_info.actuators_.front().xml_element_);
00050 TiXmlElement joint_el = loadXmlElement(transmission_info.joints_.front().xml_element_);
00051
00052
00053 double reduction = 0.0;
00054 const ParseStatus reduction_status = getActuatorReduction(actuator_el,
00055 transmission_info.actuators_.front().name_,
00056 transmission_info.name_,
00057 true,
00058 reduction);
00059 if (reduction_status != SUCCESS) {return TransmissionSharedPtr();}
00060
00061
00062
00063 double joint_offset = 0.0;
00064 const ParseStatus joint_offset_status = getJointOffset(joint_el,
00065 transmission_info.joints_.front().name_,
00066 transmission_info.name_,
00067 false,
00068 joint_offset);
00069 if (joint_offset_status == BAD_TYPE) {return TransmissionSharedPtr();}
00070
00071
00072 try
00073 {
00074 TransmissionSharedPtr transmission(new SimpleTransmission(reduction, joint_offset));
00075 return transmission;
00076 }
00077 catch(const TransmissionInterfaceException& ex)
00078 {
00079 using hardware_interface::internal::demangledTypeName;
00080 ROS_ERROR_STREAM_NAMED("parser", "Failed to construct transmission '" << transmission_info.name_ << "' of type '" <<
00081 demangledTypeName<SimpleTransmission>()<< "'. " << ex.what());
00082 return TransmissionSharedPtr();
00083 }
00084 }
00085
00086 }
00087
00088 PLUGINLIB_EXPORT_CLASS(transmission_interface::SimpleTransmissionLoader,
00089 transmission_interface::TransmissionLoader)