4 namespace experimental {
10 const Eigen::VectorXd& min_positions,
11 const Eigen::VectorXd& max_positions)
17 if (min_positions.size() != expected_size || max_positions.size() != expected_size)
21 for (
size_t i = 0; i < expected_size; ++i)
31 for (
size_t i = 0; i < expected_size; ++i)
47 const Eigen::VectorXd& initial_positions,
48 const Eigen::Vector3d& target_xyz)
const
52 Eigen::VectorXd ik_result_joint_angles(initial_positions.size());
56 ik_result_joint_angles,
63 ik_result_joint_angles,
67 return ik_result_joint_angles;
72 const Eigen::VectorXd& initial_positions,
73 const Eigen::Vector3d& target_xyz,
74 const Eigen::Vector3d& end_tip)
const
78 Eigen::VectorXd ik_result_joint_angles(initial_positions.size());
82 ik_result_joint_angles,
90 ik_result_joint_angles,
95 return ik_result_joint_angles;
100 const Eigen::VectorXd& initial_positions,
101 const Eigen::Vector3d& target_xyz,
102 const Eigen::Matrix3d& orientation)
const
106 Eigen::VectorXd ik_result_joint_angles(initial_positions.size());
110 ik_result_joint_angles,
118 ik_result_joint_angles,
123 return ik_result_joint_angles;
128 const Eigen::VectorXd& positions)
const
130 Eigen::Matrix4d transform;
132 return Eigen::Vector3d(transform(0,3), transform(1,3), transform(2,3));
137 const Eigen::VectorXd& positions,
138 Eigen::Vector3d& xyz_out,
139 Eigen::Vector3d& tip_axis)
const
141 Eigen::Matrix4d transform;
143 xyz_out = Eigen::Vector3d(transform(0,3), transform(1,3), transform(2,3));
144 tip_axis = Eigen::Vector3d(transform(0,2), transform(1,2), transform(2,2));
149 const Eigen::VectorXd& positions,
150 Eigen::Vector3d& xyz_out,
151 Eigen::Matrix3d& orientation)
const
153 Eigen::Matrix4d transform;
155 xyz_out = Eigen::Vector3d(transform(0,3), transform(1,3), transform(2,3));
156 orientation = transform.block<3,3>(0,0);