|
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
#include <Eigen/Geometry>#include "cartesian_planning/types.hpp"#include "moveit_pro_macros/macros.hpp"#include "moveit_pro_types/types.hpp"

Namespaces | |
| namespace | cartesian_planning |
Functions | |
| Eigen::Vector3d | cartesian_planning::rotationToAxisAngleVector (const Eigen::Quaterniond &rotation) |
| Converts a 3D rotation given by a quaternion into its axis-angle (u-theta) representation. | |
| Eigen::Vector6d | cartesian_planning::poseToPoseVector (const Eigen::Isometry3d &pose) |
| Converts a 3D Pose into its 6D vector representation (t, u-theta). | |
| Eigen::Vector6d | cartesian_planning::poseError (const Eigen::Isometry3d &a, const Eigen::Isometry3d &b) |
| Computes the 3D error (translation and orientation) between two poses. | |
| template<class LinearPart > | |
| Eigen::Matrix6d | cartesian_planning::twistRotationMatrix (const LinearPart &rotation) |
| Computes the 6x6 twist rotation matrix corresponding to a rotation. | |
| template<class LinearPart > | |
| Eigen::MatrixNd | cartesian_planning::multiTipTwistRotationMatrix (const LinearPart &rotation, const size_t num_tips) |
| Computes the NxN twist rotation matrix corresponding to a rotation. | |
| Eigen::Vector6d | cartesian_planning::transformTwist (const Eigen::Vector6d &twist_a, const Eigen::Isometry3d &b_pose_a) |
| Transforms a twist in frame a to frame b, including the omega.cross(r) term. | |
| double | cartesian_planning::angleDifference (const double angle_a, const double angle_b) |
| Compute the unsigned angle difference between two angles. | |