OGS
MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars > Class Template Reference

Detailed Description

template<int DisplacementDim, typename Gradients, typename TDynForces, typename ExtStateVars>
class MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars >

Uses a material model provided by MFront (via MFront's generic interface and the MGIS library).

Definition at line 241 of file MFrontGeneric.h.

#include <MFrontGeneric.h>

Collaboration diagram for MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars >:
[legend]

Public Types

using KelvinVector
 
using KelvinMatrix
 
using InternalVariable
 

Public Member Functions

 MFrontGeneric (mgis::behaviour::Behaviour &&behaviour, std::vector< ParameterLib::Parameter< double > const * > &&material_properties, std::map< std::string, ParameterLib::Parameter< double > const * > &&state_variables_initial_properties, std::optional< ParameterLib::CoordinateSystem > const &local_coordinate_system)
 
std::unique_ptr< typename MechanicsBase< DisplacementDim >::MaterialStateVariables > createMaterialStateVariables () const
 
void initializeInternalStateVariables (double const t, ParameterLib::SpatialPosition const &x, typename MechanicsBase< DisplacementDim >::MaterialStateVariables &material_state_variables) const
 
std::optional< std::tuple< OGSMFrontThermodynamicForcesData, std::unique_ptr< typename MechanicsBase< DisplacementDim >::MaterialStateVariables >, OGSMFrontTangentOperatorData > > integrateStress (MaterialPropertyLib::VariableArray const &variable_array_prev, MaterialPropertyLib::VariableArray const &variable_array, double const t, ParameterLib::SpatialPosition const &x, double const dt, typename MechanicsBase< DisplacementDim >::MaterialStateVariables const &material_state_variables) const
 
std::vector< InternalVariablegetInternalVariables () const
 
template<typename ForcesGradsCombinations = typename ForcesGradsCombinations<Gradients, TDynForces, ExtStateVars>::type>
OGSMFrontTangentOperatorBlocksView< DisplacementDim, ForcesGradsCombinationscreateTangentOperatorBlocksView () const
 
OGSMFrontThermodynamicForcesView< DisplacementDim, TDynForces > createThermodynamicForcesView () const
 
double getBulkModulus (double const, ParameterLib::SpatialPosition const &, KelvinMatrix const *const C) const
 
double computeFreeEnergyDensity (double const, ParameterLib::SpatialPosition const &, double const, KelvinVector const &, KelvinVector const &, typename MechanicsBase< DisplacementDim >::MaterialStateVariables const &) const
 

Private Types

using GradientsAndExtStateVars
 

Private Attributes

mgis::behaviour::Behaviour _behaviour
 
int const equivalent_plastic_strain_offset_
 
std::vector< ParameterLib::Parameter< double > const * > _material_properties
 
std::map< std::string, ParameterLib::Parameter< double > const * > _state_variables_initial_properties
 
ParameterLib::CoordinateSystem const *const _local_coordinate_system
 

Member Typedef Documentation

◆ GradientsAndExtStateVars

template<int DisplacementDim, typename Gradients , typename TDynForces , typename ExtStateVars >
using MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars >::GradientsAndExtStateVars
private
Initial value:
boost::mp11::mp_append<Gradients, ExtStateVars>

Definition at line 247 of file MFrontGeneric.h.

◆ InternalVariable

template<int DisplacementDim, typename Gradients , typename TDynForces , typename ExtStateVars >
using MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars >::InternalVariable
Initial value:
typename MechanicsBase<DisplacementDim>::InternalVariable

Definition at line 257 of file MFrontGeneric.h.

◆ KelvinMatrix

template<int DisplacementDim, typename Gradients , typename TDynForces , typename ExtStateVars >
using MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars >::KelvinMatrix
Initial value:
Eigen::Matrix< double, kelvin_vector_dimensions(DisplacementDim), kelvin_vector_dimensions(DisplacementDim), Eigen::RowMajor > KelvinMatrixType

Definition at line 255 of file MFrontGeneric.h.

◆ KelvinVector

template<int DisplacementDim, typename Gradients , typename TDynForces , typename ExtStateVars >
using MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars >::KelvinVector
Initial value:
Eigen::Matrix< double, kelvin_vector_dimensions(DisplacementDim), 1, Eigen::ColMajor > KelvinVectorType

Definition at line 253 of file MFrontGeneric.h.

Constructor & Destructor Documentation

◆ MFrontGeneric()

template<int DisplacementDim, typename Gradients , typename TDynForces , typename ExtStateVars >
MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars >::MFrontGeneric ( mgis::behaviour::Behaviour && behaviour,
std::vector< ParameterLib::Parameter< double > const * > && material_properties,
std::map< std::string, ParameterLib::Parameter< double > const * > && state_variables_initial_properties,
std::optional< ParameterLib::CoordinateSystem > const & local_coordinate_system )
inline

Definition at line 260 of file MFrontGeneric.h.

268 : _behaviour(std::move(behaviour)),
271 _material_properties(std::move(material_properties)),
273 std::move(state_variables_initial_properties)),
274 _local_coordinate_system(local_coordinate_system
275 ? &local_coordinate_system.value()
276 : nullptr)
277 {
278 {
279 auto check_gradient = [&grads = _behaviour.gradients,
280 hyp = _behaviour.hypothesis,
281 i = 0]<typename Grad>(Grad) mutable
282 {
283 // TODO allow reordering of gradients and thermodynamic forces?
284 if (grads[i].name != Grad::name)
285 {
286 OGS_FATAL(
287 "OGS expects the {}th gradient to be {} but MFront "
288 "provides {}.",
289 i, Grad::name, grads[i].name);
290 }
291
292 if (grads[i].type != Grad::type)
293 {
294 OGS_FATAL(
295 "The behaviour's {}th driver ({}) must be of type {}.",
296 i, grads[i].name, varTypeToString(Grad::type));
297 }
298
299 if (mgis::behaviour::getVariableSize(grads[i], hyp) !=
300 Grad::template size<DisplacementDim>())
301 {
302 OGS_FATAL(
303 "The behaviour's {}th driver's ({}) size in OGS is {} "
304 "but {} in MFront.",
305 i, grads[i].name,
306 Grad::template size<DisplacementDim>(),
307 mgis::behaviour::getVariableSize(grads[i], hyp));
308 }
309
310 i++;
311 };
312
313 if (_behaviour.gradients.size() !=
314 boost::mp11::mp_size<Gradients>::value)
315 OGS_FATAL(
316 "The behaviour must have exactly {} gradients as input.",
317 boost::mp11::mp_size<Gradients>::value);
318
319 boost::mp11::mp_for_each<Gradients>(check_gradient);
320 }
321
322 {
323 auto check_tdyn_force = [&tdfs = _behaviour.thermodynamic_forces,
324 hyp = _behaviour.hypothesis,
325 i = 0]<typename TDF>(TDF) mutable
326 {
327 if (tdfs[i].name != TDF::name)
328 {
329 OGS_FATAL(
330 "OGS expects the {}th thermodynamic force to be {} but "
331 "MFront provides {}.",
332 i, TDF::name, tdfs[i].name);
333 }
334
335 if (tdfs[i].type != TDF::type)
336 {
337 OGS_FATAL(
338 "The behaviour's {}th thermodynamic force ({}) must be "
339 "of type {}.",
340 i, tdfs[i].name, varTypeToString(TDF::type));
341 }
342
343 if (mgis::behaviour::getVariableSize(tdfs[i], hyp) !=
344 TDF::template size<DisplacementDim>())
345 {
346 OGS_FATAL(
347 "The behaviour's {}th thermodynamic force ({}) must "
348 "have size {} instead of {}.",
349 i, tdfs[i].name, TDF::template size<DisplacementDim>(),
350 mgis::behaviour::getVariableSize(tdfs[i], hyp));
351 }
352
353 i++;
354 };
355
356 if (_behaviour.thermodynamic_forces.size() !=
357 boost::mp11::mp_size<TDynForces>::value)
358 OGS_FATAL(
359 "The behaviour must compute exactly {} thermodynamic "
360 "forces.",
361 boost::mp11::mp_size<TDynForces>::value);
362
363 boost::mp11::mp_for_each<TDynForces>(check_tdyn_force);
364 }
365
366 auto const hypothesis = _behaviour.hypothesis;
367
368 static_assert(
369 std::is_same_v<ExtStateVars, boost::mp11::mp_list<Temperature>>,
370 "Temperature is the only allowed external state variable.");
371
372 if (!_behaviour.esvs.empty())
373 {
374 if (_behaviour.esvs[0].name != "Temperature")
375 {
376 OGS_FATAL(
377 "Only temperature is supported as external state "
378 "variable.");
379 }
380
381 if (mgis::behaviour::getVariableSize(_behaviour.esvs[0],
382 hypothesis) != 1)
383 OGS_FATAL(
384 "Temperature must be a scalar instead of having {:d} "
385 "components.",
386 mgis::behaviour::getVariableSize(
387 _behaviour.thermodynamic_forces[0], hypothesis));
388 }
389
390 if (_behaviour.mps.size() != _material_properties.size())
391 {
392 ERR("There are {:d} material properties in the loaded behaviour:",
393 _behaviour.mps.size());
394 for (auto const& mp : _behaviour.mps)
395 {
396 ERR("\t{:s}", mp.name);
397 }
398 OGS_FATAL("But the number of passed material properties is {:d}.",
399 _material_properties.size());
400 }
401 }
#define OGS_FATAL(...)
Definition Error.h:26
void ERR(fmt::format_string< Args... > fmt, Args &&... args)
Definition Logging.h:45
std::vector< ParameterLib::Parameter< double > const * > _material_properties
std::map< std::string, ParameterLib::Parameter< double > const * > _state_variables_initial_properties
ParameterLib::CoordinateSystem const *const _local_coordinate_system
const char * varTypeToString(int v)
int getEquivalentPlasticStrainOffset(mgis::behaviour::Behaviour const &b)

