Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
pr2_arm_kinematics::PR2ArmKinematicsPlugin Class Reference

#include <pr2_arm_kinematics_plugin.h>

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

Public Member Functions

const std::vector< std::string > & getJointNames () const override
 Return all the joint names in the order they are used internally. More...
 
const std::vector< std::string > & getLinkNames () const override
 Return all the link names in the order they are represented internally. More...
 
bool getPositionFK (const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const override
 Given a set of joint angles and a set of links, compute their pose. More...
 
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 override
 Given a desired pose of the end-effector, compute the joint angles to reach it. More...
 
bool initialize (const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization) override
 Initialization function for the kinematics. More...
 
bool isActive ()
 Specifies if the node is active or not. More...
 
 PR2ArmKinematicsPlugin ()
 Plugin-able interface to the PR2 arm kinematics. More...
 
bool searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limit, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
 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. More...
 
bool searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limit, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
 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). More...
 
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 override
 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). More...
 
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 override
 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). More...
 
- Public Member Functions inherited from kinematics::KinematicsBase
virtual const std::string & getBaseFrame () const
 Return the name of the frame in which the solver is operating. This is usually a link name. No namespacing (e.g., no "/" prefix) should be used. More...
 
double getDefaultTimeout () const
 For functions that require a timeout specified but one is not specified using arguments, this default timeout is used. More...
 
virtual const std::string & getGroupName () const
 Return the name of the group that the solver is operating on. More...
 
virtual bool getPositionIK (const std::vector< geometry_msgs::Pose > &ik_poses, const std::vector< double > &ik_seed_state, std::vector< std::vector< double > > &solutions, KinematicsResult &result, const kinematics::KinematicsQueryOptions &options) const
 Given the desired poses of all end-effectors, compute joint angles that are able to reach it. More...
 
virtual void getRedundantJoints (std::vector< unsigned int > &redundant_joint_indices) const
 Get the set of redundant joints. More...
 
double getSearchDiscretization (int joint_index=0) const
 Get the value of the search discretization. More...
 
std::vector< DiscretizationMethodgetSupportedDiscretizationMethods () const
 Returns the set of supported kinematics discretization search types. This implementation only supports the DiscretizationMethods::ONE search. More...
 
virtual const std::string & getTipFrame () const
 Return the name of the tip frame of the chain on which the solver is operating. This is usually a link name. No namespacing (e.g., no "/" prefix) should be used. More...
 
virtual const std::vector< std::string > & getTipFrames () const
 Return the names of the tip frames of the kinematic tree on which the solver is operating. This is usually a link name. No namespacing (e.g., no "/" prefix) should be used. More...
 
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, for use with kinematic chain IK solvers. More...
 
virtual bool initialize (const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization)
 Initialization function for the kinematics, for use with non-chain IK solvers. More...
 
 KinematicsBase ()
 
virtual bool searchPositionIK (const std::vector< geometry_msgs::Pose > &ik_poses, 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 moveit::core::RobotState *context_state=nullptr) const
 Given a set of desired poses for a planning group with multiple end-effectors, search for the joint angles required to reach them. This is useful for e.g. biped robots that need to perform whole-body IK. Not necessary for most robots that have kinematic chains. This particular method is intended for "searching" for a solution by stepping through the redundancy (or other numerical routines). More...
 
void setDefaultTimeout (double timeout)
 For functions that require a timeout specified but one is not specified using arguments, a default timeout is used, as set by this function (and initialized to KinematicsBase::DEFAULT_TIMEOUT) More...
 
bool setRedundantJoints (const std::vector< std::string > &redundant_joint_names)
 Set a set of redundant joints for the kinematics solver to use. This function is just a convenience function that calls the previous definition of setRedundantJoints() More...
 
virtual bool setRedundantJoints (const std::vector< unsigned int > &redundant_joint_indices)
 Set a set of redundant joints for the kinematics solver to use. This can fail, depending on the IK solver and choice of redundant joints!. Also, it sets the discretization values for each redundant joint to a default value. More...
 
void setSearchDiscretization (const std::map< int, double > &discretization)
 Sets individual discretization values for each redundant joint. More...
 
void setSearchDiscretization (double sd)
 Set the search discretization value for all the redundant joints. More...
 
virtual void setValues (const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization)
 Set the parameters for the solver, for use with kinematic chain IK solvers. More...
 
virtual void setValues (const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization)
 Set the parameters for the solver, for use with non-chain IK solvers. More...
 
virtual bool supportsGroup (const moveit::core::JointModelGroup *jmg, std::string *error_text_out=nullptr) const
 Check if this solver supports a given JointModelGroup. More...
 
