Skip to content

Commit

Permalink
Move MBP::HydroelasticContactInfoAndBodySpatialForces into internal (R…
Browse files Browse the repository at this point in the history
…obotLocomotion#12953)

MBP has a nested class that is stored in a cache entry. The hash
logic associated with the drake::Value type doesn't work well with
nested classes of templated classes (it introduces a "namespace"
with a template parameter). This clutters up the console with
warnings that don't help the end user at all. SO, for now, we'll
pull the nested class out and put it in an internal namespace.
  • Loading branch information
SeanCurtis-TRI authored Mar 27, 2020
1 parent 65dcc78 commit 875217a
Show file tree
Hide file tree
Showing 2 changed files with 31 additions and 26 deletions.
14 changes: 8 additions & 6 deletions multibody/plant/multibody_plant.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1186,7 +1186,7 @@ template <typename T>
void MultibodyPlant<T>::CalcContactResultsContinuousHydroelastic(
const systems::Context<T>& context,
ContactResults<T>* contact_results) const {
const HydroelasticContactInfoAndBodySpatialForces&
const internal::HydroelasticContactInfoAndBodySpatialForces<T>&
contact_info_and_spatial_body_forces =
EvalHydroelasticContactForces(context);
for (const HydroelasticContactInfo<T>& contact_info :
Expand Down Expand Up @@ -1415,16 +1415,17 @@ void MultibodyPlant<T>::CalcAndAddContactForcesByPenaltyMethod(
template <>
void MultibodyPlant<symbolic::Expression>::CalcHydroelasticContactForces(
const Context<symbolic::Expression>&,
HydroelasticContactInfoAndBodySpatialForces*) const {
internal::HydroelasticContactInfoAndBodySpatialForces<
symbolic::Expression>*) const {
throw std::logic_error(
"This method doesn't support T = symbolic::Expression.");
}

template <typename T>
void MultibodyPlant<T>::CalcHydroelasticContactForces(
const Context<T>& context,
HydroelasticContactInfoAndBodySpatialForces* contact_info_and_body_forces)
const {
internal::HydroelasticContactInfoAndBodySpatialForces<T>*
contact_info_and_body_forces) const {
DRAKE_DEMAND(contact_info_and_body_forces != nullptr);

std::vector<SpatialForce<T>>& F_BBo_W_array =
Expand Down Expand Up @@ -2510,15 +2511,16 @@ void MultibodyPlant<T>::DeclareCacheEntries() {
std::string("Hydroelastic contact info and body spatial forces."),
[this]() {
return AbstractValue::Make(
HydroelasticContactInfoAndBodySpatialForces(
internal::HydroelasticContactInfoAndBodySpatialForces<T>(
this->num_bodies()));
},
[this](const systems::ContextBase& context_base,
AbstractValue* cache_value) {
auto& context = dynamic_cast<const Context<T>&>(context_base);
auto& contact_info_and_body_spatial_forces_cache =
cache_value->get_mutable_value<
HydroelasticContactInfoAndBodySpatialForces>();
internal::HydroelasticContactInfoAndBodySpatialForces<
T>>();
this->CalcHydroelasticContactForces(
context, &contact_info_and_body_spatial_forces_cache);
},
Expand Down
43 changes: 23 additions & 20 deletions multibody/plant/multibody_plant.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,22 @@ struct HydroelasticFallbackCacheData {
std::vector<geometry::PenetrationAsPointPair<T>> point_pairs;
};

// Structure used in the calculation of hydroelastic contact forces.
template <typename T>
struct HydroelasticContactInfoAndBodySpatialForces {
explicit HydroelasticContactInfoAndBodySpatialForces(int num_bodies) {
F_BBo_W_array.resize(num_bodies);
}

// Forces from hydroelastic contact applied to the origin of each body
// (indexed by BodyNodeIndex) in the MultibodyPlant.
std::vector<SpatialForce<T>> F_BBo_W_array;

// Information used for contact reporting collected through the evaluation
// of the hydroelastic model.
std::vector<HydroelasticContactInfo<T>> contact_info;
};

} // namespace internal

// TODO(amcastro-tri): Add a section on contact models in
Expand Down Expand Up @@ -3343,22 +3359,6 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
// Friend class to facilitate testing.
friend class MultibodyPlantTester;

// Structure used in the calculation of hydroelastic contact forces (see
// method that follows).
struct HydroelasticContactInfoAndBodySpatialForces {
explicit HydroelasticContactInfoAndBodySpatialForces(int num_bodies) {
F_BBo_W_array.resize(num_bodies);
}

// Forces from hydroelastic contact applied to the origin of each body
// (indexed by BodyNodeIndex) in the MultibodyPlant.
std::vector<SpatialForce<T>> F_BBo_W_array;

// Information used for contact reporting collected through the evaluation
// of the hydroelastic model.
std::vector<HydroelasticContactInfo<T>> contact_info;
};

// This struct stores in one single place all indexes related to
// MultibodyPlant specific cache entries. These are initialized at Finalize()
// when the plant declares its cache entries.
Expand Down Expand Up @@ -3775,14 +3775,16 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
// thrown.
void CalcHydroelasticContactForces(
const systems::Context<T>& context,
HydroelasticContactInfoAndBodySpatialForces* F_BBo_W_array) const;
internal::HydroelasticContactInfoAndBodySpatialForces<T>* F_BBo_W_array)
const;

// Eval version of CalcHydroelasticContactForces().
const HydroelasticContactInfoAndBodySpatialForces&
const internal::HydroelasticContactInfoAndBodySpatialForces<T>&
EvalHydroelasticContactForces(const systems::Context<T>& context) const {
return this
->get_cache_entry(cache_indexes_.contact_info_and_body_spatial_forces)
.template Eval<HydroelasticContactInfoAndBodySpatialForces>(context);
.template Eval<
internal::HydroelasticContactInfoAndBodySpatialForces<T>>(context);
}

// Helper method to add the contribution of external actuation forces to the
Expand Down Expand Up @@ -4245,7 +4247,8 @@ MultibodyPlant<AutoDiffXd>::CalcPointPairPenetrations(
template <>
void MultibodyPlant<symbolic::Expression>::CalcHydroelasticContactForces(
const systems::Context<symbolic::Expression>&,
HydroelasticContactInfoAndBodySpatialForces*) const;
internal::HydroelasticContactInfoAndBodySpatialForces<
symbolic::Expression>*) const;
template <>
void MultibodyPlant<symbolic::Expression>::
CalcContactResultsContinuousHydroelastic(
Expand Down

0 comments on commit 875217a

Please sign in to comment.