Aikido
VectorFieldUtil.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_PLANNER_VECTORFIELD_VECTORFIELDUTIL_HPP_
2 #define AIKIDO_PLANNER_VECTORFIELD_VECTORFIELDUTIL_HPP_
3 
4 #include <dart/dynamics/BodyNode.hpp>
5 
10 
11 namespace aikido {
12 namespace planner {
13 namespace vectorfield {
14 
33  Eigen::VectorXd& jointVelocity,
34  const Eigen::Vector6d& desiredTwist,
35  const ::dart::dynamics::MetaSkeletonPtr metaSkeleton,
36  const ::dart::dynamics::ConstBodyNodePtr bodyNode,
37  double jointLimitPadding,
38  const Eigen::VectorXd& jointVelocityLowerLimits,
39  const Eigen::VectorXd& jointVelocityUpperLimits,
40  bool enforceJointVelocityLimits,
41  double stepSize);
42 
52 Eigen::Vector6d computeGeodesicTwist(
53  const Eigen::Isometry3d& fromTrans, const Eigen::Isometry3d& toTrans);
54 
62 Eigen::Vector4d computeGeodesicError(
63  const Eigen::Isometry3d& fromTrans, const Eigen::Isometry3d& toTrans);
64 
73  const Eigen::Isometry3d& fromTrans,
74  const Eigen::Isometry3d& toTrans,
75  double r);
76 
77 } // namespace vectorfield
78 } // namespace planner
79 } // namespace aikido
80 
81 #endif // AIKIDO_PLANNER_VECTORFIELD_VECTORFIELDUTIL_HPP_
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::planner::vectorfield::computeGeodesicDistance
double computeGeodesicDistance(const Eigen::Isometry3d &fromTrans, const Eigen::Isometry3d &toTrans, double r)
Compute the geodesic distance between two transforms.
Spline.hpp
Interpolated.hpp
MetaSkeletonStateSpace.hpp
aikido::planner::vectorfield::computeGeodesicTwist
Eigen::Vector6d computeGeodesicTwist(const Eigen::Isometry3d &fromTrans, const Eigen::Isometry3d &toTrans)
Compute the twist in global coordinate that corresponds to the gradient of the geodesic distance betw...
Spline.hpp
aikido::planner::vectorfield::computeJointVelocityFromTwist
bool computeJointVelocityFromTwist(Eigen::VectorXd &jointVelocity, const Eigen::Vector6d &desiredTwist, const ::dart::dynamics::MetaSkeletonPtr metaSkeleton, const ::dart::dynamics::ConstBodyNodePtr bodyNode, double jointLimitPadding, const Eigen::VectorXd &jointVelocityLowerLimits, const Eigen::VectorXd &jointVelocityUpperLimits, bool enforceJointVelocityLimits, double stepSize)
Compute joint velocity from a given twist.
aikido::planner::vectorfield::computeGeodesicError
Eigen::Vector4d computeGeodesicError(const Eigen::Isometry3d &fromTrans, const Eigen::Isometry3d &toTrans)
Compute the error in gloabl coordinate between two transforms.