$search
#include <reem_arm_kinematics_plugin.h>
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, const std::vector< double > &posture, std::vector< double > &solution, int &error_code) |
Given a desired pose of the end-effector, compute the joint angles to reach it. | |
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. | |
ReemKinematicsPlugin () | |
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_ |
std::vector< double > | default_posture_ |
unsigned int | dimension_ |
boost::shared_ptr < KDL::ChainFkSolverPos_recursive > | fk_solver_ |
boost::shared_ptr< IkSolver > | ik_solver_ |
KDL::JntArray | joint_max_ |
KDL::JntArray | joint_min_ |
KDL::Chain | kdl_chain_ |
int | max_search_iterations_ |
std::string | root_name_ |
std::string | tip_name_ |
Definition at line 77 of file reem_arm_kinematics_plugin.h.
reem_kinematics_constraint_aware::ReemKinematicsPlugin::ReemKinematicsPlugin | ( | ) |
Definition at line 55 of file reem_arm_kinematics_plugin.cpp.
double reem_kinematics_constraint_aware::ReemKinematicsPlugin::genRandomNumber | ( | const double & | min, | |
const double & | max | |||
) | [protected] |
Definition at line 67 of file reem_arm_kinematics_plugin.cpp.
std::string reem_kinematics_constraint_aware::ReemKinematicsPlugin::getBaseFrame | ( | ) | [virtual] |
Return the frame in which the kinematics is operating.
Implements kinematics::KinematicsBase.
Definition at line 524 of file reem_arm_kinematics_plugin.cpp.
int reem_kinematics_constraint_aware::ReemKinematicsPlugin::getJointIndex | ( | const std::string & | name | ) | [protected] |
Definition at line 268 of file reem_arm_kinematics_plugin.cpp.
std::vector< std::string > reem_kinematics_constraint_aware::ReemKinematicsPlugin::getJointNames | ( | ) | [virtual] |
Return all the joint names in the order they are used internally.
Implements kinematics::KinematicsBase.
Definition at line 544 of file reem_arm_kinematics_plugin.cpp.
int reem_kinematics_constraint_aware::ReemKinematicsPlugin::getKDLSegmentIndex | ( | const std::string & | name | ) | [protected] |
Definition at line 277 of file reem_arm_kinematics_plugin.cpp.
std::vector< std::string > reem_kinematics_constraint_aware::ReemKinematicsPlugin::getLinkNames | ( | ) | [virtual] |
Return all the link names in the order they are represented internally.
Implements kinematics::KinematicsBase.
Definition at line 555 of file reem_arm_kinematics_plugin.cpp.
bool reem_kinematics_constraint_aware::ReemKinematicsPlugin::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.
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 |
Implements kinematics::KinematicsBase.
bool reem_kinematics_constraint_aware::ReemKinematicsPlugin::getPositionIK | ( | const geometry_msgs::Pose & | ik_pose, | |
const std::vector< double > & | ik_seed_state, | |||
const std::vector< double > & | posture, | |||
std::vector< double > & | solution, | |||
int & | error_code | |||
) |
Given a desired pose of the end-effector, compute the joint angles to reach it.
ik_pose | the desired pose of the link | |
ik_seed_state | an initial guess solution for the inverse kinematics | |
posture | Joint posture to be used as secondary task, tht is projected on the nullspace of the primary IK task. |
Definition at line 289 of file reem_arm_kinematics_plugin.cpp.
bool reem_kinematics_constraint_aware::ReemKinematicsPlugin::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.
ik_pose | the desired pose of the link | |
ik_seed_state | an initial guess solution for the inverse kinematics |
Implements kinematics::KinematicsBase.
Definition at line 344 of file reem_arm_kinematics_plugin.cpp.
KDL::JntArray reem_kinematics_constraint_aware::ReemKinematicsPlugin::getRandomConfiguration | ( | ) | [protected] |
Definition at line 74 of file reem_arm_kinematics_plugin.cpp.
std::string reem_kinematics_constraint_aware::ReemKinematicsPlugin::getToolFrame | ( | ) | [virtual] |
Return the links for which kinematics can be computed.
Implements kinematics::KinematicsBase.
Definition at line 534 of file reem_arm_kinematics_plugin.cpp.
bool reem_kinematics_constraint_aware::ReemKinematicsPlugin::initialize | ( | std::string | name | ) | [virtual] |
Initialization function for the kinematics.
Implements kinematics::KinematicsBase.
Definition at line 83 of file reem_arm_kinematics_plugin.cpp.
bool reem_kinematics_constraint_aware::ReemKinematicsPlugin::isActive | ( | ) |
Specifies if the node is active or not.
Definition at line 60 of file reem_arm_kinematics_plugin.cpp.
bool reem_kinematics_constraint_aware::ReemKinematicsPlugin::loadModel | ( | const std::string | xml | ) | [protected] |
Definition at line 180 of file reem_arm_kinematics_plugin.cpp.
bool reem_kinematics_constraint_aware::ReemKinematicsPlugin::readJoints | ( | urdf::Model & | robot_model | ) | [protected] |
Definition at line 204 of file reem_arm_kinematics_plugin.cpp.
bool reem_kinematics_constraint_aware::ReemKinematicsPlugin::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).
ik_pose | the desired pose of the link | |
ik_seed_state | an initial guess solution for the inverse kinematics |
Implements kinematics::KinematicsBase.
bool reem_kinematics_constraint_aware::ReemKinematicsPlugin::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).
ik_pose | the desired pose of the link | |
ik_seed_state | an initial guess solution for the inverse kinematics |
Implements kinematics::KinematicsBase.
Definition at line 356 of file reem_arm_kinematics_plugin.cpp.
bool reem_kinematics_constraint_aware::ReemKinematicsPlugin::active_ [protected] |
Definition at line 193 of file reem_arm_kinematics_plugin.h.
kinematics_msgs::KinematicSolverInfo reem_kinematics_constraint_aware::ReemKinematicsPlugin::chain_info_ [protected] |
Definition at line 194 of file reem_arm_kinematics_plugin.h.
std::vector<double> reem_kinematics_constraint_aware::ReemKinematicsPlugin::default_posture_ [protected] |
Definition at line 203 of file reem_arm_kinematics_plugin.h.
unsigned int reem_kinematics_constraint_aware::ReemKinematicsPlugin::dimension_ [protected] |
Definition at line 199 of file reem_arm_kinematics_plugin.h.
boost::shared_ptr<KDL::ChainFkSolverPos_recursive> reem_kinematics_constraint_aware::ReemKinematicsPlugin::fk_solver_ [protected] |
Definition at line 196 of file reem_arm_kinematics_plugin.h.
boost::shared_ptr<IkSolver> reem_kinematics_constraint_aware::ReemKinematicsPlugin::ik_solver_ [protected] |
Definition at line 197 of file reem_arm_kinematics_plugin.h.
KDL::JntArray reem_kinematics_constraint_aware::ReemKinematicsPlugin::joint_max_ [protected] |
Definition at line 202 of file reem_arm_kinematics_plugin.h.
KDL::JntArray reem_kinematics_constraint_aware::ReemKinematicsPlugin::joint_min_ [protected] |
Definition at line 202 of file reem_arm_kinematics_plugin.h.
Definition at line 200 of file reem_arm_kinematics_plugin.h.
Definition at line 191 of file reem_arm_kinematics_plugin.h.
std::string reem_kinematics_constraint_aware::ReemKinematicsPlugin::root_name_ [protected] |
Definition at line 201 of file reem_arm_kinematics_plugin.h.
std::string reem_kinematics_constraint_aware::ReemKinematicsPlugin::tip_name_ [protected] |
Definition at line 201 of file reem_arm_kinematics_plugin.h.