References ERR(), MaterialLib::Solids::MFront::getEquivalentPlasticStrainOffset(), OGS_FATAL, and MaterialLib::Solids::MFront::varTypeToString().

Member Function Documentation

◆ computeFreeEnergyDensity()

template<int DisplacementDim, typename Gradients , typename TDynForces , typename ExtStateVars >
double MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars >::computeFreeEnergyDensity ( double const ,
ParameterLib::SpatialPosition const & ,
double const ,
KelvinVector const & ,
KelvinVector const & ,
typename MechanicsBase< DisplacementDim >::MaterialStateVariables const &  ) const
inline

Definition at line 710 of file MFrontGeneric.h.

718 {
719 // TODO implement
720 return std::numeric_limits<double>::quiet_NaN();
721 }

◆ createMaterialStateVariables()

template<int DisplacementDim, typename Gradients , typename TDynForces , typename ExtStateVars >
std::unique_ptr< typename MechanicsBase< DisplacementDim >::MaterialStateVariables > MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars >::createMaterialStateVariables ( ) const
inline

Definition at line 405 of file MFrontGeneric.h.

406 {
407 return std::make_unique<MaterialStateVariablesMFront<DisplacementDim>>(
409 }

◆ createTangentOperatorBlocksView()

template<int DisplacementDim, typename Gradients , typename TDynForces , typename ExtStateVars >
template<typename ForcesGradsCombinations = typename ForcesGradsCombinations<Gradients, TDynForces, ExtStateVars>::type>
OGSMFrontTangentOperatorBlocksView< DisplacementDim, ForcesGradsCombinations > MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars >::createTangentOperatorBlocksView ( ) const
inline

Definition at line 680 of file MFrontGeneric.h.

681 {
682 return OGSMFrontTangentOperatorBlocksView<DisplacementDim,
683 ForcesGradsCombinations>{
684 _behaviour.to_blocks};
685 }

◆ createThermodynamicForcesView()

template<int DisplacementDim, typename Gradients , typename TDynForces , typename ExtStateVars >
OGSMFrontThermodynamicForcesView< DisplacementDim, TDynForces > MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars >::createThermodynamicForcesView ( ) const
inline

Definition at line 688 of file MFrontGeneric.h.

689 {
690 return OGSMFrontThermodynamicForcesView<DisplacementDim, TDynForces>{};
691 }

◆ getBulkModulus()

template<int DisplacementDim, typename Gradients , typename TDynForces , typename ExtStateVars >
double MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars >::getBulkModulus ( double const ,
ParameterLib::SpatialPosition const & ,
KelvinMatrix const *const C ) const
inline

Definition at line 693 of file MFrontGeneric.h.

696 {
697 if (C == nullptr)
698 {
699 OGS_FATAL(
700 "MFront::getBulkModulus() requires the tangent stiffness C "
701 "input "
702 "argument to be valid.");
703 }
704 auto const& identity2 = MathLib::KelvinVector::Invariants<
706 DisplacementDim)>::identity2;
707 return 1. / 9. * identity2.transpose() * *C * identity2;
708 }
constexpr int kelvin_vector_dimensions(int const displacement_dim)
Kelvin vector dimensions for given displacement dimension.

