add initial examples, replacing the 'Demos/Demos3'. Will make it work cross-platform, OpenGL3/OpenGL2 and add more examples to it.
This commit is contained in:
@@ -0,0 +1,137 @@
|
||||
/*********************************************************************
|
||||
* Software License Agreement (BSD License)
|
||||
*
|
||||
* Copyright (c) 2008, Willow Garage, Inc.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* * Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* * Redistributions in binary form must reproduce the above
|
||||
* copyright notice, this list of conditions and the following
|
||||
* disclaimer in the documentation and/or other materials provided
|
||||
* with the distribution.
|
||||
* * Neither the name of the Willow Garage nor the names of its
|
||||
* contributors may be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*********************************************************************/
|
||||
|
||||
/* Author: Wim Meeussen */
|
||||
|
||||
#include "urdf/urdfdom/urdf_parser/include/urdf_parser/urdf_parser.h"
|
||||
#include <iostream>
|
||||
#include <fstream>
|
||||
|
||||
using namespace urdf;
|
||||
|
||||
void printTree(my_shared_ptr<const Link> link,int level = 0)
|
||||
{
|
||||
level+=2;
|
||||
int count = 0;
|
||||
for (std::vector<my_shared_ptr<Link> >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++)
|
||||
{
|
||||
if (*child)
|
||||
{
|
||||
for(int j=0;j<level;j++) std::cout << " "; //indent
|
||||
std::cout << "child(" << (count++)+1 << "): " << (*child)->name << std::endl;
|
||||
// first grandchild
|
||||
printTree(*child,level);
|
||||
}
|
||||
else
|
||||
{
|
||||
for(int j=0;j<level;j++) std::cout << " "; //indent
|
||||
std::cout << "root link: " << link->name << " has a null child!" << *child << std::endl;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
#define MSTRINGIFY(A) #A
|
||||
|
||||
|
||||
const char* urdf_char = MSTRINGIFY(
|
||||
<robot name="test_robot">
|
||||
<link name="link1" />
|
||||
<link name="link2" />
|
||||
<link name="link3" />
|
||||
<link name="link4" />
|
||||
|
||||
<joint name="joint1" type="continuous">
|
||||
<parent link="link1"/>
|
||||
<child link="link2"/>
|
||||
</joint>
|
||||
|
||||
<joint name="joint2" type="continuous">
|
||||
<parent link="link1"/>
|
||||
<child link="link3"/>
|
||||
</joint>
|
||||
|
||||
<joint name="joint3" type="continuous">
|
||||
<parent link="link3"/>
|
||||
<child link="link4"/>
|
||||
</joint>
|
||||
</robot>);
|
||||
|
||||
|
||||
int main(int argc, char** argv)
|
||||
{
|
||||
|
||||
std::string xml_string;
|
||||
|
||||
if (argc < 2){
|
||||
std::cerr << "No URDF file name provided, using a dummy test URDF" << std::endl;
|
||||
|
||||
xml_string = std::string(urdf_char);
|
||||
|
||||
} else
|
||||
{
|
||||
|
||||
|
||||
std::fstream xml_file(argv[1], std::fstream::in);
|
||||
while ( xml_file.good() )
|
||||
{
|
||||
std::string line;
|
||||
std::getline( xml_file, line);
|
||||
xml_string += (line + "\n");
|
||||
}
|
||||
xml_file.close();
|
||||
}
|
||||
|
||||
my_shared_ptr<ModelInterface> robot = parseURDF(xml_string);
|
||||
if (!robot){
|
||||
std::cerr << "ERROR: Model Parsing the xml failed" << std::endl;
|
||||
return -1;
|
||||
}
|
||||
std::cout << "robot name is: " << robot->getName() << std::endl;
|
||||
|
||||
// get info from parser
|
||||
std::cout << "---------- Successfully Parsed XML ---------------" << std::endl;
|
||||
// get root link
|
||||
my_shared_ptr<const Link> root_link=robot->getRoot();
|
||||
if (!root_link) return -1;
|
||||
|
||||
std::cout << "root Link: " << root_link->name << " has " << root_link->child_links.size() << " child(ren)" << std::endl;
|
||||
|
||||
|
||||
// print entire tree
|
||||
printTree(root_link);
|
||||
return 0;
|
||||
}
|
||||
|
||||
579
examples/ThirdPartyLibs/urdf/urdfdom/urdf_parser/src/joint.cpp
Normal file
579
examples/ThirdPartyLibs/urdf/urdfdom/urdf_parser/src/joint.cpp
Normal file
@@ -0,0 +1,579 @@
|
||||
/*********************************************************************
|
||||
* Software Ligcense Agreement (BSD License)
|
||||
*
|
||||
* Copyright (c) 2008, Willow Garage, Inc.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* * Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* * Redistributions in binary form must reproduce the above
|
||||
* copyright notice, this list of conditions and the following
|
||||
* disclaimer in the documentation and/or other materials provided
|
||||
* with the distribution.
|
||||
* * Neither the name of the Willow Garage nor the names of its
|
||||
* contributors may be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*********************************************************************/
|
||||
|
||||
/* Author: John Hsu */
|
||||
|
||||
#include <sstream>
|
||||
#include <urdf/urdfdom_headers/urdf_model/include/urdf_model/joint.h>
|
||||
#ifdef URDF_USE_BOOST
|
||||
#include <boost/lexical_cast.hpp>
|
||||
#else
|
||||
#include <urdf/boost_replacement/lexical_cast.h>
|
||||
#endif
|
||||
#include <urdf/urdfdom_headers/urdf_model/include/urdf_model/pose.h>
|
||||
|
||||
#ifdef URDF_USE_CONSOLE_BRIDGE
|
||||
#include <console_bridge/console.h>
|
||||
#else
|
||||
#include "urdf/boost_replacement/printf_console.h"
|
||||
#endif
|
||||
|
||||
#include <tinyxml/tinyxml.h>
|
||||
#include <urdf/urdfdom/urdf_parser/include/urdf_parser/urdf_parser.h>
|
||||
|
||||
namespace urdf{
|
||||
|
||||
bool parsePose(Pose &pose, TiXmlElement* xml);
|
||||
|
||||
bool parseJointDynamics(JointDynamics &jd, TiXmlElement* config)
|
||||
{
|
||||
jd.clear();
|
||||
|
||||
// Get joint damping
|
||||
const char* damping_str = config->Attribute("damping");
|
||||
if (damping_str == NULL){
|
||||
logDebug("urdfdom.joint_dynamics: no damping, defaults to 0");
|
||||
jd.damping = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
try
|
||||
{
|
||||
jd.damping = boost::lexical_cast<double>(damping_str);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("damping value (%s) is not a float: %s",damping_str, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// Get joint friction
|
||||
const char* friction_str = config->Attribute("friction");
|
||||
if (friction_str == NULL){
|
||||
logDebug("urdfdom.joint_dynamics: no friction, defaults to 0");
|
||||
jd.friction = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
try
|
||||
{
|
||||
jd.friction = boost::lexical_cast<double>(friction_str);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("friction value (%s) is not a float: %s",friction_str, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
if (damping_str == NULL && friction_str == NULL)
|
||||
{
|
||||
logError("joint dynamics element specified with no damping and no friction");
|
||||
return false;
|
||||
}
|
||||
else{
|
||||
logDebug("urdfdom.joint_dynamics: damping %f and friction %f", jd.damping, jd.friction);
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
bool parseJointLimits(JointLimits &jl, TiXmlElement* config)
|
||||
{
|
||||
jl.clear();
|
||||
|
||||
// Get lower joint limit
|
||||
const char* lower_str = config->Attribute("lower");
|
||||
if (lower_str == NULL){
|
||||
logDebug("urdfdom.joint_limit: no lower, defaults to 0");
|
||||
jl.lower = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
try
|
||||
{
|
||||
jl.lower = boost::lexical_cast<double>(lower_str);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("lower value (%s) is not a float: %s", lower_str, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// Get upper joint limit
|
||||
const char* upper_str = config->Attribute("upper");
|
||||
if (upper_str == NULL){
|
||||
logDebug("urdfdom.joint_limit: no upper, , defaults to 0");
|
||||
jl.upper = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
try
|
||||
{
|
||||
jl.upper = boost::lexical_cast<double>(upper_str);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("upper value (%s) is not a float: %s",upper_str, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// Get joint effort limit
|
||||
const char* effort_str = config->Attribute("effort");
|
||||
if (effort_str == NULL){
|
||||
logError("joint limit: no effort");
|
||||
return false;
|
||||
}
|
||||
else
|
||||
{
|
||||
try
|
||||
{
|
||||
jl.effort = boost::lexical_cast<double>(effort_str);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("effort value (%s) is not a float: %s",effort_str, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// Get joint velocity limit
|
||||
const char* velocity_str = config->Attribute("velocity");
|
||||
if (velocity_str == NULL){
|
||||
logError("joint limit: no velocity");
|
||||
return false;
|
||||
}
|
||||
else
|
||||
{
|
||||
try
|
||||
{
|
||||
jl.velocity = boost::lexical_cast<double>(velocity_str);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("velocity value (%s) is not a float: %s",velocity_str, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool parseJointSafety(JointSafety &js, TiXmlElement* config)
|
||||
{
|
||||
js.clear();
|
||||
|
||||
// Get soft_lower_limit joint limit
|
||||
const char* soft_lower_limit_str = config->Attribute("soft_lower_limit");
|
||||
if (soft_lower_limit_str == NULL)
|
||||
{
|
||||
logDebug("urdfdom.joint_safety: no soft_lower_limit, using default value");
|
||||
js.soft_lower_limit = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
try
|
||||
{
|
||||
js.soft_lower_limit = boost::lexical_cast<double>(soft_lower_limit_str);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("soft_lower_limit value (%s) is not a float: %s",soft_lower_limit_str, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// Get soft_upper_limit joint limit
|
||||
const char* soft_upper_limit_str = config->Attribute("soft_upper_limit");
|
||||
if (soft_upper_limit_str == NULL)
|
||||
{
|
||||
logDebug("urdfdom.joint_safety: no soft_upper_limit, using default value");
|
||||
js.soft_upper_limit = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
try
|
||||
{
|
||||
js.soft_upper_limit = boost::lexical_cast<double>(soft_upper_limit_str);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("soft_upper_limit value (%s) is not a float: %s",soft_upper_limit_str, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// Get k_position_ safety "position" gain - not exactly position gain
|
||||
const char* k_position_str = config->Attribute("k_position");
|
||||
if (k_position_str == NULL)
|
||||
{
|
||||
logDebug("urdfdom.joint_safety: no k_position, using default value");
|
||||
js.k_position = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
try
|
||||
{
|
||||
js.k_position = boost::lexical_cast<double>(k_position_str);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("k_position value (%s) is not a float: %s",k_position_str, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
// Get k_velocity_ safety velocity gain
|
||||
const char* k_velocity_str = config->Attribute("k_velocity");
|
||||
if (k_velocity_str == NULL)
|
||||
{
|
||||
logError("joint safety: no k_velocity");
|
||||
return false;
|
||||
}
|
||||
else
|
||||
{
|
||||
try
|
||||
{
|
||||
js.k_velocity = boost::lexical_cast<double>(k_velocity_str);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("k_velocity value (%s) is not a float: %s",k_velocity_str, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool parseJointCalibration(JointCalibration &jc, TiXmlElement* config)
|
||||
{
|
||||
jc.clear();
|
||||
|
||||
// Get rising edge position
|
||||
const char* rising_position_str = config->Attribute("rising");
|
||||
if (rising_position_str == NULL)
|
||||
{
|
||||
logDebug("urdfdom.joint_calibration: no rising, using default value");
|
||||
jc.rising.reset(0);
|
||||
}
|
||||
else
|
||||
{
|
||||
try
|
||||
{
|
||||
jc.rising.reset(new double(boost::lexical_cast<double>(rising_position_str)));
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("risingvalue (%s) is not a float: %s",rising_position_str, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// Get falling edge position
|
||||
const char* falling_position_str = config->Attribute("falling");
|
||||
if (falling_position_str == NULL)
|
||||
{
|
||||
logDebug("urdfdom.joint_calibration: no falling, using default value");
|
||||
jc.falling.reset(0);
|
||||
}
|
||||
else
|
||||
{
|
||||
try
|
||||
{
|
||||
jc.falling.reset(new double(boost::lexical_cast<double>(falling_position_str)));
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("fallingvalue (%s) is not a float: %s",falling_position_str, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool parseJointMimic(JointMimic &jm, TiXmlElement* config)
|
||||
{
|
||||
jm.clear();
|
||||
|
||||
// Get name of joint to mimic
|
||||
const char* joint_name_str = config->Attribute("joint");
|
||||
|
||||
if (joint_name_str == NULL)
|
||||
{
|
||||
logError("joint mimic: no mimic joint specified");
|
||||
return false;
|
||||
}
|
||||
else
|
||||
jm.joint_name = joint_name_str;
|
||||
|
||||
// Get mimic multiplier
|
||||
const char* multiplier_str = config->Attribute("multiplier");
|
||||
|
||||
if (multiplier_str == NULL)
|
||||
{
|
||||
logDebug("urdfdom.joint_mimic: no multiplier, using default value of 1");
|
||||
jm.multiplier = 1;
|
||||
}
|
||||
else
|
||||
{
|
||||
try
|
||||
{
|
||||
jm.multiplier = boost::lexical_cast<double>(multiplier_str);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("multiplier value (%s) is not a float: %s",multiplier_str, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Get mimic offset
|
||||
const char* offset_str = config->Attribute("offset");
|
||||
if (offset_str == NULL)
|
||||
{
|
||||
logDebug("urdfdom.joint_mimic: no offset, using default value of 0");
|
||||
jm.offset = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
try
|
||||
{
|
||||
jm.offset = boost::lexical_cast<double>(offset_str);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("offset value (%s) is not a float: %s",offset_str, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool parseJoint(Joint &joint, TiXmlElement* config)
|
||||
{
|
||||
joint.clear();
|
||||
|
||||
// Get Joint Name
|
||||
const char *name = config->Attribute("name");
|
||||
if (!name)
|
||||
{
|
||||
logError("unnamed joint found");
|
||||
return false;
|
||||
}
|
||||
joint.name = name;
|
||||
|
||||
// Get transform from Parent Link to Joint Frame
|
||||
TiXmlElement *origin_xml = config->FirstChildElement("origin");
|
||||
if (!origin_xml)
|
||||
{
|
||||
logDebug("urdfdom: Joint [%s] missing origin tag under parent describing transform from Parent Link to Joint Frame, (using Identity transform).", joint.name.c_str());
|
||||
joint.parent_to_joint_origin_transform.clear();
|
||||
}
|
||||
else
|
||||
{
|
||||
if (!parsePose(joint.parent_to_joint_origin_transform, origin_xml))
|
||||
{
|
||||
joint.parent_to_joint_origin_transform.clear();
|
||||
logError("Malformed parent origin element for joint [%s]", joint.name.c_str());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// Get Parent Link
|
||||
TiXmlElement *parent_xml = config->FirstChildElement("parent");
|
||||
if (parent_xml)
|
||||
{
|
||||
const char *pname = parent_xml->Attribute("link");
|
||||
if (!pname)
|
||||
{
|
||||
logInform("no parent link name specified for Joint link [%s]. this might be the root?", joint.name.c_str());
|
||||
}
|
||||
else
|
||||
{
|
||||
joint.parent_link_name = std::string(pname);
|
||||
}
|
||||
}
|
||||
|
||||
// Get Child Link
|
||||
TiXmlElement *child_xml = config->FirstChildElement("child");
|
||||
if (child_xml)
|
||||
{
|
||||
const char *pname = child_xml->Attribute("link");
|
||||
if (!pname)
|
||||
{
|
||||
logInform("no child link name specified for Joint link [%s].", joint.name.c_str());
|
||||
}
|
||||
else
|
||||
{
|
||||
joint.child_link_name = std::string(pname);
|
||||
}
|
||||
}
|
||||
|
||||
// Get Joint type
|
||||
const char* type_char = config->Attribute("type");
|
||||
if (!type_char)
|
||||
{
|
||||
logError("joint [%s] has no type, check to see if it's a reference.", joint.name.c_str());
|
||||
return false;
|
||||
}
|
||||
|
||||
std::string type_str = type_char;
|
||||
if (type_str == "planar")
|
||||
joint.type = Joint::PLANAR;
|
||||
else if (type_str == "floating")
|
||||
joint.type = Joint::FLOATING;
|
||||
else if (type_str == "revolute")
|
||||
joint.type = Joint::REVOLUTE;
|
||||
else if (type_str == "continuous")
|
||||
joint.type = Joint::CONTINUOUS;
|
||||
else if (type_str == "prismatic")
|
||||
joint.type = Joint::PRISMATIC;
|
||||
else if (type_str == "fixed")
|
||||
joint.type = Joint::FIXED;
|
||||
else
|
||||
{
|
||||
logError("Joint [%s] has no known type [%s]", joint.name.c_str(), type_str.c_str());
|
||||
return false;
|
||||
}
|
||||
|
||||
// Get Joint Axis
|
||||
if (joint.type != Joint::FLOATING && joint.type != Joint::FIXED)
|
||||
{
|
||||
// axis
|
||||
TiXmlElement *axis_xml = config->FirstChildElement("axis");
|
||||
if (!axis_xml){
|
||||
logDebug("urdfdom: no axis elemement for Joint link [%s], defaulting to (1,0,0) axis", joint.name.c_str());
|
||||
joint.axis = Vector3(1.0, 0.0, 0.0);
|
||||
}
|
||||
else{
|
||||
if (axis_xml->Attribute("xyz")){
|
||||
try {
|
||||
joint.axis.init(axis_xml->Attribute("xyz"));
|
||||
}
|
||||
catch (ParseError &e) {
|
||||
joint.axis.clear();
|
||||
logError("Malformed axis element for joint [%s]: %s", joint.name.c_str(), e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Get limit
|
||||
TiXmlElement *limit_xml = config->FirstChildElement("limit");
|
||||
if (limit_xml)
|
||||
{
|
||||
joint.limits.reset(new JointLimits());
|
||||
if (!parseJointLimits(*joint.limits, limit_xml))
|
||||
{
|
||||
logError("Could not parse limit element for joint [%s]", joint.name.c_str());
|
||||
joint.limits.reset(0);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
else if (joint.type == Joint::REVOLUTE)
|
||||
{
|
||||
logError("Joint [%s] is of type REVOLUTE but it does not specify limits", joint.name.c_str());
|
||||
return false;
|
||||
}
|
||||
else if (joint.type == Joint::PRISMATIC)
|
||||
{
|
||||
logError("Joint [%s] is of type PRISMATIC without limits", joint.name.c_str());
|
||||
return false;
|
||||
}
|
||||
|
||||
// Get safety
|
||||
TiXmlElement *safety_xml = config->FirstChildElement("safety_controller");
|
||||
if (safety_xml)
|
||||
{
|
||||
joint.safety.reset(new JointSafety());
|
||||
if (!parseJointSafety(*joint.safety, safety_xml))
|
||||
{
|
||||
logError("Could not parse safety element for joint [%s]", joint.name.c_str());
|
||||
joint.safety.reset(0);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// Get calibration
|
||||
TiXmlElement *calibration_xml = config->FirstChildElement("calibration");
|
||||
if (calibration_xml)
|
||||
{
|
||||
joint.calibration.reset(new JointCalibration());
|
||||
if (!parseJointCalibration(*joint.calibration, calibration_xml))
|
||||
{
|
||||
logError("Could not parse calibration element for joint [%s]", joint.name.c_str());
|
||||
joint.calibration.reset(0);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// Get Joint Mimic
|
||||
TiXmlElement *mimic_xml = config->FirstChildElement("mimic");
|
||||
if (mimic_xml)
|
||||
{
|
||||
joint.mimic.reset(new JointMimic());
|
||||
if (!parseJointMimic(*joint.mimic, mimic_xml))
|
||||
{
|
||||
logError("Could not parse mimic element for joint [%s]", joint.name.c_str());
|
||||
joint.mimic.reset(0);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// Get Dynamics
|
||||
TiXmlElement *prop_xml = config->FirstChildElement("dynamics");
|
||||
if (prop_xml)
|
||||
{
|
||||
joint.dynamics.reset(new JointDynamics());
|
||||
if (!parseJointDynamics(*joint.dynamics, prop_xml))
|
||||
{
|
||||
logError("Could not parse joint_dynamics element for joint [%s]", joint.name.c_str());
|
||||
joint.dynamics.reset(0);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
}
|
||||
505
examples/ThirdPartyLibs/urdf/urdfdom/urdf_parser/src/link.cpp
Normal file
505
examples/ThirdPartyLibs/urdf/urdfdom/urdf_parser/src/link.cpp
Normal file
@@ -0,0 +1,505 @@
|
||||
/*********************************************************************
|
||||
* Software License Agreement (BSD License)
|
||||
*
|
||||
* Copyright (c) 2008, Willow Garage, Inc.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* * Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* * Redistributions in binary form must reproduce the above
|
||||
* copyright notice, this list of conditions and the following
|
||||
* disclaimer in the documentation and/or other materials provided
|
||||
* with the distribution.
|
||||
* * Neither the name of the Willow Garage nor the names of its
|
||||
* contributors may be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*********************************************************************/
|
||||
|
||||
/* Author: Wim Meeussen */
|
||||
|
||||
|
||||
#include <urdf/urdfdom/urdf_parser/include/urdf_parser/urdf_parser.h>
|
||||
#include <urdf/urdfdom_headers/urdf_model/include/urdf_model/link.h>
|
||||
//#include <fstream>
|
||||
//#include <sstream>
|
||||
#ifdef URDF_USE_BOOST
|
||||
#include <boost/lexical_cast.hpp>
|
||||
#else
|
||||
#include <urdf/boost_replacement/lexical_cast.h>
|
||||
#endif
|
||||
|
||||
#include <algorithm>
|
||||
#include <tinyxml/tinyxml.h>
|
||||
#ifdef URDF_USE_CONSOLE_BRIDGE
|
||||
#include <console_bridge/console.h>
|
||||
#else
|
||||
#include "urdf/boost_replacement/printf_console.h"
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
namespace urdf{
|
||||
|
||||
bool parsePose(Pose &pose, TiXmlElement* xml);
|
||||
|
||||
bool parseMaterial(Material &material, TiXmlElement *config, bool only_name_is_ok)
|
||||
{
|
||||
bool has_rgb = false;
|
||||
bool has_filename = false;
|
||||
|
||||
material.clear();
|
||||
|
||||
if (!config->Attribute("name"))
|
||||
{
|
||||
logError("Material must contain a name attribute");
|
||||
return false;
|
||||
}
|
||||
|
||||
material.name = config->Attribute("name");
|
||||
|
||||
// texture
|
||||
TiXmlElement *t = config->FirstChildElement("texture");
|
||||
if (t)
|
||||
{
|
||||
if (t->Attribute("filename"))
|
||||
{
|
||||
material.texture_filename = t->Attribute("filename");
|
||||
has_filename = true;
|
||||
}
|
||||
}
|
||||
|
||||
// color
|
||||
TiXmlElement *c = config->FirstChildElement("color");
|
||||
if (c)
|
||||
{
|
||||
if (c->Attribute("rgba")) {
|
||||
|
||||
try {
|
||||
material.color.init(c->Attribute("rgba"));
|
||||
has_rgb = true;
|
||||
}
|
||||
catch (ParseError &e) {
|
||||
material.color.clear();
|
||||
logError(std::string("Material [" + material.name + "] has malformed color rgba values: " + e.what()).c_str());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (!has_rgb && !has_filename) {
|
||||
if (!only_name_is_ok) // no need for an error if only name is ok
|
||||
{
|
||||
if (!has_rgb) logError(std::string("Material ["+material.name+"] color has no rgba").c_str());
|
||||
if (!has_filename) logError(std::string("Material ["+material.name+"] not defined in file").c_str());
|
||||
}
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
bool parseSphere(Sphere &s, TiXmlElement *c)
|
||||
{
|
||||
s.clear();
|
||||
|
||||
s.type = Geometry::SPHERE;
|
||||
if (!c->Attribute("radius"))
|
||||
{
|
||||
logError("Sphere shape must have a radius attribute");
|
||||
return false;
|
||||
}
|
||||
|
||||
try
|
||||
{
|
||||
s.radius = boost::lexical_cast<double>(c->Attribute("radius"));
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
// std::stringstream stm;
|
||||
// stm << "radius [" << c->Attribute("radius") << "] is not a valid float: " << e.what();
|
||||
// logError(stm.str().c_str());
|
||||
logError("radius issue");
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool parseBox(Box &b, TiXmlElement *c)
|
||||
{
|
||||
b.clear();
|
||||
|
||||
b.type = Geometry::BOX;
|
||||
if (!c->Attribute("size"))
|
||||
{
|
||||
logError("Box shape has no size attribute");
|
||||
return false;
|
||||
}
|
||||
try
|
||||
{
|
||||
b.dim.init(c->Attribute("size"));
|
||||
}
|
||||
catch (ParseError &e)
|
||||
{
|
||||
b.dim.clear();
|
||||
logError(e.what());
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool parseCylinder(Cylinder &y, TiXmlElement *c)
|
||||
{
|
||||
y.clear();
|
||||
|
||||
y.type = Geometry::CYLINDER;
|
||||
if (!c->Attribute("length") ||
|
||||
!c->Attribute("radius"))
|
||||
{
|
||||
logError("Cylinder shape must have both length and radius attributes");
|
||||
return false;
|
||||
}
|
||||
|
||||
try
|
||||
{
|
||||
y.length = boost::lexical_cast<double>(c->Attribute("length"));
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
// std::stringstream stm;
|
||||
// stm << "length [" << c->Attribute("length") << "] is not a valid float";
|
||||
//logError(stm.str().c_str());
|
||||
logError("length");
|
||||
return false;
|
||||
}
|
||||
|
||||
try
|
||||
{
|
||||
y.radius = boost::lexical_cast<double>(c->Attribute("radius"));
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
// std::stringstream stm;
|
||||
// stm << "radius [" << c->Attribute("radius") << "] is not a valid float";
|
||||
//logError(stm.str().c_str());
|
||||
logError("radius");
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
bool parseMesh(Mesh &m, TiXmlElement *c)
|
||||
{
|
||||
m.clear();
|
||||
|
||||
m.type = Geometry::MESH;
|
||||
if (!c->Attribute("filename")) {
|
||||
logError("Mesh must contain a filename attribute");
|
||||
return false;
|
||||
}
|
||||
|
||||
m.filename = c->Attribute("filename");
|
||||
|
||||
if (c->Attribute("scale")) {
|
||||
try {
|
||||
m.scale.init(c->Attribute("scale"));
|
||||
}
|
||||
catch (ParseError &e) {
|
||||
m.scale.clear();
|
||||
logError("Mesh scale was specified, but could not be parsed: %s", e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
m.scale.x = m.scale.y = m.scale.z = 1;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
my_shared_ptr<Geometry> parseGeometry(TiXmlElement *g)
|
||||
{
|
||||
my_shared_ptr<Geometry> geom;
|
||||
if (!g) return geom;
|
||||
|
||||
TiXmlElement *shape = g->FirstChildElement();
|
||||
if (!shape)
|
||||
{
|
||||
logError("Geometry tag contains no child element.");
|
||||
return geom;
|
||||
}
|
||||
|
||||
const std::string type_name = shape->ValueTStr().c_str();
|
||||
if (type_name == "sphere")
|
||||
{
|
||||
Sphere *s = new Sphere();
|
||||
geom.reset(s);
|
||||
if (parseSphere(*s, shape))
|
||||
return geom;
|
||||
}
|
||||
else if (type_name == "box")
|
||||
{
|
||||
Box *b = new Box();
|
||||
geom.reset(b);
|
||||
if (parseBox(*b, shape))
|
||||
return geom;
|
||||
}
|
||||
else if (type_name == "cylinder")
|
||||
{
|
||||
Cylinder *c = new Cylinder();
|
||||
geom.reset(c);
|
||||
if (parseCylinder(*c, shape))
|
||||
return geom;
|
||||
}
|
||||
else if (type_name == "mesh")
|
||||
{
|
||||
Mesh *m = new Mesh();
|
||||
geom.reset(m);
|
||||
if (parseMesh(*m, shape))
|
||||
return geom;
|
||||
}
|
||||
else
|
||||
{
|
||||
logError("Unknown geometry type '%s'", type_name.c_str());
|
||||
return geom;
|
||||
}
|
||||
|
||||
return my_shared_ptr<Geometry>();
|
||||
}
|
||||
|
||||
bool parseInertial(Inertial &i, TiXmlElement *config)
|
||||
{
|
||||
i.clear();
|
||||
|
||||
// Origin
|
||||
TiXmlElement *o = config->FirstChildElement("origin");
|
||||
if (o)
|
||||
{
|
||||
if (!parsePose(i.origin, o))
|
||||
return false;
|
||||
}
|
||||
|
||||
TiXmlElement *mass_xml = config->FirstChildElement("mass");
|
||||
if (!mass_xml)
|
||||
{
|
||||
logError("Inertial element must have a mass element");
|
||||
return false;
|
||||
}
|
||||
if (!mass_xml->Attribute("value"))
|
||||
{
|
||||
logError("Inertial: mass element must have value attribute");
|
||||
return false;
|
||||
}
|
||||
|
||||
try
|
||||
{
|
||||
i.mass = boost::lexical_cast<double>(mass_xml->Attribute("value"));
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
// std::stringstream stm;
|
||||
// stm << "Inertial: mass [" << mass_xml->Attribute("value")
|
||||
// << "] is not a float";
|
||||
//logError(stm.str().c_str());
|
||||
logError("Inertial mass issue");
|
||||
return false;
|
||||
}
|
||||
|
||||
TiXmlElement *inertia_xml = config->FirstChildElement("inertia");
|
||||
if (!inertia_xml)
|
||||
{
|
||||
logError("Inertial element must have inertia element");
|
||||
return false;
|
||||
}
|
||||
if (!(inertia_xml->Attribute("ixx") && inertia_xml->Attribute("ixy") && inertia_xml->Attribute("ixz") &&
|
||||
inertia_xml->Attribute("iyy") && inertia_xml->Attribute("iyz") &&
|
||||
inertia_xml->Attribute("izz")))
|
||||
{
|
||||
logError("Inertial: inertia element must have ixx,ixy,ixz,iyy,iyz,izz attributes");
|
||||
return false;
|
||||
}
|
||||
try
|
||||
{
|
||||
i.ixx = boost::lexical_cast<double>(inertia_xml->Attribute("ixx"));
|
||||
i.ixy = boost::lexical_cast<double>(inertia_xml->Attribute("ixy"));
|
||||
i.ixz = boost::lexical_cast<double>(inertia_xml->Attribute("ixz"));
|
||||
i.iyy = boost::lexical_cast<double>(inertia_xml->Attribute("iyy"));
|
||||
i.iyz = boost::lexical_cast<double>(inertia_xml->Attribute("iyz"));
|
||||
i.izz = boost::lexical_cast<double>(inertia_xml->Attribute("izz"));
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
/* std::stringstream stm;
|
||||
stm << "Inertial: one of the inertia elements is not a valid double:"
|
||||
<< " ixx [" << inertia_xml->Attribute("ixx") << "]"
|
||||
<< " ixy [" << inertia_xml->Attribute("ixy") << "]"
|
||||
<< " ixz [" << inertia_xml->Attribute("ixz") << "]"
|
||||
<< " iyy [" << inertia_xml->Attribute("iyy") << "]"
|
||||
<< " iyz [" << inertia_xml->Attribute("iyz") << "]"
|
||||
<< " izz [" << inertia_xml->Attribute("izz") << "]";
|
||||
logError(stm.str().c_str());
|
||||
*/
|
||||
logError("Inertia error");
|
||||
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool parseVisual(Visual &vis, TiXmlElement *config)
|
||||
{
|
||||
vis.clear();
|
||||
|
||||
// Origin
|
||||
TiXmlElement *o = config->FirstChildElement("origin");
|
||||
if (o) {
|
||||
if (!parsePose(vis.origin, o))
|
||||
return false;
|
||||
}
|
||||
|
||||
// Geometry
|
||||
TiXmlElement *geom = config->FirstChildElement("geometry");
|
||||
vis.geometry = parseGeometry(geom);
|
||||
if (!vis.geometry)
|
||||
return false;
|
||||
|
||||
const char *name_char = config->Attribute("name");
|
||||
if (name_char)
|
||||
vis.name = name_char;
|
||||
|
||||
// Material
|
||||
TiXmlElement *mat = config->FirstChildElement("material");
|
||||
if (mat) {
|
||||
// get material name
|
||||
if (!mat->Attribute("name")) {
|
||||
logError("Visual material must contain a name attribute");
|
||||
return false;
|
||||
}
|
||||
vis.material_name = mat->Attribute("name");
|
||||
|
||||
// try to parse material element in place
|
||||
vis.material.reset(new Material());
|
||||
if (!parseMaterial(*vis.material, mat, true))
|
||||
{
|
||||
logDebug("urdfdom: material has only name, actual material definition may be in the model");
|
||||
}
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool parseCollision(Collision &col, TiXmlElement* config)
|
||||
{
|
||||
col.clear();
|
||||
|
||||
// Origin
|
||||
TiXmlElement *o = config->FirstChildElement("origin");
|
||||
if (o) {
|
||||
if (!parsePose(col.origin, o))
|
||||
return false;
|
||||
}
|
||||
|
||||
// Geometry
|
||||
TiXmlElement *geom = config->FirstChildElement("geometry");
|
||||
col.geometry = parseGeometry(geom);
|
||||
if (!col.geometry)
|
||||
return false;
|
||||
|
||||
const char *name_char = config->Attribute("name");
|
||||
if (name_char)
|
||||
col.name = name_char;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool parseLink(Link &link, TiXmlElement* config)
|
||||
{
|
||||
|
||||
link.clear();
|
||||
|
||||
const char *name_char = config->Attribute("name");
|
||||
if (!name_char)
|
||||
{
|
||||
logError("No name given for the link.");
|
||||
return false;
|
||||
}
|
||||
link.name = std::string(name_char);
|
||||
|
||||
// Inertial (optional)
|
||||
TiXmlElement *i = config->FirstChildElement("inertial");
|
||||
if (i)
|
||||
{
|
||||
link.inertial.reset(new Inertial());
|
||||
if (!parseInertial(*link.inertial, i))
|
||||
{
|
||||
logError("Could not parse inertial element for Link [%s]", link.name.c_str());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// Multiple Visuals (optional)
|
||||
for (TiXmlElement* vis_xml = config->FirstChildElement("visual"); vis_xml; vis_xml = vis_xml->NextSiblingElement("visual"))
|
||||
{
|
||||
|
||||
my_shared_ptr<Visual> vis;
|
||||
vis.reset(new Visual());
|
||||
if (parseVisual(*vis, vis_xml))
|
||||
{
|
||||
link.visual_array.push_back(vis);
|
||||
}
|
||||
else
|
||||
{
|
||||
vis.reset(0);
|
||||
logError("Could not parse visual element for Link [%s]", link.name.c_str());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// Visual (optional)
|
||||
// Assign the first visual to the .visual ptr, if it exists
|
||||
if (!link.visual_array.empty())
|
||||
link.visual = link.visual_array[0];
|
||||
|
||||
// Multiple Collisions (optional)
|
||||
for (TiXmlElement* col_xml = config->FirstChildElement("collision"); col_xml; col_xml = col_xml->NextSiblingElement("collision"))
|
||||
{
|
||||
my_shared_ptr<Collision> col;
|
||||
col.reset(new Collision());
|
||||
if (parseCollision(*col, col_xml))
|
||||
{
|
||||
link.collision_array.push_back(col);
|
||||
}
|
||||
else
|
||||
{
|
||||
col.reset(0);
|
||||
logError("Could not parse collision element for Link [%s]", link.name.c_str());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// Collision (optional)
|
||||
// Assign the first collision to the .collision ptr, if it exists
|
||||
if (!link.collision_array.empty())
|
||||
link.collision = link.collision_array[0];
|
||||
return true;
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
240
examples/ThirdPartyLibs/urdf/urdfdom/urdf_parser/src/model.cpp
Normal file
240
examples/ThirdPartyLibs/urdf/urdfdom/urdf_parser/src/model.cpp
Normal file
@@ -0,0 +1,240 @@
|
||||
/*********************************************************************
|
||||
* Software License Agreement (BSD License)
|
||||
*
|
||||
* Copyright (c) 2008, Willow Garage, Inc.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* * Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* * Redistributions in binary form must reproduce the above
|
||||
* copyright notice, this list of conditions and the following
|
||||
* disclaimer in the documentation and/or other materials provided
|
||||
* with the distribution.
|
||||
* * Neither the name of the Willow Garage nor the names of its
|
||||
* contributors may be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*********************************************************************/
|
||||
|
||||
/* Author: Wim Meeussen */
|
||||
//#include <boost/algorithm/string.hpp>
|
||||
#include <vector>
|
||||
#include "urdf/urdfdom/urdf_parser/include/urdf_parser/urdf_parser.h"
|
||||
#ifdef URDF_USE_CONSOLE_BRIDGE
|
||||
#include <console_bridge/console.h>
|
||||
#else
|
||||
#include "urdf/boost_replacement/printf_console.h"
|
||||
#endif
|
||||
|
||||
namespace urdf{
|
||||
|
||||
bool parseMaterial(Material &material, TiXmlElement *config, bool only_name_is_ok);
|
||||
bool parseLink(Link &link, TiXmlElement *config);
|
||||
bool parseJoint(Joint &joint, TiXmlElement *config);
|
||||
|
||||
|
||||
my_shared_ptr<ModelInterface> parseURDF(const std::string &xml_string)
|
||||
{
|
||||
my_shared_ptr<ModelInterface> model(new ModelInterface);
|
||||
model->clear();
|
||||
|
||||
TiXmlDocument xml_doc;
|
||||
xml_doc.Parse(xml_string.c_str());
|
||||
if (xml_doc.Error())
|
||||
{
|
||||
logError(xml_doc.ErrorDesc());
|
||||
xml_doc.ClearError();
|
||||
model.reset(0);
|
||||
return model;
|
||||
}
|
||||
|
||||
TiXmlElement *robot_xml = xml_doc.FirstChildElement("robot");
|
||||
if (!robot_xml)
|
||||
{
|
||||
logError("Could not find the 'robot' element in the xml file");
|
||||
model.reset(0);
|
||||
return model;
|
||||
}
|
||||
|
||||
// Get robot name
|
||||
const char *name = robot_xml->Attribute("name");
|
||||
if (!name)
|
||||
{
|
||||
logError("No name given for the robot.");
|
||||
model.reset(0);
|
||||
return model;
|
||||
}
|
||||
model->name_ = std::string(name);
|
||||
|
||||
// Get all Material elements
|
||||
for (TiXmlElement* material_xml = robot_xml->FirstChildElement("material"); material_xml; material_xml = material_xml->NextSiblingElement("material"))
|
||||
{
|
||||
my_shared_ptr<Material> material;
|
||||
material.reset(new Material);
|
||||
|
||||
try {
|
||||
parseMaterial(*material, material_xml, false); // material needs to be fully defined here
|
||||
if (model->getMaterial(material->name))
|
||||
{
|
||||
logError("material '%s' is not unique.", material->name.c_str());
|
||||
material.reset(0);
|
||||
model.reset(0);
|
||||
return model;
|
||||
}
|
||||
else
|
||||
{
|
||||
model->materials_.insert(make_pair(material->name,material));
|
||||
logDebug("urdfdom: successfully added a new material '%s'", material->name.c_str());
|
||||
}
|
||||
}
|
||||
catch (ParseError &e) {
|
||||
logError("material xml is not initialized correctly");
|
||||
material.reset(0);
|
||||
model.reset(0);
|
||||
return model;
|
||||
}
|
||||
}
|
||||
|
||||
// Get all Link elements
|
||||
for (TiXmlElement* link_xml = robot_xml->FirstChildElement("link"); link_xml; link_xml = link_xml->NextSiblingElement("link"))
|
||||
{
|
||||
my_shared_ptr<Link> link;
|
||||
link.reset(new Link);
|
||||
model->m_numLinks++;
|
||||
|
||||
try {
|
||||
parseLink(*link, link_xml);
|
||||
if (model->getLink(link->name))
|
||||
{
|
||||
logError("link '%s' is not unique.", link->name.c_str());
|
||||
model.reset(0);
|
||||
return model;
|
||||
}
|
||||
else
|
||||
{
|
||||
// set link visual material
|
||||
logDebug("urdfdom: setting link '%s' material", link->name.c_str());
|
||||
if (link->visual)
|
||||
{
|
||||
if (!link->visual->material_name.empty())
|
||||
{
|
||||
if (model->getMaterial(link->visual->material_name))
|
||||
{
|
||||
logDebug("urdfdom: setting link '%s' material to '%s'", link->name.c_str(),link->visual->material_name.c_str());
|
||||
link->visual->material = model->getMaterial( link->visual->material_name.c_str() );
|
||||
}
|
||||
else
|
||||
{
|
||||
if (link->visual->material)
|
||||
{
|
||||
logDebug("urdfdom: link '%s' material '%s' defined in Visual.", link->name.c_str(),link->visual->material_name.c_str());
|
||||
model->materials_.insert(make_pair(link->visual->material->name,link->visual->material));
|
||||
}
|
||||
else
|
||||
{
|
||||
logError("link '%s' material '%s' undefined.", link->name.c_str(),link->visual->material_name.c_str());
|
||||
model.reset(0);
|
||||
return model;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
model->links_.insert(make_pair(link->name,link));
|
||||
logDebug("urdfdom: successfully added a new link '%s'", link->name.c_str());
|
||||
}
|
||||
}
|
||||
catch (ParseError &e) {
|
||||
logError("link xml is not initialized correctly");
|
||||
model.reset(0);
|
||||
return model;
|
||||
}
|
||||
}
|
||||
if (model->links_.empty()){
|
||||
logError("No link elements found in urdf file");
|
||||
model.reset(0);
|
||||
return model;
|
||||
}
|
||||
|
||||
// Get all Joint elements
|
||||
for (TiXmlElement* joint_xml = robot_xml->FirstChildElement("joint"); joint_xml; joint_xml = joint_xml->NextSiblingElement("joint"))
|
||||
{
|
||||
my_shared_ptr<Joint> joint;
|
||||
joint.reset(new Joint);
|
||||
model->m_numJoints++;
|
||||
|
||||
if (parseJoint(*joint, joint_xml))
|
||||
{
|
||||
if (model->getJoint(joint->name))
|
||||
{
|
||||
logError("joint '%s' is not unique.", joint->name.c_str());
|
||||
model.reset(0);
|
||||
return model;
|
||||
}
|
||||
else
|
||||
{
|
||||
model->joints_.insert(make_pair(joint->name,joint));
|
||||
logDebug("urdfdom: successfully added a new joint '%s'", joint->name.c_str());
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
logError("joint xml is not initialized correctly");
|
||||
model.reset(0);
|
||||
return model;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// every link has children links and joints, but no parents, so we create a
|
||||
// local convenience data structure for keeping child->parent relations
|
||||
std::map<std::string, std::string> parent_link_tree;
|
||||
parent_link_tree.clear();
|
||||
|
||||
// building tree: name mapping
|
||||
try
|
||||
{
|
||||
model->initTree(parent_link_tree);
|
||||
}
|
||||
catch(ParseError &e)
|
||||
{
|
||||
logError("Failed to build tree: %s", e.what());
|
||||
model.reset(0);
|
||||
return model;
|
||||
}
|
||||
|
||||
// find the root link
|
||||
try
|
||||
{
|
||||
model->initRoot(parent_link_tree);
|
||||
}
|
||||
catch(ParseError &e)
|
||||
{
|
||||
logError("Failed to find root link: %s", e.what());
|
||||
model.reset(0);
|
||||
return model;
|
||||
}
|
||||
|
||||
return model;
|
||||
}
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
@@ -0,0 +1,91 @@
|
||||
/*********************************************************************
|
||||
* Software License Agreement (BSD License)
|
||||
*
|
||||
* Copyright (c) 2008, Willow Garage, Inc.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* * Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* * Redistributions in binary form must reproduce the above
|
||||
* copyright notice, this list of conditions and the following
|
||||
* disclaimer in the documentation and/or other materials provided
|
||||
* with the distribution.
|
||||
* * Neither the name of the Willow Garage nor the names of its
|
||||
* contributors may be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*********************************************************************/
|
||||
|
||||
/* Author: Wim Meeussen, John Hsu */
|
||||
|
||||
|
||||
#include <urdf/urdfdom_headers/urdf_model/include/urdf_model/pose.h>
|
||||
#include <fstream>
|
||||
#include <sstream>
|
||||
//#include <boost/lexical_cast.hpp>
|
||||
#include <algorithm>
|
||||
|
||||
#ifdef URDF_USE_CONSOLE_BRIDGE
|
||||
#include <console_bridge/console.h>
|
||||
#else
|
||||
#include "urdf/boost_replacement/printf_console.h"
|
||||
#endif
|
||||
|
||||
#include <tinyxml/tinyxml.h>
|
||||
#include <urdf/urdfdom_headers/urdf_exception/include/urdf_exception/exception.h>
|
||||
|
||||
|
||||
namespace urdf{
|
||||
|
||||
bool parsePose(Pose &pose, TiXmlElement* xml)
|
||||
{
|
||||
pose.clear();
|
||||
if (xml)
|
||||
{
|
||||
const char* xyz_str = xml->Attribute("xyz");
|
||||
if (xyz_str != NULL)
|
||||
{
|
||||
try {
|
||||
pose.position.init(xyz_str);
|
||||
}
|
||||
catch (ParseError &e) {
|
||||
logError(e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
const char* rpy_str = xml->Attribute("rpy");
|
||||
if (rpy_str != NULL)
|
||||
{
|
||||
try {
|
||||
pose.rotation.init(rpy_str);
|
||||
}
|
||||
catch (ParseError &e) {
|
||||
logError(e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
@@ -0,0 +1,85 @@
|
||||
/*********************************************************************
|
||||
* Software License Agreement (BSD License)
|
||||
*
|
||||
* Copyright (c) 2008, Willow Garage, Inc.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* * Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* * Redistributions in binary form must reproduce the above
|
||||
* copyright notice, this list of conditions and the following
|
||||
* disclaimer in the documentation and/or other materials provided
|
||||
* with the distribution.
|
||||
* * Neither the name of the Willow Garage nor the names of its
|
||||
* contributors may be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*********************************************************************/
|
||||
|
||||
/* Author: John Hsu */
|
||||
|
||||
|
||||
#include <urdf/urdfdom_headers/urdf_model/include/urdf_model/twist.h>
|
||||
#include <fstream>
|
||||
#include <sstream>
|
||||
#include <boost/lexical_cast.hpp>
|
||||
#include <algorithm>
|
||||
#include <tinyxml.h>
|
||||
#include <console_bridge/console.h>
|
||||
|
||||
namespace urdf{
|
||||
|
||||
bool parseTwist(Twist &twist, TiXmlElement* xml)
|
||||
{
|
||||
twist.clear();
|
||||
if (xml)
|
||||
{
|
||||
const char* linear_char = xml->Attribute("linear");
|
||||
if (linear_char != NULL)
|
||||
{
|
||||
try {
|
||||
twist.linear.init(linear_char);
|
||||
}
|
||||
catch (ParseError &e) {
|
||||
twist.linear.clear();
|
||||
logError("Malformed linear string [%s]: %s", linear_char, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
const char* angular_char = xml->Attribute("angular");
|
||||
if (angular_char != NULL)
|
||||
{
|
||||
try {
|
||||
twist.angular.init(angular_char);
|
||||
}
|
||||
catch (ParseError &e) {
|
||||
twist.angular.clear();
|
||||
logError("Malformed angular [%s]: %s", angular_char, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -0,0 +1,154 @@
|
||||
/*********************************************************************
|
||||
* Software License Agreement (BSD License)
|
||||
*
|
||||
* Copyright (c) 2008, Willow Garage, Inc.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* * Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* * Redistributions in binary form must reproduce the above
|
||||
* copyright notice, this list of conditions and the following
|
||||
* disclaimer in the documentation and/or other materials provided
|
||||
* with the distribution.
|
||||
* * Neither the name of the Willow Garage nor the names of its
|
||||
* contributors may be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*********************************************************************/
|
||||
|
||||
/* Author: John Hsu */
|
||||
|
||||
|
||||
#include <urdf/urdfdom_headers/urdf_model_state/include/urdf_model_state/model_state.h>
|
||||
#include <fstream>
|
||||
#include <sstream>
|
||||
#include <boost/lexical_cast.hpp>
|
||||
#include <algorithm>
|
||||
#include <tinyxml.h>
|
||||
#include <console_bridge/console.h>
|
||||
|
||||
namespace urdf{
|
||||
|
||||
bool parseModelState(ModelState &ms, TiXmlElement* config)
|
||||
{
|
||||
ms.clear();
|
||||
|
||||
const char *name_char = config->Attribute("name");
|
||||
if (!name_char)
|
||||
{
|
||||
logError("No name given for the model_state.");
|
||||
return false;
|
||||
}
|
||||
ms.name = std::string(name_char);
|
||||
|
||||
const char *time_stamp_char = config->Attribute("time_stamp");
|
||||
if (time_stamp_char)
|
||||
{
|
||||
try {
|
||||
double sec = boost::lexical_cast<double>(time_stamp_char);
|
||||
ms.time_stamp.set(sec);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e) {
|
||||
logError("Parsing time stamp [%s] failed: %s", time_stamp_char, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
TiXmlElement *joint_state_elem = config->FirstChildElement("joint_state");
|
||||
if (joint_state_elem)
|
||||
{
|
||||
boost::shared_ptr<JointState> joint_state;
|
||||
joint_state.reset(new JointState());
|
||||
|
||||
const char *joint_char = joint_state_elem->Attribute("joint");
|
||||
if (joint_char)
|
||||
joint_state->joint = std::string(joint_char);
|
||||
else
|
||||
{
|
||||
logError("No joint name given for the model_state.");
|
||||
return false;
|
||||
}
|
||||
|
||||
// parse position
|
||||
const char *position_char = joint_state_elem->Attribute("position");
|
||||
if (position_char)
|
||||
{
|
||||
|
||||
std::vector<std::string> pieces;
|
||||
boost::split( pieces, position_char, boost::is_any_of(" "));
|
||||
for (unsigned int i = 0; i < pieces.size(); ++i){
|
||||
if (pieces[i] != ""){
|
||||
try {
|
||||
joint_state->position.push_back(boost::lexical_cast<double>(pieces[i].c_str()));
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e) {
|
||||
throw ParseError("position element ("+ pieces[i] +") is not a valid float");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// parse velocity
|
||||
const char *velocity_char = joint_state_elem->Attribute("velocity");
|
||||
if (velocity_char)
|
||||
{
|
||||
|
||||
std::vector<std::string> pieces;
|
||||
boost::split( pieces, velocity_char, boost::is_any_of(" "));
|
||||
for (unsigned int i = 0; i < pieces.size(); ++i){
|
||||
if (pieces[i] != ""){
|
||||
try {
|
||||
joint_state->velocity.push_back(boost::lexical_cast<double>(pieces[i].c_str()));
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e) {
|
||||
throw ParseError("velocity element ("+ pieces[i] +") is not a valid float");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// parse effort
|
||||
const char *effort_char = joint_state_elem->Attribute("effort");
|
||||
if (effort_char)
|
||||
{
|
||||
|
||||
std::vector<std::string> pieces;
|
||||
boost::split( pieces, effort_char, boost::is_any_of(" "));
|
||||
for (unsigned int i = 0; i < pieces.size(); ++i){
|
||||
if (pieces[i] != ""){
|
||||
try {
|
||||
joint_state->effort.push_back(boost::lexical_cast<double>(pieces[i].c_str()));
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e) {
|
||||
throw ParseError("effort element ("+ pieces[i] +") is not a valid float");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// add to vector
|
||||
ms.joint_states.push_back(joint_state);
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
@@ -0,0 +1,364 @@
|
||||
/*********************************************************************
|
||||
* Software License Agreement (BSD License)
|
||||
*
|
||||
* Copyright (c) 2008, Willow Garage, Inc.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* * Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* * Redistributions in binary form must reproduce the above
|
||||
* copyright notice, this list of conditions and the following
|
||||
* disclaimer in the documentation and/or other materials provided
|
||||
* with the distribution.
|
||||
* * Neither the name of the Willow Garage nor the names of its
|
||||
* contributors may be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*********************************************************************/
|
||||
|
||||
/* Author: John Hsu */
|
||||
|
||||
|
||||
#include <urdf/urdfdom_headers/urdf_sensor/include/urdf_sensor/sensor.h>
|
||||
#include <fstream>
|
||||
#include <sstream>
|
||||
#include <boost/lexical_cast.hpp>
|
||||
#include <algorithm>
|
||||
#include <tinyxml.h>
|
||||
#include <console_bridge/console.h>
|
||||
|
||||
namespace urdf{
|
||||
|
||||
bool parsePose(Pose &pose, TiXmlElement* xml);
|
||||
|
||||
bool parseCamera(Camera &camera, TiXmlElement* config)
|
||||
{
|
||||
camera.clear();
|
||||
camera.type = VisualSensor::CAMERA;
|
||||
|
||||
TiXmlElement *image = config->FirstChildElement("image");
|
||||
if (image)
|
||||
{
|
||||
const char* width_char = image->Attribute("width");
|
||||
if (width_char)
|
||||
{
|
||||
try
|
||||
{
|
||||
camera.width = boost::lexical_cast<unsigned int>(width_char);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("Camera image width [%s] is not a valid int: %s", width_char, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
logError("Camera sensor needs an image width attribute");
|
||||
return false;
|
||||
}
|
||||
|
||||
const char* height_char = image->Attribute("height");
|
||||
if (height_char)
|
||||
{
|
||||
try
|
||||
{
|
||||
camera.height = boost::lexical_cast<unsigned int>(height_char);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("Camera image height [%s] is not a valid int: %s", height_char, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
logError("Camera sensor needs an image height attribute");
|
||||
return false;
|
||||
}
|
||||
|
||||
const char* format_char = image->Attribute("format");
|
||||
if (format_char)
|
||||
camera.format = std::string(format_char);
|
||||
else
|
||||
{
|
||||
logError("Camera sensor needs an image format attribute");
|
||||
return false;
|
||||
}
|
||||
|
||||
const char* hfov_char = image->Attribute("hfov");
|
||||
if (hfov_char)
|
||||
{
|
||||
try
|
||||
{
|
||||
camera.hfov = boost::lexical_cast<double>(hfov_char);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("Camera image hfov [%s] is not a valid float: %s", hfov_char, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
logError("Camera sensor needs an image hfov attribute");
|
||||
return false;
|
||||
}
|
||||
|
||||
const char* near_char = image->Attribute("near");
|
||||
if (near_char)
|
||||
{
|
||||
try
|
||||
{
|
||||
camera.near = boost::lexical_cast<double>(near_char);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("Camera image near [%s] is not a valid float: %s", near_char, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
logError("Camera sensor needs an image near attribute");
|
||||
return false;
|
||||
}
|
||||
|
||||
const char* far_char = image->Attribute("far");
|
||||
if (far_char)
|
||||
{
|
||||
try
|
||||
{
|
||||
camera.far = boost::lexical_cast<double>(far_char);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("Camera image far [%s] is not a valid float: %s", far_char, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
logError("Camera sensor needs an image far attribute");
|
||||
return false;
|
||||
}
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
logError("Camera sensor has no <image> element");
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool parseRay(Ray &ray, TiXmlElement* config)
|
||||
{
|
||||
ray.clear();
|
||||
ray.type = VisualSensor::RAY;
|
||||
|
||||
TiXmlElement *horizontal = config->FirstChildElement("horizontal");
|
||||
if (horizontal)
|
||||
{
|
||||
const char* samples_char = horizontal->Attribute("samples");
|
||||
if (samples_char)
|
||||
{
|
||||
try
|
||||
{
|
||||
ray.horizontal_samples = boost::lexical_cast<unsigned int>(samples_char);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("Ray horizontal samples [%s] is not a valid float: %s", samples_char, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
const char* resolution_char = horizontal->Attribute("resolution");
|
||||
if (resolution_char)
|
||||
{
|
||||
try
|
||||
{
|
||||
ray.horizontal_resolution = boost::lexical_cast<double>(resolution_char);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("Ray horizontal resolution [%s] is not a valid float: %s", resolution_char, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
const char* min_angle_char = horizontal->Attribute("min_angle");
|
||||
if (min_angle_char)
|
||||
{
|
||||
try
|
||||
{
|
||||
ray.horizontal_min_angle = boost::lexical_cast<double>(min_angle_char);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("Ray horizontal min_angle [%s] is not a valid float: %s", min_angle_char, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
const char* max_angle_char = horizontal->Attribute("max_angle");
|
||||
if (max_angle_char)
|
||||
{
|
||||
try
|
||||
{
|
||||
ray.horizontal_max_angle = boost::lexical_cast<double>(max_angle_char);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("Ray horizontal max_angle [%s] is not a valid float: %s", max_angle_char, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
TiXmlElement *vertical = config->FirstChildElement("vertical");
|
||||
if (vertical)
|
||||
{
|
||||
const char* samples_char = vertical->Attribute("samples");
|
||||
if (samples_char)
|
||||
{
|
||||
try
|
||||
{
|
||||
ray.vertical_samples = boost::lexical_cast<unsigned int>(samples_char);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("Ray vertical samples [%s] is not a valid float: %s", samples_char, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
const char* resolution_char = vertical->Attribute("resolution");
|
||||
if (resolution_char)
|
||||
{
|
||||
try
|
||||
{
|
||||
ray.vertical_resolution = boost::lexical_cast<double>(resolution_char);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("Ray vertical resolution [%s] is not a valid float: %s", resolution_char, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
const char* min_angle_char = vertical->Attribute("min_angle");
|
||||
if (min_angle_char)
|
||||
{
|
||||
try
|
||||
{
|
||||
ray.vertical_min_angle = boost::lexical_cast<double>(min_angle_char);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("Ray vertical min_angle [%s] is not a valid float: %s", min_angle_char, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
const char* max_angle_char = vertical->Attribute("max_angle");
|
||||
if (max_angle_char)
|
||||
{
|
||||
try
|
||||
{
|
||||
ray.vertical_max_angle = boost::lexical_cast<double>(max_angle_char);
|
||||
}
|
||||
catch (boost::bad_lexical_cast &e)
|
||||
{
|
||||
logError("Ray vertical max_angle [%s] is not a valid float: %s", max_angle_char, e.what());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
boost::shared_ptr<VisualSensor> parseVisualSensor(TiXmlElement *g)
|
||||
{
|
||||
boost::shared_ptr<VisualSensor> visual_sensor;
|
||||
|
||||
// get sensor type
|
||||
TiXmlElement *sensor_xml;
|
||||
if (g->FirstChildElement("camera"))
|
||||
{
|
||||
Camera *camera = new Camera();
|
||||
visual_sensor.reset(camera);
|
||||
sensor_xml = g->FirstChildElement("camera");
|
||||
if (!parseCamera(*camera, sensor_xml))
|
||||
visual_sensor.reset();
|
||||
}
|
||||
else if (g->FirstChildElement("ray"))
|
||||
{
|
||||
Ray *ray = new Ray();
|
||||
visual_sensor.reset(ray);
|
||||
sensor_xml = g->FirstChildElement("ray");
|
||||
if (!parseRay(*ray, sensor_xml))
|
||||
visual_sensor.reset();
|
||||
}
|
||||
else
|
||||
{
|
||||
logError("No know sensor types [camera|ray] defined in <sensor> block");
|
||||
}
|
||||
return visual_sensor;
|
||||
}
|
||||
|
||||
|
||||
bool parseSensor(Sensor &sensor, TiXmlElement* config)
|
||||
{
|
||||
sensor.clear();
|
||||
|
||||
const char *name_char = config->Attribute("name");
|
||||
if (!name_char)
|
||||
{
|
||||
logError("No name given for the sensor.");
|
||||
return false;
|
||||
}
|
||||
sensor.name = std::string(name_char);
|
||||
|
||||
// parse parent_link_name
|
||||
const char *parent_link_name_char = config->Attribute("parent_link_name");
|
||||
if (!parent_link_name_char)
|
||||
{
|
||||
logError("No parent_link_name given for the sensor.");
|
||||
return false;
|
||||
}
|
||||
sensor.parent_link_name = std::string(parent_link_name_char);
|
||||
|
||||
// parse origin
|
||||
TiXmlElement *o = config->FirstChildElement("origin");
|
||||
if (o)
|
||||
{
|
||||
if (!parsePose(sensor.origin, o))
|
||||
return false;
|
||||
}
|
||||
|
||||
// parse sensor
|
||||
sensor.sensor = parseVisualSensor(config);
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
@@ -0,0 +1,71 @@
|
||||
/*********************************************************************
|
||||
* Software License Agreement (BSD License)
|
||||
*
|
||||
* Copyright (c) 2008, Willow Garage, Inc.
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* * Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* * Redistributions in binary form must reproduce the above
|
||||
* copyright notice, this list of conditions and the following
|
||||
* disclaimer in the documentation and/or other materials provided
|
||||
* with the distribution.
|
||||
* * Neither the name of the Willow Garage nor the names of its
|
||||
* contributors may be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*********************************************************************/
|
||||
|
||||
/* Author: Wim Meeussen */
|
||||
|
||||
|
||||
#include <urdf/urdfdom_headers/urdf_world/include/urdf_world/world.h>
|
||||
#include <urdf/urdfdom_headers/urdf_model/include/urdf_model/model.h>
|
||||
#include <urdf_parser/urdf_parser.h>
|
||||
#include <fstream>
|
||||
#include <sstream>
|
||||
#include <boost/lexical_cast.hpp>
|
||||
#include <algorithm>
|
||||
#include <tinyxml.h>
|
||||
#include <console_bridge/console.h>
|
||||
|
||||
namespace urdf{
|
||||
|
||||
bool parseWorld(World &world, TiXmlElement* config)
|
||||
{
|
||||
|
||||
// to be implemented
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool exportWorld(World &world, TiXmlElement* xml)
|
||||
{
|
||||
TiXmlElement * world_xml = new TiXmlElement("world");
|
||||
world_xml->SetAttribute("name", world.name);
|
||||
|
||||
// to be implemented
|
||||
// exportModels(*world.models, world_xml);
|
||||
|
||||
xml->LinkEndChild(world_xml);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
}
|
||||
Reference in New Issue
Block a user