Public Member Functions | Private Member Functions | Private Attributes
ikfast_kinematics_plugin::IKFastKinematicsPlugin Class Reference
Inheritance diagram for ikfast_kinematics_plugin::IKFastKinematicsPlugin:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool getPositionFK (const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const
 Given a set of joint angles and a set of links, compute their pose.
bool getPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const
 Given a desired pose of the end-effector, compute the joint angles to reach it.
bool getPositionIK (const std::vector< geometry_msgs::Pose > &ik_poses, const std::vector< double > &ik_seed_state, std::vector< std::vector< double > > &solutions, kinematics::KinematicsResult &result, const kinematics::KinematicsQueryOptions &options) const
 Given a desired pose of the end-effector, compute the set joint angles solutions that are able to reach it.
 IKFastKinematicsPlugin ()
bool searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const
 Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines).
bool searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const
 Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines).
bool searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const
 Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines).
bool searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const
 Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines). The consistency_limit specifies that only certain redundancy positions around those specified in the seed state are admissible and need to be searched.
bool setRedundantJoints (const std::vector< unsigned int > &redundant_joint_indices)
 Overrides the default method to prevent changing the redundant joints.
void setSearchDiscretization (const std::map< int, double > &discretization)
 Sets the discretization value for the redundant joint.

Private Member Functions

void fillFreeParams (int count, int *array)
void getClosestSolution (const IkSolutionList< IkReal > &solutions, const std::vector< double > &ik_seed_state, std::vector< double > &solution) const
bool getCount (int &count, const int &max_count, const int &min_count) const
const std::vector< std::string > & getJointNames () const
const std::vector< std::string > & getLinkNames () const
void getSolution (const IkSolutionList< IkReal > &solutions, int i, std::vector< double > &solution) const
 Gets a specific solution from the set.
double harmonize (const std::vector< double > &ik_seed_state, std::vector< double > &solution) const
bool initialize (const std::string &robot_description, const std::string &group_name, const std::string &base_name, const std::string &tip_name, double search_discretization)
bool sampleRedundantJoint (kinematics::DiscretizationMethod method, std::vector< double > &sampled_joint_vals) const
 samples the designated redundant joint using the chosen discretization method
int solve (KDL::Frame &pose_frame, const std::vector< double > &vfree, IkSolutionList< IkReal > &solutions) const
 Calls the IK solver from IKFast.

Private Attributes

bool active_
std::vector< int > free_params_
std::vector< bool > joint_has_limits_vector_
std::vector< double > joint_max_vector_
std::vector< double > joint_min_vector_
std::vector< std::string > joint_names_
std::vector< std::string > link_names_
size_t num_joints_

Detailed Description

Definition at line 131 of file fetch_arm_ikfast_moveit_plugin.cpp.


Constructor & Destructor Documentation

Definition at line 150 of file fetch_arm_ikfast_moveit_plugin.cpp.


Member Function Documentation

void ikfast_kinematics_plugin::IKFastKinematicsPlugin::fillFreeParams ( int  count,
int *  array 
) [private]

Definition at line 649 of file fetch_arm_ikfast_moveit_plugin.cpp.

void ikfast_kinematics_plugin::IKFastKinematicsPlugin::getClosestSolution ( const IkSolutionList< IkReal > &  solutions,
const std::vector< double > &  ik_seed_state,
std::vector< double > &  solution 
) const [private]

Definition at line 625 of file fetch_arm_ikfast_moveit_plugin.cpp.

bool ikfast_kinematics_plugin::IKFastKinematicsPlugin::getCount ( int &  count,
const int &  max_count,
const int &  min_count 
) const [private]

Definition at line 655 of file fetch_arm_ikfast_moveit_plugin.cpp.

const std::vector<std::string>& ikfast_kinematics_plugin::IKFastKinematicsPlugin::getJointNames ( ) const [inline, private, virtual]

Implements kinematics::KinematicsBase.

Definition at line 142 of file fetch_arm_ikfast_moveit_plugin.cpp.

const std::vector<std::string>& ikfast_kinematics_plugin::IKFastKinematicsPlugin::getLinkNames ( ) const [inline, private, virtual]

Implements kinematics::KinematicsBase.

Definition at line 143 of file fetch_arm_ikfast_moveit_plugin.cpp.