References MathLib::KelvinVector::kelvin_vector_dimensions(), and OGS_FATAL.

◆ getInternalVariables()

template<int DisplacementDim, typename Gradients , typename TDynForces , typename ExtStateVars >
std::vector< InternalVariable > MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars >::getInternalVariables ( ) const
inline

Definition at line 619 of file MFrontGeneric.h.

620 {
621 std::vector<InternalVariable> internal_variables;
622
623 for (auto const& iv : _behaviour.isvs)
624 {
625 auto const name = iv.name;
626 auto const offset = mgis::behaviour::getVariableOffset(
627 _behaviour.isvs, name, _behaviour.hypothesis);
628 auto const size =
629 mgis::behaviour::getVariableSize(iv, _behaviour.hypothesis);
630
631 // TODO (naumov): For orthotropic materials the internal variables
632 // should be rotated to the global coordinate system before output.
633 // MFront stores the variables in local coordinate system.
634 // The `size` variable could be used to find out the type of
635 // variable.
636 InternalVariable new_variable{
637 name, static_cast<int>(size),
638 [offset, size](
639 typename MechanicsBase<
640 DisplacementDim>::MaterialStateVariables const& state,
641 std::vector<double>& cache) -> std::vector<double> const&
642 {
643 assert(dynamic_cast<MaterialStateVariablesMFront<
644 DisplacementDim> const*>(&state) != nullptr);
645 auto const& internal_state_variables =
646 static_cast<MaterialStateVariablesMFront<
647 DisplacementDim> const&>(state)
648 ._behaviour_data.s1.internal_state_variables;
649
650 cache.resize(size);
651 std::copy_n(internal_state_variables.data() + offset,
652 size,
653 begin(cache));
654 return cache;
655 },
656 [offset, size](typename MechanicsBase<
657 DisplacementDim>::MaterialStateVariables& state)
658 -> std::span<double>
659 {
660 assert(dynamic_cast<MaterialStateVariablesMFront<
661 DisplacementDim> const*>(&state) != nullptr);
662 auto& internal_state_variables =
663 static_cast<
664 MaterialStateVariablesMFront<DisplacementDim>&>(
665 state)
666 ._behaviour_data.s1.internal_state_variables;
667
668 return {internal_state_variables.data() + offset, size};
669 }};
670 internal_variables.push_back(new_variable);
671 }
672
673 return internal_variables;
674 }
typename MechanicsBase< DisplacementDim >::InternalVariable InternalVariable
constexpr int size(int const displacement_dim)
Vectorized tensor size for given displacement dimension.

