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) 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.
 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 boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> &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 boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> &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.

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
double harmonize_old (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)
int solve (KDL::Frame &pose_frame, const std::vector< double > &vfree, IkSolutionList< IkReal > &solutions) const
 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_

Detailed Description

Definition at line 72 of file irb_2400_manipulator_ikfast_moveit_plugin.cpp.


Constructor & Destructor Documentation


Member Function Documentation

void irb_2400_manipulator_kinematics::IKFastKinematicsPlugin::fillFreeParams ( int  count,
int *  array 
) [private]
void irb_2400_manipulator_kinematics::IKFastKinematicsPlugin::getClosestSolution ( const IkSolutionList< IkReal > &  solutions,
const std::vector< double > &  ik_seed_state,
std::vector< double > &  solution 
) const [private]
bool irb_2400_manipulator_kinematics::IKFastKinematicsPlugin::getCount ( int &  count,
const int &  max_count,
const int &  min_count 
) const [private]
const std::vector<std::string>& irb_2400_manipulator_kinematics::IKFastKinematicsPlugin::getJointNames ( ) const [inline, private, virtual]
const std::vector<std::string>& irb_2400_manipulator_kinematics::IKFastKinematicsPlugin::getLinkNames ( ) const [inline, private, virtual]
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 
) const [virtual]

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

Implements kinematics::KinematicsBase.

Definition at line 482 of file irb_2400_manipulator_ikfast_moveit_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,
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
Returns:
True if a valid solution was found, false otherwise

Implements kinematics::KinematicsBase.

Definition at line 514 of file irb_2400_manipulator_ikfast_moveit_plugin.cpp.

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

Gets a specific solution from the set.

Definition at line 339 of file irb_2400_manipulator_ikfast_moveit_plugin.cpp.

double irb_2400_manipulator_kinematics::IKFastKinematicsPlugin::harmonize ( const std::vector< double > &  ik_seed_state,
std::vector< double > &  solution 
) const [private]
double irb_2400_manipulator_kinematics::IKFastKinematicsPlugin::harmonize_old ( const std::vector< double > &  ik_seed_state,
std::vector< double > &  solution 
) const [private]
bool irb_2400_manipulator_kinematics::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]
bool irb_2400_manipulator_kinematics::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 569 of file irb_2400_manipulator_ikfast_moveit_plugin.cpp.

bool irb_2400_manipulator_kinematics::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 660 of file irb_2400_manipulator_ikfast_moveit_plugin.cpp.

bool irb_2400_manipulator_kinematics::IKFastKinematicsPlugin::searchPositionIK ( const geometry_msgs::Pose ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
std::vector< double > &  solution,
const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> &  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).

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 761 of file irb_2400_manipulator_ikfast_moveit_plugin.cpp.

bool irb_2400_manipulator_kinematics::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 boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> &  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.

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 863 of file irb_2400_manipulator_ikfast_moveit_plugin.cpp.

int irb_2400_manipulator_kinematics::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 309 of file irb_2400_manipulator_ikfast_moveit_plugin.cpp.


Member Data Documentation


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


abb_moveit_plugins
Author(s): Jeremy Zoss
autogenerated on Thu Aug 27 2015 11:57:40