39 for (
int i = 0; i <
kinematics[0].Phi.rows(); ++i)
49 for (
int i = 0; i <
kinematics[0].Phi.rows(); ++i)
60 for (
int i = 0; i <
kinematics[0].Phi.rows(); ++i)
66 const Eigen::RowVectorXd& dp_x_dq =
kinematics[0].jacobian[i].data.row(0);
67 const Eigen::RowVectorXd& dp_y_dq =
kinematics[0].jacobian[i].data.row(1);
68 const Eigen::RowVectorXd& dp_z_dq =
kinematics[0].jacobian[i].data.row(2);
69 Eigen::MatrixXd& ddp_x_ddq =
kinematics[0].hessian[i](0);
70 Eigen::MatrixXd& ddp_y_ddq =
kinematics[0].hessian[i](1);
71 Eigen::MatrixXd& ddp_z_ddq =
kinematics[0].hessian[i](2);
75 jacobian.row(i).noalias() = jacobian_numerator / phi(i);
78 Eigen::MatrixXd hessian_part1 = -jacobian_numerator.transpose() * jacobian_numerator;
79 hessian_part1 /= std::pow((p_x * p_x + p_y * p_y + p_z * p_z), (3 / 2));
81 Eigen::MatrixXd hessian_part2 = (p_x * ddp_x_ddq + p_y * ddp_y_ddq + p_z * ddp_z_ddq) + (dp_x_dq.transpose() * dp_x_dq + dp_y_dq.transpose() * dp_y_dq + dp_z_dq.transpose() * dp_z_dq);
82 hessian_part2 /= phi(i);
84 hessian(i).noalias() = hessian_part1 + hessian_part2;
Eigen::Ref< Eigen::VectorXd > VectorXdRef
void Update(Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi) override
int TaskSpaceDim() override
const Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Eigen::Ref< Hessian > HessianRef
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
REGISTER_TASKMAP_TYPE("Distance", exotica::Distance)