-
Notifications
You must be signed in to change notification settings - Fork 26
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
One link multiple geom #77
Merged
Merged
Changes from all commits
Commits
Show all changes
8 commits
Select commit
Hold shift + click to select a range
8d84594
compiles
Lexseal 6025046
passes all tests
Lexseal 068730f
better performance
Lexseal 6462462
Remove FCLModel::parent_link_names_
KolinGuo 06cd26d
Change all CollisionObject to FCLObject; Fix merge
KolinGuo c8b1ed7
Update FCLObject constructors
KolinGuo b832918
Bring back PlanningWorld::addNormalObject method with CollisionObjectPtr
KolinGuo 3d83181
Fix tests
KolinGuo File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,97 @@ | ||
#pragma once | ||
|
||
#include <string> | ||
#include <vector> | ||
|
||
#include <fcl/narrowphase/collision.h> | ||
#include <fcl/narrowphase/distance.h> | ||
|
||
#include "mplib/collision_detection/fcl/types.h" | ||
#include "mplib/macros/class_forward.h" | ||
#include "mplib/types.h" | ||
|
||
namespace mplib::collision_detection::fcl { | ||
|
||
// FCLObjectPtr | ||
MPLIB_STRUCT_TEMPLATE_FORWARD(FCLObject); | ||
|
||
/** | ||
* A general high-level object which consists of multiple FCLCollisionObjects. | ||
* It is the top level data structure which is used in the collision checking process. | ||
* | ||
* Mimicking MoveIt2's ``collision_detection::FCLObject`` and | ||
* ``collision_detection::World::Object`` | ||
* | ||
* https://moveit.picknik.ai/main/api/html/structcollision__detection_1_1FCLObject.html | ||
* https://moveit.picknik.ai/main/api/html/structcollision__detection_1_1World_1_1Object.html | ||
*/ | ||
template <typename S> | ||
struct FCLObject { | ||
/** | ||
* Construct a new FCLObject with the given name | ||
* | ||
* @param name: name of this FCLObject | ||
*/ | ||
FCLObject(const std::string &name) : name(name), pose(Isometry3<S>::Identity()) {} | ||
|
||
/** | ||
* Construct a new FCLObject with the given name and shapes | ||
* | ||
* @param name: name of this FCLObject | ||
* @param pose: pose of this FCLObject. All shapes are relative to this pose | ||
* @param shapes: all collision shapes as a vector of ``fcl::CollisionObjectPtr`` | ||
* @param shape_poses: relative poses from this FCLObject to each collision shape | ||
*/ | ||
FCLObject(const std::string &name, const Isometry3<S> &pose, | ||
const std::vector<fcl::CollisionObjectPtr<S>> &shapes, | ||
const std::vector<Isometry3<S>> &shape_poses); | ||
|
||
std::string name; ///< Name of this FCLObject | ||
Isometry3<S> pose; ///< Pose of this FCLObject. All shapes are relative to this pose | ||
/// All collision shapes (``fcl::CollisionObjectPtr``) making up this FCLObject | ||
std::vector<fcl::CollisionObjectPtr<S>> shapes; | ||
/// Relative poses from this FCLObject to each collision shape | ||
std::vector<Isometry3<S>> shape_poses; | ||
}; | ||
|
||
/** | ||
* Collision function between two ``FCLObject`` | ||
* | ||
* @param[in] obj1: the first object | ||
* @param[in] obj2: the second object | ||
* @param[in] request: ``fcl::CollisionRequest`` | ||
* @param[out] result: ``fcl::CollisionResult`` | ||
* @return: number of contacts generated between the two objects | ||
*/ | ||
template <typename S> | ||
size_t collide(const FCLObjectPtr<S> &obj1, const FCLObjectPtr<S> &obj2, | ||
const fcl::CollisionRequest<S> &request, | ||
fcl::CollisionResult<S> &result); | ||
|
||
/** | ||
* Distance function between two ``FCLObject`` | ||
* | ||
* @param[in] obj1: the first object | ||
* @param[in] obj2: the second object | ||
* @param[in] request: ``fcl::DistanceRequest`` | ||
* @param[out] result: ``fcl::DistanceResult`` | ||
* @return: minimum distance generated between the two objects | ||
*/ | ||
template <typename S> | ||
S distance(const FCLObjectPtr<S> &obj1, const FCLObjectPtr<S> &obj2, | ||
const fcl::DistanceRequest<S> &request, fcl::DistanceResult<S> &result); | ||
|
||
// Explicit Template Instantiation Declaration ========================================= | ||
#define DECLARE_TEMPLATE_FCL_COMMON(S) \ | ||
extern template struct FCLObject<S>; \ | ||
extern template size_t collide<S>( \ | ||
const FCLObjectPtr<S> &obj1, const FCLObjectPtr<S> &obj2, \ | ||
const fcl::CollisionRequest<S> &request, fcl::CollisionResult<S> &result); \ | ||
extern template S distance<S>( \ | ||
const FCLObjectPtr<S> &obj1, const FCLObjectPtr<S> &obj2, \ | ||
const fcl::DistanceRequest<S> &request, fcl::DistanceResult<S> &result) | ||
|
||
DECLARE_TEMPLATE_FCL_COMMON(float); | ||
DECLARE_TEMPLATE_FCL_COMMON(double); | ||
|
||
} // namespace mplib::collision_detection::fcl |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
What is this todo for?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
FCLObject already contains name. No need to require an extra argument to
addNormalObject
.For the overloaded
addNormalObject
taking aCollisionObjectPtr
as input, the name is still required.