From ae2e368b220351e800054f8118129ac012c7a279 Mon Sep 17 00:00:00 2001 From: Simon Schmeisser Date: Mon, 4 Mar 2024 17:00:52 +0100 Subject: [PATCH] lrmate200ic ikfast: relax lower j3-j2 to -55 --- .../src/fanuc_lrmate200ic_manipulator_ikfast_moveit_plugin.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/moveit_cfgs/fanuc_lrmate200ic_moveit_plugins/lrmate200ic_kinematics/src/fanuc_lrmate200ic_manipulator_ikfast_moveit_plugin.cpp b/moveit_cfgs/fanuc_lrmate200ic_moveit_plugins/lrmate200ic_kinematics/src/fanuc_lrmate200ic_manipulator_ikfast_moveit_plugin.cpp index 1da90db7..baaf1f1d 100755 --- a/moveit_cfgs/fanuc_lrmate200ic_moveit_plugins/lrmate200ic_kinematics/src/fanuc_lrmate200ic_manipulator_ikfast_moveit_plugin.cpp +++ b/moveit_cfgs/fanuc_lrmate200ic_moveit_plugins/lrmate200ic_kinematics/src/fanuc_lrmate200ic_manipulator_ikfast_moveit_plugin.cpp @@ -57,7 +57,7 @@ const double LIMIT_TOLERANCE = .0000001; const double J3J2_LIMIT_MAX = 25.0/180.0*M_PI; -const double J3J2_LIMIT_MIN = -20.0/180.0*M_PI; +const double J3J2_LIMIT_MIN = -55.0/180.0*M_PI; /// \brief Search modes for searchPositionIK(), see there enum SEARCH_MODE { OPTIMIZE_FREE_JOINT=1, OPTIMIZE_MAX_JOINT=2 };