diff --git a/tesseract_kinematics/kdl/include/tesseract_kinematics/kdl/kdl_fwd_kin_chain.h b/tesseract_kinematics/kdl/include/tesseract_kinematics/kdl/kdl_fwd_kin_chain.h index be0672d68dd..5113d427162 100644 --- a/tesseract_kinematics/kdl/include/tesseract_kinematics/kdl/kdl_fwd_kin_chain.h +++ b/tesseract_kinematics/kdl/include/tesseract_kinematics/kdl/kdl_fwd_kin_chain.h @@ -30,7 +30,6 @@ TESSERACT_COMMON_IGNORE_WARNINGS_PUSH #include #include -#include #include TESSERACT_COMMON_IGNORE_WARNINGS_POP diff --git a/tesseract_kinematics/kdl/include/tesseract_kinematics/kdl/kdl_inv_kin_chain_lma.h b/tesseract_kinematics/kdl/include/tesseract_kinematics/kdl/kdl_inv_kin_chain_lma.h index d5698c503e2..8441eb1d0c6 100644 --- a/tesseract_kinematics/kdl/include/tesseract_kinematics/kdl/kdl_inv_kin_chain_lma.h +++ b/tesseract_kinematics/kdl/include/tesseract_kinematics/kdl/kdl_inv_kin_chain_lma.h @@ -28,7 +28,6 @@ #include TESSERACT_COMMON_IGNORE_WARNINGS_PUSH #include -#include #include #include TESSERACT_COMMON_IGNORE_WARNINGS_POP @@ -59,7 +58,7 @@ class KDLInvKinChainLMA : public InverseKinematics * @brief The Config struct * * This contains parameters that can be used to customize the KDL solver for your application. - * They are ultimately passed to the constuctor of the undelying ChainIkSolver. + * They are ultimately passed to the constuctor of the underlying ChainIkSolver. * * The defaults provided here are the same defaults imposed by the KDL library. */ diff --git a/tesseract_kinematics/kdl/include/tesseract_kinematics/kdl/kdl_inv_kin_chain_nr.h b/tesseract_kinematics/kdl/include/tesseract_kinematics/kdl/kdl_inv_kin_chain_nr.h index 8e1a1d61e00..a8f081eb593 100644 --- a/tesseract_kinematics/kdl/include/tesseract_kinematics/kdl/kdl_inv_kin_chain_nr.h +++ b/tesseract_kinematics/kdl/include/tesseract_kinematics/kdl/kdl_inv_kin_chain_nr.h @@ -30,7 +30,6 @@ TESSERACT_COMMON_IGNORE_WARNINGS_PUSH #include #include #include -#include #include TESSERACT_COMMON_IGNORE_WARNINGS_POP @@ -60,7 +59,7 @@ class KDLInvKinChainNR : public InverseKinematics * @brief The Config struct * * This contains parameters that can be used to customize the KDL solver for your application. - * They are ultimately passed to the constuctors of the undelying ChainIkSolver. + * They are ultimately passed to the constuctors of the underlying ChainIkSolver. * The NR version creates both position and velocity solvers with different defaults for each. * * The defaults provided here are the same defaults imposed by the KDL library. diff --git a/tesseract_kinematics/kdl/include/tesseract_kinematics/kdl/kdl_inv_kin_chain_nr_jl.h b/tesseract_kinematics/kdl/include/tesseract_kinematics/kdl/kdl_inv_kin_chain_nr_jl.h index 8e9937cdaaf..bd8041cc400 100644 --- a/tesseract_kinematics/kdl/include/tesseract_kinematics/kdl/kdl_inv_kin_chain_nr_jl.h +++ b/tesseract_kinematics/kdl/include/tesseract_kinematics/kdl/kdl_inv_kin_chain_nr_jl.h @@ -55,6 +55,23 @@ class KDLInvKinChainNR_JL : public InverseKinematics using UPtr = std::unique_ptr; using ConstUPtr = std::unique_ptr; + /** + * @brief The Config struct + * + * This contains parameters that can be used to customize the KDL solver for your application. + * They are ultimately passed to the constuctors of the underlying ChainIkSolver. + * The NR version creates both position and velocity solvers with different defaults for each. + * + * The defaults provided here are the same defaults imposed by the KDL library. + */ + struct Config + { + double vel_eps{ 0.00001 }; + int vel_iterations{ 150 }; + double pos_eps{ 1e-6 }; + int pos_iterations{ 100 }; + }; + ~KDLInvKinChainNR_JL() override = default; KDLInvKinChainNR_JL(const KDLInvKinChainNR_JL& other); KDLInvKinChainNR_JL& operator=(const KDLInvKinChainNR_JL& other); @@ -72,6 +89,7 @@ class KDLInvKinChainNR_JL : public InverseKinematics KDLInvKinChainNR_JL(const tesseract_scene_graph::SceneGraph& scene_graph, const std::string& base_link, const std::string& tip_link, + Config kdl_config, std::string solver_name = KDL_INV_KIN_CHAIN_NR_JL_SOLVER_NAME); /** @@ -83,6 +101,7 @@ class KDLInvKinChainNR_JL : public InverseKinematics */ KDLInvKinChainNR_JL(const tesseract_scene_graph::SceneGraph& scene_graph, const std::vector >& chains, + Config kdl_config, std::string solver_name = KDL_INV_KIN_CHAIN_NR_JL_SOLVER_NAME); IKSolutions calcInvKin(const tesseract_common::TransformMap& tip_link_poses, @@ -97,10 +116,11 @@ class KDLInvKinChainNR_JL : public InverseKinematics InverseKinematics::UPtr clone() const override final; private: - KDLChainData kdl_data_; /**< @brief KDL data parsed from Scene Graph */ - std::unique_ptr fk_solver_; /**< @brief KDL Forward Kinematic Solver */ - std::unique_ptr ik_vel_solver_; /**< @brief KDL Inverse kinematic velocity solver */ - std::unique_ptr ik_solver_; /**< @brief KDL Inverse kinematic solver */ + KDLChainData kdl_data_; /**< @brief KDL data parsed from Scene Graph */ + Config kdl_config_; /**< @brief KDL configuration data parsed from YAML */ + std::unique_ptr fk_solver_; /**< @brief KDL Forward Kinematic Solver */ + std::unique_ptr ik_vel_solver_; /**< @brief KDL Inverse kinematic velocity solver */ + std::unique_ptr ik_solver_; /**< @brief KDL Inverse kinematic solver */ std::string solver_name_{ KDL_INV_KIN_CHAIN_NR_JL_SOLVER_NAME }; /**< @brief Name of this solver */ mutable std::mutex mutex_; /**< @brief KDL is not thread safe due to mutable variables in Joint Class */ diff --git a/tesseract_kinematics/kdl/src/kdl_factories.cpp b/tesseract_kinematics/kdl/src/kdl_factories.cpp index 913fbacf728..816ae6483f4 100644 --- a/tesseract_kinematics/kdl/src/kdl_factories.cpp +++ b/tesseract_kinematics/kdl/src/kdl_factories.cpp @@ -171,6 +171,7 @@ KDLInvKinChainNR_JLFactory::create(const std::string& solver_name, { std::string base_link; std::string tip_link; + KDLInvKinChainNR_JL::Config kdl_config; try { @@ -183,6 +184,18 @@ KDLInvKinChainNR_JLFactory::create(const std::string& solver_name, tip_link = n.as(); else throw std::runtime_error("KDLInvKinChainNR_JLFactory, missing 'tip_link' entry"); + // Optional configuration parameters + if (YAML::Node n = config["velocity_eps"]) + kdl_config.vel_eps = n.as(); + + if (YAML::Node n = config["velocity_iterations"]) + kdl_config.vel_iterations = n.as(); + + if (YAML::Node n = config["position_eps"]) + kdl_config.pos_eps = n.as(); + + if (YAML::Node n = config["position_iterations"]) + kdl_config.pos_iterations = n.as(); } catch (const std::exception& e) { @@ -190,7 +203,7 @@ KDLInvKinChainNR_JLFactory::create(const std::string& solver_name, return nullptr; } - return std::make_unique(scene_graph, base_link, tip_link, solver_name); + return std::make_unique(scene_graph, base_link, tip_link, kdl_config, solver_name); } TESSERACT_PLUGIN_ANCHOR_IMPL(KDLFactoriesAnchor) diff --git a/tesseract_kinematics/kdl/src/kdl_inv_kin_chain_lma.cpp b/tesseract_kinematics/kdl/src/kdl_inv_kin_chain_lma.cpp index 1779ec615d7..dbb77a65176 100644 --- a/tesseract_kinematics/kdl/src/kdl_inv_kin_chain_lma.cpp +++ b/tesseract_kinematics/kdl/src/kdl_inv_kin_chain_lma.cpp @@ -42,7 +42,7 @@ KDLInvKinChainLMA::KDLInvKinChainLMA(const tesseract_scene_graph::SceneGraph& sc const std::vector>& chains, Config kdl_config, std::string solver_name) - : kdl_config_(std::move(kdl_config)), solver_name_(std::move(solver_name)) + : kdl_config_(kdl_config), solver_name_(std::move(solver_name)) { if (!scene_graph.getLink(scene_graph.getRoot())) throw std::runtime_error("The scene graph has an invalid root."); @@ -64,10 +64,7 @@ KDLInvKinChainLMA::KDLInvKinChainLMA(const tesseract_scene_graph::SceneGraph& sc const std::string& tip_link, Config kdl_config, std::string solver_name) - : KDLInvKinChainLMA(scene_graph, - { std::make_pair(base_link, tip_link) }, - std::move(kdl_config), - std::move(solver_name)) + : KDLInvKinChainLMA(scene_graph, { std::make_pair(base_link, tip_link) }, kdl_config, std::move(solver_name)) { } @@ -95,7 +92,8 @@ IKSolutions KDLInvKinChainLMA::calcInvKinHelper(const Eigen::Isometry3d& pose, int /*segment_num*/) const { assert(std::abs(1.0 - pose.matrix().determinant()) < 1e-6); // NOLINT - KDL::JntArray kdl_seed, kdl_solution; + KDL::JntArray kdl_seed; + KDL::JntArray kdl_solution; EigenToKDL(seed, kdl_seed); kdl_solution.resize(static_cast(seed.size())); Eigen::VectorXd solution(seed.size()); diff --git a/tesseract_kinematics/kdl/src/kdl_inv_kin_chain_nr.cpp b/tesseract_kinematics/kdl/src/kdl_inv_kin_chain_nr.cpp index ecf98caecb5..8393fac2c74 100644 --- a/tesseract_kinematics/kdl/src/kdl_inv_kin_chain_nr.cpp +++ b/tesseract_kinematics/kdl/src/kdl_inv_kin_chain_nr.cpp @@ -42,7 +42,7 @@ KDLInvKinChainNR::KDLInvKinChainNR(const tesseract_scene_graph::SceneGraph& scen const std::vector>& chains, Config kdl_config, std::string solver_name) - : kdl_config_(std::move(kdl_config)), solver_name_(std::move(solver_name)) + : kdl_config_(kdl_config), solver_name_(std::move(solver_name)) { if (!scene_graph.getLink(scene_graph.getRoot())) throw std::runtime_error("The scene graph has an invalid root."); @@ -63,10 +63,7 @@ KDLInvKinChainNR::KDLInvKinChainNR(const tesseract_scene_graph::SceneGraph& scen const std::string& tip_link, Config kdl_config, std::string solver_name) - : KDLInvKinChainNR(scene_graph, - { std::make_pair(base_link, tip_link) }, - std::move(kdl_config), - std::move(solver_name)) + : KDLInvKinChainNR(scene_graph, { std::make_pair(base_link, tip_link) }, kdl_config, std::move(solver_name)) { } @@ -93,13 +90,14 @@ IKSolutions KDLInvKinChainNR::calcInvKinHelper(const Eigen::Isometry3d& pose, int /*segment_num*/) const { assert(std::abs(1.0 - pose.matrix().determinant()) < 1e-6); // NOLINT - KDL::JntArray kdl_seed, kdl_solution; + KDL::JntArray kdl_seed; + KDL::JntArray kdl_solution; EigenToKDL(seed, kdl_seed); kdl_solution.resize(static_cast(seed.size())); Eigen::VectorXd solution(seed.size()); // run IK solver - // TODO: Need to update to handle seg number. Neet to create an IK solver for each seg. + // TODO: Need to update to handle seg number. Need to create an IK solver for each seg. KDL::Frame kdl_pose; EigenToKDL(pose, kdl_pose); int status{ -1 }; diff --git a/tesseract_kinematics/kdl/src/kdl_inv_kin_chain_nr_jl.cpp b/tesseract_kinematics/kdl/src/kdl_inv_kin_chain_nr_jl.cpp index 4b01995a97b..bb70340dd26 100644 --- a/tesseract_kinematics/kdl/src/kdl_inv_kin_chain_nr_jl.cpp +++ b/tesseract_kinematics/kdl/src/kdl_inv_kin_chain_nr_jl.cpp @@ -40,8 +40,9 @@ using Eigen::VectorXd; KDLInvKinChainNR_JL::KDLInvKinChainNR_JL(const tesseract_scene_graph::SceneGraph& scene_graph, const std::vector>& chains, + Config kdl_config, std::string solver_name) - : solver_name_(std::move(solver_name)) + : kdl_config_(kdl_config), solver_name_(std::move(solver_name)) { if (!scene_graph.getLink(scene_graph.getRoot())) throw std::runtime_error("The scene graph has an invalid root."); @@ -51,16 +52,23 @@ KDLInvKinChainNR_JL::KDLInvKinChainNR_JL(const tesseract_scene_graph::SceneGraph // Create KDL FK and IK Solver fk_solver_ = std::make_unique(kdl_data_.robot_chain); - ik_vel_solver_ = std::make_unique(kdl_data_.robot_chain); - ik_solver_ = std::make_unique( - kdl_data_.robot_chain, kdl_data_.q_min, kdl_data_.q_max, *fk_solver_, *ik_vel_solver_); + ik_vel_solver_ = std::make_unique( + kdl_data_.robot_chain, kdl_config_.vel_eps, kdl_config_.vel_iterations); + ik_solver_ = std::make_unique(kdl_data_.robot_chain, + kdl_data_.q_min, + kdl_data_.q_max, + *fk_solver_, + *ik_vel_solver_, + kdl_config_.pos_iterations, + kdl_config_.pos_eps); } KDLInvKinChainNR_JL::KDLInvKinChainNR_JL(const tesseract_scene_graph::SceneGraph& scene_graph, const std::string& base_link, const std::string& tip_link, + Config kdl_config, std::string solver_name) - : KDLInvKinChainNR_JL(scene_graph, { std::make_pair(base_link, tip_link) }, std::move(solver_name)) + : KDLInvKinChainNR_JL(scene_graph, { std::make_pair(base_link, tip_link) }, kdl_config, std::move(solver_name)) { } @@ -71,10 +79,17 @@ KDLInvKinChainNR_JL::KDLInvKinChainNR_JL(const KDLInvKinChainNR_JL& other) { *th KDLInvKinChainNR_JL& KDLInvKinChainNR_JL::operator=(const KDLInvKinChainNR_JL& other) { kdl_data_ = other.kdl_data_; + kdl_config_ = other.kdl_config_; fk_solver_ = std::make_unique(kdl_data_.robot_chain); - ik_vel_solver_ = std::make_unique(kdl_data_.robot_chain); - ik_solver_ = std::make_unique( - kdl_data_.robot_chain, kdl_data_.q_min, kdl_data_.q_max, *fk_solver_, *ik_vel_solver_); + ik_vel_solver_ = std::make_unique( + kdl_data_.robot_chain, kdl_config_.vel_eps, kdl_config_.vel_iterations); + ik_solver_ = std::make_unique(kdl_data_.robot_chain, + kdl_data_.q_min, + kdl_data_.q_max, + *fk_solver_, + *ik_vel_solver_, + kdl_config_.pos_iterations, + kdl_config_.pos_eps); solver_name_ = other.solver_name_; return *this; @@ -85,7 +100,8 @@ IKSolutions KDLInvKinChainNR_JL::calcInvKinHelper(const Eigen::Isometry3d& pose, int /*segment_num*/) const { assert(std::abs(1.0 - pose.matrix().determinant()) < 1e-6); // NOLINT - KDL::JntArray kdl_seed, kdl_solution; + KDL::JntArray kdl_seed; + KDL::JntArray kdl_solution; EigenToKDL(seed, kdl_seed); kdl_solution.resize(static_cast(seed.size())); Eigen::VectorXd solution(seed.size()); @@ -105,30 +121,30 @@ IKSolutions KDLInvKinChainNR_JL::calcInvKinHelper(const Eigen::Isometry3d& pose, // LCOV_EXCL_START if (status == KDL::ChainIkSolverPos_NR_JL::E_DEGRADED) { - CONSOLE_BRIDGE_logDebug("KDL NR Failed to calculate IK, solution converged to