Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

possible Self-Collision Problem #188

Open
david-huck opened this issue May 23, 2017 · 5 comments
Open

possible Self-Collision Problem #188

david-huck opened this issue May 23, 2017 · 5 comments

Comments

@david-huck
Copy link

david-huck commented May 23, 2017

Hello everyone,

I've recently ran into a problem using your lwa4p robot model and moveit. Trajectory planning didn't work very well with default joint limits as described here.
Perhaps i did something wrong in the setup, but so far i haven't spotted the issue.

For now have now adjusted the Limits to these values:
Joint: 1 -2.9 2.9
Joint: 2 -2.9 2.9
Joint: 3 -2.7 2.7
Joint: 4 -2.9 2.9
Joint: 5 -2.9 2.9
Joint: 6 -2.9 2.9
which greatly improved the rate of successful motion plans.

There is an ongoing discussion about a problem which may have a similar cause: ros-industrial/universal_robot#265

@fmessmer
Copy link
Member

fmessmer commented May 23, 2017

Did not read through all the threads you linked...

But you mean changing the limits, e.g. for arm_1_joint from lower..upper to [-2.9...2.9] solved your problem?

As you see in https://github.com/ipa320/schunk_modular_robotics/blob/indigo_dev/schunk_description/urdf/lwa4p/lwa4p.urdf.xacro#L61 the actual limits are computed with an additional safety_offsetproperty.
You could provide a PR that allows to set this property via an xacro argument...then you could adjust the joint range to your needs...

@gavanderhoorn
Copy link

@ipa-fxm: the suggestion of @Dav1d11 is that the LWA robots suffer from the same problem as the UR robots do, namely that even with their default joint limits they can cause self-collisions (the joint_limited vs non-joint_limited problem with the URs).

I guess the question is also partly whether someone else has encountered this with the LWA, as the difference between the regular limits and the ones that @Dav1d11 posted is quite significant.

@fmessmer
Copy link
Member

fmessmer commented May 24, 2017

Well, as far as I can tell: we at IPA do not have an lwa4p....so we did not experience this issue...

Also, the joint_limited vs non-joint_limited problem with the URs has different reasons (not primarily self-collision): Briefly summarized to MoveIt having problems to sample densely enough in the Configuration space when using the actual joint range which is something like [-2pi, 2pi], thus much larger than lwa4p

Coming back to this issue...i
From what I see @Dav1d11 only truncated the decimals from -2.967 + safety_offset=-2.947 to -2.9 which is a difference of 0.047 radians...IMO not that significant...
But in case there actually always is a collision within the configurations 0.047 away from the limits...feel free to set the safety_offset to 0.067 to achieve the same effect...maybe even 0.1 for additional safety...or "joint-specific" if desired...

@gavanderhoorn
Copy link

gavanderhoorn commented May 24, 2017

Also, the joint_limited vs non-joint_limited problem with the URs has different reasons (not primarily self-collision): Briefly summarized to MoveIt having problems to sample densely enough in the Configuration space when using the actual joint range which is something like [-2pi, 2pi], thus much larger than lwa4p

Wasn't the 'conclusion' of ros-industrial/universal_robot#265 that it was actually due to the split / break / gap in the solution space due to the +-2pi limits on the elbow joint (and the resulting collisions of the upper arm / wrist with the shoulder) that OMPL can't deal with? See ros-industrial/universal_robot#265 (comment).

The LWA seems to have a similar problem in some configurations? But just as you guys I don't have the actual robot, so it is/was just a guess.

@gavanderhoorn wrote:

I guess the question is also partly whether someone else has encountered this with the LWA, as the difference between the regular limits and the ones that @Dav1d11 posted is quite significant.

this might have been slightly ambiguous: I was referring to planning performance, not the actual difference between the sets of joint limits.

The change from +-2.9 to +-2.7 on joint_3 is probably to avoid the problem with the shoulder/wrist links.

@gavanderhoorn
Copy link

gavanderhoorn commented May 24, 2017

Just re-read ros-industrial/universal_robot#265 (comment): I see what you mean now with "not sampling dense enough".

Reducing the joint limits on joint_3 is still recommended by the OP in that thread though.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

3 participants