◆ initializeInternalStateVariables()

template<int DisplacementDim, typename Gradients , typename TDynForces , typename ExtStateVars >
void MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars >::initializeInternalStateVariables ( double const t,
ParameterLib::SpatialPosition const & x,
typename MechanicsBase< DisplacementDim >::MaterialStateVariables & material_state_variables ) const
inline

Definition at line 411 of file MFrontGeneric.h.

416 {
417 assert(dynamic_cast<MaterialStateVariablesMFront<DisplacementDim>*>(
418 &material_state_variables));
419
420 auto& state =
421 static_cast<MaterialStateVariablesMFront<DisplacementDim>&>(
422 material_state_variables);
423
424 auto const& ivs = getInternalVariables();
425
426 for (auto& [name, parameter] : _state_variables_initial_properties)
427 {
428 // find corresponding internal variable
429 auto const& iv = BaseLib::findElementOrError(
430 ivs,
431 [name = name](InternalVariable const& iv)
432 { return iv.name == name; },
433 [name = name]()
434 { OGS_FATAL("Internal variable `{:s}' not found.", name); });
435
436 // evaluate parameter
437 std::vector<double> values = (*parameter)(t, x);
438
439 // copy parameter data into iv
440 auto const values_span = iv.reference(state);
441 assert(values.size() == values_span.size());
442 std::copy_n(begin(values), values_span.size(), values_span.begin());
443 }
444
445 auto const& s1 = state._behaviour_data.s1.internal_state_variables;
446 auto& s0 = state._behaviour_data.s0.internal_state_variables;
447 std::copy(begin(s1), end(s1), begin(s0));
448 }
std::vector< InternalVariable > getInternalVariables() const
ranges::range_reference_t< Range > findElementOrError(Range &range, std::predicate< ranges::range_reference_t< Range > > auto &&predicate, std::invocable auto error_callback)
Definition Algorithm.h:76