bool ikfast_kinematics_plugin::IKFastKinematicsPlugin::getPositionFK ( const std::vector< std::string > &  link_names,
const std::vector< double > &  joint_angles,
std::vector< geometry_msgs::Pose > &  poses 
) const [virtual]

Given a set of joint angles and a set of links, compute their pose.

Parameters:
link_namesA set of links for which FK needs to be computed
joint_anglesThe state for which FK is being computed
posesThe resultant set of poses (in the frame returned by getBaseFrame())
Returns:
True if a valid solution was found, false otherwise

Implements kinematics::KinematicsBase.

Definition at line 691 of file fetch_arm_ikfast_moveit_plugin.cpp.

bool ikfast_kinematics_plugin::IKFastKinematicsPlugin::getPositionIK ( const geometry_msgs::Pose ik_pose,
const std::vector< double > &  ik_seed_state,
std::vector< double > &  solution,
moveit_msgs::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions() 
) const [virtual]

Given a desired pose of the end-effector, compute the joint angles to reach it.

Parameters:
ik_posethe desired pose of the link
ik_seed_statean initial guess solution for the inverse kinematics
solutionthe solution vector
error_codean error code that encodes the reason for failure or success
Returns:
True if a valid solution was found, false otherwise

Implements kinematics::KinematicsBase.

Definition at line 1007 of file fetch_arm_ikfast_moveit_plugin.cpp.

bool ikfast_kinematics_plugin::IKFastKinematicsPlugin::getPositionIK ( const std::vector< geometry_msgs::Pose > &  ik_poses,
const std::vector< double > &  ik_seed_state,
std::vector< std::vector< double > > &  solutions,
kinematics::KinematicsResult result,
const kinematics::KinematicsQueryOptions options 
) const [virtual]

Given a desired pose of the end-effector, compute the set joint angles solutions that are able to reach it.

This is a default implementation that returns only one solution and so its result is equivalent to calling 'getPositionIK(...)' with a zero initialized seed.

Parameters:
ik_posesThe desired pose of each tip link
ik_seed_statean initial guess solution for the inverse kinematics
solutionsA vector of vectors where each entry is a valid joint solution
resultA struct that reports the results of the query
optionsAn option struct which contains the type of redundancy discretization used. This default implementation only supports the KinmaticSearches::NO_DISCRETIZATION method; requesting any other will result in failure.
Returns:
True if a valid set of solutions was found, false otherwise.

Reimplemented from kinematics::KinematicsBase.

Definition at line 1076 of file fetch_arm_ikfast_moveit_plugin.cpp.

void ikfast_kinematics_plugin::IKFastKinematicsPlugin::getSolution ( const IkSolutionList< IkReal > &  solutions,
int  i,
std::vector< double > &  solution 
) const [private]

Gets a specific solution from the set.

Definition at line 561 of file fetch_arm_ikfast_moveit_plugin.cpp.

double ikfast_kinematics_plugin::IKFastKinematicsPlugin::harmonize ( const std::vector< double > &  ik_seed_state,
std::vector< double > &  solution 
) const [private]

Definition at line 579 of file fetch_arm_ikfast_moveit_plugin.cpp.

bool ikfast_kinematics_plugin::IKFastKinematicsPlugin::initialize ( const std::string &  robot_description,
const std::string &  group_name,
const std::string &  base_name,
const std::string &  tip_name,
double  search_discretization 
) [private, virtual]

Implements kinematics::KinematicsBase.

Definition at line 327 of file fetch_arm_ikfast_moveit_plugin.cpp.

bool ikfast_kinematics_plugin::IKFastKinematicsPlugin::sampleRedundantJoint ( kinematics::DiscretizationMethod  method,
std::vector< double > &  sampled_joint_vals 
) const [private]

samples the designated redundant joint using the chosen discretization method

Parameters:
methodAn enumeration flag indicating the discretization method to be used
sampled_joint_valsSampled joint values for the redundant joint
Returns:
True if sampling succeeded.

Definition at line 1219 of file fetch_arm_ikfast_moveit_plugin.cpp.

bool ikfast_kinematics_plugin::IKFastKinematicsPlugin::searchPositionIK ( const geometry_msgs::Pose ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
std::vector< double > &  solution,
moveit_msgs::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions() 
) const [virtual]

Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines).

Parameters:
ik_posethe desired pose of the link
ik_seed_statean initial guess solution for the inverse kinematics
Returns:
True if a valid solution was found, false otherwise

