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

collision world: check for empty shapes vector before access #2026

Merged

Conversation

v4hn
Copy link
Contributor

@v4hn v4hn commented Apr 16, 2020

Copy link
Contributor

@felixvd felixvd left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM. There is another unguarded check like this in moveShapeInObject, but I suppose users who want to move empty shapes deserve the error.

I also think that method can be deleted, but that's just me.

@@ -186,6 +191,7 @@ const Eigen::Isometry3d& World::getTransform(const std::string& name, bool& fram
}
}

// we need a persisting isometry for the API
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
// we need a persisting isometry for the API
// Return an identity transform so there is a persisting isometry object for the API

nit

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Don't like the suggestion because we return a reference, not the transform.

@v4hn
Copy link
Contributor Author

v4hn commented Apr 16, 2020

I believe you are talking about this access operator?

This is actually guarded by ensuring there exists a shape for this index.
I believe the structure holds the invariant shapes_.size() == shape_poses_.size().

Edit:

but I suppose users who want to move empty shapes deserve the error.

No they don't. A framework should not segfault for bad input (Eigen possibly excluded....)

Copy link
Contributor

@rhaschke rhaschke left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks.

@@ -174,7 +174,7 @@ const Eigen::Isometry3d& World::getTransform(const std::string& name, bool& fram
std::map<std::string, ObjectPtr>::const_iterator it = objects_.find(name);
if (it != objects_.end())
{
if (!it->second->shape_poses_.empty())
if (it->second->shape_poses_.size() == 1)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Actually back when we last discussed this, we kept the case with multiple shape_poses_ a gray area on purpose. If you ask for the frame you get the first one, if you ask whether the frame exists, it says no.
I don't have a use-case for objects with multiple shapes, so I don't care too much.

It does seem uncalled for to change this semantic in a segfault fix though. ;)

The proper way to fix this is @felixvd proposal to have a global pose for the object...

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I cannot believe we agreed on inconsistent behavior on purpose. As both fixes are strongly related, I'm fine to have them in a single PR. IMHO it doesn't make sense to split this tiny PR up into even smaller ones.

@codecov-io
Copy link

codecov-io commented Apr 16, 2020

Codecov Report

Merging #2026 into master will increase coverage by 0.04%.
The diff coverage is 0.00%.

Impacted file tree graph

@@            Coverage Diff             @@
##           master    #2026      +/-   ##
==========================================
+ Coverage   54.04%   54.08%   +0.03%     
==========================================
  Files         319      319              
  Lines       24997    24997              
==========================================
+ Hits        13509    13519      +10     
+ Misses      11488    11478      -10     
Impacted Files Coverage Δ
moveit_core/collision_detection/src/world.cpp 90.47% <0.00%> (ø)
...anning_scene_monitor/src/current_state_monitor.cpp 51.28% <0.00%> (-1.54%) ⬇️
...meterization/work_space/pose_model_state_space.cpp 82.31% <0.00%> (-0.69%) ⬇️
...nning_scene_monitor/src/planning_scene_monitor.cpp 70.50% <0.00%> (-0.45%) ⬇️
...veit_experimental/moveit_jog_arm/src/jog_calcs.cpp 75.00% <0.00%> (+5.37%) ⬆️

Continue to review full report at Codecov.

Legend - Click here to learn more
Δ = absolute <relative> (impact), ø = not affected, ? = missing data
Powered by Codecov. Last update 4d30621...64d6789. Read the comment docs.

@v4hn
Copy link
Contributor Author

v4hn commented Apr 16, 2020 via email

@rhaschke
Copy link
Contributor

After all, it is an arbitrary and restrictive decision to stop treating the first transform of an object as its frame.

I agree. We should change both checks to !it->second->shape_poses_.empty() then.
My key point was to make it consistent 😉

@v4hn
Copy link
Contributor Author

v4hn commented Apr 16, 2020 via email

@rhaschke
Copy link
Contributor

If @felixvd is going to change the semantics anyway, I think we don't need to further discuss this topic here...

By convention, the first pose of the object has been the objects frame
for a looong time (though with warning output).
@v4hn v4hn force-pushed the pr-master-check-gettransform-for-segfault branch from 72dc527 to 64d6789 Compare April 16, 2020 20:08
@v4hn
Copy link
Contributor Author

v4hn commented Apr 16, 2020 via email

@rhaschke rhaschke merged commit 173d6a6 into moveit:master Apr 16, 2020
@tylerjw tylerjw mentioned this pull request May 8, 2020
20 tasks
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

Successfully merging this pull request may close these issues.

None yet

4 participants