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

Commit 3e5a220

Browse files
committed
Remove old gazebo settings.
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>
1 parent 85b9a6e commit 3e5a220

File tree

1 file changed

+1
-39
lines changed

1 file changed

+1
-39
lines changed

collada_urdf/src/collada_to_urdf.cpp

Lines changed: 1 addition & 39 deletions
Original file line numberDiff line numberDiff line change
@@ -31,10 +31,8 @@
3131
#include <tf/LinearMath/Transform.h>
3232
#include <tf/LinearMath/Quaternion.h>
3333

34-
#undef GAZEBO_1_0
3534
#undef GAZEBO_1_3
3635

37-
//#define GAZEBO_1_0
3836
#define GAZEBO_1_3
3937

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

388-
#ifdef GAZEBO_1_0
389-
if ( add_gazebo_description ) {
390-
os << " <gazebo reference=\"" << link->name << "\">" << endl;
391-
os << " <material>Gazebo/Grey</material>" << endl;
392-
//os << " <mu1>0.9</mu1>" << endl;
393-
//os << " <mu2>0.9</mu2>" << endl;
394-
os << " <turnGravityOff>false</turnGravityOff>" << endl;
395-
os << " </gazebo>" << endl;
396-
}
397-
#endif
398-
399386
#ifdef GAZEBO_1_3
400387
if ( add_gazebo_description ) {
401388
os << " <gazebo reference=\"" << link->name << "\">" << endl;
@@ -507,37 +494,12 @@ void printTreeXML(boost::shared_ptr<const Link> link, string name, string file)
507494
os.open(file.c_str());
508495
os << "<?xml version=\"1.0\"?>" << endl;
509496
os << "<robot name=\"" << name << "\"" << endl;
510-
os << " xmlns:xi=\"http://www.w3.org/2001/XInclude\"" << endl;
511-
os << " xmlns:gazebo=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#gz\"" << endl;
512-
os << " xmlns:model=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#model\"" << endl;
513-
os << " xmlns:sensor=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor\"" << endl;
514-
os << " xmlns:body=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#body\"" << endl;
515-
os << " xmlns:geom=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#geom\"" << endl;
516-
os << " xmlns:joint=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#joint\"" << endl;
517-
os << " xmlns:interface=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#interface\"" << endl;
518-
os << " xmlns:rendering=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering\"" << endl;
519-
os << " xmlns:renderable=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable\"" << endl;
520-
os << " xmlns:controller=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#controller\"" << endl;
521-
os << " xmlns:physics=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#physics\">" << endl;
497+
os << " xmlns:xi=\"http://www.w3.org/2001/XInclude\">" << endl;
522498

523499
addChildLinkNamesXML(link, os);
524500

525501
addChildJointNamesXML(link, os);
526502

527-
if ( add_gazebo_description ) {
528-
#ifdef GAZEBO_1_0
529-
// old gazebo (gazebo on ROS Fuerte)
530-
os << " <gazebo>" << endl;
531-
os << " <controller:gazebo_ros_controller_manager" << endl;
532-
os << " name=\"gazebo_ros_controller_manager\"" << endl;
533-
os << " plugin=\"libgazebo_ros_controller_manager.so\">" << endl;
534-
os << " <alwaysOn>true</alwaysOn>" << endl;
535-
os << " <updateRate>1000.0</updateRate>" << endl;
536-
os << " </controller:gazebo_ros_controller_manager>" << endl;
537-
os << " </gazebo>" << endl;
538-
#endif
539-
}
540-
541503
os << "</robot>" << endl;
542504
os.close();
543505
}

0 commit comments

Comments
 (0)