Implements kinematics::KinematicsBase.

Definition at line 737 of file fetch_arm_ikfast_moveit_plugin.cpp.

bool ikfast_kinematics_plugin::IKFastKinematicsPlugin::searchPositionIK ( const geometry_msgs::Pose ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
const std::vector< double > &  consistency_limits,
std::vector< double > &  solution,
moveit_msgs::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions() 
) const [virtual]

Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines).

Parameters:
ik_posethe desired pose of the link
ik_seed_statean initial guess solution for the inverse kinematics
thedistance that the redundancy can be from the current position
Returns:
True if a valid solution was found, false otherwise

Implements kinematics::KinematicsBase.

Definition at line 757 of file fetch_arm_ikfast_moveit_plugin.cpp.

bool ikfast_kinematics_plugin::IKFastKinematicsPlugin::searchPositionIK ( const geometry_msgs::Pose ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
std::vector< double > &  solution,
const IKCallbackFn solution_callback,
moveit_msgs::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions() 
) const [virtual]

Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines).

Parameters:
ik_posethe desired pose of the link
ik_seed_statean initial guess solution for the inverse kinematics
Returns:
True if a valid solution was found, false otherwise

Implements kinematics::KinematicsBase.

Definition at line 776 of file fetch_arm_ikfast_moveit_plugin.cpp.

bool ikfast_kinematics_plugin::IKFastKinematicsPlugin::searchPositionIK ( const geometry_msgs::Pose ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
const std::vector< double > &  consistency_limits,
std::vector< double > &  solution,
const IKCallbackFn solution_callback,
moveit_msgs::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions() 
) const [virtual]

Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines). The consistency_limit specifies that only certain redundancy positions around those specified in the seed state are admissible and need to be searched.

Parameters:
ik_posethe desired pose of the link
ik_seed_statean initial guess solution for the inverse kinematics
consistency_limitthe distance that the redundancy can be from the current position
Returns:
True if a valid solution was found, false otherwise

search_mode is currently fixed during code generation

Implements kinematics::KinematicsBase.

Definition at line 795 of file fetch_arm_ikfast_moveit_plugin.cpp.

bool ikfast_kinematics_plugin::IKFastKinematicsPlugin::setRedundantJoints ( const std::vector< unsigned int > &  redundant_joint_indices) [virtual]

Overrides the default method to prevent changing the redundant joints.

Reimplemented from kinematics::KinematicsBase.

Definition at line 481 of file fetch_arm_ikfast_moveit_plugin.cpp.

void ikfast_kinematics_plugin::IKFastKinematicsPlugin::setSearchDiscretization ( const std::map< int, double > &  discretization)

Sets the discretization value for the redundant joint.

Since this ikfast implementation allows for one redundant joint then only the first entry will be in the discretization map will be used. Calling this method replaces previous discretization settings.

Parameters:
discretizationa map of joint indices and discretization value pairs.

Reimplemented from kinematics::KinematicsBase.

Definition at line 447 of file fetch_arm_ikfast_moveit_plugin.cpp.

int ikfast_kinematics_plugin::IKFastKinematicsPlugin::solve ( KDL::Frame pose_frame,
const std::vector< double > &  vfree,
IkSolutionList< IkReal > &  solutions 
) const [private]

Calls the IK solver from IKFast.

Returns:
The number of solutions found

Definition at line 488 of file fetch_arm_ikfast_moveit_plugin.cpp.


Member Data Documentation

Definition at line 140 of file fetch_arm_ikfast_moveit_plugin.cpp.

Definition at line 139 of file fetch_arm_ikfast_moveit_plugin.cpp.

Definition at line 136 of file fetch_arm_ikfast_moveit_plugin.cpp.

Definition at line 135 of file fetch_arm_ikfast_moveit_plugin.cpp.

Definition at line 134 of file fetch_arm_ikfast_moveit_plugin.cpp.

Definition at line 133 of file fetch_arm_ikfast_moveit_plugin.cpp.

Definition at line 137 of file fetch_arm_ikfast_moveit_plugin.cpp.

Definition at line 138 of file fetch_arm_ikfast_moveit_plugin.cpp.


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


fetch_ikfast_plugin
Author(s): Michael Ferguson
autogenerated on Sat Apr 27 2019 03:12:11