Skip to content
Open
Show file tree
Hide file tree
Changes from 19 commits
Commits
Show all changes
23 commits
Select commit Hold shift + click to select a range
9c73b25
Kelvin-Voight Boundary Condition Implementation
cgeudeker Mar 24, 2021
55d7b19
First Edits, and absorbing constraint file
cgeudeker Mar 25, 2021
97e282d
Merge branch 'develop' into material
cgeudeker Mar 25, 2021
e1d24ce
Test cases
cgeudeker May 19, 2021
d61aafa
Test cases
cgeudeker May 19, 2021
e30d186
Test cases, minor fix
cgeudeker May 19, 2021
6a53280
Test Case for Absorbing Constraint File
cgeudeker May 25, 2021
04380c3
Minor Fixes
cgeudeker May 25, 2021
4999748
Switched Assert for If Statement
cgeudeker May 25, 2021
e1ccc53
Absorbing Boundary in Scheme
cgeudeker Aug 1, 2021
f082fbf
Merge branch 'develop' of https://github.com/cb-geo/mpm into material
jgiven100 Aug 12, 2021
fe5f74e
:hammer: add position input to absorb boundary
jgiven100 Aug 19, 2021
472fce5
:hammer::fire: remove unused variables
jgiven100 Aug 19, 2021
f3b70e6
:hammer: change absorb bound position from string to enum
jgiven100 Aug 19, 2021
fd06771
:dart::heavy_check_mark: update absorb boundary tests
jgiven100 Aug 19, 2021
f5f2d1b
:hammer::bug: replace if with switch statement and cppcheck suppress
jgiven100 Aug 19, 2021
805626c
:bug::hammer: fix traction -> force for absorb boundary
jgiven100 Sep 21, 2021
1e3e479
Merge branch 'develop' of https://github.com/cb-geo/mpm into material
jgiven100 Nov 24, 2021
229e1d7
:wrench::sparkles: add 3d support for Kelvin-Voigt
jgiven100 Nov 24, 2021
746283d
:construction::dart: improve test coverage
jgiven100 Nov 25, 2021
397e6e9
:bug: clang-format
jgiven100 Nov 25, 2021
6fa65b9
:construction::dart: improve test coverage
jgiven100 Nov 25, 2021
4cbc60a
:dart::fire: tidy commented-out lines
jgiven100 Nov 25, 2021
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 7 additions & 0 deletions include/data_types.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,13 @@ inline double zero() {
return 0.;
}

//! Position type
//! None: No position is specified
//! Corner: Nodes at boundary corners
//! Edge: Nodes along boundary edges
//! Face: Nodes on boundary faces
enum class Position { None, Corner, Edge, Face };

} // namespace mpm

#endif // MPM_DATA_TYPES_H_
70 changes: 70 additions & 0 deletions include/loads_bcs/absorbing_constraint.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
#ifndef MPM_ABSORBING_CONSTRAINT_H_
#define MPM_ABSORBING_CONSTRAINT_H_

#include "data_types.h"

namespace mpm {

//! AbsorbingConstraint class to store friction constraint on a set
//! \brief AbsorbingConstraint class to store a constraint on a set
//! \details AbsorbingConstraint stores the constraint as a static value
class AbsorbingConstraint {
public:
// Constructor
//! \param[in] setid set id
//! \param[in] dir Direction of p-wave propagation in model
//! \param[in] delta Virtual viscous layer thickness
//! \param[in] h_min Characteristic length (cell height)
//! \param[in] a Dimensionless dashpot weight factor, p-wave
//! \param[in] b Dimensionless dashpot weight factor, s-wave
//! \param[in] position Nodal position along boundary
AbsorbingConstraint(int setid, unsigned dir, double delta, double h_min,
double a = 1., double b = 1.,
mpm::Position position = mpm::Position::None)
: setid_{setid},
dir_{dir},
delta_{delta},
h_min_{h_min},
a_{a},
b_{b},
position_{position} {};

// Set id
int setid() const { return setid_; }

// Direction
unsigned dir() const { return dir_; }

// Virtual viscous layer thickness
double delta() const { return delta_; }

// Cell height
double h_min() const { return h_min_; }

// Return a
double a() const { return a_; }

// Return b
double b() const { return b_; }

// Return position
mpm::Position position() const { return position_; }

private:
// ID
int setid_;
// Direction
unsigned dir_;
// Delta
double delta_;
// Cell height
double h_min_;
// a
double a_;
// b
double b_;
// Node position
mpm::Position position_;
};
} // namespace mpm
#endif // MPM_ABSORBING_CONSTRAINT_H_
17 changes: 17 additions & 0 deletions include/loads_bcs/constraints.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@

