simple_transmission_loader.cpp
Go to the documentation of this file.
00001 
00002 // Copyright (C) 2013, PAL Robotics S.L.
00003 //
00004 // Redistribution and use in source and binary forms, with or without
00005 // modification, are permitted provided that the following conditions are met:
00006 //   * Redistributions of source code must retain the above copyright notice,
00007 //     this list of conditions and the following disclaimer.
00008 //   * Redistributions in binary form must reproduce the above copyright
00009 //     notice, this list of conditions and the following disclaimer in the
00010 //     documentation and/or other materials provided with the distribution.
00011 //   * Neither the name of PAL Robotics S.L. nor the names of its
00012 //     contributors may be used to endorse or promote products derived from
00013 //     this software without specific prior written permission.
00014 //
00015 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025 // POSSIBILITY OF SUCH DAMAGE.
00027 
00028 // ROS
00029 #include <ros/console.h>
00030 
00031 // Pluginlib
00032 #include <pluginlib/class_list_macros.h>
00033 
00034 // ros_control
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   // Transmission should contain only one actuator/joint
00045   if (!checkActuatorDimension(transmission_info, 1)) {return TransmissionSharedPtr();}
00046   if (!checkJointDimension(transmission_info,    1)) {return TransmissionSharedPtr();}
00047 
00048   // Parse actuator and joint xml elements
00049   TiXmlElement actuator_el = loadXmlElement(transmission_info.actuators_.front().xml_element_);
00050   TiXmlElement joint_el    = loadXmlElement(transmission_info.joints_.front().xml_element_);
00051 
00052   // Parse required mechanical reduction
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, // Required
00058                                                             reduction);
00059   if (reduction_status != SUCCESS) {return TransmissionSharedPtr();}
00060 
00061   // Parse optional joint offset. Even though it's optional --and to avoid surprises-- we fail if the element is
00062   // specified but is of the wrong type
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, // Optional
00068                                                          joint_offset);
00069   if (joint_offset_status == BAD_TYPE) {return TransmissionSharedPtr();}
00070 
00071   // Transmission instance
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 } // namespace
00087 
00088 PLUGINLIB_EXPORT_CLASS(transmission_interface::SimpleTransmissionLoader,
00089                        transmission_interface::TransmissionLoader)


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