#include <Eigen/Core>
#include <Eigen/Geometry>
#include <ros/ros.h>
#include <urdf_traverser/Functions.h>
#include <urdf_traverser/Helpers.h>
#include <urdf_traverser/UrdfTraverser.h>
#include <urdf_transform/AlignRotationAxis.h>
Go to the source code of this file.
Classes | |
class | Vector3RecursionParams |
Recursion parameters with one 3D vector. More... | |
Functions | |
int | allRotationsToAxisCB (urdf_traverser::RecursionParamsPtr &p) |
Recursion method to be used with traverseTreeTopDown() and recursion parameters of type *Vector3RecursionParams*.
Re-arranges the joint-transform of the recursion link's *parent joint*, along with the link's visual/collision/intertial rotations, such that all joints rotate around the axis given in the recursion parameters vector.
Definition at line 73 of file AlignRotationAxis.cpp.