33 #ifndef DART_MATH_DETAIL_CONFIGURATIONSPACE_H_
34 #define DART_MATH_DETAIL_CONFIGURATIONSPACE_H_
48 template <
typename MatrixType,
int Size,
typename Enable = Range<true>>
51 static void run(
const MatrixType& matrix, MatrixType&
result)
53 result = matrix.ldlt().solve(MatrixType::Identity());
58 template <
typename MatrixType,
int Size>
61 static void run(
const MatrixType& matrix, MatrixType&
result)
68 template <
typename SpaceT>
71 static typename SpaceT::EuclideanPoint
run(
72 const typename SpaceT::Point& point)
99 x.tail<3>() = point.translation();
106 template <
typename SpaceT>
109 static typename SpaceT::Point
run(
110 const typename SpaceT::EuclideanPoint& point)
134 Eigen::Isometry3d tf(Eigen::Isometry3d::Identity());
137 tf.translation() = point.tail<3>();
144 template <
typename SpaceT>
147 static typename SpaceT::Point
run(
148 const typename SpaceT::Point& pos,
149 const typename SpaceT::Vector& vel,
152 return pos + dt * vel;
165 return pos * toManifoldPoint<SO3Space>(vel * dt);
178 return pos * toManifoldPoint<SE3Space>(vel * dt);
187 template <
typename SpaceT>
188 typename SpaceT::Matrix
inverse(
const typename SpaceT::Matrix& mat)
190 typename SpaceT::Matrix res;
199 template <
typename SpaceT>
200 typename SpaceT::EuclideanPoint
207 template <
typename SpaceT>
208 typename SpaceT::Point
215 template <
typename SpaceT>
217 const typename SpaceT::Point& pos,
218 const typename SpaceT::Vector& vel,
225 template <
typename SpaceT>
227 const typename SpaceT::Vector& vel,
228 const typename SpaceT::Vector& acc,
231 return vel + acc * dt;
CollisionResult * result
Collision result of DART.
Definition: FCLCollisionDetector.cpp:157
Matrix< double, 6, 1 > Vector6d
Definition: MathTypes.hpp:49
SpaceT::Matrix inverse(const typename SpaceT::Matrix &mat)
Definition: ConfigurationSpace.hpp:188
SpaceT::EuclideanPoint toEuclideanPoint(const typename SpaceT::Point &point)
Definition: ConfigurationSpace.hpp:201
SpaceT::Point toManifoldPoint(const typename SpaceT::EuclideanPoint &point)
Definition: ConfigurationSpace.hpp:209
SpaceT::Vector integrateVelocity(const typename SpaceT::Vector &vel, const typename SpaceT::Vector &acc, double dt)
Definition: ConfigurationSpace.hpp:226
Eigen::Vector3d logMap(const Eigen::Matrix3d &_R)
Log mapping.
Definition: Geometry.cpp:515
SpaceT::Point integratePosition(const typename SpaceT::Point &pos, const typename SpaceT::Vector &vel, double dt)
Definition: ConfigurationSpace.hpp:216
Eigen::Matrix3d expMapRot(const Eigen::Vector3d &_q)
Computes the Rotation matrix from a given expmap vector.
Definition: Geometry.cpp:427
Definition: BulletCollisionDetector.cpp:63
Definition: ConfigurationSpace.hpp:93
Eigen::Vector6d EuclideanPoint
Definition: ConfigurationSpace.hpp:100
Eigen::Isometry3d Point
Definition: ConfigurationSpace.hpp:99
Eigen::Vector6d Vector
Definition: ConfigurationSpace.hpp:101
Definition: ConfigurationSpace.hpp:78
Eigen::Vector3d EuclideanPoint
Definition: ConfigurationSpace.hpp:85
Eigen::Vector3d Vector
Definition: ConfigurationSpace.hpp:86
Eigen::Matrix3d Point
Definition: ConfigurationSpace.hpp:84
Definition: ConfigurationSpace.hpp:45
static SE3Space::Point run(const typename SE3Space::Point &pos, const typename SE3Space::Vector &vel, double dt)
Definition: ConfigurationSpace.hpp:173
static SO3Space::Point run(const typename SO3Space::Point &pos, const typename SO3Space::Vector &vel, double dt)
Definition: ConfigurationSpace.hpp:160
Definition: ConfigurationSpace.hpp:146
static SpaceT::Point run(const typename SpaceT::Point &pos, const typename SpaceT::Vector &vel, double dt)
Definition: ConfigurationSpace.hpp:147
static void run(const MatrixType &matrix, MatrixType &result)
Definition: ConfigurationSpace.hpp:61
Definition: ConfigurationSpace.hpp:50
static void run(const MatrixType &matrix, MatrixType &result)
Definition: ConfigurationSpace.hpp:51
static SE3Space::EuclideanPoint run(const typename SE3Space::Point &point)
Definition: ConfigurationSpace.hpp:93
static SO3Space::EuclideanPoint run(const typename SO3Space::Point &point)
Definition: ConfigurationSpace.hpp:82
Definition: ConfigurationSpace.hpp:70
static SpaceT::EuclideanPoint run(const typename SpaceT::Point &point)
Definition: ConfigurationSpace.hpp:71
static SE3Space::Point run(const typename SE3Space::EuclideanPoint &point)
Definition: ConfigurationSpace.hpp:131
static SO3Space::Point run(const typename SO3Space::EuclideanPoint &point)
Definition: ConfigurationSpace.hpp:120
Definition: ConfigurationSpace.hpp:108
static SpaceT::Point run(const typename SpaceT::EuclideanPoint &point)
Definition: ConfigurationSpace.hpp:109