virtual ~KinematicsBase ()
 Virtual destructor for the interface. More...
 

Protected Member Functions

void desiredPoseCallback (const KDL::JntArray &jnt_array, const KDL::Frame &ik_pose, moveit_msgs::MoveItErrorCodes &error_code) const
 
void jointSolutionCallback (const KDL::JntArray &jnt_array, const KDL::Frame &ik_pose, moveit_msgs::MoveItErrorCodes &error_code) const
 
- Protected Member Functions inherited from kinematics::KinematicsBase
template<typename T >
bool lookupParam (const std::string &param, T &val, const T &default_val) const
 Enables kinematics plugins access to parameters that are defined for the private namespace and inside 'robot_description_kinematics'. Parameters are searched in the following locations and order. More...
 
void storeValues (const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization)
 

Protected Attributes

bool active_
 
IKCallbackFn desiredPoseCallback_
 
int dimension_
 
moveit_msgs::KinematicSolverInfo fk_solver_info_
 
int free_angle_
 
moveit_msgs::KinematicSolverInfo ik_solver_info_
 
std::shared_ptr< KDL::ChainFkSolverPos_recursive > jnt_to_pose_solver_
 
KDL::Chain kdl_chain_
 
pr2_arm_kinematics::PR2ArmIKSolverPtr pr2_arm_ik_solver_
 
std::string root_name_
 
IKCallbackFn solutionCallback_
 
- Protected Attributes inherited from kinematics::KinematicsBase
std::string base_frame_
 
double default_timeout_
 
std::string group_name_
 
std::map< int, double > redundant_joint_discretization_
 
std::vector< unsigned int > redundant_joint_indices_
 
std::string robot_description_
 
moveit::core::RobotModelConstPtr robot_model_
 
double search_discretization_
 
std::vector< DiscretizationMethodsupported_methods_
 
std::string tip_frame_
 
std::vector< std::string > tip_frames_
 

Additional Inherited Members

- Public Types inherited from kinematics::KinematicsBase
using IKCallbackFn = boost::function< void(const geometry_msgs::Pose &, const std::vector< double > &, moveit_msgs::MoveItErrorCodes &)>
 Signature for a callback to validate an IK solution. Typically used for collision checking. More...
 
- Static Public Attributes inherited from kinematics::KinematicsBase
static const MOVEIT_KINEMATICS_BASE_EXPORT double DEFAULT_SEARCH_DISCRETIZATION = 0.1
 
static const MOVEIT_KINEMATICS_BASE_EXPORT double DEFAULT_TIMEOUT = 1.0
 

Detailed Description

Definition at line 162 of file pr2_arm_kinematics_plugin.h.

Constructor & Destructor Documentation

◆ PR2ArmKinematicsPlugin()

pr2_arm_kinematics::PR2ArmKinematicsPlugin::PR2ArmKinematicsPlugin ( )

Plugin-able interface to the PR2 arm kinematics.

Definition at line 255 of file pr2_arm_kinematics_plugin.cpp.

Member Function Documentation

◆ desiredPoseCallback()

void pr2_arm_kinematics::PR2ArmKinematicsPlugin::desiredPoseCallback ( const KDL::JntArray &  jnt_array,
const KDL::Frame &  ik_pose,
moveit_msgs::MoveItErrorCodes &  error_code 
) const
protected

◆ getJointNames()

const std::vector< std::string > & pr2_arm_kinematics::PR2ArmKinematicsPlugin::getJointNames ( ) const
overridevirtual

Return all the joint names in the order they are used internally.

Implements kinematics::KinematicsBase.

Definition at line 411 of file pr2_arm_kinematics_plugin.cpp.

◆ getLinkNames()

const std::vector< std::string > & pr2_arm_kinematics::PR2ArmKinematicsPlugin::getLinkNames ( ) const
overridevirtual

Return all the link names in the order they are represented internally.

Implements kinematics::KinematicsBase.

Definition at line 420 of file pr2_arm_kinematics_plugin.cpp.

◆ getPositionFK()

bool pr2_arm_kinematics::PR2ArmKinematicsPlugin::getPositionFK ( const std::vector< std::string > &  link_names,
const std::vector< double > &  joint_angles,
std::vector< geometry_msgs::Pose > &  poses 
) const
overridevirtual

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

Returns
True if a valid solution was found, false otherwise

Implements kinematics::KinematicsBase.

Definition at line 404 of file pr2_arm_kinematics_plugin.cpp.

◆ getPositionIK()

bool pr2_arm_kinematics::PR2ArmKinematicsPlugin::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
overridevirtual

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

◆ initialize()

