|
template<typename MatrixType > |
tl::expected< MatrixType, std::string > | cartesian_planning::computeJacobianForChain (const moveit::core::RobotState &state, const moveit::core::JointModelGroup &group, const moveit::core::LinkModel &tip_link, const Eigen::Vector3d &tip_offset) |
| Compute the Jacobian matrix for a given tip link in a kinematic chain.
|
|
tl::expected< Eigen::MatrixXd, std::string > | cartesian_planning::computeMultiTipJacobian (const moveit::core::RobotState &state, const moveit::core::JointModelGroup &group, const std::vector< const moveit::core::LinkModel * > &tip_links, const std::vector< Eigen::Vector3d > &tip_offsets) |
| Compute the Jacobian matrix for a kinematic tree with multiple tips.
|
|
const moveit::core::JointModel * | cartesian_planning::internal::getCommonRoot (const moveit::core::JointModelGroup &group) |
|
template<class JacobianMatrixType > |
void | cartesian_planning::internal::fillInRevoluteJacobian (const Eigen::Isometry3d &root_pose_link, const moveit::core::RevoluteJointModel &joint_model, const Eigen::Vector3d &tip_point, int tip_id, int column_index, JacobianMatrixType &jacobian) |
|
template<class JacobianMatrixType > |
void | cartesian_planning::internal::fillInPrismaticJacobian (const Eigen::Isometry3d &root_pose_link, const moveit::core::PrismaticJointModel &joint_model, int tip_id, int column_index, JacobianMatrixType &jacobian) |
|
template<class JacobianMatrixType > |
void | cartesian_planning::internal::fillInPlanarJacobian (const Eigen::Isometry3d &root_pose_link, const Eigen::Vector3d &tip_point, int tip_id, int column_index, JacobianMatrixType &jacobian) |
|
template<class JacobianMatrixType > |
tl::expected< void, std::string > | cartesian_planning::internal::fillInJointJacobian (const Eigen::Isometry3d &root_pose_link, const moveit::core::JointModel &joint_model, const Eigen::Vector3d &tip_point, int tip_id, int column_index, JacobianMatrixType &jacobian) |
|
Eigen::Isometry3d | cartesian_planning::getWorldPoseInRootCoordinates (const moveit::core::RobotState &state, const moveit::core::JointModelGroup &group) |
| Get the pose of the world frame given in the group root link frame, i.e. `root_pose_world. at the given state.
|
|