Skip to content

Commit

Permalink
Add a binding for LinearSpringDamper and a test for it.
Browse files Browse the repository at this point in the history
This will be useful once RobotLocomotion#11090 is resolved and we can't add
UniformGravityFieldElement anymore.
  • Loading branch information
sammy-tri committed Sep 11, 2019
1 parent d2d1cc3 commit 5ed2f4d
Show file tree
Hide file tree
Showing 2 changed files with 33 additions and 0 deletions.
19 changes: 19 additions & 0 deletions bindings/pydrake/multibody/test/plant_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
JointActuator_,
JointActuatorIndex,
JointIndex,
LinearSpringDamper_,
ModelInstanceIndex,
MultibodyForces_,
RevoluteJoint_,
Expand Down Expand Up @@ -318,6 +319,24 @@ def test_friction_api(self, T):
CoulombFriction = CoulombFriction_[T]
CoulombFriction(static_friction=0.7, dynamic_friction=0.6)

@numpy_compare.check_all_types
def test_multibody_force_element(self, T):
MultibodyPlant = MultibodyPlant_[T]
LinearSpringDamper = LinearSpringDamper_[T]
SpatialInertia = SpatialInertia_[float]

plant = MultibodyPlant()
spatial_inertia = SpatialInertia()
body_a = plant.AddRigidBody(name="body_a",
M_BBo_B=spatial_inertia)
body_b = plant.AddRigidBody(name="body_b",
M_BBo_B=spatial_inertia)
plant.AddForceElement(LinearSpringDamper(
bodyA=body_a, p_AP=[0., 0., 0.],
bodyB=body_b, p_BQ=[0., 0., 0.],
free_length=1., stiffness=2., damping=3.))
plant.Finalize()

@numpy_compare.check_all_types
def test_multibody_gravity_default(self, T):
MultibodyPlant = MultibodyPlant_[T]
Expand Down
14 changes: 14 additions & 0 deletions bindings/pydrake/multibody/tree_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#include "drake/multibody/tree/frame.h"
#include "drake/multibody/tree/joint.h"
#include "drake/multibody/tree/joint_actuator.h"
#include "drake/multibody/tree/linear_spring_damper.h"
#include "drake/multibody/tree/multibody_forces.h"
#include "drake/multibody/tree/multibody_tree.h" // `JacobianWrtVariable`
#include "drake/multibody/tree/multibody_tree_indexes.h"
Expand Down Expand Up @@ -297,6 +298,19 @@ void DoScalarDependentDefinitions(py::module m, T) {
BindMultibodyTreeElementMixin(&cls);
}

{
using Class = LinearSpringDamper<T>;
constexpr auto& cls_doc = doc.LinearSpringDamper;
auto cls = DefineTemplateClassWithDefault<Class, ForceElement<T>>(
m, "LinearSpringDamper", param, cls_doc.doc);
cls // BR
.def(py::init<const Body<T>&, const Vector3<double>&, const Body<T>&,
const Vector3<double>&, double, double, double>(),
py::arg("bodyA"), py::arg("p_AP"), py::arg("bodyB"),
py::arg("p_BQ"), py::arg("free_length"), py::arg("stiffness"),
py::arg("damping"), cls_doc.ctor.doc);
}

{
using Class = UniformGravityFieldElement<T>;
constexpr auto& cls_doc = doc.UniformGravityFieldElement;
Expand Down

0 comments on commit 5ed2f4d

Please sign in to comment.