Skip to content
This repository has been archived by the owner on Aug 3, 2020. It is now read-only.

Commit

Permalink
Remove old gazebo settings.
Browse files Browse the repository at this point in the history
Based on an initial patch from YoheiKakiuchi, just totally
remove old Gazebo 1.0 settings, as they are never used and
almost certainly will never be used.

Signed-off-by: Chris Lalancette <clalancette@osrfoundation.org>
  • Loading branch information
clalancette committed Feb 14, 2017
1 parent 85b9a6e commit 3e5a220
Showing 1 changed file with 1 addition and 39 deletions.
40 changes: 1 addition & 39 deletions collada_urdf/src/collada_to_urdf.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,10 +31,8 @@
#include <tf/LinearMath/Transform.h>
#include <tf/LinearMath/Quaternion.h>

#undef GAZEBO_1_0
#undef GAZEBO_1_3

//#define GAZEBO_1_0
#define GAZEBO_1_3

using namespace urdf;
Expand Down Expand Up @@ -385,17 +383,6 @@ void addChildLinkNamesXML(boost::shared_ptr<const Link> link, ofstream& os)
}
os << " </link>" << endl;

#ifdef GAZEBO_1_0
if ( add_gazebo_description ) {
os << " <gazebo reference=\"" << link->name << "\">" << endl;
os << " <material>Gazebo/Grey</material>" << endl;
//os << " <mu1>0.9</mu1>" << endl;
//os << " <mu2>0.9</mu2>" << endl;
os << " <turnGravityOff>false</turnGravityOff>" << endl;
os << " </gazebo>" << endl;
}
#endif

#ifdef GAZEBO_1_3
if ( add_gazebo_description ) {
os << " <gazebo reference=\"" << link->name << "\">" << endl;
Expand Down Expand Up @@ -507,37 +494,12 @@ void printTreeXML(boost::shared_ptr<const Link> link, string name, string file)
os.open(file.c_str());
os << "<?xml version=\"1.0\"?>" << endl;
os << "<robot name=\"" << name << "\"" << endl;
os << " xmlns:xi=\"http://www.w3.org/2001/XInclude\"" << endl;
os << " xmlns:gazebo=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#gz\"" << endl;
os << " xmlns:model=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#model\"" << endl;
os << " xmlns:sensor=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor\"" << endl;
os << " xmlns:body=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#body\"" << endl;
os << " xmlns:geom=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#geom\"" << endl;
os << " xmlns:joint=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#joint\"" << endl;
os << " xmlns:interface=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#interface\"" << endl;
os << " xmlns:rendering=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering\"" << endl;
os << " xmlns:renderable=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable\"" << endl;
os << " xmlns:controller=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#controller\"" << endl;
os << " xmlns:physics=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#physics\">" << endl;
os << " xmlns:xi=\"http://www.w3.org/2001/XInclude\">" << endl;

addChildLinkNamesXML(link, os);

addChildJointNamesXML(link, os);

if ( add_gazebo_description ) {
#ifdef GAZEBO_1_0
// old gazebo (gazebo on ROS Fuerte)
os << " <gazebo>" << endl;
os << " <controller:gazebo_ros_controller_manager" << endl;
os << " name=\"gazebo_ros_controller_manager\"" << endl;
os << " plugin=\"libgazebo_ros_controller_manager.so\">" << endl;
os << " <alwaysOn>true</alwaysOn>" << endl;
os << " <updateRate>1000.0</updateRate>" << endl;
os << " </controller:gazebo_ros_controller_manager>" << endl;
os << " </gazebo>" << endl;
#endif
}

os << "</robot>" << endl;
os.close();
}
Expand Down

0 comments on commit 3e5a220

Please sign in to comment.