Skip to content

Commit

Permalink
Apply suggestions from code review
Browse files Browse the repository at this point in the history
Co-authored-by: Addisu Taddese <addisu@gmail.com>
Signed-off-by: Diego Ferigo <diego.ferigo@iit.it>
  • Loading branch information
diegoferigo and azeey committed Jun 10, 2020
1 parent 21edcba commit 47dd41b
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 10 deletions.
2 changes: 1 addition & 1 deletion dartsim/src/SimulationFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ SimulationFeatures::GetContactsFromLastStep(const Identity &_worldID) const
CompositeData extraData;

// Add normal, depth and wrench to extraData.
auto& extraContactData = extraData.Get<ExtraContactData>();
auto &extraContactData = extraData.Get<ExtraContactData>();
extraContactData.force = dtContact.force;
extraContactData.normal = dtContact.normal;
extraContactData.depth = dtContact.penetrationDepth;
Expand Down
12 changes: 6 additions & 6 deletions include/ignition/physics/GetContacts.hh
Original file line number Diff line number Diff line change
Expand Up @@ -36,14 +36,14 @@ class IGNITION_PHYSICS_VISIBLE GetContactsFromLastStepFeature
public: template <typename PolicyT>
struct ExtraContactDataT
{
using Scalar = typename PolicyT::Scalar;
using VectorType = typename FromPolicy<PolicyT>::template Use<Vector>;
using Scalar = typename PolicyT::Scalar;
using VectorType = typename FromPolicy<PolicyT>::template Use<Vector>;

/// \brief The contact force from body acting on the first body
/// expressed in the world frame
/// \brief The contact force acting on the first body expressed
/// in the world frame
VectorType force;
/// \brief The normal of the force from the second body to the first
/// body expressed in the world frame
/// \brief The normal of the force acting on the first body expressed
/// in the world frame
VectorType normal;
/// \brief The penetration depth
Scalar depth;
Expand Down
8 changes: 5 additions & 3 deletions include/ignition/physics/detail/GetContacts.hh
Original file line number Diff line number Diff line change
Expand Up @@ -58,10 +58,12 @@ auto GetContactsFromLastStepFeature::World<
auto *extraContactData =
contact.extraData.template Query<ExtraContactData>();

if (extraContactData) {
contactOutput.template Get<ExtraContactData>() =
std::move(*extraContactData);
if (extraContactData)
{
contactOutput.template Get<ExtraContactData>() =
std::move(*extraContactData);
}

}
return output;
}
Expand Down

0 comments on commit 47dd41b

Please sign in to comment.