Public Member Functions | Protected Member Functions | Protected Attributes
pr2_arm_kinematics::PR2ArmKinematicsPlugin Class Reference

#include <pr2_arm_kinematics_plugin.h>

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

List of all members.

Public Member Functions

const std::vector< std::string > & getJointNames () const
 Return all the joint names in the order they are used internally.
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=kinematics::KinematicsQueryOptions()) const
 Given a desired pose of the end-effector, compute the joint angles to reach it.
virtual 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)
 Initialization function for the kinematics.
bool isActive ()
 Specifies if the node is active or not.
 PR2ArmKinematicsPlugin ()
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=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).
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=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).
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=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).
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=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.
void setRobotModel (boost::shared_ptr< urdf::ModelInterface > &robot_model)

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 Attributes

bool active_
IKCallbackFn desiredPoseCallback_
int dimension_
moveit_msgs::KinematicSolverInfo fk_solver_info_
int free_angle_
moveit_msgs::KinematicSolverInfo ik_solver_info_
boost::shared_ptr
< KDL::ChainFkSolverPos_recursive
jnt_to_pose_solver_
KDL::Chain kdl_chain_
boost::shared_ptr
< pr2_arm_kinematics::PR2ArmIKSolver
pr2_arm_ik_solver_
boost::shared_ptr
< urdf::ModelInterface > 
robot_model_
std::string root_name_
IKCallbackFn solutionCallback_

Detailed Description

Definition at line 130 of file pr2_arm_kinematics_plugin.h.


Constructor & Destructor Documentation

Definition at line 248 of file pr2_arm_kinematics_plugin.cpp.


Member Function Documentation

void pr2_arm_kinematics::PR2ArmKinematicsPlugin::desiredPoseCallback ( const KDL::JntArray jnt_array,
const KDL::Frame ik_pose,
moveit_msgs::MoveItErrorCodes &  error_code 
) const [protected]
const std::vector< std::string > & pr2_arm_kinematics::PR2ArmKinematicsPlugin::getJointNames ( ) const [virtual]

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

Implements kinematics::KinematicsBase.

Definition at line 417 of file pr2_arm_kinematics_plugin.cpp.

const std::vector< std::string > & pr2_arm_kinematics::PR2ArmKinematicsPlugin::getLinkNames ( ) const [virtual]

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

Implements kinematics::KinematicsBase.

Definition at line 426 of file pr2_arm_kinematics_plugin.cpp.

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 [virtual]

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

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

Implements kinematics::KinematicsBase.

Definition at line 410 of file pr2_arm_kinematics_plugin.cpp.

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 [virtual]

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

Parameters:
ik_link_name- the name of the link for which IK is being computed
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 312 of file pr2_arm_kinematics_plugin.cpp.

bool pr2_arm_kinematics::PR2ArmKinematicsPlugin::initialize ( const std::string &  robot_description,
const std::string &  group_name,
const std::string &  base_name,
const std::string &  tip_name,
double  search_discretization 
) [virtual]

Initialization function for the kinematics.

Returns:
True if initialization was successful, false otherwise

Implements kinematics::KinematicsBase.

Definition at line 262 of file pr2_arm_kinematics_plugin.cpp.

Specifies if the node is active or not.

Returns:
True if the node is active, false otherwise.

Definition at line 250 of file pr2_arm_kinematics_plugin.cpp.

void pr2_arm_kinematics::PR2ArmKinematicsPlugin::jointSolutionCallback ( const KDL::JntArray jnt_array,
const KDL::Frame ik_pose,
moveit_msgs::MoveItErrorCodes &  error_code 
) const [protected]
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 [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 321 of file pr2_arm_kinematics_plugin.cpp.

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

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

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_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

Implements kinematics::KinematicsBase.

Definition at line 398 of file pr2_arm_kinematics_plugin.cpp.

void pr2_arm_kinematics::PR2ArmKinematicsPlugin::setRobotModel ( boost::shared_ptr< urdf::ModelInterface > &  robot_model)

Definition at line 257 of file pr2_arm_kinematics_plugin.cpp.


Member Data Documentation

Definition at line 258 of file pr2_arm_kinematics_plugin.h.

Definition at line 268 of file pr2_arm_kinematics_plugin.h.

Definition at line 263 of file pr2_arm_kinematics_plugin.h.

moveit_msgs::KinematicSolverInfo pr2_arm_kinematics::PR2ArmKinematicsPlugin::fk_solver_info_ [protected]

Definition at line 266 of file pr2_arm_kinematics_plugin.h.

Definition at line 259 of file pr2_arm_kinematics_plugin.h.

moveit_msgs::KinematicSolverInfo pr2_arm_kinematics::PR2ArmKinematicsPlugin::ik_solver_info_ [protected]

Definition at line 266 of file pr2_arm_kinematics_plugin.h.

Definition at line 264 of file pr2_arm_kinematics_plugin.h.

Definition at line 265 of file pr2_arm_kinematics_plugin.h.

Definition at line 261 of file pr2_arm_kinematics_plugin.h.

boost::shared_ptr<urdf::ModelInterface> pr2_arm_kinematics::PR2ArmKinematicsPlugin::robot_model_ [protected]

Definition at line 260 of file pr2_arm_kinematics_plugin.h.

Definition at line 262 of file pr2_arm_kinematics_plugin.h.

Definition at line 269 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 Aug 27 2015 13:58:54