#include <memory>

#include "absorbing_constraint.h"
#include "friction_constraint.h"
#include "logger.h"
#include "mesh.h"
Expand Down Expand Up @@ -48,6 +49,22 @@ class Constraints {
const std::vector<std::tuple<mpm::Index, unsigned, int, double>>&
friction_constraints);

//! Assign nodal absorbing constraints
//! \param[in] setid Node set id
//! \param[in] absorbing_constraints Constraint at node, dir, delta, h_min, a,
//! b
bool assign_nodal_absorbing_constraint(
int nset_id,
const std::shared_ptr<mpm::AbsorbingConstraint>& absorbing_constraints);

//! Assign absorbing constraints to nodes
//! \param[in] absorbing_constraints Constraint at node, dir, delta, h_min, a,
//! b, and position
bool assign_nodal_absorbing_constraints(
const std::vector<std::tuple<mpm::Index, unsigned, double, double, double,
double, mpm::Position>>&
absorbing_constraints);

private:
//! Mesh object
std::shared_ptr<mpm::Mesh<Tdim>> mesh_;
Expand Down
80 changes: 80 additions & 0 deletions include/loads_bcs/constraints.tcc
Original file line number Diff line number Diff line change
Expand Up @@ -105,3 +105,83 @@ bool mpm::Constraints<Tdim>::assign_nodal_friction_constraints(
}
return status;
}

//! Apply absorbing constraints to nodes
template <unsigned Tdim>
bool mpm::Constraints<Tdim>::assign_nodal_absorbing_constraint(
int nset_id,
const std::shared_ptr<mpm::AbsorbingConstraint>& absorbing_constraint) {
bool status = true;
try {
// int set_id = absorbing_constraint->setid();
int set_id = nset_id;
auto nset = mesh_->nodes(set_id);
if (nset.size() == 0)
throw std::runtime_error(
"Node set is empty for application of absorbing constraints");
unsigned dir = absorbing_constraint->dir();
double delta = absorbing_constraint->delta();
double h_min = absorbing_constraint->h_min();
double a = absorbing_constraint->a();
double b = absorbing_constraint->b();
mpm::Position position = absorbing_constraint->position();
if (delta >= h_min / (2 * a) and delta >= h_min / (2 * b))
for (auto nitr = nset.cbegin(); nitr != nset.cend(); ++nitr) {
if (!(*nitr)->apply_absorbing_constraint(dir, delta, h_min, a, b,
position))
throw std::runtime_error(
"Failed to apply absorbing constraint at node");
}
else
throw std::runtime_error("Invalid value for delta");
} catch (std::exception& exception) {
console_->error("{} #{}: {}\n", __FILE__, __LINE__, exception.what());
status = false;
}
return status;
}

//! Assign absorbing constraints to nodes
template <unsigned Tdim>
bool mpm::Constraints<Tdim>::assign_nodal_absorbing_constraints(
const std::vector<std::tuple<mpm::Index, unsigned, double, double, double,
double, mpm::Position>>&
absorbing_constraints) {
bool status = true;
try {
for (const auto& absorbing_constraint : absorbing_constraints) {
// Node id
mpm::Index nid = std::get<0>(absorbing_constraint);
// Direction
unsigned dir = std::get<1>(absorbing_constraint);
// Delta
double delta = std::get<2>(absorbing_constraint);
// h_min
double h_min = std::get<3>(absorbing_constraint);
// a
double a = std::get<4>(absorbing_constraint);
// b
double b = std::get<5>(absorbing_constraint);
// Position
mpm::Position position = std::get<6>(absorbing_constraint);
// delta check
if (delta >= h_min / (2 * a) and delta >= h_min / (2 * b)) {
if (position == mpm::Position::Corner or
position == mpm::Position::Edge or
position == mpm::Position::Face) {
// Apply constraint
if (!mesh_->node(nid)->apply_absorbing_constraint(dir, delta, h_min,
a, b, position))
throw std::runtime_error(
"Nodal absorbing constraints assignment failed");
} else
throw std::runtime_error("Invalid position");
} else
throw std::runtime_error("Invalid value for delta");
}
} catch (std::exception& exception) {
console_->error("{} #{}: {}\n", __FILE__, __LINE__, exception.what());
status = false;
}
return status;
}
1 change: 1 addition & 0 deletions include/mesh.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include "json.hpp"
using Json = nlohmann::json;

