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 46b1abcdb7f..d5698c503e2 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 @@ -29,6 +29,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_PUSH #include #include +#include #include TESSERACT_COMMON_IGNORE_WARNINGS_POP @@ -64,13 +65,10 @@ class KDLInvKinChainLMA : public InverseKinematics */ struct Config { - Eigen::Matrix task_weights{ std::vector{ 1.0, 1.0, 1.0, 0.1, 0.1, 0.1 }.data() }; + std::array task_weights{ 1.0, 1.0, 1.0, 0.1, 0.1, 0.1 }; double eps{ 1E-5 }; int max_iterations{ 500 }; double eps_joints{ 1E-15 }; - - public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; ~KDLInvKinChainLMA() override = default; @@ -90,7 +88,7 @@ class KDLInvKinChainLMA : public InverseKinematics KDLInvKinChainLMA(const tesseract_scene_graph::SceneGraph& scene_graph, const std::string& base_link, const std::string& tip_link, - const Config& kdl_config, + Config kdl_config, std::string solver_name = KDL_INV_KIN_CHAIN_LMA_SOLVER_NAME); /** @@ -102,7 +100,7 @@ class KDLInvKinChainLMA : public InverseKinematics */ KDLInvKinChainLMA(const tesseract_scene_graph::SceneGraph& scene_graph, const std::vector >& chains, - const Config& kdl_config, + Config kdl_config, std::string solver_name = KDL_INV_KIN_CHAIN_LMA_SOLVER_NAME); IKSolutions calcInvKin(const tesseract_common::TransformMap& tip_link_poses, 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 80cacf8a8f8..8e1a1d61e00 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 @@ -90,7 +90,7 @@ class KDLInvKinChainNR : public InverseKinematics KDLInvKinChainNR(const tesseract_scene_graph::SceneGraph& scene_graph, const std::string& base_link, const std::string& tip_link, - const Config& kdl_config, + Config kdl_config, std::string solver_name = KDL_INV_KIN_CHAIN_NR_SOLVER_NAME); /** @@ -102,7 +102,7 @@ class KDLInvKinChainNR : public InverseKinematics */ KDLInvKinChainNR(const tesseract_scene_graph::SceneGraph& scene_graph, const std::vector >& chains, - const Config& kdl_config, + Config kdl_config, std::string solver_name = KDL_INV_KIN_CHAIN_NR_SOLVER_NAME); IKSolutions calcInvKin(const tesseract_common::TransformMap& tip_link_poses, diff --git a/tesseract_kinematics/kdl/src/kdl_factories.cpp b/tesseract_kinematics/kdl/src/kdl_factories.cpp index c08d77d0b96..913fbacf728 100644 --- a/tesseract_kinematics/kdl/src/kdl_factories.cpp +++ b/tesseract_kinematics/kdl/src/kdl_factories.cpp @@ -93,16 +93,10 @@ KDLInvKinChainLMAFactory::create(const std::string& solver_name, if (YAML::Node n = config["task_weights"]) { // Make sure the length matches the constructor interface - if (n.size() != kdl_config.task_weights.size()) - { - std::ostringstream what; - what << "KDLInvKinChainLMAFactory, size of task_weights needs to be " << kdl_config.task_weights.size(); - throw std::runtime_error(what.str()); - } - - auto w = 0; - for (auto const& v : n) - kdl_config.task_weights(w++) = v.as(); + if (n.size() != 6) + throw std::runtime_error("KDLInvKinChainLMAFactory, size of task_weights needs to be 6"); + + kdl_config.task_weights = n.as>(); } if (YAML::Node n = config["eps"]) 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 c1f41d5cc69..1779ec615d7 100644 --- a/tesseract_kinematics/kdl/src/kdl_inv_kin_chain_lma.cpp +++ b/tesseract_kinematics/kdl/src/kdl_inv_kin_chain_lma.cpp @@ -40,9 +40,9 @@ using Eigen::VectorXd; KDLInvKinChainLMA::KDLInvKinChainLMA(const tesseract_scene_graph::SceneGraph& scene_graph, const std::vector>& chains, - const Config& kdl_config, + Config kdl_config, std::string solver_name) - : kdl_config_(kdl_config), solver_name_(std::move(solver_name)) + : kdl_config_(std::move(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 +51,23 @@ KDLInvKinChainLMA::KDLInvKinChainLMA(const tesseract_scene_graph::SceneGraph& sc throw std::runtime_error("Failed to parse KDL data from Scene Graph"); // Create KDL IK Solver - ik_solver_ = std::make_unique( - kdl_data_.robot_chain, kdl_config_.task_weights, kdl_config_.eps, kdl_config_.max_iterations, kdl_config_.eps_joints); + ik_solver_ = + std::make_unique(kdl_data_.robot_chain, + Eigen::Matrix{ kdl_config_.task_weights.data() }, + kdl_config_.eps, + kdl_config_.max_iterations, + kdl_config_.eps_joints); } KDLInvKinChainLMA::KDLInvKinChainLMA(const tesseract_scene_graph::SceneGraph& scene_graph, const std::string& base_link, const std::string& tip_link, - const Config& kdl_config, + Config kdl_config, std::string solver_name) - : KDLInvKinChainLMA(scene_graph, { std::make_pair(base_link, tip_link) }, kdl_config, std::move(solver_name)) + : KDLInvKinChainLMA(scene_graph, + { std::make_pair(base_link, tip_link) }, + std::move(kdl_config), + std::move(solver_name)) { } @@ -72,7 +79,12 @@ KDLInvKinChainLMA& KDLInvKinChainLMA::operator=(const KDLInvKinChainLMA& other) { kdl_data_ = other.kdl_data_; kdl_config_ = other.kdl_config_; - ik_solver_ = std::make_unique(kdl_data_.robot_chain, kdl_config_.task_weights, kdl_config_.eps, kdl_config_.max_iterations, kdl_config_.eps_joints); + ik_solver_ = + std::make_unique(kdl_data_.robot_chain, + Eigen::Matrix{ kdl_config_.task_weights.data() }, + kdl_config_.eps, + kdl_config_.max_iterations, + kdl_config_.eps_joints); solver_name_ = other.solver_name_; return *this; 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 23f60d9b434..ecf98caecb5 100644 --- a/tesseract_kinematics/kdl/src/kdl_inv_kin_chain_nr.cpp +++ b/tesseract_kinematics/kdl/src/kdl_inv_kin_chain_nr.cpp @@ -40,9 +40,9 @@ using Eigen::VectorXd; KDLInvKinChainNR::KDLInvKinChainNR(const tesseract_scene_graph::SceneGraph& scene_graph, const std::vector>& chains, - const Config& kdl_config, + Config kdl_config, std::string solver_name) - : kdl_config_(kdl_config), solver_name_(std::move(solver_name)) + : kdl_config_(std::move(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."); @@ -61,9 +61,12 @@ KDLInvKinChainNR::KDLInvKinChainNR(const tesseract_scene_graph::SceneGraph& scen KDLInvKinChainNR::KDLInvKinChainNR(const tesseract_scene_graph::SceneGraph& scene_graph, const std::string& base_link, const std::string& tip_link, - const Config& kdl_config, + Config kdl_config, std::string solver_name) - : KDLInvKinChainNR(scene_graph, { std::make_pair(base_link, tip_link) }, kdl_config, std::move(solver_name)) + : KDLInvKinChainNR(scene_graph, + { std::make_pair(base_link, tip_link) }, + std::move(kdl_config), + std::move(solver_name)) { } diff --git a/tesseract_kinematics/test/kdl_kinematics_unit.cpp b/tesseract_kinematics/test/kdl_kinematics_unit.cpp index 0e43e7c2b9f..c47a942eec0 100644 --- a/tesseract_kinematics/test/kdl_kinematics_unit.cpp +++ b/tesseract_kinematics/test/kdl_kinematics_unit.cpp @@ -17,7 +17,8 @@ TEST(TesseractKinematicsUnit, KDLKinChainLMAInverseKinematicUnit) // NOLINT { auto scene_graph = getSceneGraphIIWA(); - tesseract_kinematics::KDLInvKinChainLMA derived_kin(*scene_graph, "base_link", "tool0"); + tesseract_kinematics::KDLInvKinChainLMA::Config config; + tesseract_kinematics::KDLInvKinChainLMA derived_kin(*scene_graph, "base_link", "tool0", config); tesseract_kinematics::KinematicsPluginFactory factory; runInvKinIIWATest(factory, "KDLInvKinChainLMAFactory", "KDLFwdKinChainFactory"); @@ -27,7 +28,8 @@ TEST(TesseractKinematicsUnit, KDLKinChainNRInverseKinematicUnit) // NOLINT { auto scene_graph = getSceneGraphIIWA(); - tesseract_kinematics::KDLInvKinChainNR derived_kin(*scene_graph, "base_link", "tool0"); + tesseract_kinematics::KDLInvKinChainNR::Config config; + tesseract_kinematics::KDLInvKinChainNR derived_kin(*scene_graph, "base_link", "tool0", config); tesseract_kinematics::KinematicsPluginFactory factory; runInvKinIIWATest(factory, "KDLInvKinChainNRFactory", "KDLFwdKinChainFactory"); diff --git a/tesseract_kinematics/test/kinematics_factory_unit.cpp b/tesseract_kinematics/test/kinematics_factory_unit.cpp index 98ae2f56d67..6b1f0ddf0ca 100644 --- a/tesseract_kinematics/test/kinematics_factory_unit.cpp +++ b/tesseract_kinematics/test/kinematics_factory_unit.cpp @@ -1138,7 +1138,25 @@ TEST(TesseractKinematicsFactoryUnit, LoadKDLKinematicsUnit) // NOLINT class: KDLInvKinChainNR_JLFactory config: base_link: base_link - tip_link: tool0)"; + tip_link: tool0 + KDLInvKinChainLMA_AllParams: + class: KDLInvKinChainLMAFactory + config: + base_link: base_link + tip_link: tool0 + task_weights: [1, 1, 1, 0.1, 0.1, 0.1] + eps: 1e-5 + max_iterations: 500 + eps_joints: 1e-15 + KDLInvKinChainNR_AllParams: + class: KDLInvKinChainNRFactory + config: + base_link: base_link + tip_link: tool0 + velocity_eps: 0.00001 + velocity_iterations: 150 + position_eps: 1e-6 + position_iterations: 100)"; { KinematicsPluginFactory factory(YAML::Load(yaml_string));