Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
hand_kinematics::HandKinematicsPlugin Class Reference

#include <hand_kinematics_plugin.h>

Inheritance diagram for hand_kinematics::HandKinematicsPlugin:
Inheritance graph
[legend]

Public Member Functions

const std::vector< std::string > & getJointNames () const
 Return all the joint names in the order they are used internally. More...
 
const std::vector< std::string > & getLinkNames () const
 Return all the link names in the order they are represented internally. More...
 
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. More...
 
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. More...
 
 HandKinematicsPlugin ()
 
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. More...
 
bool isActive ()
 Specifies if the node is active or not. More...
 
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
 
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
 
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). More...
 
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). More...
 
- Public Member Functions inherited from kinematics::KinematicsBase
virtual const std::string & getBaseFrame () const
 
double getDefaultTimeout () const
 
virtual const std::string & getGroupName () const
 
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
 
virtual void getRedundantJoints (std::vector< unsigned int > &redundant_joint_indices) const
 
double getSearchDiscretization (int joint_index=0) const
 
std::vector< DiscretizationMethodgetSupportedDiscretizationMethods () const
 
virtual const std::string & getTipFrame () const
 
virtual const std::vector< std::string > & getTipFrames () const
 
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)
 
 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=NULL) const
 
void setDefaultTimeout (double timeout)
 
virtual bool setRedundantJoints (const std::vector< unsigned int > &redundant_joint_indices)
 
bool setRedundantJoints (const std::vector< std::string > &redundant_joint_names)
 
void setSearchDiscretization (const std::map< int, double > &discretization)
 
void setSearchDiscretization (double sd)
 
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)
 
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)
 
virtual bool supportsGroup (const moveit::core::JointModelGroup *jmg, std::string *error_text_out=NULL) const
 
virtual ~KinematicsBase ()
 

Protected Member Functions

void generateRandomJntSeed (KDL::JntArray &jnt_pos_in) const
 This method generates a random joint array vector between the joint limits so that local minima in IK can be avoided. More...
 
- Protected Member Functions inherited from kinematics::KinematicsBase
bool lookupParam (const std::string &param, T &val, const T &default_val) const
 

Protected Attributes

bool active_
 
int dimension_
 
std::string finger_base_name
 
KDL::ChainFkSolverPos_recursivefk_solver
 
moveit_msgs::KinematicSolverInfo fk_solver_info_
 
moveit_msgs::KinematicSolverInfo ik_solver_info_
 
KDL::ChainIkSolverPos_NR_JL_couplingik_solver_pos
 
KDL::ChainIkSolverVel_wdls_couplingik_solver_vel
 
boost::shared_ptr< KDL::ChainFkSolverPos_recursivejnt_to_pose_solver_
 
KDL::JntArray joint_max_
 
KDL::JntArray joint_min_
 
KDL::Chain_coupling kdl_chain_
 
ros::NodeHandle node_handle_
 
urdf::Model robot_model_
 
ros::NodeHandle root_handle_
 
double search_discretization_
 
moveit_msgs::KinematicSolverInfo solver_info_
 
- 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_
 
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
typedef boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
 
- Static Public Attributes inherited from kinematics::KinematicsBase
static const double DEFAULT_SEARCH_DISCRETIZATION
 
static const double DEFAULT_TIMEOUT
 

Detailed Description

Definition at line 69 of file hand_kinematics_plugin.h.

Constructor & Destructor Documentation

hand_kinematics::HandKinematicsPlugin::HandKinematicsPlugin ( )

Definition at line 79 of file hand_kinematics_coupling_plugin.cpp.

Member Function Documentation

void hand_kinematics::HandKinematicsPlugin::generateRandomJntSeed ( KDL::JntArray jnt_pos_in) const
protected

This method generates a random joint array vector between the joint limits so that local minima in IK can be avoided.

Parameters
Jointvector to be initialized with random values.

Definition at line 467 of file hand_kinematics_coupling_plugin.cpp.

const std::vector< std::string > & hand_kinematics::HandKinematicsPlugin::getJointNames ( ) const
virtual

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

Implements kinematics::KinematicsBase.

Definition at line 449 of file hand_kinematics_coupling_plugin.cpp.

const std::vector< std::string > & hand_kinematics::HandKinematicsPlugin::getLinkNames ( ) const
virtual

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

Implements kinematics::KinematicsBase.

Definition at line 458 of file hand_kinematics_coupling_plugin.cpp.

bool hand_kinematics::HandKinematicsPlugin::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- the contains the joint angles
poses- the response contains pose information for all the requested links
Returns
True if a valid solution was found, false otherwise

Implements kinematics::KinematicsBase.

Definition at line 393 of file hand_kinematics_coupling_plugin.cpp.

