#include <ros/ros.h>
#include <urdf/model.h>
#include <collada_parser/collada_parser.h>
#include <urdf_parser/urdf_parser.h>
#include <assimp.hpp>
#include <aiScene.h>
#include <aiPostProcess.h>
#include <iostream>
#include <fstream>
#include <boost/program_options.hpp>
#include <boost/filesystem/path.hpp>
#include <boost/filesystem/operations.hpp>
#include <tf/LinearMath/Transform.h>
#include <tf/LinearMath/Quaternion.h>
Go to the source code of this file.
Defines | |
#define | DEBUG_MAT(mat) |
#define | GAZEBO_1_3 |
#define | PRINT_GEOM(os, geometry) if ( geometry->type == urdf::Geometry::MESH ) { os << "geom: name: " << ((urdf::Mesh *)geometry.get())->filename; } |
#define | PRINT_ORIGIN(os, origin) |
#define | PRINT_ORIGIN_XML(os, origin) |
Functions | |
void | addChildJointNamesXML (boost::shared_ptr< const Link > link, ofstream &os) |
void | addChildLinkNamesXML (boost::shared_ptr< const Link > link, ofstream &os) |
void | assimp_calc_bbox (string fname, float &minx, float &miny, float &minz, float &maxx, float &maxy, float &maxz) |
void | assimp_file_export (std::string fname, std::string ofname, std::string mesh_type="collada") |
int | main (int argc, char **argv) |
void | printTreeXML (boost::shared_ptr< const Link > link, string name, string file) |
Variables | |
bool | add_gazebo_description = false |
string | arobot_name = "" |
bool | export_collision_mesh = false |
string | mesh_dir = "/tmp" |
string | mesh_prefix = "" |
string | output_file = "" |
bool | rotate_inertia_frame = true |
bool | use_assimp_export = false |
bool | use_same_collision_as_visual = true |
bool | use_simple_collision = false |
bool | use_simple_visual = false |
#define DEBUG_MAT | ( | mat | ) |
cout << "#2f((" << mat[0][0] << " " << mat[0][1] << " " << mat[0][2] << ")"; \ cout << "(" << mat[1][0] << " " << mat[1][1] << " " << mat[1][2] << ")"; \ cout << "(" << mat[2][0] << " " << mat[2][1] << " " << mat[2][2] << "))" << endl;
#define GAZEBO_1_3 |
Definition at line 38 of file collada_to_urdf.cpp.
#define PRINT_GEOM | ( | os, | |
geometry | |||
) | if ( geometry->type == urdf::Geometry::MESH ) { os << "geom: name: " << ((urdf::Mesh *)geometry.get())->filename; } |
Definition at line 67 of file collada_to_urdf.cpp.
#define PRINT_ORIGIN | ( | os, | |
origin | |||
) |
os << "xyz: " << origin.position.x << " " << origin.position.y << " " << origin.position.z << " "; \ { double r,p,y; origin.rotation.getRPY(r, p, y); \ os << "rpy: " << r << " " << p << " " << y; }
Definition at line 56 of file collada_to_urdf.cpp.
#define PRINT_ORIGIN_XML | ( | os, | |
origin | |||
) |
os << "xyz=\"" << origin.position.x << " " << origin.position.y << " " << origin.position.z << "\""; \ { double h___r, h___p, h___y; \ origin.rotation.getRPY(h___r, h___p, h___y); \ os << " rpy=\"" << h___r << " " << h___p << " " << h___y << "\""; }
Definition at line 61 of file collada_to_urdf.cpp.
void addChildJointNamesXML | ( | boost::shared_ptr< const Link > | link, |
ofstream & | os | ||
) |
error
Definition at line 412 of file collada_to_urdf.cpp.
void addChildLinkNamesXML | ( | boost::shared_ptr< const Link > | link, |
ofstream & | os | ||
) |
Definition at line 191 of file collada_to_urdf.cpp.
void assimp_calc_bbox | ( | string | fname, |
float & | minx, | ||
float & | miny, | ||
float & | minz, | ||
float & | maxx, | ||
float & | maxy, | ||
float & | maxz | ||
) |
Definition at line 110 of file collada_to_urdf.cpp.
void assimp_file_export | ( | std::string | fname, |
std::string | ofname, | ||
std::string | mesh_type = "collada" |
||
) |
Definition at line 70 of file collada_to_urdf.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 548 of file collada_to_urdf.cpp.
void printTreeXML | ( | boost::shared_ptr< const Link > | link, |
string | name, | ||
string | file | ||
) |
Definition at line 504 of file collada_to_urdf.cpp.
bool add_gazebo_description = false |
Definition at line 45 of file collada_to_urdf.cpp.
string arobot_name = "" |
Definition at line 52 of file collada_to_urdf.cpp.
bool export_collision_mesh = false |
Definition at line 49 of file collada_to_urdf.cpp.
string mesh_dir = "/tmp" |
Definition at line 51 of file collada_to_urdf.cpp.
string mesh_prefix = "" |
Definition at line 54 of file collada_to_urdf.cpp.
string output_file = "" |
Definition at line 53 of file collada_to_urdf.cpp.
bool rotate_inertia_frame = true |
Definition at line 48 of file collada_to_urdf.cpp.
bool use_assimp_export = false |
Definition at line 46 of file collada_to_urdf.cpp.
bool use_same_collision_as_visual = true |
Definition at line 47 of file collada_to_urdf.cpp.
bool use_simple_collision = false |
Definition at line 44 of file collada_to_urdf.cpp.
bool use_simple_visual = false |
Definition at line 43 of file collada_to_urdf.cpp.