$search

arm_kinematics_constraint_aware::KDLArmKinematicsPlugin Class Reference

#include <kdl_arm_kinematics_plugin.h>

Inheritance diagram for arm_kinematics_constraint_aware::KDLArmKinematicsPlugin:
Inheritance graph
[legend]

List of all members.

Public Member Functions

std::string getBaseFrame ()
 Return the frame in which the kinematics is operating.
std::vector< std::string > getJointNames ()
 Return all the joint names in the order they are used internally.
std::vector< std::string > getLinkNames ()
 Return all the link names in the order they are represented internally.
bool getPositionFK (const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses)
 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, int &error_code)
 Given a desired pose of the end-effector, compute the joint angles to reach it.
std::string getToolFrame ()
 Return the links for which kinematics can be computed.
bool initialize (std::string name)
 Initialization function for the kinematics.
bool isActive ()
 Specifies if the node is active or not.
 KDLArmKinematicsPlugin ()
bool searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, const double &timeout, std::vector< double > &solution, const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> &desired_pose_callback, const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> &solution_callback, int &error_code)
 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, const double &timeout, std::vector< double > &solution, int &error_code)
 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).

Protected Member Functions

double genRandomNumber (const double &min, const double &max)
int getJointIndex (const std::string &name)
int getKDLSegmentIndex (const std::string &name)
KDL::JntArray getRandomConfiguration ()
bool loadModel (const std::string xml)
bool readJoints (urdf::Model &robot_model)

Protected Attributes

bool active_
kinematics_msgs::KinematicSolverInfo chain_info_
unsigned int dimension_
boost::shared_ptr
< KDL::ChainFkSolverPos_recursive
fk_solver_
boost::shared_ptr
< KDL::ChainIkSolverPos_NR_JL
ik_solver_pos_
boost::shared_ptr
< KDL::ChainIkSolverVel_pinv
ik_solver_vel_
KDL::JntArray joint_max_
KDL::JntArray joint_min_
KDL::Chain kdl_chain_
int max_search_iterations_
std::string root_name_
std::string tip_name_

Detailed Description

Definition at line 75 of file kdl_arm_kinematics_plugin.h.


Constructor & Destructor Documentation

arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::KDLArmKinematicsPlugin (  ) 

Definition at line 49 of file kdl_arm_kinematics_plugin.cpp.


Member Function Documentation

double arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::genRandomNumber ( const double &  min,
const double &  max 
) [protected]

Definition at line 61 of file kdl_arm_kinematics_plugin.cpp.

std::string arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::getBaseFrame (  )  [virtual]

Return the frame in which the kinematics is operating.

Returns:
the string name of the frame in which the kinematics is operating

Implements kinematics::KinematicsBase.

Definition at line 449 of file kdl_arm_kinematics_plugin.cpp.

int arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::getJointIndex ( const std::string &  name  )  [protected]

Definition at line 212 of file kdl_arm_kinematics_plugin.cpp.

std::vector< std::string > arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::getJointNames (  )  [virtual]

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

Implements kinematics::KinematicsBase.

Definition at line 469 of file kdl_arm_kinematics_plugin.cpp.

int arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::getKDLSegmentIndex ( const std::string &  name  )  [protected]

Definition at line 221 of file kdl_arm_kinematics_plugin.cpp.

std::vector< std::string > arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::getLinkNames (  )  [virtual]

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

Implements kinematics::KinematicsBase.

Definition at line 480 of file kdl_arm_kinematics_plugin.cpp.

bool arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::getPositionFK ( const std::vector< std::string > &  link_names,
const std::vector< double > &  joint_angles,
std::vector< geometry_msgs::Pose > &  poses 
) [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.

bool arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::getPositionIK ( const geometry_msgs::Pose ik_pose,
const std::vector< double > &  ik_seed_state,
std::vector< double > &  solution,
int &  error_code 
) [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_pose the desired pose of the link
ik_seed_state an initial guess solution for the inverse kinematics
Returns:
True if a valid solution was found, false otherwise

Implements kinematics::KinematicsBase.

Definition at line 233 of file kdl_arm_kinematics_plugin.cpp.

KDL::JntArray arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::getRandomConfiguration (  )  [protected]

Definition at line 68 of file kdl_arm_kinematics_plugin.cpp.

std::string arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::getToolFrame (  )  [virtual]

Return the links for which kinematics can be computed.

Implements kinematics::KinematicsBase.

Definition at line 459 of file kdl_arm_kinematics_plugin.cpp.

bool arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::initialize ( std::string  name  )  [virtual]

Initialization function for the kinematics.

Returns:
True if initialization was successful, false otherwise

Implements kinematics::KinematicsBase.

Definition at line 77 of file kdl_arm_kinematics_plugin.cpp.

bool arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::isActive (  ) 

Specifies if the node is active or not.

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

Definition at line 54 of file kdl_arm_kinematics_plugin.cpp.

bool arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::loadModel ( const std::string  xml  )  [protected]

Definition at line 124 of file kdl_arm_kinematics_plugin.cpp.

bool arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::readJoints ( urdf::Model robot_model  )  [protected]

Definition at line 148 of file kdl_arm_kinematics_plugin.cpp.

bool arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::searchPositionIK ( const geometry_msgs::Pose ik_pose,
const std::vector< double > &  ik_seed_state,
const double &  timeout,
std::vector< double > &  solution,
const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> &  desired_pose_callback,
const boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, int &error_code)> &  solution_callback,
int &  error_code 
) [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_pose the desired pose of the link
ik_seed_state an initial guess solution for the inverse kinematics
Returns:
True if a valid solution was found, false otherwise

Implements kinematics::KinematicsBase.

bool arm_kinematics_constraint_aware::KDLArmKinematicsPlugin::searchPositionIK ( const geometry_msgs::Pose ik_pose,
const std::vector< double > &  ik_seed_state,
const double &  timeout,
std::vector< double > &  solution,
int &  error_code 
) [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_pose the desired pose of the link
ik_seed_state an initial guess solution for the inverse kinematics
Returns:
True if a valid solution was found, false otherwise

Implements kinematics::KinematicsBase.

Definition at line 284 of file kdl_arm_kinematics_plugin.cpp.


Member Data Documentation

Definition at line 178 of file kdl_arm_kinematics_plugin.h.

Definition at line 179 of file kdl_arm_kinematics_plugin.h.

Definition at line 185 of file kdl_arm_kinematics_plugin.h.

Definition at line 182 of file kdl_arm_kinematics_plugin.h.

Definition at line 183 of file kdl_arm_kinematics_plugin.h.

Definition at line 181 of file kdl_arm_kinematics_plugin.h.

Definition at line 188 of file kdl_arm_kinematics_plugin.h.

Definition at line 188 of file kdl_arm_kinematics_plugin.h.

Definition at line 186 of file kdl_arm_kinematics_plugin.h.

Definition at line 176 of file kdl_arm_kinematics_plugin.h.

Definition at line 187 of file kdl_arm_kinematics_plugin.h.

Definition at line 187 of file kdl_arm_kinematics_plugin.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


arm_kinematics_constraint_aware
Author(s): Sachin Chitta
autogenerated on Fri Mar 1 14:19:56 2013