![]() |
FancySafeBot 0.0.1
A safe robotics library
|
Inverse kinematics. More...
Classes | |
struct | fsb::OptimParameters |
struct | fsb::InverseKinematicsResult |
Enumerations | |
enum class | fsb::InverseKinematicsInfo : uint8_t { INVALID_INPUT = 0 , InverseKinematicsInfo::SUCCESS = 1 , InverseKinematicsInfo::WITHIN_FTOL = 2 , InverseKinematicsInfo::WITHIN_XTOL = 3 , InverseKinematicsInfo::WITHIN_FTOL_XTOL = 4 , InverseKinematicsInfo::MAXIMUM_EVALUATIONS_REACHED = 5 , InverseKinematicsInfo::SINGULAR_UPDATE_MATRIX = 6 } |
Functions | |
OptimParameters | fsb::default_optim_parameters () |
InverseKinematicsResult | fsb::compute_inverse_kinematics (const BodyTree &body_tree, const OptimParameters ¶ms, const JointSpacePosition &initial_config, size_t body_index, const Transform &target_pose, const Transform &base_pose=transform_identity()) |
Compute inverse kinematics for a given end-effector pose. | |
Inverse kinematics.
|
strong |
InverseKinematicsResult fsb::compute_inverse_kinematics | ( | const BodyTree & | body_tree, |
const OptimParameters & | params, | ||
const JointSpacePosition & | initial_config, | ||
size_t | body_index, | ||
const Transform & | target_pose, | ||
const Transform & | base_pose = transform_identity() |
||
) |
Compute inverse kinematics for a given end-effector pose.
body_tree | Body tree with link definitions |
params | Optimization parameters |
initial_config | Initial joint configuration |
body_index | Index of body to compute inverse kinematics for |
target_pose | Desired body target pose |
base_pose | Base pose (default is identity transform) |