4
$\begingroup$

I am using ikfast in OpenRave for my inverse kinematics. This is an analytical solver, so if your robot's DOF matches the IK type's DOF, then you get all possible solutions. But if your robot has more DOFs, then you need to pick some joints to have a constant value. (However, if you use OpenRave's Python interface it will discretize that joint for you. i.e. give you a set of solutions for every 0.1 radians of that joint. But my question holds for either interface.) I have a 7 DOF anthropomorphic arm with joints: Roll-Pitch-Roll-Pitch-Roll-Pitch-Yaw as seen in this image:

7 DOF arm

The discretized joints are call "free joints" in OpenRave's terminology. If I let ikfast decide, it picks joint 3 (upper arm roll) to be the free joint. However, I have been using joint 4 (elbow) to be the free joint because it is easier for me to think about. But then I realized that perhaps joint 5, 6, or 7 would be better to discretize because they are closer to the end of the chain. Won't the IK solutions suffer if joints closer to the start of the chain have a large discretization? Or is OpenRave picking the optimal joint to discretize?

I was just wondering if there is some standard practices or known conventions for this sort of thing.

Put simply: I want a set of IK solutions for the end-effector at some pose. I will fix a joint either near the start or end of the kinematic chain. And what i set it to isn't going to be perfect. Lets say it is off from some "ideal" position by some epsilon. Now you can imagine that if i want the hand in-front of the robot, and I pick a bad angle for the shoulder (like straight up for example), the rest of the joints will have a hard time getting the end-effector to the target pose, if at all. But If I fix the wrist to be at some awkward angle, there is still a good chance of getting the end-effector there, or at lease close. What kind of trade-offs are there? Which will have a "better" set of solutions?

$\endgroup$

3 Answers 3

2
$\begingroup$

Which will have a "better" set of solutions?

I could think of some requirements so "better" becomes a measurable value. A better solution:

  1. exists: As you say, fixing a joint in one position can make it difficult for other joints to reach the position, but it could also become impossible. This may or may not be a real problem, but I think keeping the possibility in mind that there might be no solution due to the choice of a fixed joint is important.
  2. is reached quickly: Each actuator has to move a certain distance (angle). Given that some actuators move quicker than others the time it takes to reach the target position can be optimised. It seems desireable to distribute the motion in a way that minimises the overall time it takes to reach the target position.
  3. is efficient: The first joint has to hold all other parts. It might require more torque/force to move it instead of several other joints. Maybe the joint has a built in break/clamping mechanism that allows it to stay steady without power consumption. If it has no break, how much power is required to stay in the target position? Is there a target position that minimises the overall consumed power (due to different power consumption of joints and/or loads they have to hold in that position)? Power is consumed during the motion and while holding the target position. Given that the target position is only held for a certain amount of time, there could be a trade-off between how to move and what target position to reach in terms of overall power consumption.
  4. is precise: How precise is the motion of the joints? Maybe the last joint has a smaller actuator and is more precise than the first joint (or any other) Is precision necessary?
  5. is aware of the application: Let's not forget that there's a hand at the end of the arm that's supposed to do something. If each joint can apply different amount of force/torque, a certain motion of all the joints might cause a minimum load that the hand can hold. Take your own hand as an example: consider how much force (in x,y,z direction) your hand can hold. Now keep your hand steady and move your arm. The values probably changed.
  6. happens in minimum/appropriate space: Requiring less space to perform a motion is generally desirable. Are there solutions that keep the overall bounding box of the robot small?

That list is probably incomplete. As you see, there is a lot of maybe, could, should, probably, in this answer. I guess that a lot of these points are not even worth considering, but then you might have an application that does have very strict requirements.

Depending on the available computational power and time you have for the IK calculation, run the algorithm for every joint. You can then compare different solutions depending on your requirements. Give each requirement a weight so each solution has a certain score, pick the solution with the highest score.

$\endgroup$
1
  • 1
    $\begingroup$ You are right that "best" depends on the application, so some heuristic must be used. I like your list, it is pretty comprehensive, however, you did leave off a few metrics that you typically read about in textbooks. i.e. manipulability measure, distance from joint limits, and distance from obstacles. $\endgroup$
    – Ben
    Aug 4, 2015 at 13:43
1
$\begingroup$

Rosen Diankov answered this question for me in a separate thread:

That's an excellent question, and actually very difficult to answer. The general rule of thumb is that the closer it is to the end effector the better, but this is not always the case. For example, there's only one set of 3 intersecting axes and that's the final 3 joints, then choosing a free joint at the end will mean the resulting IK solver cannot exploit the 3 intersecting axis property to simplify the IK.

The only way I've found to truly get the best free joint is to solve for all of them and see which one is better

$\endgroup$
0
$\begingroup$

So I have some experience with kinematic models, but I'm by no means an expert. What do you mean you are "discretizing" a joint? From the documentation you linked:

For chains containing more degrees of freedom (DOF) than the IK type requires, the user can set arbitrary values of a subset of the joints until the number of unknown joints matches the degrees of freedom of the IK type.

This makes sense to me. You have an end effector for which you want six degrees of freedom, so you get enough joints chained together for six degrees of freedom. If you have more than six degrees of freedom, you fix ("set arbitrary values of") the excess joints, eliminating degrees of freedom until you're left with what "fits" in the IK solver.

So what I'm not sure about is what you mean by "discretizing". As I read their documentation (I couldn't seem to find an in-depth guide at a glance), and as conceptually makes sense to me, you must fix the extra joints, and you must fix them at whatever "arbitrary value" you chose when configuring the IK solver.