References BaseLib::findElementOrError(), and OGS_FATAL.

◆ integrateStress()

template<int DisplacementDim, typename Gradients , typename TDynForces , typename ExtStateVars >
std::optional< std::tuple< OGSMFrontThermodynamicForcesData, std::unique_ptr< typename MechanicsBase< DisplacementDim >::MaterialStateVariables >, OGSMFrontTangentOperatorData > > MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars >::integrateStress ( MaterialPropertyLib::VariableArray const & variable_array_prev,
MaterialPropertyLib::VariableArray const & variable_array,
double const t,
ParameterLib::SpatialPosition const & x,
double const dt,
typename MechanicsBase< DisplacementDim >::MaterialStateVariables const & material_state_variables ) const
inline

Definition at line 454 of file MFrontGeneric.h.

462 {
463 using namespace MathLib::KelvinVector;
464
465 assert(
466 dynamic_cast<MaterialStateVariablesMFront<DisplacementDim> const*>(
467 &material_state_variables));
468 // New state, copy of current one, packed in unique_ptr for return.
469 auto state = std::make_unique<
470 MaterialStateVariablesMFront<DisplacementDim>>(
471 static_cast<MaterialStateVariablesMFront<DisplacementDim> const&>(
472 material_state_variables));
473 auto& behaviour_data = state->_behaviour_data;
474
475 behaviour_data.dt = dt;
476 behaviour_data.rdt = 1.0;
477 behaviour_data.K[0] =
478 4.0; // if K[0] is greater than 3.5, the consistent
479 // tangent operator must be computed.
480 if (behaviour_data.s0.b.btype ==
481 mgis::behaviour::Behaviour::STANDARDFINITESTRAINBEHAVIOUR)
482 {
483 behaviour_data.K[1] = 1.0; // The second Piola-Kirchoff stress is
484 // used for the stress measure
485 behaviour_data.K[2] =
486 1.0; // The derivative of the second
487 // Piola-Kirchoff stress with respect to
488 // the Green-Lagrange strain is returned.
489 }
490
491 // evaluate parameters at (t, x)
492 {
493 {
494 auto out = behaviour_data.s0.material_properties.begin();
495 for (auto* param : _material_properties)
496 {
497 auto const& vals = (*param)(t - dt, x);
498 out = std::copy(vals.begin(), vals.end(), out);
499 }
500 assert(out == behaviour_data.s0.material_properties.end());
501 }
502
503 {
504 auto out = behaviour_data.s1.material_properties.begin();
505 for (auto* param : _material_properties)
506 {
507 auto const& vals = (*param)(t, x);
508 out = std::copy(vals.begin(), vals.end(), out);
509 }
510 assert(out == behaviour_data.s1.material_properties.end());
511 }
512 }
513
514 // TODO unify with gradient handling? Make gradient and external state
515 // var input both optional?
516 if (!behaviour_data.s0.external_state_variables.empty())
517 {
518 // assuming that there is only temperature
519 // NOTE the temperature can be NaN, e.g., if OGS's process does not
520 // have a temperature defined
521 behaviour_data.s0.external_state_variables[0] =
522 variable_array_prev.temperature;
523 }
524
525 if (!behaviour_data.s1.external_state_variables.empty())
526 {
527 // assuming that there is only temperature
528 // NOTE the temperature can be NaN, e.g., if OGS's process does not
529 // have a temperature defined
530 behaviour_data.s1.external_state_variables[0] =
531 variable_array.temperature;
532 }
533
534 // rotation tensor
535 std::optional<KelvinMatrixType<DisplacementDim>> Q;
537 {
539 _local_coordinate_system->transformation<DisplacementDim>(x));
540 }
541
542 boost::mp11::mp_for_each<Gradients>(
543 detail::SetGradient<DisplacementDim>{
544 variable_array_prev, Q, behaviour_data.s0.gradients.data()});
545 boost::mp11::mp_for_each<Gradients>(
546 detail::SetGradient<DisplacementDim>{
547 variable_array, Q, behaviour_data.s1.gradients.data()});
548
549 // previous and current state of thermodynamic forces are both set from
550 // variable_array_prev. TODO optimization potential compute Q * grad_ogs
551 // only once for both cases.
552 boost::mp11::mp_for_each<TDynForces>(
553 detail::SetGradient<DisplacementDim>{
554 variable_array_prev, Q,
555 behaviour_data.s0.thermodynamic_forces.data()});
556 boost::mp11::mp_for_each<TDynForces>(
557 detail::SetGradient<DisplacementDim>{
558 variable_array_prev, Q,
559 behaviour_data.s1.thermodynamic_forces.data()});
560
561 auto v = mgis::behaviour::make_view(behaviour_data);
562 auto const status = mgis::behaviour::integrate(v, _behaviour);
563 if (status != 1)
564 {
566 "MFront: integration failed with status " +
567 std::to_string(status) + ".");
568 }
569
570 OGSMFrontThermodynamicForcesData tdyn_forces_data;
571 tdyn_forces_data.data.resize( // TODO data stored on heap but size is
572 // compile-time constant
573 behaviour_data.s1.thermodynamic_forces.size());
574
575 boost::mp11::mp_for_each<TDynForces>(
576 [&out_data = tdyn_forces_data,
577 &in_data = behaviour_data.s1.thermodynamic_forces,
578 &Q]<typename TDF>(TDF tdf)
579 {
580 OGSMFrontThermodynamicForcesView<DisplacementDim, TDynForces>
581 view;
582
583 if constexpr (TDF::type ==
584 mgis::behaviour::Variable::Type::STENSOR)
585 {
586 if (Q)
587 {
588 view.block(tdf, out_data) =
589 *Q * eigenSwap45View(view.block(tdf, in_data));
590 }
591 else
592 {
593 view.block(tdf, out_data) =
594 eigenSwap45View(view.block(tdf, in_data));
595 }
596 }
597 else if constexpr (TDF::type ==
598 mgis::behaviour::Variable::Type::SCALAR)
599 {
600 view.block(tdf, out_data) = view.block(tdf, in_data);
601 }
602 else
603 {
604 OGS_FATAL("Not yet implemented.");
605 }
606 });
607
608 return std::make_optional(
609 std::make_tuple<OGSMFrontThermodynamicForcesData,
610 std::unique_ptr<typename MechanicsBase<
611 DisplacementDim>::MaterialStateVariables>,
612 OGSMFrontTangentOperatorData>(
613 std::move(tdyn_forces_data),
614 std::move(state),
615 tangentOperatorDataMFrontToOGS<DisplacementDim>(
616 behaviour_data.K, Q, _behaviour)));
617 }
KelvinMatrixType< DisplacementDim > fourthOrderRotationMatrix(Eigen::Matrix< double, DisplacementDim, DisplacementDim, Eigen::ColMajor, DisplacementDim, DisplacementDim > const &transformation)
Eigen::Matrix< double, Dimension, Dimension > transformation(SpatialPosition const &pos) const

