5
$\begingroup$

I want to implement Inverse Kinematics and i understand the inverse jacobian method but the servos i have only have a range from -90 to +90 degrees, how can i implement this detail in the algorithm? I can't simply set each joint to its maximum/minimum if the calculated angle is above/below the constraints because if i do future calculations will not understand that the maximum angle is not the correct path

$\endgroup$
  • $\begingroup$ How many DoF does your arm have? $\endgroup$ – Ben Jul 26 '17 at 13:53
  • $\begingroup$ 4Dof + wrist rotation and claw open/close which i will control entirely seperate. So only 4DOF in regards to IK. the first degree of freedom sets the base angle on the XY plane, and the last three angles set the Z height $\endgroup$ – spetty flakson Jul 26 '17 at 14:15
  • $\begingroup$ A planar 3 link arm mounted on a rotating base? (A picture would be help). $\endgroup$ – Ben Jul 26 '17 at 14:18
  • $\begingroup$ yes that is correct. The base rotates -90 to 90, the first segment is mounted on the rotating base and facing the +Z so it can effectively rotate 0 to pi, the second and third segments are mounted facing +X so they can rotate -90 to 90. i will try to draw a picture but here a a link to the actual robot: ae01.alicdn.com/kf/HTB12Q9VPpXXXXX7XVXXq6xXFXXX7/… $\endgroup$ – spetty flakson Jul 26 '17 at 14:47
1
$\begingroup$

The Inverse Kinematics (IK) solver needs to be aware of the joint bounds in order to provide always a feasible solution lying in the allowed range.

In literature, there are essentially two diverse methodologies to deal with constrained IK in a principled way:

  • The Gradient Projection method that makes use of the null space of the Jacobian to establish a secondary task that attempts to keep joints far from their constraints while converging to the solution of the primary task. See for example [1]. You can resort to tools like KDL.

  • Nonlinear optimization techniques that inherently deal with bounded search regions and thus demonstrate to outperform other approaches. Nowadays, computational resources are such that these demanding techniques can be run even in real-time. See [2], [3] and [4]. Tools implementing this approach are for example TRAC-IK, iKin (tutorial is available) and iDynTree.


References

[1] H.-Y. Lee, B.-J. Yi, Y. Choi, “A Realistic Joint Limit Algorithm for Kinematically Redundant Manipulators,” IEEE International Conference on Control, Automation and Systems, 2007.

[2] P. Beeson, B. Ames, "TRAC-IK: An open-source library for improved solving of generic inverse kinematics," IEEE-RAS International Conference on Humanoid Robots, 2015.

[3] U. Pattacini, F. Nori, L. Natale, G. Metta, G. Sandini, "An experimental evaluation of a novel minimum-jerk cartesian controller for humanoid robots," IEEE-RSJ International Conference on Intelligent Robots and Systems, 2010.

[4] https://robotics.stackexchange.com/a/10008/6941

$\endgroup$
0
$\begingroup$

it depends on your design,how many joints you have, all the movement might happen in 180 degree/depending on the work space you want ,let say for a x,y,z point for the end effector ,you could have multiple angles but different paths to get to same,for a point you might have multiple set of angles for each joint. you could use limits to pick one set of angles which doesnt have any degree more than 180, but if a point which cant be reached unless you need to have an angle that is more than 90/-90 then you cant go there,as i said it depends on your workspace and design also be aware from singularity points,

$\endgroup$
  • $\begingroup$ the second joint which controls the elevation of the first segment is placed in an orientation so that it can reach 0 to pi. If you combine this with the -90 to 90 of the first segment angle you should be able to reach all positions. in a semi sphere of radius (l1+l2+l3) where l is the segment lengths. I just dont know how to modify the algorithm $\endgroup$ – spetty flakson Jul 26 '17 at 14:17
0
$\begingroup$

As it seams from the comments you have some redundant mechanism is you want to track a 3D position, if you also want to track an orientation you are down to non redundant mechanism. Which means that in the first case you might have several IK solution that satisfy your desired position and you can then pick one not violating you actuator constrains. In the second case if actuators constrains are violated by the IK it means you are out of your workspace.

What is a typical approach is to compute the workspace of your arm in Cartesian space, then when you have a desired position (with or without orientation) You can check that this point is in your workspace and if not find the closest point in the workspace. Then for this point there is a IK solution not violating your actuation limits. Once you get a solution from the IK you should also check for self-collision, or include that in your workspace description.

$\endgroup$

Your Answer

By clicking "Post Your Answer", you acknowledge that you have read our updated terms of service, privacy policy and cookie policy, and that your continued use of the website is subject to these policies.

Not the answer you're looking for? Browse other questions tagged or ask your own question.