Skip to content

Commit

Permalink
[fem] Move DeformableBodyConfig out of dev (RobotLocomotion#17108)
Browse files Browse the repository at this point in the history
  • Loading branch information
xuchenhan-tri authored May 9, 2022
1 parent 1b2aa38 commit 38086c0
Show file tree
Hide file tree
Showing 4 changed files with 26 additions and 25 deletions.
18 changes: 18 additions & 0 deletions multibody/fem/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@ drake_cc_package_library(
":corotated_model",
":corotated_model_data",
":damping_model",
":deformable_body_config",
":deformation_gradient_data",
":dirichlet_boundary_condition",
":discrete_time_integrator",
Expand Down Expand Up @@ -131,6 +132,16 @@ drake_cc_library(
],
)

drake_cc_library(
name = "deformable_body_config",
hdrs = [
"deformable_body_config.h",
],
deps = [
"//common:essential",
],
)

drake_cc_library(
name = "deformation_gradient_data",
srcs = [
Expand Down Expand Up @@ -509,6 +520,13 @@ drake_cc_googletest(
],
)

drake_cc_googletest(
name = "deformable_body_config_test",
deps = [
":deformable_body_config",
],
)

drake_cc_googletest(
name = "deformation_gradient_data_test",
deps = [
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,12 @@ enum class MaterialModel {
};

/** %DeformableBodyConfig stores the physical parameters for a deformable body.
It contains the following fields with their corresponding valid ranges:
A default constructed configuration approximately represents a hard rubber
material (density, elasticity, and poisson's ratio) without any damping.
Damping coefficients are generally difficult to measure and we expect users
will typically start with zero damping and tune the values to achieve
reasonable dynamics.
The config contains the following fields with their corresponding valid ranges:
- Young's modulus: Measures the stiffness of the material, has unit N/m². Must
be positive. Default to 1e8.
- Poisson's ratio: Measures the Poisson effect (how much the material expands
Expand All @@ -38,12 +43,7 @@ enum class MaterialModel {
- Material model: The constitutive model that describes the stress-strain
relationship of the body, see MaterialModel. Default to
MaterialModel::kCorotated.
A default constructed configuration approximately represents a hard rubber
material (density, elasticity, and poisson's ratio) without any damping.
Damping coefficients are generally difficult to measure and we expect users
will typically start with zero damping and tune the values to achieve
reasonable dynamics. */
@tparam_nonsymbolic_scalar */
template <typename T>
class DeformableBodyConfig {
public:
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include "drake/multibody/fixed_fem/dev/deformable_body_config.h"
#include "drake/multibody/fem/deformable_body_config.h"

#include <gtest/gtest.h>

Expand Down
17 changes: 0 additions & 17 deletions multibody/fixed_fem/dev/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -11,16 +11,6 @@ package(
default_visibility = ["//visibility:private"],
)

drake_cc_library(
name = "deformable_body_config",
hdrs = [
"deformable_body_config.h",
],
deps = [
"//common:essential",
],
)

drake_cc_library(
name = "deformable_contact",
srcs = ["deformable_rigid_mesh_intersection.cc"],
Expand Down Expand Up @@ -131,13 +121,6 @@ drake_cc_googletest(
],
)

drake_cc_googletest(
name = "deformable_body_config_test",
deps = [
":deformable_body_config",
],
)

drake_cc_googletest(
name = "deformable_contact_test",
deps = [
Expand Down

0 comments on commit 38086c0

Please sign in to comment.