JointCommandFactory.cpp
Go to the documentation of this file.
00001 #include "robodyn_mechanisms/JointCommandFactory.h"
00002 
00003 using namespace std;
00004 using namespace log4cpp;
00005 namespace RSU = StringUtilities;
00006 
00007 /***************************************************************************/
00017 JointCommandInterfacePtr JointCommandFactory::generate(const std::string& mechanism, const JointCommandInterface::IoFunctions& io)
00018 {
00019     JointCommandInterfacePtr interfacePtr;
00020 
00021     string jointType;
00022 
00023     if (io.getCommandFile.empty())
00024     {
00025         std::stringstream err;
00026         err << "generate requires 'io.getCommandFile' be non-empty.";
00027         NasaCommonLogging::Logger::log("gov.nasa.robonet.JointCommandFactory", log4cpp::Priority::FATAL, err.str());
00028         throw std::invalid_argument(err.str());
00029     }
00030 
00031     jointType = Private::getJointTypeFromParameterFile(io.getCommandFile(mechanism));
00032 
00033     if (jointType == "SeriesElastic")
00034     {
00035         interfacePtr = boost::make_shared<JointCommandSeriesElastic>(mechanism, io);
00036     }
00037 
00038     else if (jointType == "Rigid")
00039     {
00040         interfacePtr = boost::make_shared<JointCommandRigid>(mechanism, io);
00041     }
00042 
00043     else if (jointType == "Gripper")
00044     {
00045         interfacePtr = boost::make_shared<JointCommandGripper>(mechanism, io);
00046     }
00047 
00048     else if (jointType == "PrimaryFinger")
00049     {
00050         interfacePtr = boost::make_shared<JointCommandFinger<3, 4> >(mechanism, io);
00051     }
00052 
00053     else if (jointType == "SecondaryFingers")
00054     {
00055         // Both fingers are independent and have Hall sensors on their proximal
00056         // and medial joints. The distal joints are mechanically coupled and are
00057         // completely determined by the other two joints.
00058         interfacePtr = boost::make_shared<JointCommandFinger<2, 6> >(mechanism, io);
00059     }
00060 
00061     else if (jointType == "Thumb")
00062     {
00063         interfacePtr = boost::make_shared<JointCommandFinger<4> >(mechanism, io);
00064     }
00065 
00066     else if (jointType == "Wrist")
00067     {
00068         interfacePtr = boost::make_shared<JointCommandWrist>(mechanism, io);
00069     }
00070 
00071     else
00072     {
00073         stringstream err;
00074         err << "Unsupported joint type [" << jointType << "] found in CommandFile";
00075         NasaCommonLogging::Logger::log("gov.nasa.robonet.JointCommandFactory", Priority::ERROR, err.str());
00076         throw runtime_error(err.str());
00077     }
00078 
00079     return interfacePtr;
00080 }
00081 
00082 /***************************************************************************/
00091 std::string JointCommandFactory::Private::getJointTypeFromParameterFile(const std::string& parameterFile)
00092 {
00094     TiXmlDocument file(parameterFile.c_str());
00095     bool          loadOkay = file.LoadFile();
00096 
00097     if (!loadOkay)
00098     {
00099         stringstream err;
00100         err << "Failed to load file [" << parameterFile << "]";
00101         NasaCommonLogging::Logger::log("gov.nasa.robonet.JointCommandFactory", Priority::ERROR, err.str());
00102         throw runtime_error(err.str());
00103     }
00104 
00105     TiXmlHandle doc(&file);
00106     NasaCommonLogging::Logger::log("gov.nasa.robonet.JointCommandFactory", Priority::INFO, "CommandFile [" + parameterFile + "] successfully loaded.");
00107 
00108     // Check for ApiMap
00109     TiXmlHandle parametersElement(doc.FirstChildElement("ApiMap"));
00110 
00111     if (parametersElement.ToElement())
00112     {
00113         // Check for Properties
00114         TiXmlHandle propertiesElement(parametersElement.FirstChildElement("Properties"));
00115 
00116         if (propertiesElement.ToElement())
00117         {
00118             // Check for JointType
00119             if (propertiesElement.FirstChildElement("JointType").ToElement())
00120             {
00121                 return string(propertiesElement.FirstChildElement("JointType").ToElement()->Attribute("id"));
00122             }
00123             else
00124             {
00125                 stringstream err;
00126                 err << "The ApiMap file has no element named [JointType]";
00127                 NasaCommonLogging::Logger::log("gov.nasa.robonet.JointCommandFactory", Priority::ERROR, err.str());
00128                 throw runtime_error(err.str());
00129             }
00130         }
00131         else
00132         {
00133             stringstream err;
00134             err << "The file " << parameterFile << " has no element named [Properties]";
00135             NasaCommonLogging::Logger::log("gov.nasa.robonet.JointCommandFactory", Priority::ERROR, err.str());
00136             throw runtime_error(err.str());
00137         }
00138     }
00139     else
00140     {
00141         stringstream err;
00142         err << "The file " << parameterFile << " has no element named [ApiMap]";
00143         NasaCommonLogging::Logger::log("gov.nasa.robonet.JointCommandFactory", Priority::ERROR, err.str());
00144         throw runtime_error(err.str());
00145     }
00146 
00147     return string();
00148 }
00149 


robodyn_mechanisms
Author(s):
autogenerated on Thu Jun 6 2019 21:22:48