Public Member Functions | Protected Attributes | List of all members
stomp_moveit::utils::kinematics::IKSolver Class Reference

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_IKik_solver_impl_
 
moveit::core::RobotModelConstPtr robot_model_
 
moveit::core::RobotStatePtr robot_state_
 
Eigen::Affine3d tf_base_to_root_
 

Detailed Description

Wrapper around an IK solver implementation.

Definition at line 70 of file kinematics.h.

Constructor & Destructor Documentation

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.

Parameters
robot_stateThe current robot state
group_nameThe planning group name
max_timeMax time allowed to find a solution.

Definition at line 100 of file kinematics.cpp.

Member Function Documentation

void stomp_moveit::utils::kinematics::IKSolver::setKinematicState ( const moveit::core::RobotState state)

Should be called whenever the robot's kinematic state has changed.

Parameters
stateThe 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.

Parameters
seedA joint pose to seed the solver.
tool_poseThe tool pose for which a joint solution must be found. The frame of reference is assumed to be the model root
solutionThe joint values that place the tool in the requested cartesian pose
tolThe tolerance values for each dimension of position and orientation relative to the tool pose.
Returns
True if a solution was found, false otherwise.

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.

Parameters
seedA joint pose to seed the solver.
tool_poseThe tool pose for which a joint solution must be found. The frame of reference is assumed to be the model root
solutionThe joint values that place the tool in the requested cartesian pose
tolThe tolerance values for each dimension of position and orientation relative to the tool pose.
Returns
True if a solution was found, false otherwise.

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.

Parameters
seedA joint pose to seed the solver.
tool_constraintsThe Cartesian constraint info to be used in determining the tool pose and tolerances
solutionThe joint values that comply with the Cartesian constraint.
Returns
True if a solution was found, false otherwise.

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.

Parameters
seedA joint pose to seed the solver.
tool_constraintsThe Cartesian constraint info to be used in determining the tool pose and tolerances
solutionThe joint values that comply with the Cartesian constraint.
Returns
True if a solution was found, false otherwise.

Definition at line 194 of file kinematics.cpp.


The documentation for this class was generated from the following files:


stomp_moveit
Author(s): Jorge Nicho
autogenerated on Fri May 8 2020 03:35:47