Public Member Functions | |
virtual const std::vector < std::string > & | getJointNames () const |
Return all the joint names in the order they are used internally. | |
virtual const std::vector < std::string > & | getLinkNames () const |
Return all the link names in the order they are represented internally. | |
virtual 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. | |
virtual 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) const |
Given a desired pose of the end-effector, compute the joint angles to reach it. | |
IKFastPlugin () | |
virtual bool | initialize (const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization) |
Initialization function for the kinematics. | |
virtual 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) 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). | |
virtual 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) 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). | |
virtual 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) 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). | |
virtual 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) 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. | |
virtual | ~IKFastPlugin () |
Virtual destructor for the interface. | |
Protected Member Functions | |
bool | loadModel (const std::string param) |
bool | readJoints (urdf::Model &robot_model) |
bool | searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, const std::vector< std::pair< double, double > > &min_max, moveit_msgs::MoveItErrorCodes &error_code, const double timeout=-1, const IKCallbackFn &solution_callback=0) const |
Protected Attributes | |
double | bounds_epsilon_ |
std::vector< double > | indices_ |
std::vector< std::string > | joints_ |
std::vector< std::string > | links_ |
std::vector< std::pair< double, double > > | min_max_ |
Definition at line 208 of file ikfast_plugin.cpp.
virtual IKFAST_NAMESPACE::IKFastPlugin::~IKFastPlugin | ( | ) | [inline, virtual] |
Virtual destructor for the interface.
Definition at line 384 of file ikfast_plugin.cpp.
IKFAST_NAMESPACE::IKFastPlugin::IKFastPlugin | ( | ) | [inline] |
Definition at line 386 of file ikfast_plugin.cpp.
virtual const std::vector<std::string>& IKFAST_NAMESPACE::IKFastPlugin::getJointNames | ( | ) | const [inline, virtual] |
Return all the joint names in the order they are used internally.
Implements kinematics::KinematicsBase.
Definition at line 370 of file ikfast_plugin.cpp.
virtual const std::vector<std::string>& IKFAST_NAMESPACE::IKFastPlugin::getLinkNames | ( | ) | const [inline, virtual] |
Return all the link names in the order they are represented internally.
Implements kinematics::KinematicsBase.
Definition at line 377 of file ikfast_plugin.cpp.
virtual bool IKFAST_NAMESPACE::IKFastPlugin::getPositionFK | ( | const std::vector< std::string > & | link_names, |
const std::vector< double > & | joint_angles, | ||
std::vector< geometry_msgs::Pose > & | poses | ||
) | const [inline, virtual] |
Given a set of joint angles and a set of links, compute their pose.
request | - the request contains the joint angles, set of links for which poses are to be computed and a timeout |
response | - the response contains stamped pose information for all the requested links |
Implements kinematics::KinematicsBase.
Definition at line 320 of file ikfast_plugin.cpp.
virtual bool IKFAST_NAMESPACE::IKFastPlugin::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 | ||
) | const [inline, virtual] |
Given a desired pose of the end-effector, compute the joint angles to reach it.
ik_link_name | - the name of the link for which IK is being computed |
ik_pose | the desired pose of the link |
ik_seed_state | an initial guess solution for the inverse kinematics |
Implements kinematics::KinematicsBase.
Definition at line 217 of file ikfast_plugin.cpp.
virtual bool IKFAST_NAMESPACE::IKFastPlugin::initialize | ( | const std::string & | robot_description, |
const std::string & | group_name, | ||
const std::string & | base_frame, | ||
const std::string & | tip_frame, | ||
double | search_discretization | ||
) | [inline, virtual] |
Initialization function for the kinematics.
Implements kinematics::KinematicsBase.
Definition at line 346 of file ikfast_plugin.cpp.
bool IKFAST_NAMESPACE::IKFastPlugin::loadModel | ( | const std::string | param | ) | [inline, protected] |
Definition at line 437 of file ikfast_plugin.cpp.
bool IKFAST_NAMESPACE::IKFastPlugin::readJoints | ( | urdf::Model & | robot_model | ) | [inline, protected] |
Definition at line 451 of file ikfast_plugin.cpp.
virtual bool IKFAST_NAMESPACE::IKFastPlugin::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 | ||
) | const [inline, 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).
ik_pose | the desired pose of the link |
ik_seed_state | an initial guess solution for the inverse kinematics |
Implements kinematics::KinematicsBase.
Definition at line 235 of file ikfast_plugin.cpp.
virtual bool IKFAST_NAMESPACE::IKFastPlugin::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 | ||
) | const [inline, 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).
ik_pose | the desired pose of the link |
ik_seed_state | an initial guess solution for the inverse kinematics |
the | distance that the redundancy can be from the current position |
Implements kinematics::KinematicsBase.
Definition at line 255 of file ikfast_plugin.cpp.
virtual bool IKFAST_NAMESPACE::IKFastPlugin::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 | ||
) | const [inline, 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).
ik_pose | the desired pose of the link |
ik_seed_state | an initial guess solution for the inverse kinematics |
Implements kinematics::KinematicsBase.
Definition at line 277 of file ikfast_plugin.cpp.
virtual bool IKFAST_NAMESPACE::IKFastPlugin::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 | ||
) | const [inline, 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.
ik_pose | the desired pose of the link |
ik_seed_state | an initial guess solution for the inverse kinematics |
consistency_limit | the distance that the redundancy can be from the current position |
Implements kinematics::KinematicsBase.
Definition at line 299 of file ikfast_plugin.cpp.
bool IKFAST_NAMESPACE::IKFastPlugin::searchPositionIK | ( | const geometry_msgs::Pose & | ik_pose, |
const std::vector< double > & | ik_seed_state, | ||
std::vector< double > & | solution, | ||
const std::vector< std::pair< double, double > > & | min_max, | ||
moveit_msgs::MoveItErrorCodes & | error_code, | ||
const double | timeout = -1 , |
||
const IKCallbackFn & | solution_callback = 0 |
||
) | const [inline, protected] |
Definition at line 395 of file ikfast_plugin.cpp.
double IKFAST_NAMESPACE::IKFastPlugin::bounds_epsilon_ [protected] |
Definition at line 391 of file ikfast_plugin.cpp.
std::vector<double> IKFAST_NAMESPACE::IKFastPlugin::indices_ [protected] |
Definition at line 392 of file ikfast_plugin.cpp.
std::vector<std::string> IKFAST_NAMESPACE::IKFastPlugin::joints_ [protected] |
Definition at line 394 of file ikfast_plugin.cpp.
std::vector<std::string> IKFAST_NAMESPACE::IKFastPlugin::links_ [protected] |
Definition at line 393 of file ikfast_plugin.cpp.
std::vector<std::pair<double, double> > IKFAST_NAMESPACE::IKFastPlugin::min_max_ [protected] |
Definition at line 390 of file ikfast_plugin.cpp.