Public Member Functions | Private Member Functions | Private Attributes
eus_kinematics::EusKinematicsPlugin Class Reference
Inheritance diagram for eus_kinematics::EusKinematicsPlugin:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 EusKinematicsPlugin ()
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.
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.
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).
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).
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).
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.

Private Member Functions

void ComputeFkEus (void) const
int ComputeIkEus (const geometry_msgs::Pose ik_pose, std::vector< double > &result_angle) const
const std::vector< std::string > & getJointNames () const
const std::vector< std::string > & getLinkNames () const
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)

Private Attributes

bool active_
boost::shared_ptr
< ros::ServiceClient
ik_service_client
std::vector< bool > joint_has_limits_vector_
std::vector< double > joint_max_vector_
std::vector< double > joint_min_vector_
std::vector< std::stringjoint_names_
std::vector< std::stringlink_names_
size_t num_joints_

Detailed Description

Definition at line 29 of file eus_kinematics_plugin.cpp.


Constructor & Destructor Documentation

Definition at line 49 of file eus_kinematics_plugin.cpp.


Member Function Documentation

void eus_kinematics::EusKinematicsPlugin::ComputeFkEus ( void  ) const [private]

Definition at line 416 of file eus_kinematics_plugin.cpp.

int eus_kinematics::EusKinematicsPlugin::ComputeIkEus ( const geometry_msgs::Pose  ik_pose,
std::vector< double > &  result_angle 
) const [private]

Definition at line 389 of file eus_kinematics_plugin.cpp.

const std::vector<std::string>& eus_kinematics::EusKinematicsPlugin::getJointNames ( ) const [inline, private, virtual]

Implements kinematics::KinematicsBase.

Definition at line 39 of file eus_kinematics_plugin.cpp.

const std::vector<std::string>& eus_kinematics::EusKinematicsPlugin::getLinkNames ( ) const [inline, private, virtual]

Implements kinematics::KinematicsBase.

Definition at line 40 of file eus_kinematics_plugin.cpp.

bool eus_kinematics::EusKinematicsPlugin::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.

This FK routine is only used if 'use_plugin_fk' is set in the 'arm_kinematics_constraint_aware' node, otherwise ROS TF is used to calculate the forward kinematics

Parameters:
link_namesA set of links for which FK needs to be computed
joint_anglesThe state for which FK is being computed
posesThe resultant set of poses (in the frame returned by getBaseFrame())
Returns:
True if a valid solution was found, false otherwise

Implements kinematics::KinematicsBase.

Definition at line 355 of file eus_kinematics_plugin.cpp.

bool eus_kinematics::EusKinematicsPlugin::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_posethe desired pose of the link
ik_seed_statean initial guess solution for the inverse kinematics
solutionthe solution vector
error_codean error code that encodes the reason for failure or success
Returns:
True if a valid solution was found, false otherwise

Implements kinematics::KinematicsBase.

Definition at line 272 of file eus_kinematics_plugin.cpp.

bool eus_kinematics::EusKinematicsPlugin::initialize ( const std::string robot_description,
const std::string group_name,
const std::string base_name,
const std::string tip_name,
double  search_discretization 
) [private, virtual]

Implements kinematics::KinematicsBase.

Definition at line 162 of file eus_kinematics_plugin.cpp.

bool eus_kinematics::EusKinematicsPlugin::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 307 of file eus_kinematics_plugin.cpp.

bool eus_kinematics::EusKinematicsPlugin::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
thedistance 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 319 of file eus_kinematics_plugin.cpp.

bool eus_kinematics::EusKinematicsPlugin::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 331 of file eus_kinematics_plugin.cpp.

bool eus_kinematics::EusKinematicsPlugin::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 343 of file eus_kinematics_plugin.cpp.


Member Data Documentation

Definition at line 37 of file eus_kinematics_plugin.cpp.

Definition at line 42 of file eus_kinematics_plugin.cpp.

Definition at line 34 of file eus_kinematics_plugin.cpp.

Definition at line 33 of file eus_kinematics_plugin.cpp.

Definition at line 32 of file eus_kinematics_plugin.cpp.

Definition at line 31 of file eus_kinematics_plugin.cpp.

Definition at line 35 of file eus_kinematics_plugin.cpp.

Definition at line 36 of file eus_kinematics_plugin.cpp.


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


moveit_eus_ik_plugin
Author(s): murooka
autogenerated on Wed Sep 16 2015 10:56:25