For my reasoning on this, consider a thought experiment: You want to model how your hands move when you bend your elbow, and you make the assumption that your hands are out in front of you and your palms are down. Your model shows your hands move in toward your body. Now you run a test, with your palms up. Should you be surprised that your model didn't predict your hands moving toward your face?

It sounds like the IK solver is returning closed solutions to the inverse kinematics. How can you expect it to account for a motion you don't model, or a joint position/location that's incorrect because your "arbitrary value" doesn't match how it's actually configured?

Can you link to documentation that shows a procedure for discretizing a joint? I didn't see anything on a preliminary search.

I'm assuming this is related to your other question, I think my advice from there still stands - measure your physical robot and check that it matches your model. In this case, with the information you gave, I would look squarely at whatever joint you dicretized and check that it is both fixed and in the orientation you gave in the IK model configuration.

$\endgroup$
6
  • $\begingroup$ Yes, you do get closed solutions from ikfast. And you are correct about fixing the excess joints. I should have described OpenRave's discretization procedure. And no, this is not related to my other question. Please see the elaborated question. $\endgroup$
    – Ben
    Aug 1, 2015 at 22:34
  • $\begingroup$ A comment and a question then: Yes, if you fix the shoulder to point away from the region of interest, the rest of the joints might have a tough time getting to the target location, but it's up to you, the designer, to fix the joint such that the operating envelope encompasses the region of interest. But my question: if you're okay with fixing a joint, why bother adding it to begin with? $\endgroup$
    – Chuck
    Aug 1, 2015 at 23:06
  • $\begingroup$ And I guess a follow up question, if your joint actuator can't drive the joint accurately to the value you chose and keep it there, how are you expecting the robot arm to function correctly? $\endgroup$
    – Chuck
    Aug 1, 2015 at 23:08
  • $\begingroup$ Well, I'm not fixing a joint. I am discretizing it's range. I am getting solutions for the joint at 0, 0.1, 0.2, and so on. Again, this question is about IK theory, and unrelated to hardware, physical implementation, or control. $\endgroup$
    – Ben
    Aug 2, 2015 at 18:44
  • $\begingroup$ Is this a procedure you read that is published somewhere or is this something you are trying to implement on your own? Regarding the IK theory, you either derive the closed equations yourself, use a solver like you are now, or you do approximated IK calculations at each time step. You have opted to use a solver, but you do not appear to be complying with the fixed joint requirement for the solver to return a valid answer. I understand what you're going for, but I don't think it's going to give you what you want. $\endgroup$
    – Chuck
    Aug 3, 2015 at 0:16

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge that you have read and understand our privacy policy and code of conduct.

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