#include <iostream>
#include <fstream>
#include <string>
#include <vector>
#include <ros/console.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 <boost/program_options.hpp>
#include <boost/filesystem/path.hpp>
#include <boost/filesystem/operations.hpp>
#include <Eigen/Geometry>
Go to the source code of this file.
|
void | addChildJointNamesXML (urdf::LinkConstSharedPtr link, ofstream &os) |
|
void | addChildLinkNamesXML (urdf::LinkConstSharedPtr 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 (urdf::LinkConstSharedPtr link, string name, string file) |
|
Value: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 PRINT_ORIGIN |
( |
|
os, |
|
|
|
origin |
|
) |
| |
Value: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 57 of file collada_to_urdf.cpp.
#define PRINT_ORIGIN_XML |
( |
|
os, |
|
|
|
origin |
|
) |
| |
Value: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 62 of file collada_to_urdf.cpp.
void addChildJointNamesXML |
( |
urdf::LinkConstSharedPtr |
link, |
|
|
ofstream & |
os |
|
) |
| |
void addChildLinkNamesXML |
( |
urdf::LinkConstSharedPtr |
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 |
( |
urdf::LinkConstSharedPtr |
link, |
|
|
string |
name, |
|
|
string |
file |
|
) |
| |
bool add_gazebo_description = false |
bool export_collision_mesh = false |
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 |
bool use_transmission_interface = false |