Skip to content

Commit a730a7d

Browse files
committed
Inverse Dynamics 2 (in M) proto + cassiebench test
1 parent f4c19e7 commit a730a7d

27 files changed

+1154
-80
lines changed

multibody/benchmarking/cassie.cc

Lines changed: 33 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -146,6 +146,16 @@ class Cassie : public benchmark::Fixture {
146146
}
147147
}
148148

149+
// Runs the InverseDynamics2 benchmark.
150+
// NOLINTNEXTLINE(runtime/references)
151+
void DoInverseDynamics2(benchmark::State& state) {
152+
DRAKE_DEMAND(want_grad_u(state) == false);
153+
for (auto _ : state) {
154+
InvalidateState();
155+
plant_->CalcInverseDynamics2(*context_, desired_vdot_, external_forces_);
156+
}
157+
}
158+
149159
// Runs the ForwardDynamics benchmark.
150160
// NOLINTNEXTLINE(runtime/references)
151161
void DoForwardDynamics(benchmark::State& state) {
@@ -327,6 +337,14 @@ BENCHMARK_REGISTER_F(CassieDouble, InverseDynamics)
327337
->Unit(benchmark::kMicrosecond)
328338
->Arg(kWantNoGrad);
329339

340+
// NOLINTNEXTLINE(runtime/references)
341+
BENCHMARK_DEFINE_F(CassieDouble, InverseDynamics2)(benchmark::State& state) {
342+
DoInverseDynamics2(state);
343+
}
344+
BENCHMARK_REGISTER_F(CassieDouble, InverseDynamics2)
345+
->Unit(benchmark::kMicrosecond)
346+
->Arg(kWantNoGrad);
347+
330348
// NOLINTNEXTLINE(runtime/references)
331349
BENCHMARK_DEFINE_F(CassieDouble, ForwardDynamics)(benchmark::State& state) {
332350
DoForwardDynamics(state);
@@ -383,6 +401,21 @@ BENCHMARK_REGISTER_F(CassieAutoDiff, InverseDynamics)
383401
->Arg(kWantGradV|kWantGradVdot)
384402
->Arg(kWantGradX|kWantGradVdot);
385403

404+
// NOLINTNEXTLINE(runtime/references)
405+
BENCHMARK_DEFINE_F(CassieAutoDiff, InverseDynamics2)(benchmark::State& state) {
406+
DoInverseDynamics2(state);
407+
}
408+
BENCHMARK_REGISTER_F(CassieAutoDiff, InverseDynamics2)
409+
->Unit(benchmark::kMicrosecond)
410+
->Arg(kWantNoGrad)
411+
->Arg(kWantGradQ)
412+
->Arg(kWantGradV)
413+
->Arg(kWantGradX)
414+
->Arg(kWantGradVdot)
415+
->Arg(kWantGradQ|kWantGradVdot)
416+
->Arg(kWantGradV|kWantGradVdot)
417+
->Arg(kWantGradX|kWantGradVdot);
418+
386419
// NOLINTNEXTLINE(runtime/references)
387420
BENCHMARK_DEFINE_F(CassieAutoDiff, ForwardDynamics)(benchmark::State& state) {
388421
DoForwardDynamics(state);

multibody/plant/multibody_plant.h

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3871,6 +3871,14 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
38713871
external_forces);
38723872
}
38733873

3874+
VectorX<T> CalcInverseDynamics2(
3875+
const systems::Context<T>& context, const VectorX<T>& known_vdot,
3876+
const MultibodyForces<T>& external_forces) const {
3877+
this->ValidateContext(context);
3878+
return internal_tree().CalcInverseDynamics2(context, known_vdot,
3879+
external_forces);
3880+
}
3881+
38743882
#ifdef DRAKE_DOXYGEN_CXX
38753883
// MultibodyPlant uses the NVI implementation of
38763884
// CalcImplicitTimeDerivativesResidual from

multibody/plant/test/external_forces_test.cc

Lines changed: 8 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,12 @@
11
#include <limits>
22

3-
#include <gmock/gmock.h>
43
#include <gtest/gtest.h>
54

6-
#include "drake/common/autodiff.h"
5+
#include "drake/common/fmt_eigen.h"
76
#include "drake/common/test_utilities/eigen_matrix_compare.h"
87
#include "drake/common/test_utilities/limit_malloc.h"
98
#include "drake/multibody/plant/test/kuka_iiwa_model_tests.h"
109
#include "drake/multibody/tree/frame.h"
11-
#include "drake/multibody/tree/rigid_body.h"
1210

1311
namespace drake {
1412

@@ -41,6 +39,9 @@ TEST_F(KukaIiwaModelTests, ExternalBodyForces) {
4139
end_effector_link_->body_frame(), &forces);
4240
const VectorX<double> tau_id =
4341
plant_->CalcInverseDynamics(*context_, vdot, forces);
42+
const VectorX<double> tau_id2 =
43+
plant_->CalcInverseDynamics2(*context_, vdot, forces);
44+
4445
{ // Repeat the computation to confirm the heap behavior. We allow the
4546
// method to heap-allocate 2 temporaries and 1 return value.
4647
drake::test::LimitMalloc guard({.max_num_allocations = 3});
@@ -75,6 +76,10 @@ TEST_F(KukaIiwaModelTests, ExternalBodyForces) {
7576
const double kTolerance = 50 * std::numeric_limits<double>::epsilon();
7677
EXPECT_TRUE(CompareMatrices(tau_id, tau_id_expected, kTolerance,
7778
MatrixCompareType::relative));
79+
// W & M frame ID should be very close.
80+
EXPECT_TRUE(CompareMatrices(tau_id2, tau_id,
81+
16 * std::numeric_limits<double>::epsilon(),
82+
MatrixCompareType::relative));
7883
}
7984

8085
TEST_F(KukaIiwaModelTests, BodyForceApi) {

multibody/tree/body_node.h

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -241,6 +241,10 @@ class BodyNode : public MultibodyElement<T> {
241241
const FrameBodyPoseCache<T>& frame_body_pose_cache, const T* positions,
242242
PositionKinematicsCache<T>* pc) const = 0;
243243

244+
virtual void CalcPositionKinematicsCache2_BaseToTip(
245+
const FrameBodyPoseCache<T>& frame_body_pose_cache, const T* positions,
246+
PositionKinematicsCache2<T>* pc2) const = 0;
247+
244248
// Calculates the hinge matrix H_PB_W, the `6 x nm` hinge matrix that relates
245249
// V_PB_W`(body B's spatial velocity in its parent body P, expressed in world
246250
// W) to this node's nm generalized velocities (or mobilities) v_B as
@@ -290,6 +294,10 @@ class BodyNode : public MultibodyElement<T> {
290294
const std::vector<Vector6<T>>& H_PB_W_cache, const T* velocities,
291295
VelocityKinematicsCache<T>* vc) const = 0;
292296

297+
virtual void CalcVelocityKinematicsCache2_BaseToTip(
298+
const T* positions, const PositionKinematicsCache2<T>& pc2,
299+
const T* velocities, VelocityKinematicsCache2<T>* vc2) const = 0;
300+
293301
// The CalcMassMatrix() algorithm invokes this on each body k, serving
294302
// as the composite body R(k) in the outer loop of Jain's algorithm 9.3.
295303
// This node must fill in its nv x nv diagonal block in M, and then
@@ -373,6 +381,12 @@ class BodyNode : public MultibodyElement<T> {
373381
const VelocityKinematicsCache<T>* vc, const T* accelerations,
374382
std::vector<SpatialAcceleration<T>>* A_WB_array) const = 0;
375383

384+
virtual void CalcSpatialAcceleration2_BaseToTip(
385+
const T* positions, const PositionKinematicsCache2<T>& pc2,
386+
const T* velocities, const VelocityKinematicsCache2<T>& vc2,
387+
const T* accelerations,
388+
std::vector<SpatialAcceleration<T>>* A_WM_M_array) const = 0;
389+
376390
// Computes the generalized forces `tau` for a single BodyNode.
377391
// This method is used by MultibodyTree within a tip-to-base loop to compute
378392
// the vector of generalized forces `tau` that would correspond with a known
@@ -432,6 +446,17 @@ class BodyNode : public MultibodyElement<T> {
432446
std::vector<SpatialForce<T>>* F_BMo_W_array,
433447
EigenPtr<VectorX<T>> tau_array) const = 0;
434448

449+
virtual void CalcInverseDynamics2_TipToBase(
450+
const FrameBodyPoseCache<T>& frame_body_pose_cache, // M_BMo_M, X_BM
451+
const T* positions,
452+
const PositionKinematicsCache2<T>& pc, // X_MpM, X_WB
453+
const VelocityKinematicsCache2<T>& vc, // V_WM_M
454+
const std::vector<SpatialAcceleration<T>>& A_WM_M_array,
455+
const std::vector<SpatialForce<T>>& Fapplied_Bo_W_array, // Bo, W !
456+
const Eigen::Ref<const VectorX<T>>& tau_applied_array,
457+
std::vector<SpatialForce<T>>* F_BMo_M_array,
458+
EigenPtr<VectorX<T>> tau_array) const = 0;
459+
435460
// This method is used by MultibodyTree within a tip-to-base loop to compute
436461
// this node's articulated body inertia quantities that depend only on the
437462
// generalized positions.

0 commit comments

Comments
 (0)