Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
pr2_arm_kinematics::PR2ArmIKSolver Class Reference

#include <pr2_arm_kinematics_plugin.h>

Inheritance diagram for pr2_arm_kinematics::PR2ArmIKSolver:
Inheritance graph
[legend]

Public Member Functions

int CartToJnt (const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out)
 
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)
 
 ~PR2ArmIKSolver ()
 
- Public Member Functions inherited from KDL::ChainIkSolverPos
virtual void updateInternalDataStructures ()=0
 
virtual ~ChainIkSolverPos ()
 
- Public Member Functions inherited from KDL::SolverI
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...
 
- Public Attributes inherited from KDL::SolverI
 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

- Protected Attributes inherited from KDL::SolverI
int error
 

Detailed Description

Definition at line 72 of file pr2_arm_kinematics_plugin.h.

Constructor & Destructor Documentation

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 87 of file pr2_arm_kinematics_plugin.cpp.

pr2_arm_kinematics::PR2ArmIKSolver::~PR2ArmIKSolver ( )
inline

Definition at line 88 of file pr2_arm_kinematics_plugin.h.

Member Function Documentation

int pr2_arm_kinematics::PR2ArmIKSolver::CartToJnt ( const KDL::JntArray q_init,
const KDL::Frame p_in,
KDL::JntArray q_out 
)
virtual

Implements KDL::ChainIkSolverPos.

Definition at line 101 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 157 of file pr2_arm_kinematics_plugin.cpp.

bool pr2_arm_kinematics::PR2ArmIKSolver::getCount ( int &  count,
const int &  max_count,
const int &  min_count 
)
private

Definition at line 51 of file pr2_arm_kinematics_plugin.cpp.

void pr2_arm_kinematics::PR2ArmIKSolver::getSolverInfo ( moveit_msgs::KinematicSolverInfo &  response)
inline

Definition at line 104 of file pr2_arm_kinematics_plugin.h.

Member Data Documentation

bool pr2_arm_kinematics::PR2ArmIKSolver::active_

Indicates whether the solver has been successfully initialized.

Definition at line 98 of file pr2_arm_kinematics_plugin.h.

int pr2_arm_kinematics::PR2ArmIKSolver::free_angle_
private

Definition at line 114 of file pr2_arm_kinematics_plugin.h.

PR2ArmIK pr2_arm_kinematics::PR2ArmIKSolver::pr2_arm_ik_

The PR2 inverse kinematics solver.

Definition at line 88 of file pr2_arm_kinematics_plugin.h.

std::string pr2_arm_kinematics::PR2ArmIKSolver::root_frame_name_
private

Definition at line 116 of file pr2_arm_kinematics_plugin.h.

double pr2_arm_kinematics::PR2ArmIKSolver::search_discretization_angle_
private

Definition at line 112 of file pr2_arm_kinematics_plugin.h.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jul 10 2019 04:03:06