-
Notifications
You must be signed in to change notification settings - Fork 41
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Ray intersection simulation feature (#641)
dartsim does support ray-based collisions via Bullet backend, which is also supported by gz-physics. This PR creates a simulation feature to compute and retrieve ray castings. Also, it updates dartsim version >= 6.10, which fixes the issues when no ray hit. This addition is useful for range-based applications (e.g. laser, altimeter etc.). --------- Signed-off-by: Rômulo Cerqueira <romulogcerqueira@gmail.com> Co-authored-by: Addisu Z. Taddese <addisuzt@intrinsic.ai>
- Loading branch information
1 parent
1d9ede3
commit b5d1508
Showing
6 changed files
with
285 additions
and
2 deletions.
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
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
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,86 @@ | ||
/* | ||
* Copyright (C) 2024 Open Source Robotics Foundation | ||
* | ||
* Licensed under the Apache License, Version 2.0 (the "License"); | ||
* you may not use this file except in compliance with the License. | ||
* You may obtain a copy of the License at | ||
* | ||
* http://www.apache.org/licenses/LICENSE-2.0 | ||
* | ||
* Unless required by applicable law or agreed to in writing, software | ||
* distributed under the License is distributed on an "AS IS" BASIS, | ||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
* See the License for the specific language governing permissions and | ||
* limitations under the License. | ||
* | ||
*/ | ||
|
||
#ifndef GZ_PHYSICS_GETRAYINTERSECTION_HH_ | ||
#define GZ_PHYSICS_GETRAYINTERSECTION_HH_ | ||
|
||
#include <gz/physics/FeatureList.hh> | ||
#include <gz/physics/ForwardStep.hh> | ||
#include <gz/physics/Geometry.hh> | ||
#include <gz/physics/SpecifyData.hh> | ||
|
||
namespace gz | ||
{ | ||
namespace physics | ||
{ | ||
/// \brief GetRayIntersectionFromLastStepFeature is a feature for retrieving | ||
/// the ray intersection generated in the previous simulation step. | ||
class GZ_PHYSICS_VISIBLE GetRayIntersectionFromLastStepFeature | ||
: public virtual FeatureWithRequirements<ForwardStep> | ||
{ | ||
public: template <typename PolicyT> | ||
struct RayIntersectionT | ||
{ | ||
public: using Scalar = typename PolicyT::Scalar; | ||
public: using VectorType = | ||
typename FromPolicy<PolicyT>::template Use<LinearVector>; | ||
|
||
/// \brief The hit point in the world coordinates | ||
VectorType point; | ||
|
||
/// \brief The fraction of the ray length at the intersection/hit point. | ||
Scalar fraction; | ||
|
||
/// \brief The normal at the hit point in the world coordinates | ||
VectorType normal; | ||
}; | ||
|
||
public: template <typename PolicyT, typename FeaturesT> | ||
class World : public virtual Feature::World<PolicyT, FeaturesT> | ||
{ | ||
public: using VectorType = | ||
typename FromPolicy<PolicyT>::template Use<LinearVector>; | ||
public: using RayIntersection = RayIntersectionT<PolicyT>; | ||
public: using RayIntersectionData = | ||
SpecifyData<RequireData<RayIntersection>>; | ||
|
||
/// \brief Get ray intersection generated in the previous simulation step | ||
/// \param[in] _from The start point of the ray in world coordinates | ||
/// \param[in] _to The end point of the ray in world coordinates | ||
public: RayIntersectionData GetRayIntersectionFromLastStep( | ||
const VectorType &_from, const VectorType &_to) const; | ||
}; | ||
|
||
public: template <typename PolicyT> | ||
class Implementation : public virtual Feature::Implementation<PolicyT> | ||
{ | ||
public: using RayIntersection = RayIntersectionT<PolicyT>; | ||
public: using VectorType = | ||
typename FromPolicy<PolicyT>::template Use<LinearVector>; | ||
|
||
public: virtual RayIntersection GetRayIntersectionFromLastStep( | ||
const Identity &_worldID, | ||
const VectorType &_from, | ||
const VectorType &_to) const = 0; | ||
}; | ||
}; | ||
} | ||
} | ||
|
||
#include "gz/physics/detail/GetRayIntersection.hh" | ||
|
||
#endif /* end of include guard: GZ_PHYSICS_GETRAYINTERSECTION_HH_ */ |
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,49 @@ | ||
/* | ||
* Copyright (C) 2024 Open Source Robotics Foundation | ||
* | ||
* Licensed under the Apache License, Version 2.0 (the "License"); | ||
* you may not use this file except in compliance with the License. | ||
* You may obtain a copy of the License at | ||
* | ||
* http://www.apache.org/licenses/LICENSE-2.0 | ||
* | ||
* Unless required by applicable law or agreed to in writing, software | ||
* distributed under the License is distributed on an "AS IS" BASIS, | ||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
* See the License for the specific language governing permissions and | ||
* limitations under the License. | ||
* | ||
*/ | ||
|
||
#ifndef GZ_PHYSICS_DETAIL_GETRAYINTERSECTION_HH_ | ||
#define GZ_PHYSICS_DETAIL_GETRAYINTERSECTION_HH_ | ||
|
||
#include <utility> | ||
#include <gz/physics/GetRayIntersection.hh> | ||
|
||
namespace gz | ||
{ | ||
namespace physics | ||
{ | ||
///////////////////////////////////////////////// | ||
template <typename PolicyT, typename FeaturesT> | ||
auto GetRayIntersectionFromLastStepFeature::World< | ||
PolicyT, FeaturesT>::GetRayIntersectionFromLastStep( | ||
const VectorType &_from, | ||
const VectorType &_to) const -> RayIntersectionData | ||
{ | ||
auto result = | ||
this->template Interface<GetRayIntersectionFromLastStepFeature>() | ||
->GetRayIntersectionFromLastStep(this->identity, _from, _to); | ||
|
||
RayIntersection intersection{result.point, result.fraction, result.normal}; | ||
|
||
RayIntersectionData output; | ||
output.template Get<RayIntersection>() = std::move(intersection); | ||
return output; | ||
} | ||
|
||
} // namespace physics | ||
} // namespace gz | ||
|
||
#endif |
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