#include <moveit/robot_model/joint_model_group.hpp>
#include <moveit/robot_model/link_model.hpp>
#include <moveit/robot_state/robot_state.hpp>
#include <Eigen/Geometry>
#include <chrono>
#include <rclcpp/duration.hpp>
#include <tl_expected/expected.hpp>
#include "pose_ik/pose_ik_parameters.hpp"
|
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 ¶ms) |
| Computes pose inverse kinematics for the given group and set of targets.
|
|
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::unwindAndCheckLimits (const moveit::core::JointModelGroup &group, Eigen::VectorXd &joint_values) |
|