bool pr2_arm_kinematics::PR2ArmKinematicsPlugin::initialize ( const moveit::core::RobotModel robot_model,
const std::string &  group_name,
const std::string &  base_frame,
const std::vector< std::string > &  tip_frames,
double  search_discretization 
)
overridevirtual

Initialization function for the kinematics.

Returns
True if initialization was successful, false otherwise

Reimplemented from kinematics::KinematicsBase.

Definition at line 264 of file pr2_arm_kinematics_plugin.cpp.

◆ isActive()

bool pr2_arm_kinematics::PR2ArmKinematicsPlugin::isActive ( )

Specifies if the node is active or not.

Returns
True if the node is active, false otherwise.

Definition at line 259 of file pr2_arm_kinematics_plugin.cpp.

◆ jointSolutionCallback()

void pr2_arm_kinematics::PR2ArmKinematicsPlugin::jointSolutionCallback ( const KDL::JntArray &  jnt_array,
const KDL::Frame &  ik_pose,
moveit_msgs::MoveItErrorCodes &  error_code 
) const
protected

◆ searchPositionIK() [1/4]

bool pr2_arm_kinematics::PR2ArmKinematicsPlugin::searchPositionIK ( const geometry_msgs::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
const std::vector< double > &  consistency_limit,
std::vector< double > &  solution,
const IKCallbackFn solution_callback,
moveit_msgs::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions() 
) const
overridevirtual

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

Implements kinematics::KinematicsBase.

Definition at line 393 of file pr2_arm_kinematics_plugin.cpp.

◆ searchPositionIK() [2/4]

bool pr2_arm_kinematics::PR2ArmKinematicsPlugin::searchPositionIK ( const geometry_msgs::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
const std::vector< double > &  consistency_limit,
std::vector< double > &  solution,
moveit_msgs::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions() 
) const
overridevirtual

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
consistency_limitthe distance 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 373 of file pr2_arm_kinematics_plugin.cpp.

◆ searchPositionIK() [3/4]

bool pr2_arm_kinematics::PR2ArmKinematicsPlugin::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
overridevirtual

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

◆ searchPositionIK() [4/4]

bool pr2_arm_kinematics::PR2ArmKinematicsPlugin::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
overridevirtual

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

Member Data Documentation

◆ active_

bool pr2_arm_kinematics::PR2ArmKinematicsPlugin::active_
protected

Definition at line 267 of file pr2_arm_kinematics_plugin.h.

◆ desiredPoseCallback_

IKCallbackFn pr2_arm_kinematics::PR2ArmKinematicsPlugin::desiredPoseCallback_
mutableprotected

Definition at line 276 of file pr2_arm_kinematics_plugin.h.

◆ dimension_

int pr2_arm_kinematics::PR2ArmKinematicsPlugin::dimension_
protected

Definition at line 271 of file pr2_arm_kinematics_plugin.h.

◆ fk_solver_info_

moveit_msgs::KinematicSolverInfo pr2_arm_kinematics::PR2ArmKinematicsPlugin::fk_solver_info_
protected

Definition at line 274 of file pr2_arm_kinematics_plugin.h.

◆ free_angle_

int pr2_arm_kinematics::PR2ArmKinematicsPlugin::free_angle_
protected

Definition at line 268 of file pr2_arm_kinematics_plugin.h.

◆ ik_solver_info_

moveit_msgs::KinematicSolverInfo pr2_arm_kinematics::PR2ArmKinematicsPlugin::ik_solver_info_
protected

Definition at line 274 of file pr2_arm_kinematics_plugin.h.

◆ jnt_to_pose_solver_

std::shared_ptr<KDL::ChainFkSolverPos_recursive> pr2_arm_kinematics::PR2ArmKinematicsPlugin::jnt_to_pose_solver_
protected

Definition at line 272 of file pr2_arm_kinematics_plugin.h.

◆ kdl_chain_

KDL::Chain pr2_arm_kinematics::PR2ArmKinematicsPlugin::kdl_chain_
protected

Definition at line 273 of file pr2_arm_kinematics_plugin.h.

◆ pr2_arm_ik_solver_

pr2_arm_kinematics::PR2ArmIKSolverPtr pr2_arm_kinematics::PR2ArmKinematicsPlugin::pr2_arm_ik_solver_
protected

Definition at line 269 of file pr2_arm_kinematics_plugin.h.

◆ root_name_

std::string pr2_arm_kinematics::PR2ArmKinematicsPlugin::root_name_
protected

Definition at line 270 of file pr2_arm_kinematics_plugin.h.

◆ solutionCallback_

IKCallbackFn pr2_arm_kinematics::PR2ArmKinematicsPlugin::solutionCallback_
mutableprotected

Definition at line 277 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 Thu Apr 18 2024 02:23:41