Go to the documentation of this file.00001 #include <ros/ros.h>
00002 #include <collada_parser/collada_parser.h>
00003 #include <urdf_parser/urdf_parser.h>
00004 #include <urdf/model.h>
00005
00006
00007 #include <iostream>
00008 #include <fstream>
00009
00010 #undef GAZEBO_1_0
00011 #undef GAZEBO_1_3
00012
00013 #define GAZEBO_1_3
00014
00015 using namespace urdf;
00016 using namespace std;
00017
00018 int main(int argc, char **argv) {
00019 if (argc != 5){
00020 std::cerr << "Usage: collada_gazebo_gen package_name dir input dae" << std::endl;
00021 std::cerr << "collada file: $(rospack find package_name)/dir/input.dae is needed." << std::endl;
00022 return -1;
00023 }
00024 bool colladafile = false;
00025 std::string package_name(argv[1]);
00026 std::string dir_name(argv[2]);
00027 std::string dae_fname(argv[3]);
00028 std::string prefix(argv[4]);
00029
00030 ROS_INFO("%s %s %s -> %s",package_name.c_str(),dir_name.c_str(),dae_fname.c_str(), (dir_name + "/" + dae_fname + "." + prefix).c_str());
00031
00032 std::string xml_string;
00033 std::fstream xml_file((dir_name + "/" + dae_fname + "." + prefix).c_str(), std::fstream::in);
00034 while ( xml_file.good() )
00035 {
00036 std::string line;
00037 std::getline( xml_file, line);
00038 xml_string += (line + "\n");
00039 }
00040 xml_file.close();
00041
00042 boost::shared_ptr<ModelInterface> robot;
00043 if( xml_string.find("<COLLADA") != std::string::npos )
00044 {
00045 ROS_INFO("Parsing robot collada xml string");
00046 robot = parseCollada(xml_string);
00047 colladafile = true;
00048 }
00049 else
00050 {
00051 ROS_INFO("Parsing robot urdf xml string");
00052 robot = parseURDF(xml_string);
00053 }
00054
00055 if (!robot){
00056 std::cerr << "ERROR: Model Parsing the xml failed" << std::endl;
00057 return -1;
00058 }
00059
00060 {
00061 int cnt = 0;
00062 std::ofstream os;
00063 std::string fname = dir_name + "/" + dae_fname + "_transmission.xacro";
00064 os.open(fname.c_str());
00065 if (colladafile) {
00066 os << "<COLLADA xmlns:xacro=\"http://www.ros.org/wiki/xacro\">\n";
00067 } else {
00068 os << "<robot xmlns:xacro=\"http://www.ros.org/wiki/xacro\">\n";
00069 }
00070 os << " <xacro:property name=\"mechanical_reduction\" value=\"1\" />\n";
00071 os << " <xacro:property name=\"motor_torque_constant\" value=\"1\" />\n";
00072 os << " <xacro:property name=\"pulses_per_revolution\" value=\"90000\" />\n\n";
00073 os << " <xacro:macro name=\"pr2_transmission\" params=\"joint_name link_name\">\n";
00074 os << " <transmission type=\"pr2_mechanism_model/SimpleTransmission\" name=\"${joint_name}_trans\">\n";
00075 os << " <actuator name=\"${joint_name}_motor\" />\n";
00076 os << " <joint name=\"${joint_name}\" />\n";
00077 os << " <mechanicalReduction>${mechanical_reduction}</mechanicalReduction>\n";
00078 os << " <motorTorqueConstant>${motor_torque_constant}</motorTorqueConstant>\n";
00079 os << " <pulsesPerRevolution>${pulses_per_revolution}</pulsesPerRevolution>\n";
00080 os << " </transmission>\n";
00081 os << " </xacro:macro>\n";
00082 for ( std::map<std::string,boost::shared_ptr<Joint> >::iterator joint = robot->joints_.begin();
00083 joint != robot->joints_.end(); joint++) {
00084 if ( joint->second->type == Joint::REVOLUTE ||
00085 joint->second->type == Joint::CONTINUOUS ) {
00086 os << " <xacro:pr2_transmission joint_name=\"" << joint->first;
00087 os << "\" link_name=\"link" << cnt++ << "\"/>\n";
00088 }
00089 }
00090 if (colladafile) {
00091 os << "</COLLADA>";
00092 } else {
00093 os << "</robot>";
00094 }
00095 os.close();
00096 }
00097
00098 {
00099 std::ofstream os;
00100 std::string fname = dir_name + "/" + dae_fname + "_gazebo.xacro";
00101 os.open(fname.c_str());
00102 if (colladafile) {
00103 os << "<COLLADA xmlns:controller=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#controller\"\n";
00104 } else {
00105 os << "<robot xmlns:controller=\"http://playerstage.sourceforge.net/gazebo/xmlschema/#controller\"\n";
00106 }
00107 os << " xmlns:xacro=\"http://www.ros.org/wiki/xacro\">\n";
00108 #ifdef GAZEBO_1_0
00109 os << " <xacro:macro name=\"gazebo_reference\" params=\"reference material gravity\">\n";
00110 os << " <gazebo reference=\"${reference}\">\n";
00111 os << " <material>${material}</material>\n";
00112 os << " <turnGravityOff>${gravity}</turnGravityOff>\n";
00113 os << " </gazebo>\n";
00114 os << " </xacro:macro>\n";
00115 #endif
00116
00117 if (colladafile) {
00118 os << " <extra type=\"physics\" name=\"gazebo\">\n";
00119 os << " <technique profile=\"gazebo\">\n";
00120 }
00121 #ifdef GAZEBO_1_0
00122
00123 os << " <gazebo>\n";
00124 os << " <controller:gazebo_ros_controller_manager\n";
00125 os << " name=\"gazebo_ros_controller_manager\"\n";
00126 os << " plugin=\"libgazebo_ros_controller_manager.so\">\n";
00127 os << " <alwaysOn>true</alwaysOn>\n";
00128 os << " <updateRate>1000.0</updateRate>\n";
00129 os << " </controller:gazebo_ros_controller_manager>\n";
00130 os << " </gazebo>\n";
00131 #endif
00132 #ifdef GAZEBO_1_3
00133 os << " <gazebo>" << endl;
00134 os << " <!--plugin filename=\"libMultiSenseSLPlugin.so\" name=\"multisense_plugin\" /-->" << endl;
00135 os << " <!--plugin filename=\"libAtlasPlugin.so\" name=\"atlas_plugin\"/-->" << endl;
00136 os << " <plugin filename=\"libgazebo_ros_joint_trajectory.so\" name=\"joint_trajectory_plugin\">" << endl;
00137 os << " <topicName>joint_trajectory</topicName>" << endl;
00138 os << " <updateRate>1000.0</updateRate>" << endl;
00139 os << " </plugin>" << endl;
00140 os << " <plugin filename=\"libgazebo_ros_controller_manager.so\" name=\"gazebo_ros_controller_manager\">" << endl;
00141 os << " <alwaysOn>true</alwaysOn>" << endl;
00142 os << " <updateRate>1000.0</updateRate>" << endl;
00143 os << " </plugin>" << endl;
00144 os << " </gazebo>" << endl;
00145 #endif
00146
00147 #ifdef GAZEBO_1_0
00148 for ( std::map<std::string,boost::shared_ptr<Link> >::iterator link = robot->links_.begin();
00149 link != robot->links_.end(); link++) {
00150 os << " <xacro:gazebo_reference reference=\"" << link->first;
00151 os << "\" material=\"Gazebo/Blue\" gravity=\"False\" />\n";
00152 }
00153 #endif
00154 if (colladafile) {
00155 os << " </technique>\n";
00156 os << " </extra>\n";
00157 }
00158
00159 os << " <xacro:include filename=\"$(find " << package_name;
00160 os << ")/" << dir_name << "/" << dae_fname << "_transmission.xacro\" />\n";
00161 if (colladafile) {
00162 os << "</COLLADA>\n";
00163 } else {
00164 os << "</robot>\n";
00165 }
00166 os.close();
00167 }
00168
00169 {
00170 std::ofstream os;
00171 std::string fname = dir_name + "/" + dae_fname + "_controllers.yaml";
00172 os.open(fname.c_str());
00173 os << "fullbody_controller:\n";
00174 os << " type: robot_mechanism_controllers/JointTrajectoryActionController\n";
00175 os << " joints:\n";
00176 for ( std::map<std::string,boost::shared_ptr<Joint> >::iterator joint = robot->joints_.begin();
00177 joint != robot->joints_.end(); joint++) {
00178 if ( joint->second->type == Joint::REVOLUTE ||
00179 joint->second->type == Joint::CONTINUOUS ) {
00180 os << " - " << joint->first << "\n";
00181 }
00182 }
00183 os << " gains:\n";
00184 for ( std::map<std::string,boost::shared_ptr<Joint> >::iterator joint = robot->joints_.begin();
00185 joint != robot->joints_.end(); joint++) {
00186 if ( joint->second->type == Joint::REVOLUTE ||
00187 joint->second->type == Joint::CONTINUOUS ) {
00188 os << " " << joint->first << ": {p: 200.0, d: 0.0002, i: 0.0, i_clamp: 0.0}\n";
00189 }
00190 }
00191 os << " joint_trajectory_action_node:\n";
00192 os << " joints:\n";
00193 for ( std::map<std::string,boost::shared_ptr<Joint> >::iterator joint = robot->joints_.begin();
00194 joint != robot->joints_.end(); joint++) {
00195 if ( joint->second->type == Joint::REVOLUTE ||
00196 joint->second->type == Joint::CONTINUOUS ) {
00197 os << " - " << joint->first << "\n";
00198 }
00199 }
00200 os << " constraints:\n";
00201 os << " goal_time: 0.0\n";
00202 for ( std::map<std::string,boost::shared_ptr<Joint> >::iterator joint = robot->joints_.begin();
00203 joint != robot->joints_.end(); joint++) {
00204 if ( joint->second->type == Joint::REVOLUTE ||
00205 joint->second->type == Joint::CONTINUOUS ) {
00206 os << " " << joint->first << ":\n";
00207 os << " goal: 0.02\n";
00208 }
00209 }
00210 os.close();
00211 }
00212
00213 return 0;
00214 }