bool hand_kinematics::HandKinematicsPlugin::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.

Returns
True if a valid solution was found, false otherwise

Implements kinematics::KinematicsBase.

Definition at line 208 of file hand_kinematics_coupling_plugin.cpp.

bool hand_kinematics::HandKinematicsPlugin::initialize ( const std::string &  robot_description,
const std::string &  group_name,
const std::string &  base_frame,
const std::string &  tip_frame,
double  search_discretization 
)
virtual

Initialization function for the kinematics.

Returns
True if initialization was successful, false otherwise

Implements kinematics::KinematicsBase.

Definition at line 92 of file hand_kinematics_coupling_plugin.cpp.

bool hand_kinematics::HandKinematicsPlugin::isActive ( )

Specifies if the node is active or not.

Returns
True if the node is active, false otherwise.

Definition at line 83 of file hand_kinematics_coupling_plugin.cpp.

bool hand_kinematics::HandKinematicsPlugin::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

Implements kinematics::KinematicsBase.

Definition at line 276 of file hand_kinematics_coupling_plugin.cpp.

bool hand_kinematics::HandKinematicsPlugin::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

Implements kinematics::KinematicsBase.

Definition at line 289 of file hand_kinematics_coupling_plugin.cpp.

bool hand_kinematics::HandKinematicsPlugin::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).

Implements kinematics::KinematicsBase.

Definition at line 302 of file hand_kinematics_coupling_plugin.cpp.

bool hand_kinematics::HandKinematicsPlugin::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).

Implements kinematics::KinematicsBase.

Definition at line 316 of file hand_kinematics_coupling_plugin.cpp.

Member Data Documentation

bool hand_kinematics::HandKinematicsPlugin::active_
protected

Definition at line 178 of file hand_kinematics_plugin.h.

int hand_kinematics::HandKinematicsPlugin::dimension_
protected

Definition at line 189 of file hand_kinematics_plugin.h.

std::string hand_kinematics::HandKinematicsPlugin::finger_base_name
protected

Definition at line 188 of file hand_kinematics_plugin.h.

KDL::ChainFkSolverPos_recursive* hand_kinematics::HandKinematicsPlugin::fk_solver
protected

Definition at line 183 of file hand_kinematics_plugin.h.

moveit_msgs::KinematicSolverInfo hand_kinematics::HandKinematicsPlugin::fk_solver_info_
protected

Definition at line 196 of file hand_kinematics_plugin.h.

moveit_msgs::KinematicSolverInfo hand_kinematics::HandKinematicsPlugin::ik_solver_info_
protected

Definition at line 196 of file hand_kinematics_plugin.h.

KDL::ChainIkSolverPos_NR_JL_coupling* hand_kinematics::HandKinematicsPlugin::ik_solver_pos
protected

Definition at line 184 of file hand_kinematics_plugin.h.

KDL::ChainIkSolverVel_wdls_coupling* hand_kinematics::HandKinematicsPlugin::ik_solver_vel
protected

Definition at line 185 of file hand_kinematics_plugin.h.

boost::shared_ptr<KDL::ChainFkSolverPos_recursive> hand_kinematics::HandKinematicsPlugin::jnt_to_pose_solver_
protected

Definition at line 190 of file hand_kinematics_plugin.h.

KDL::JntArray hand_kinematics::HandKinematicsPlugin::joint_max_
protected

Definition at line 194 of file hand_kinematics_plugin.h.

KDL::JntArray hand_kinematics::HandKinematicsPlugin::joint_min_
protected

Definition at line 194 of file hand_kinematics_plugin.h.

KDL::Chain_coupling hand_kinematics::HandKinematicsPlugin::kdl_chain_
protected

Definition at line 192 of file hand_kinematics_plugin.h.

ros::NodeHandle hand_kinematics::HandKinematicsPlugin::node_handle_
protected

Definition at line 181 of file hand_kinematics_plugin.h.

urdf::Model hand_kinematics::HandKinematicsPlugin::robot_model_
protected

Definition at line 179 of file hand_kinematics_plugin.h.

ros::NodeHandle hand_kinematics::HandKinematicsPlugin::root_handle_
protected

Definition at line 181 of file hand_kinematics_plugin.h.

double hand_kinematics::HandKinematicsPlugin::search_discretization_
protected

Definition at line 180 of file hand_kinematics_plugin.h.

moveit_msgs::KinematicSolverInfo hand_kinematics::HandKinematicsPlugin::solver_info_
protected

Definition at line 186 of file hand_kinematics_plugin.h.


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


hand_kinematics
Author(s): Juan Antonio Corrales Ramon (UPMC),, Guillaume Walck (CITEC)
autogenerated on Wed Oct 14 2020 04:05:07