Skip to content

Commit

Permalink
[multibody] APIs to set the default joint damping (RobotLocomotion#17151
Browse files Browse the repository at this point in the history
)
  • Loading branch information
amcastro-tri authored May 10, 2022
1 parent 3ce091d commit 55b8b27
Show file tree
Hide file tree
Showing 5 changed files with 68 additions and 14 deletions.
12 changes: 12 additions & 0 deletions multibody/tree/joint.h
Original file line number Diff line number Diff line change
Expand Up @@ -460,6 +460,18 @@ class Joint : public MultibodyElement<Joint, T, JointIndex> {
return damping_;
}

/// Sets the default value of the viscous damping coefficients for this joint.
/// Refer to damping_vector() for details.
/// @throws std::exception if damping.size() != num_velocities().
/// @throws std::exception if any of the damping coefficients is negative.
/// @pre the MultibodyPlant must not be finalized.
void set_default_damping_vector(const VectorX<double>& damping) {
DRAKE_THROW_UNLESS(damping.size() == num_velocities());
DRAKE_THROW_UNLESS((damping.array() >= 0).all());
DRAKE_DEMAND(!this->get_parent_tree().topology_is_valid());
damping_ = damping;
}

// Hide the following section from Doxygen.
#ifndef DRAKE_DOXYGEN_CXX
// NVI to DoCloneToScalar() templated on the scalar type of the new clone to
Expand Down
9 changes: 9 additions & 0 deletions multibody/tree/prismatic_joint.h
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,15 @@ class PrismaticJoint final : public Joint<T> {
/// Returns `this` joint's damping constant in N⋅s/m.
double damping() const { return this->damping_vector()[0]; }

/// Sets the default value of viscous damping for this joint, in N⋅s/m.
/// @throws std::exception if damping is negative.
/// @pre the MultibodyPlant must not be finalized.
void set_default_damping(double damping) {
DRAKE_THROW_UNLESS(damping >= 0);
DRAKE_DEMAND(!this->get_parent_tree().topology_is_valid());
this->set_default_damping_vector(Vector1d(damping));
}

/// Returns the position lower limit for `this` joint in meters.
double position_lower_limit() const {
return this->position_lower_limits()[0];
Expand Down
9 changes: 9 additions & 0 deletions multibody/tree/revolute_joint.h
Original file line number Diff line number Diff line change
Expand Up @@ -137,6 +137,15 @@ class RevoluteJoint final : public Joint<T> {
/// Returns `this` joint's damping constant in N⋅m⋅s.
double damping() const { return this->damping_vector()[0]; }

/// Sets the default value of viscous damping for this joint, in N⋅m⋅s.
/// @throws std::exception if damping is negative.
/// @pre the MultibodyPlant must not be finalized.
void set_default_damping(double damping) {
DRAKE_THROW_UNLESS(damping >= 0);
DRAKE_DEMAND(!this->get_parent_tree().topology_is_valid());
this->set_default_damping_vector(Vector1d(damping));
}

/// Returns the position lower limit for `this` joint in radians.
double position_lower_limit() const {
return this->position_lower_limits()[0];
Expand Down
26 changes: 19 additions & 7 deletions multibody/tree/test/prismatic_joint_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,16 @@ class PrismaticJointTest : public ::testing::Test {
// Creates a simple model consisting of a single body with a prismatic joint
// with the sole purpose of testing the PrismaticJoint user facing API.
void SetUp() override {
std::unique_ptr<internal::MultibodyTree<double>> model = MakeModel();

// We are done adding modeling elements. Transfer tree to system and get
// a Context.
system_ = std::make_unique<internal::MultibodyTreeSystem<double>>(
std::move(model), true/* is_discrete */);
context_ = system_->CreateDefaultContext();
}

std::unique_ptr<internal::MultibodyTree<double>> MakeModel() {
// Spatial inertia for adding body. The actual value is not important for
// these tests and therefore we do not initialize it.
const SpatialInertia<double> M_B; // Default construction is ok for this.
Expand All @@ -53,11 +63,7 @@ class PrismaticJointTest : public ::testing::Test {
Vector1<double>::Constant(kAccelerationLowerLimit),
Vector1<double>::Constant(kAccelerationUpperLimit));

// We are done adding modeling elements. Transfer tree to system and get
// a Context.
system_ = std::make_unique<internal::MultibodyTreeSystem<double>>(
std::move(model), true/* is_discrete */);
context_ = system_->CreateDefaultContext();
return model;
}

const internal::MultibodyTree<double>& tree() const {
Expand Down Expand Up @@ -110,8 +116,14 @@ TEST_F(PrismaticJointTest, GetJointLimits) {
}

TEST_F(PrismaticJointTest, Damping) {
EXPECT_EQ(joint1_->damping(), kDamping);
EXPECT_EQ(joint1_->damping_vector(), Vector1d(kDamping));
std::unique_ptr<internal::MultibodyTree<double>> model = MakeModel();
auto& joint = model->GetMutableJointByName<PrismaticJoint>("Joint1");
EXPECT_EQ(joint.damping(), kDamping);
EXPECT_EQ(joint.damping_vector(), Vector1d(kDamping));
const double new_damping = 2.0 * kDamping;
joint.set_default_damping(new_damping);
EXPECT_EQ(joint.damping(), new_damping);
EXPECT_EQ(joint.damping_vector(), Vector1d(new_damping));
}

// Context-dependent value access.
Expand Down
26 changes: 19 additions & 7 deletions multibody/tree/test/revolute_joint_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,16 @@ class RevoluteJointTest : public ::testing::Test {
// Creates a DoublePendulumModel class with an underlying MultibodyTree model
// of a double pendulum.
void SetUp() override {
std::unique_ptr<internal::MultibodyTree<double>> model = MakeModel();

// We are done adding modeling elements. Transfer tree to system and get
// a Context.
system_ = std::make_unique<internal::MultibodyTreeSystem<double>>(
std::move(model));
context_ = system_->CreateDefaultContext();
}

std::unique_ptr<internal::MultibodyTree<double>> MakeModel() {
// Spatial inertia for adding bodies. The actual value is not important for
// these tests and therefore we do not initialize it.
const SpatialInertia<double> M_B; // Default construction is ok for this.
Expand All @@ -55,11 +65,7 @@ class RevoluteJointTest : public ::testing::Test {
Vector1<double>::Constant(kAccelerationLowerLimit),
Vector1<double>::Constant(kAccelerationUpperLimit));

// We are done adding modeling elements. Transfer tree to system and get
// a Context.
system_ = std::make_unique<internal::MultibodyTreeSystem<double>>(
std::move(model));
context_ = system_->CreateDefaultContext();
return model;
}

const internal::MultibodyTree<double>& tree() const {
Expand Down Expand Up @@ -112,8 +118,14 @@ TEST_F(RevoluteJointTest, GetJointLimits) {
}

TEST_F(RevoluteJointTest, Damping) {
EXPECT_EQ(joint1_->damping(), kDamping);
EXPECT_EQ(joint1_->damping_vector(), Vector1d(kDamping));
std::unique_ptr<internal::MultibodyTree<double>> model = MakeModel();
auto& joint = model->GetMutableJointByName<RevoluteJoint>("Joint1");
EXPECT_EQ(joint.damping(), kDamping);
EXPECT_EQ(joint.damping_vector(), Vector1d(kDamping));
const double new_damping = 2.0 * kDamping;
joint.set_default_damping(new_damping);
EXPECT_EQ(joint.damping(), new_damping);
EXPECT_EQ(joint.damping_vector(), Vector1d(new_damping));
}

// Context-dependent value access.
Expand Down

0 comments on commit 55b8b27

Please sign in to comment.