References MaterialLib::Solids::MFront::OGSMFrontThermodynamicForcesData::data, OGS_FATAL, and MaterialPropertyLib::VariableArray::temperature.

Member Data Documentation

◆ _behaviour

template<int DisplacementDim, typename Gradients , typename TDynForces , typename ExtStateVars >
mgis::behaviour::Behaviour MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars >::_behaviour
private

Definition at line 724 of file MFrontGeneric.h.

◆ _local_coordinate_system

template<int DisplacementDim, typename Gradients , typename TDynForces , typename ExtStateVars >
ParameterLib::CoordinateSystem const* const MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars >::_local_coordinate_system
private

Definition at line 729 of file MFrontGeneric.h.

◆ _material_properties

template<int DisplacementDim, typename Gradients , typename TDynForces , typename ExtStateVars >
std::vector<ParameterLib::Parameter<double> const*> MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars >::_material_properties
private

Definition at line 726 of file MFrontGeneric.h.

◆ _state_variables_initial_properties

template<int DisplacementDim, typename Gradients , typename TDynForces , typename ExtStateVars >
std::map<std::string, ParameterLib::Parameter<double> const*> MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars >::_state_variables_initial_properties
private

Definition at line 728 of file MFrontGeneric.h.

◆ equivalent_plastic_strain_offset_

template<int DisplacementDim, typename Gradients , typename TDynForces , typename ExtStateVars >
int const MaterialLib::Solids::MFront::MFrontGeneric< DisplacementDim, Gradients, TDynForces, ExtStateVars >::equivalent_plastic_strain_offset_
private

Definition at line 725 of file MFrontGeneric.h.


The documentation for this class was generated from the following file: