#include <pr2_arm_kinematics_plugin.h>
Public Member Functions | |
int | CartToJnt (const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out) override |
int | cartToJntSearch (const KDL::JntArray &q_in, const KDL::Frame &p_in, KDL::JntArray &q_out, const double &timeout) |
void | getSolverInfo (moveit_msgs::KinematicSolverInfo &response) |
PR2ArmIKSolver (const urdf::ModelInterface &robot_model, const std::string &root_frame_name, const std::string &tip_frame_name, const double &search_discretization_angle, const int &free_angle) | |
void | updateInternalDataStructures () |
~PR2ArmIKSolver () override | |
![]() | |
virtual | ~ChainIkSolverPos () |
![]() | |
virtual int | getError () const |
SolverI () | |
virtual const char * | strError (const int error) const |
virtual | ~SolverI () |
Public Attributes | |
bool | active_ |
Indicates whether the solver has been successfully initialized. More... | |
PR2ArmIK | pr2_arm_ik_ |
The PR2 inverse kinematics solver. More... | |
![]() | |
E_DEGRADED | |
E_MAX_ITERATIONS_EXCEEDED | |
E_NO_CONVERGE | |
E_NOERROR | |
E_NOT_IMPLEMENTED | |
E_NOT_UP_TO_DATE | |
E_OUT_OF_RANGE | |
E_SIZE_MISMATCH | |
E_SVD_FAILED | |
E_UNDEFINED | |
Private Member Functions | |
bool | getCount (int &count, const int &max_count, const int &min_count) |
Private Attributes | |
int | free_angle_ |
std::string | root_frame_name_ |
double | search_discretization_angle_ |
Additional Inherited Members | |
![]() | |
int | error |
Definition at line 70 of file pr2_arm_kinematics_plugin.h.
pr2_arm_kinematics::PR2ArmIKSolver::PR2ArmIKSolver | ( | const urdf::ModelInterface & | robot_model, |
const std::string & | root_frame_name, | ||
const std::string & | tip_frame_name, | ||
const double & | search_discretization_angle, | ||
const int & | free_angle | ||
) |
Definition at line 86 of file pr2_arm_kinematics_plugin.cpp.
|
inlineoverride |
Definition at line 86 of file pr2_arm_kinematics_plugin.h.
|
overridevirtual |
Implements KDL::ChainIkSolverPos.
Definition at line 106 of file pr2_arm_kinematics_plugin.cpp.
int pr2_arm_kinematics::PR2ArmIKSolver::cartToJntSearch | ( | const KDL::JntArray & | q_in, |
const KDL::Frame & | p_in, | ||
KDL::JntArray & | q_out, | ||
const double & | timeout | ||
) |
Definition at line 162 of file pr2_arm_kinematics_plugin.cpp.
|
private |
Definition at line 50 of file pr2_arm_kinematics_plugin.cpp.
|
inline |
Definition at line 111 of file pr2_arm_kinematics_plugin.h.
|
virtual |
Implements KDL::ChainIkSolverPos.
Definition at line 100 of file pr2_arm_kinematics_plugin.cpp.
bool pr2_arm_kinematics::PR2ArmIKSolver::active_ |
Indicates whether the solver has been successfully initialized.
Definition at line 105 of file pr2_arm_kinematics_plugin.h.
|
private |
Definition at line 121 of file pr2_arm_kinematics_plugin.h.
PR2ArmIK pr2_arm_kinematics::PR2ArmIKSolver::pr2_arm_ik_ |
The PR2 inverse kinematics solver.
Definition at line 100 of file pr2_arm_kinematics_plugin.h.
|
private |
Definition at line 123 of file pr2_arm_kinematics_plugin.h.
|
private |
Definition at line 119 of file pr2_arm_kinematics_plugin.h.