Wrapper around an IK solver implementation. More...
#include <kinematics.h>
Public Member Functions | |
IKSolver (const moveit::core::RobotState &robot_state, std::string group_name, double max_time=0.005) | |
Creates an internal IK solver for the specified robot and planning group. More... | |
void | setKinematicState (const moveit::core::RobotState &state) |
Should be called whenever the robot's kinematic state has changed. More... | |
bool | solve (const Eigen::VectorXd &seed, const Eigen::Affine3d &tool_pose, Eigen::VectorXd &solution, Eigen::VectorXd tol=Eigen::VectorXd::Constant(6, 0.005)) |
Find the joint position that achieves the requested tool pose. More... | |
bool | solve (const std::vector< double > &seed, const Eigen::Affine3d &tool_pose, std::vector< double > &solution, std::vector< double > tol=std::vector< double >(6, 0.005)) |
Find the joint position that achieves the requested tool pose. More... | |
bool | solve (const std::vector< double > &seed, const moveit_msgs::Constraints &tool_constraints, std::vector< double > &solution) |
Find the joint position that obeys the specified Cartesian constraint. More... | |
bool | solve (const Eigen::VectorXd &seed, const moveit_msgs::Constraints &tool_constraints, Eigen::VectorXd &solution) |
Find the joint position that obeys the specified Cartesian constraint. More... | |
Protected Attributes | |
std::string | group_name_ |
std::shared_ptr< TRAC_IK::TRAC_IK > | ik_solver_impl_ |
moveit::core::RobotModelConstPtr | robot_model_ |
moveit::core::RobotStatePtr | robot_state_ |
Eigen::Affine3d | tf_base_to_root_ |
Wrapper around an IK solver implementation.
Definition at line 70 of file kinematics.h.
stomp_moveit::utils::kinematics::IKSolver::IKSolver | ( | const moveit::core::RobotState & | robot_state, |
std::string | group_name, | ||
double | max_time = 0.005 |
||
) |
Creates an internal IK solver for the specified robot and planning group.
robot_state | The current robot state |
group_name | The planning group name |
max_time | Max time allowed to find a solution. |
Definition at line 100 of file kinematics.cpp.
void stomp_moveit::utils::kinematics::IKSolver::setKinematicState | ( | const moveit::core::RobotState & | state | ) |
Should be called whenever the robot's kinematic state has changed.
state | The current robot state |
Definition at line 116 of file kinematics.cpp.
bool stomp_moveit::utils::kinematics::IKSolver::solve | ( | const Eigen::VectorXd & | seed, |
const Eigen::Affine3d & | tool_pose, | ||
Eigen::VectorXd & | solution, | ||
Eigen::VectorXd | tol = Eigen::VectorXd::Constant(6,0.005) |
||
) |
Find the joint position that achieves the requested tool pose.
seed | A joint pose to seed the solver. |
tool_pose | The tool pose for which a joint solution must be found. The frame of reference is assumed to be the model root |
solution | The joint values that place the tool in the requested cartesian pose |
tol | The tolerance values for each dimension of position and orientation relative to the tool pose. |
Definition at line 128 of file kinematics.cpp.
bool stomp_moveit::utils::kinematics::IKSolver::solve | ( | const std::vector< double > & | seed, |
const Eigen::Affine3d & | tool_pose, | ||
std::vector< double > & | solution, | ||
std::vector< double > | tol = std::vector<double>(6,0.005) |
||
) |
Find the joint position that achieves the requested tool pose.
seed | A joint pose to seed the solver. |
tool_pose | The tool pose for which a joint solution must be found. The frame of reference is assumed to be the model root |
solution | The joint values that place the tool in the requested cartesian pose |
tol | The tolerance values for each dimension of position and orientation relative to the tool pose. |
Definition at line 150 of file kinematics.cpp.
bool stomp_moveit::utils::kinematics::IKSolver::solve | ( | const std::vector< double > & | seed, |
const moveit_msgs::Constraints & | tool_constraints, | ||
std::vector< double > & | solution | ||
) |
Find the joint position that obeys the specified Cartesian constraint.
seed | A joint pose to seed the solver. |
tool_constraints | The Cartesian constraint info to be used in determining the tool pose and tolerances |
solution | The joint values that comply with the Cartesian constraint. |
Definition at line 182 of file kinematics.cpp.
bool stomp_moveit::utils::kinematics::IKSolver::solve | ( | const Eigen::VectorXd & | seed, |
const moveit_msgs::Constraints & | tool_constraints, | ||
Eigen::VectorXd & | solution | ||
) |
Find the joint position that obeys the specified Cartesian constraint.
seed | A joint pose to seed the solver. |
tool_constraints | The Cartesian constraint info to be used in determining the tool pose and tolerances |
solution | The joint values that comply with the Cartesian constraint. |
Definition at line 194 of file kinematics.cpp.