#include "absorbing_constraint.h"
#include "cell.h"
#include "factory.h"
#include "friction_constraint.h"
Expand Down
4 changes: 4 additions & 0 deletions include/mesh.tcc
Original file line number Diff line number Diff line change
Expand Up @@ -2000,6 +2000,10 @@ void mpm::Mesh<Tdim>::create_nodal_properties() {
materials_.size());
nodal_properties_->create_property("normal_unit_vectors", nrows,
materials_.size());
nodal_properties_->create_property("wave_velocities", nrows,
materials_.size());
nodal_properties_->create_property("density", nodes_.size(),
materials_.size());

// Iterate over all nodes to initialise the property handle in each node
// and assign its node id as the prop id in the nodal property data pool
Expand Down
12 changes: 12 additions & 0 deletions include/node.h
Original file line number Diff line number Diff line change
Expand Up @@ -213,6 +213,18 @@ class Node : public NodeBase<Tdim> {
//! \param[in] dt Time-step
void apply_friction_constraints(double dt) override;

//! Apply absorbing constraint
//! Directions can take values between 0 and Dim * Nphases
//! \param[in] dir Direction of p-wave propagation in model
//! \param[in] delta Virtual viscous layer thickness
//! \param[in] h_min Characteristic length (cell height)
//! \param[in] a Dimensionless dashpot weight factor, p-wave
//! \param[in] b Dimensionless dashpot weight factor, s-wave
//! \param[in] position Nodal position along boundary
bool apply_absorbing_constraint(unsigned dir, double delta, double h_min,
double a, double b,
mpm::Position position) override;

//! Assign rotation matrix
//! \param[in] rotation_matrix Rotation matrix of the node
void assign_rotation_matrix(
Expand Down
97 changes: 95 additions & 2 deletions include/node.tcc
Original file line number Diff line number Diff line change
Expand Up @@ -346,6 +346,94 @@ void mpm::Node<Tdim, Tdof, Tnphases>::apply_velocity_constraints() {
}
}

// !Apply absorbing constraints
template <unsigned Tdim, unsigned Tdof, unsigned Tnphases>
bool mpm::Node<Tdim, Tdof, Tnphases>::apply_absorbing_constraint(
unsigned dir, double delta, double h_min, double a, double b,
mpm::Position position) {
bool status = true;
try {

if (dir >= Tdim) {
throw std::runtime_error("Direction is out of bounds");
status = false;
}
if (material_ids_.size() != 0) {
// Get material id
auto mat_id = material_ids_.begin();

// Extract material properties and displacements
double pwave_v = this->property_handle_->property(
"wave_velocities", prop_id_, *mat_id, Tdim)(0);
double swave_v = this->property_handle_->property(
"wave_velocities", prop_id_, *mat_id, Tdim)(1);
double density =
this->property_handle_->property("density", prop_id_, *mat_id)(0);
Eigen::Matrix<double, Tdim, 1> material_displacement =
this->property_handle_->property("displacements", prop_id_, *mat_id,
Tdim);
material_displacement /= this->mass(*mat_id);

// Wave velocity Eigen Matrix
Eigen::Matrix<double, Tdim, 1> wave_velocity =
Eigen::MatrixXd::Constant(Tdim, 1, b * swave_v);
wave_velocity(dir, 0) = a * pwave_v;
// Spring constant Eigen matrix
double k_s = (density * pow(swave_v, 2)) / delta;
double k_p = (density * pow(pwave_v, 2)) / delta;
Eigen::Matrix<double, Tdim, 1> spring_constant =
Eigen::MatrixXd::Constant(Tdim, 1, k_s);
spring_constant(dir, 0) = k_p;

// Iterate through each phase
for (unsigned phase = 0; phase < Tnphases; ++phase) {
// Calculate Aborbing Traction
Eigen::Matrix<double, Tdim, 1> absorbing_traction_ =
this->velocity_.col(phase).cwiseProduct(wave_velocity) * density +
material_displacement.cwiseProduct(spring_constant);

// Update external force
if (Tdim == 2) {
Eigen::Matrix<double, Tdim, 1> absorbing_force_;
switch (position) {
case mpm::Position::Corner:
absorbing_force_ = 0.5 * h_min * absorbing_traction_;
break;
case mpm::Position::Edge:
absorbing_force_ = h_min * absorbing_traction_;
break;
default:
throw std::runtime_error("Invalid absorbing boundary position");
break;
}
this->update_external_force(true, phase, -absorbing_force_);
} else if (Tdim == 3) {
Eigen::Matrix<double, Tdim, 1> absorbing_force_;
switch (position) {
case mpm::Position::Corner:
absorbing_force_ = 0.25 * pow(h_min, 2) * absorbing_traction_;
break;
case mpm::Position::Edge:
absorbing_force_ = 0.5 * pow(h_min, 2) * absorbing_traction_;
break;
case mpm::Position::Face:
absorbing_force_ = pow(h_min, 2) * absorbing_traction_;
break;
default:
throw std::runtime_error("Invalid absorbing boundary position");
break;
}
this->update_external_force(true, phase, -absorbing_force_);
}
}
}
} catch (std::exception& exception) {
console_->error("{} #{}: {}\n", __FILE__, __LINE__, exception.what());
status = false;
}
return status;
}

//! Assign friction constraint
//! Constrain directions can take values between 0 and Dim * Nphases
template <unsigned Tdim, unsigned Tdof, unsigned Tnphases>
Expand Down Expand Up @@ -543,10 +631,15 @@ void mpm::Node<Tdim, Tdof, Tnphases>::update_property(
bool update, const std::string& property,
const Eigen::MatrixXd& property_value, unsigned mat_id,
unsigned nprops) noexcept {

// Update/assign property
node_mutex_.lock();
property_handle_->update_property(property, prop_id_, mat_id, property_value,
nprops);
if (update)
property_handle_->update_property(property, prop_id_, mat_id,
property_value, nprops);
else
property_handle_->assign_property(property, prop_id_, mat_id,
property_value, nprops);
node_mutex_.unlock();
}

Expand Down
12 changes: 12 additions & 0 deletions include/node_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -205,6 +205,18 @@ class NodeBase {
//! \param[in] dt Time-step
virtual void apply_friction_constraints(double dt) = 0;

//! Apply absorbing constraint
//! Directions can take values between 0 and Dim * Nphases
//! \param[in] dir Direction of p-wave propagation in model
//! \param[in] delta Virtual viscous layer thickness
//! \param[in] h_min Characteristic length (cell height)
//! \param[in] a Dimensionless dashpot weight factor, p-wave
//! \param[in] b Dimensionless dashpot weight factor, s-wave
//! \param[in] position Nodal position along boundary
virtual bool apply_absorbing_constraint(unsigned dir, double delta,
double h_min, double a, double b,
mpm::Position position) = 0;

//! Assign rotation matrix
//! \param[in] rotation_matrix Rotation matrix of the node
virtual void assign_rotation_matrix(
Expand Down
3 changes: 3 additions & 0 deletions include/particles/particle.h
Original file line number Diff line number Diff line change
Expand Up @@ -149,6 +149,9 @@ class Particle : public ParticleBase<Tdim> {
//! Map multimaterial domain gradients to nodes
void map_multimaterial_domain_gradients_to_nodes() noexcept override;

// ! Map linear elastic wave velocities to nodes
void map_wave_velocities_to_nodes() noexcept override;

//! Assign nodal mass to particles
//! \param[in] mass Mass from the particles in a cell
//! \retval status Assignment status
Expand Down
Loading