Specific implementation of kinematics using KDL. This version can be used with any robot. More...
#include <aubo_moveit_plugin.h>
Public Member Functions | |
AuboKinematicsPlugin () | |
Default constructor. | |
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 |
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 |
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) |
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 |
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 |
Protected Member Functions | |
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 std::vector< double > &consistency_limits, 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 | setRedundantJoints (const std::vector< unsigned int > &redundant_joint_indices) |
Private Member Functions | |
bool | checkConsistency (const KDL::JntArray &seed_state, const std::vector< double > &consistency_limit, const KDL::JntArray &solution) const |
Check whether the solution lies within the consistency limit of the seed state. | |
int | getJointIndex (const std::string &name) const |
int | getKDLSegmentIndex (const std::string &name) const |
void | getRandomConfiguration (KDL::JntArray &jnt_array, bool lock_redundancy) const |
void | getRandomConfiguration (const KDL::JntArray &seed_state, const std::vector< double > &consistency_limits, KDL::JntArray &jnt_array, bool lock_redundancy) const |
Get a random configuration within joint limits close to the seed state. | |
bool | isRedundantJoint (unsigned int index) const |
bool | timedOut (const ros::WallTime &start_time, double duration) const |
Private Attributes | |
bool | active_ |
std::string | arm_prefix_ |
int | aubo_joint_inds_start_ |
std::vector< std::string > | aubo_joint_names_ |
std::vector< std::string > | aubo_link_names_ |
unsigned int | dimension_ |
double | epsilon_ |
moveit_msgs::KinematicSolverInfo | fk_chain_info_ |
moveit_msgs::KinematicSolverInfo | ik_chain_info_ |
std::vector< double > | ik_weights_ |
KDL::JntArray | joint_max_ |
KDL::JntArray | joint_min_ |
robot_model::JointModelGroup * | joint_model_group_ |
KDL::Chain | kdl_base_chain_ |
KDL::Chain | kdl_chain_ |
KDL::Chain | kdl_tip_chain_ |
double | max_solver_iterations_ |
std::vector < kdl_kinematics_plugin::JointMimic > | mimic_joints_ |
int | num_possible_redundant_joints_ |
bool | position_ik_ |
random_numbers::RandomNumberGenerator | random_number_generator_ |
std::vector< unsigned int > | redundant_joints_map_index_ |
robot_model::RobotModelPtr | robot_model_ |
robot_state::RobotStatePtr | state_ |
robot_state::RobotStatePtr | state_2_ |
Specific implementation of kinematics using KDL. This version can be used with any robot.
Definition at line 37 of file aubo_moveit_plugin.h.
Default constructor.
Definition at line 23 of file aubo_moveit_plugin.cpp.
bool aubo_kinematics::AuboKinematicsPlugin::checkConsistency | ( | const KDL::JntArray & | seed_state, |
const std::vector< double > & | consistency_limit, | ||
const KDL::JntArray & | solution | ||
) | const [private] |
Check whether the solution lies within the consistency limit of the seed state.
seed_state | Seed state |
redundancy | Index of the redundant joint within the chain |
consistency_limit | The returned state for redundant joint should be in the range [seed_state(redundancy_limit)-consistency_limit,seed_state(redundancy_limit)+consistency_limit] |
solution | solution configuration |
Definition at line 84 of file aubo_moveit_plugin.cpp.
int aubo_kinematics::AuboKinematicsPlugin::getJointIndex | ( | const std::string & | name | ) | const [private] |
Definition at line 357 of file aubo_moveit_plugin.cpp.
const std::vector< std::string > & aubo_kinematics::AuboKinematicsPlugin::getJointNames | ( | ) | const [virtual] |
Return all the joint names in the order they are used internally.
Implements kinematics::KinematicsBase.
Definition at line 756 of file aubo_moveit_plugin.cpp.
int aubo_kinematics::AuboKinematicsPlugin::getKDLSegmentIndex | ( | const std::string & | name | ) | const [private] |
Definition at line 366 of file aubo_moveit_plugin.cpp.
const std::vector< std::string > & aubo_kinematics::AuboKinematicsPlugin::getLinkNames | ( | ) | const [virtual] |
Return all the link names in the order they are represented internally.
Implements kinematics::KinematicsBase.
Definition at line 761 of file aubo_moveit_plugin.cpp.
bool aubo_kinematics::AuboKinematicsPlugin::getPositionFK | ( | const std::vector< std::string > & | link_names, |
const std::vector< double > & | joint_angles, | ||
std::vector< geometry_msgs::Pose > & | poses | ||
) | const [virtual] |
Implements kinematics::KinematicsBase.
Definition at line 710 of file aubo_moveit_plugin.cpp.
bool aubo_kinematics::AuboKinematicsPlugin::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] |
Implements kinematics::KinematicsBase.
Definition at line 383 of file aubo_moveit_plugin.cpp.
void aubo_kinematics::AuboKinematicsPlugin::getRandomConfiguration | ( | KDL::JntArray & | jnt_array, |
bool | lock_redundancy | ||
) | const [private] |
Definition at line 25 of file aubo_moveit_plugin.cpp.
void aubo_kinematics::AuboKinematicsPlugin::getRandomConfiguration | ( | const KDL::JntArray & | seed_state, |
const std::vector< double > & | consistency_limits, | ||
KDL::JntArray & | jnt_array, | ||
bool | lock_redundancy | ||
) | const [private] |
Get a random configuration within joint limits close to the seed state.
seed_state | Seed state |
redundancy | Index of the redundant joint within the chain |
consistency_limit | The returned state will contain a value for the redundant joint in the range [seed_state(redundancy_limit)-consistency_limit,seed_state(redundancy_limit)+consistency_limit] |
jnt_array | Returned random configuration |
Definition at line 47 of file aubo_moveit_plugin.cpp.
bool aubo_kinematics::AuboKinematicsPlugin::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] |
Implements kinematics::KinematicsBase.
Definition at line 94 of file aubo_moveit_plugin.cpp.
bool aubo_kinematics::AuboKinematicsPlugin::isRedundantJoint | ( | unsigned int | index | ) | const [private] |
Definition at line 39 of file aubo_moveit_plugin.cpp.
bool aubo_kinematics::AuboKinematicsPlugin::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 402 of file aubo_moveit_plugin.cpp.
bool aubo_kinematics::AuboKinematicsPlugin::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 422 of file aubo_moveit_plugin.cpp.
bool aubo_kinematics::AuboKinematicsPlugin::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] |
Implements kinematics::KinematicsBase.
Definition at line 441 of file aubo_moveit_plugin.cpp.
bool aubo_kinematics::AuboKinematicsPlugin::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] |
Implements kinematics::KinematicsBase.
Definition at line 460 of file aubo_moveit_plugin.cpp.
bool aubo_kinematics::AuboKinematicsPlugin::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 std::vector< double > & | consistency_limits, | ||
const kinematics::KinematicsQueryOptions & | options = kinematics::KinematicsQueryOptions() |
||
) | const [protected] |
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 |
timeout | The amount of time (in seconds) available to the solver |
solution | the solution vector |
solution_callback | A callback solution for the IK solution |
error_code | an error code that encodes the reason for failure or success |
check_consistency | Set to true if consistency check needs to be performed |
redundancy | The index of the redundant joint |
consistency_limit | The returned solutuion will contain a value for the redundant joint in the range [seed_state(redundancy_limit)-consistency_limit,seed_state(redundancy_limit)+consistency_limit] |
Definition at line 483 of file aubo_moveit_plugin.cpp.
bool aubo_kinematics::AuboKinematicsPlugin::setRedundantJoints | ( | const std::vector< unsigned int > & | redundant_joint_indices | ) | [protected, virtual] |
Reimplemented from kinematics::KinematicsBase.
Definition at line 313 of file aubo_moveit_plugin.cpp.
bool aubo_kinematics::AuboKinematicsPlugin::timedOut | ( | const ros::WallTime & | start_time, |
double | duration | ||
) | const [private] |
Definition at line 378 of file aubo_moveit_plugin.cpp.
bool aubo_kinematics::AuboKinematicsPlugin::active_ [private] |
Definition at line 167 of file aubo_moveit_plugin.h.
std::string aubo_kinematics::AuboKinematicsPlugin::arm_prefix_ [private] |
Definition at line 199 of file aubo_moveit_plugin.h.
Definition at line 198 of file aubo_moveit_plugin.h.
std::vector<std::string> aubo_kinematics::AuboKinematicsPlugin::aubo_joint_names_ [private] |
Definition at line 196 of file aubo_moveit_plugin.h.
std::vector<std::string> aubo_kinematics::AuboKinematicsPlugin::aubo_link_names_ [private] |
Definition at line 197 of file aubo_moveit_plugin.h.
unsigned int aubo_kinematics::AuboKinematicsPlugin::dimension_ [private] |
Definition at line 175 of file aubo_moveit_plugin.h.
double aubo_kinematics::AuboKinematicsPlugin::epsilon_ [private] |
Definition at line 192 of file aubo_moveit_plugin.h.
moveit_msgs::KinematicSolverInfo aubo_kinematics::AuboKinematicsPlugin::fk_chain_info_ [private] |
Stores information for the inverse kinematics solver
Definition at line 171 of file aubo_moveit_plugin.h.
moveit_msgs::KinematicSolverInfo aubo_kinematics::AuboKinematicsPlugin::ik_chain_info_ [private] |
Internal variable that indicates whether solvers are configured and ready
Definition at line 169 of file aubo_moveit_plugin.h.
std::vector<double> aubo_kinematics::AuboKinematicsPlugin::ik_weights_ [private] |
Definition at line 195 of file aubo_moveit_plugin.h.
Definition at line 177 of file aubo_moveit_plugin.h.
Dimension of the group
Definition at line 177 of file aubo_moveit_plugin.h.
robot_model::JointModelGroup* aubo_kinematics::AuboKinematicsPlugin::joint_model_group_ [private] |
Definition at line 190 of file aubo_moveit_plugin.h.
Definition at line 203 of file aubo_moveit_plugin.h.
Store information for the forward kinematics solver
Definition at line 173 of file aubo_moveit_plugin.h.
Definition at line 204 of file aubo_moveit_plugin.h.
double aubo_kinematics::AuboKinematicsPlugin::max_solver_iterations_ [private] |
Definition at line 191 of file aubo_moveit_plugin.h.
std::vector<kdl_kinematics_plugin::JointMimic> aubo_kinematics::AuboKinematicsPlugin::mimic_joints_ [private] |
Definition at line 193 of file aubo_moveit_plugin.h.
Definition at line 185 of file aubo_moveit_plugin.h.
bool aubo_kinematics::AuboKinematicsPlugin::position_ik_ [private] |
Definition at line 189 of file aubo_moveit_plugin.h.
random_numbers::RandomNumberGenerator aubo_kinematics::AuboKinematicsPlugin::random_number_generator_ [mutable, private] |
Joint limits
Definition at line 179 of file aubo_moveit_plugin.h.
std::vector<unsigned int> aubo_kinematics::AuboKinematicsPlugin::redundant_joints_map_index_ [private] |
Definition at line 186 of file aubo_moveit_plugin.h.
robot_model::RobotModelPtr aubo_kinematics::AuboKinematicsPlugin::robot_model_ [private] |
Definition at line 181 of file aubo_moveit_plugin.h.
robot_state::RobotStatePtr aubo_kinematics::AuboKinematicsPlugin::state_ [private] |
Definition at line 183 of file aubo_moveit_plugin.h.
robot_state::RobotStatePtr aubo_kinematics::AuboKinematicsPlugin::state_2_ [private] |
Definition at line 183 of file aubo_moveit_plugin.h.