Public Member Functions | Private Member Functions | Private Attributes
irb_2400_manipulator_kinematics::IKFastKinematicsPlugin Class Reference
Inheritance diagram for irb_2400_manipulator_kinematics::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)
 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, int &error_code)
 Given a desired pose of the end-effector, compute the joint angles to reach it.
 IKFastKinematicsPlugin ()
bool searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, const double &timeout, std::vector< double > &solution, int &error_code)
 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, const double &timeout, const unsigned int &redundancy, const double &consistency_limit, std::vector< double > &solution, int &error_code)
 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, const double &timeout, std::vector< double > &solution, const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> &desired_pose_callback, const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> &solution_callback, int &error_code)
 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, const double &timeout, const unsigned int &redundancy, const double &consistency_limit, std::vector< double > &solution, const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> &desired_pose_callback, const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> &solution_callback, int &error_code)
 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.

Private Member Functions

void fillFreeParams (int count, int *array)
void getClosestSolution (const std::vector< double > &ik_seed_state, std::vector< double > &solution)
bool getCount (int &count, const int &max_count, const int &min_count)
const std::vector< std::string > & getJointNames () const
const std::vector< std::string > & getLinkNames () const
void getSolution (int i, std::vector< double > &solution)
 Gets a specific solution from the set.
double harmonize (const std::vector< double > &ik_seed_state, std::vector< double > &solution)
double harmonize_old (const std::vector< double > &ik_seed_state, std::vector< double > &solution)
bool initialize (const std::string &group_name, const std::string &base_name, const std::string &tip_name, const double &search_discretization)
int solve (KDL::Frame &pose_frame, const std::vector< double > &vfree)
 Calls the IK solver from IKFast.

Private Attributes

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_
IkSolutionList< IkReal > solutions_

Detailed Description

Definition at line 72 of file irb_2400_manipulator_ikfast_plugin.cpp.


Constructor & Destructor Documentation

Definition at line 93 of file irb_2400_manipulator_ikfast_plugin.cpp.


Member Function Documentation

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

Definition at line 443 of file irb_2400_manipulator_ikfast_plugin.cpp.

void irb_2400_manipulator_kinematics::IKFastKinematicsPlugin::getClosestSolution ( const std::vector< double > &  ik_seed_state,
std::vector< double > &  solution 
) [private]

Definition at line 419 of file irb_2400_manipulator_ikfast_plugin.cpp.

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

Definition at line 449 of file irb_2400_manipulator_ikfast_plugin.cpp.

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

Implements kinematics::KinematicsBase.

Definition at line 85 of file irb_2400_manipulator_ikfast_plugin.cpp.

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

Implements kinematics::KinematicsBase.

Definition at line 86 of file irb_2400_manipulator_ikfast_plugin.cpp.

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

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

Parameters:
link_names- set of links for which poses are to be computed
joint_angles- current joint angles the response contains stamped pose information for all the requested links
Returns:
True if a valid solution was found, false otherwise

Definition at line 485 of file irb_2400_manipulator_ikfast_plugin.cpp.

bool irb_2400_manipulator_kinematics::IKFastKinematicsPlugin::getPositionIK ( const geometry_msgs::Pose ik_pose,
const std::vector< double > &  ik_seed_state,
std::vector< double > &  solution,
int &  error_code 
)

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
Returns:
True if a valid solution was found, false otherwise

Definition at line 517 of file irb_2400_manipulator_ikfast_plugin.cpp.

void irb_2400_manipulator_kinematics::IKFastKinematicsPlugin::getSolution ( int  i,
std::vector< double > &  solution 
) [private]

Gets a specific solution from the set.

Definition at line 342 of file irb_2400_manipulator_ikfast_plugin.cpp.

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

Definition at line 360 of file irb_2400_manipulator_ikfast_plugin.cpp.

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

Definition at line 383 of file irb_2400_manipulator_ikfast_plugin.cpp.

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

Definition at line 217 of file irb_2400_manipulator_ikfast_plugin.cpp.

bool irb_2400_manipulator_kinematics::IKFastKinematicsPlugin::searchPositionIK ( const geometry_msgs::Pose ik_pose,
const std::vector< double > &  ik_seed_state,
const double &  timeout,
std::vector< double > &  solution,
int &  error_code 
)

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

Definition at line 570 of file irb_2400_manipulator_ikfast_plugin.cpp.

bool irb_2400_manipulator_kinematics::IKFastKinematicsPlugin::searchPositionIK ( const geometry_msgs::Pose ik_pose,
const std::vector< double > &  ik_seed_state,
const double &  timeout,
const unsigned int &  redundancy,
const double &  consistency_limit,
std::vector< double > &  solution,
int &  error_code 
)

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

Definition at line 659 of file irb_2400_manipulator_ikfast_plugin.cpp.

bool irb_2400_manipulator_kinematics::IKFastKinematicsPlugin::searchPositionIK ( const geometry_msgs::Pose ik_pose,
const std::vector< double > &  ik_seed_state,
const double &  timeout,
std::vector< double > &  solution,
const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> &  desired_pose_callback,
const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> &  solution_callback,
int &  error_code 
)

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

Definition at line 762 of file irb_2400_manipulator_ikfast_plugin.cpp.

bool irb_2400_manipulator_kinematics::IKFastKinematicsPlugin::searchPositionIK ( const geometry_msgs::Pose ik_pose,
const std::vector< double > &  ik_seed_state,
const double &  timeout,
const unsigned int &  redundancy,
const double &  consistency_limit,
std::vector< double > &  solution,
const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> &  desired_pose_callback,
const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> &  solution_callback,
int &  error_code 
)

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

Definition at line 872 of file irb_2400_manipulator_ikfast_plugin.cpp.

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

Calls the IK solver from IKFast.

Returns:
The number of solutions found

Definition at line 312 of file irb_2400_manipulator_ikfast_plugin.cpp.


Member Data Documentation

Definition at line 80 of file irb_2400_manipulator_ikfast_plugin.cpp.

Definition at line 77 of file irb_2400_manipulator_ikfast_plugin.cpp.

Definition at line 76 of file irb_2400_manipulator_ikfast_plugin.cpp.

Definition at line 75 of file irb_2400_manipulator_ikfast_plugin.cpp.

Definition at line 74 of file irb_2400_manipulator_ikfast_plugin.cpp.

Definition at line 78 of file irb_2400_manipulator_ikfast_plugin.cpp.

Definition at line 79 of file irb_2400_manipulator_ikfast_plugin.cpp.

Definition at line 83 of file irb_2400_manipulator_ikfast_plugin.cpp.


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


irb_2400_arm_navigation
Author(s): Shaun Edwards
autogenerated on Sat Apr 12 2014 13:57:18