![]() |
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Classes | |
struct | PoseTarget |
Typedefs | |
using | IKValidationFunction = std::function< bool(const Eigen::VectorXd &solution)> |
Functions | |
bool | emptyValidationFunction (const Eigen::VectorXd &) |
tl::expected< Eigen::VectorXd, std::string > | solveIK (moveit::core::RobotState &robot_state, const moveit::core::JointModelGroup &group, const std::vector< PoseTarget > &targets, const Eigen::VectorXd &seed, const rclcpp::Duration &timeout, const IKValidationFunction &validation_fn, const Params ¶ms) |
Computes pose inverse kinematics for the given group and set of targets. | |
tl::expected< void, std::string > | checkPreconditions (const moveit::core::JointModelGroup &group, const std::vector< PoseTarget > &targets, const Eigen::VectorXd &seed) |
bool | unwindAndCheckLimits (const moveit::core::JointModelGroup &group, Eigen::VectorXd &joint_values) |
using pose_ik::IKValidationFunction = typedef std::function<bool(const Eigen::VectorXd& solution)> |
tl::expected< void, std::string > pose_ik::checkPreconditions | ( | const moveit::core::JointModelGroup & | group, |
const std::vector< PoseTarget > & | targets, | ||
const Eigen::VectorXd & | seed | ||
) |
bool pose_ik::emptyValidationFunction | ( | const Eigen::VectorXd & | ) |
tl::expected< Eigen::VectorXd, std::string > pose_ik::solveIK | ( | moveit::core::RobotState & | robot_state, |
const moveit::core::JointModelGroup & | group, | ||
const std::vector< PoseTarget > & | targets, | ||
const Eigen::VectorXd & | seed, | ||
const rclcpp::Duration & | timeout, | ||
const IKValidationFunction & | validation_fn, | ||
const Params & | params | ||
) |
Computes pose inverse kinematics for the given group and set of targets.
This implements a Jacobian-based Newton-Raphson IK solver. The random sequence used internally is deterministic: given the same inputs, the solver will always find the same solution.
robot_state | A robot state, used to compute FK. It will be updated to the solution, if a solution is found, or arbitrarily if not. |
group | The joint model group to compute IK for. |
targets | The target poses to compute IK for. |
seed | A joint configuration to be used as a first seed, before starting taking random configurations. |
timeout | Search timeout in seconds. |
params | Other IK parameters like tolerance, etc. |
tip_link
to root_pose_tip
, or an error message if the preconditions are not met. bool pose_ik::unwindAndCheckLimits | ( | const moveit::core::JointModelGroup & | group, |
Eigen::VectorXd & | joint_values | ||
) |