Implementation of kinematics using Levenberg-Marquardt (LMA) solver from KDL. This version supports any kinematic chain without mimic joints. More...
#include <lma_kinematics_plugin.h>
Public Member Functions | |
const std::vector< std::string > & | getJointNames () const override |
Return all the joint names in the order they are used internally. More... | |
const std::vector< std::string > & | getLinkNames () const override |
Return all the link names in the order they are represented internally. More... | |
bool | getPositionFK (const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const override |
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 override |
bool | initialize (const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization) override |
LMAKinematicsPlugin () | |
Default constructor. More... | |
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 override |
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 override |
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 override |
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 override |
![]() | |
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< DiscretizationMethod > | getSupportedDiscretizationMethods () 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::string &tip_frame, double search_discretization) |
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=nullptr) const |
void | setDefaultTimeout (double timeout) |
bool | setRedundantJoints (const std::vector< std::string > &redundant_joint_names) |
virtual bool | setRedundantJoints (const std::vector< unsigned int > &redundant_joint_indices) |
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=nullptr) const |
virtual | ~KinematicsBase () |
Private Member Functions | |
bool | checkConsistency (const Eigen::VectorXd &seed_state, const std::vector< double > &consistency_limits, const Eigen::VectorXd &solution) const |
Check whether the solution lies within the consistency limits of the seed state. More... | |
void | getRandomConfiguration (const Eigen::VectorXd &seed_state, const std::vector< double > &consistency_limits, Eigen::VectorXd &jnt_array) const |
Get a random configuration within consistency limits close to the seed state. More... | |
void | getRandomConfiguration (Eigen::VectorXd &jnt_array) const |
void | harmonize (Eigen::VectorXd &values) const |
bool | obeysLimits (const Eigen::VectorXd &values) const |
bool | timedOut (const ros::WallTime &start_time, double duration) const |
Private Attributes | |
unsigned int | dimension_ |
Dimension of the group. More... | |
double | epsilon_ |
std::unique_ptr< KDL::ChainFkSolverPos > | fk_solver_ |
bool | initialized_ |
Internal variable that indicates whether solver is configured and ready. More... | |
const moveit::core::JointModelGroup * | joint_model_group_ |
std::vector< std::string > | joint_names_ |
std::vector< const moveit::core::JointModel * > | joints_ |
KDL::Chain | kdl_chain_ |
int | max_solver_iterations_ |
double | orientation_vs_position_weight_ |
moveit_msgs::KinematicSolverInfo | solver_info_ |
Stores information for the inverse kinematics solver. More... | |
moveit::core::RobotStatePtr | state_ |
Additional Inherited Members | |
![]() | |
typedef boost::function< void(const geometry_msgs::Pose &, const std::vector< double > &, moveit_msgs::MoveItErrorCodes &)> | IKCallbackFn |
![]() | |
static const MOVEIT_KINEMATICS_BASE_EXPORT double | DEFAULT_SEARCH_DISCRETIZATION |
static const MOVEIT_KINEMATICS_BASE_EXPORT double | DEFAULT_TIMEOUT |
![]() | |
bool | lookupParam (const std::string ¶m, T &val, const T &default_val) const |
void | storeValues (const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization) |
![]() | |
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_ |
moveit::core::RobotModelConstPtr | robot_model_ |
double | search_discretization_ |
std::vector< DiscretizationMethod > | supported_methods_ |
std::string | tip_frame_ |
std::vector< std::string > | tip_frames_ |
Implementation of kinematics using Levenberg-Marquardt (LMA) solver from KDL. This version supports any kinematic chain without mimic joints.
Definition at line 98 of file lma_kinematics_plugin.h.
lma_kinematics_plugin::LMAKinematicsPlugin::LMAKinematicsPlugin | ( | ) |
Default constructor.
Definition at line 84 of file lma_kinematics_plugin.cpp.
|
private |
Check whether the solution lies within the consistency limits of the seed state.
seed_state | Seed state |
consistency_limits | |
solution | solution configuration |
Definition at line 102 of file lma_kinematics_plugin.cpp.
|
overridevirtual |
Return all the joint names in the order they are used internally.
Implements kinematics::KinematicsBase.
Definition at line 374 of file lma_kinematics_plugin.cpp.
|
overridevirtual |
Return all the link names in the order they are represented internally.
Implements kinematics::KinematicsBase.
Definition at line 379 of file lma_kinematics_plugin.cpp.
|
overridevirtual |
Implements kinematics::KinematicsBase.
Definition at line 338 of file lma_kinematics_plugin.cpp.
|
overridevirtual |
Implements kinematics::KinematicsBase.
Definition at line 182 of file lma_kinematics_plugin.cpp.
|
private |
Get a random configuration within consistency limits close to the seed state.
seed_state | Seed state |
consistency_limits | |
jnt_array | Returned random configuration |
Definition at line 94 of file lma_kinematics_plugin.cpp.
|
private |
Definition at line 88 of file lma_kinematics_plugin.cpp.
|
private |
Harmonize revolute joint values into the range -2 Pi .. 2 Pi
Definition at line 224 of file lma_kinematics_plugin.cpp.
|
overridevirtual |
Reimplemented from kinematics::KinematicsBase.
Definition at line 112 of file lma_kinematics_plugin.cpp.
|
private |
Check whether joint values satisfy joint limits
Definition at line 231 of file lma_kinematics_plugin.cpp.
|
overridevirtual |
Implements kinematics::KinematicsBase.
Definition at line 240 of file lma_kinematics_plugin.cpp.
|
overridevirtual |
Implements kinematics::KinematicsBase.
Definition at line 204 of file lma_kinematics_plugin.cpp.
|
overridevirtual |
Implements kinematics::KinematicsBase.
Definition at line 213 of file lma_kinematics_plugin.cpp.
|
overridevirtual |
Implements kinematics::KinematicsBase.
Definition at line 193 of file lma_kinematics_plugin.cpp.
|
private |
Definition at line 177 of file lma_kinematics_plugin.cpp.
|
private |
Dimension of the group.
Definition at line 210 of file lma_kinematics_plugin.h.
|
private |
Definition at line 221 of file lma_kinematics_plugin.h.
|
private |
Definition at line 216 of file lma_kinematics_plugin.h.
|
private |
Internal variable that indicates whether solver is configured and ready.
Definition at line 208 of file lma_kinematics_plugin.h.
|
private |
Definition at line 213 of file lma_kinematics_plugin.h.
|
private |
Definition at line 218 of file lma_kinematics_plugin.h.
|
private |
Definition at line 217 of file lma_kinematics_plugin.h.
|
private |
Definition at line 215 of file lma_kinematics_plugin.h.
|
private |
Definition at line 220 of file lma_kinematics_plugin.h.
|
private |
weight of orientation error vs position error
< 1.0: orientation has less importance than position
1.0: orientation has more importance than position
= 0.0: perform position-only IK
Definition at line 227 of file lma_kinematics_plugin.h.
|
private |
Stores information for the inverse kinematics solver.
Definition at line 211 of file lma_kinematics_plugin.h.
|
private |
Definition at line 214 of file lma_kinematics_plugin.h.