Skip to content

Commit 3b90621

Browse files
committed
Inverse Dynamics in M proto + cassiebench test
1 parent a15bcd7 commit 3b90621

30 files changed

+1213
-67
lines changed

.gitignore

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
/.project/
1414
/.settings/
1515
/.clwb/
16+
/.clwb_aspects/
1617
/.vscode
1718
/.history
1819

multibody/benchmarking/cassie.cc

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

149+
// Runs the InverseDynamicsInM benchmark.
150+
// NOLINTNEXTLINE(runtime/references)
151+
void DoInverseDynamicsInM(benchmark::State& state) {
152+
DRAKE_DEMAND(want_grad_u(state) == false);
153+
for (auto _ : state) {
154+
InvalidateState();
155+
plant_->CalcInverseDynamicsInM(*context_, desired_vdot_,
156+
external_forces_);
157+
}
158+
}
159+
149160
// Runs the ForwardDynamics benchmark.
150161
// NOLINTNEXTLINE(runtime/references)
151162
void DoForwardDynamics(benchmark::State& state) {
@@ -327,6 +338,14 @@ BENCHMARK_REGISTER_F(CassieDouble, InverseDynamics)
327338
->Unit(benchmark::kMicrosecond)
328339
->Arg(kWantNoGrad);
329340

341+
// NOLINTNEXTLINE(runtime/references)
342+
BENCHMARK_DEFINE_F(CassieDouble, InverseDynamicsInM)(benchmark::State& state) {
343+
DoInverseDynamicsInM(state);
344+
}
345+
BENCHMARK_REGISTER_F(CassieDouble, InverseDynamicsInM)
346+
->Unit(benchmark::kMicrosecond)
347+
->Arg(kWantNoGrad);
348+
330349
// NOLINTNEXTLINE(runtime/references)
331350
BENCHMARK_DEFINE_F(CassieDouble, ForwardDynamics)(benchmark::State& state) {
332351
DoForwardDynamics(state);
@@ -383,6 +402,22 @@ BENCHMARK_REGISTER_F(CassieAutoDiff, InverseDynamics)
383402
->Arg(kWantGradV|kWantGradVdot)
384403
->Arg(kWantGradX|kWantGradVdot);
385404

405+
BENCHMARK_DEFINE_F(CassieAutoDiff, InverseDynamicsInM)
406+
// NOLINTNEXTLINE(runtime/references)
407+
(benchmark::State& state) {
408+
DoInverseDynamicsInM(state);
409+
}
410+
BENCHMARK_REGISTER_F(CassieAutoDiff, InverseDynamicsInM)
411+
->Unit(benchmark::kMicrosecond)
412+
->Arg(kWantNoGrad)
413+
->Arg(kWantGradQ)
414+
->Arg(kWantGradV)
415+
->Arg(kWantGradX)
416+
->Arg(kWantGradVdot)
417+
->Arg(kWantGradQ|kWantGradVdot)
418+
->Arg(kWantGradV|kWantGradVdot)
419+
->Arg(kWantGradX|kWantGradVdot);
420+
386421
// NOLINTNEXTLINE(runtime/references)
387422
BENCHMARK_DEFINE_F(CassieAutoDiff, ForwardDynamics)(benchmark::State& state) {
388423
DoForwardDynamics(state);

multibody/math/spatial_acceleration.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -134,7 +134,7 @@ class SpatialAcceleration : public SpatialVector<SpatialAcceleration, T> {
134134
const Vector3<T>& alpha_MB_E = this->rotational();
135135
// Calculate point Co's translational acceleration measured in M.
136136
Vector3<T>& a_MCo_E = this->translational();
137-
a_MCo_E += (alpha_MB_E.cross(p_BoCo_E)
137+
a_MCo_E += (alpha_MB_E.cross(p_BoCo_E) // 33 flops total
138138
+ w_MB_E.cross(w_MB_E.cross(p_BoCo_E)));
139139
}
140140

multibody/plant/multibody_plant.h

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4033,6 +4033,14 @@ class MultibodyPlant final : public internal::MultibodyTreeSystem<T> {
40334033
external_forces);
40344034
}
40354035

4036+
VectorX<T> CalcInverseDynamicsInM(
4037+
const systems::Context<T>& context, const VectorX<T>& known_vdot,
4038+
const MultibodyForces<T>& external_forces) const {
4039+
this->ValidateContext(context);
4040+
return internal_tree().CalcInverseDynamicsInM(context, known_vdot,
4041+
external_forces);
4042+
}
4043+
40364044
#ifdef DRAKE_DOXYGEN_CXX
40374045
// MultibodyPlant uses the NVI implementation of
40384046
// 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_id_in_m =
43+
plant_->CalcInverseDynamicsInM(*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_id_in_m, 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
@@ -242,6 +242,10 @@ class BodyNode : public MultibodyElement<T> {
242242
const FrameBodyPoseCache<T>& frame_body_pose_cache, const T* positions,
243243
PositionKinematicsCache<T>* pc) const = 0;
244244

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

298+
virtual void CalcVelocityKinematicsCacheInM_BaseToTip(
299+
const T* positions, const PositionKinematicsCacheInM<T>& pcm,
300+
const T* velocities, VelocityKinematicsCacheInM<T>* vcm) const = 0;
301+
294302
// The CalcMassMatrix() algorithm invokes this on each body k, serving
295303
// as the composite body R(k) in the outer loop of Jain's algorithm 9.3.
296304
// This node must fill in its nv x nv diagonal block in M, and then
@@ -374,6 +382,12 @@ class BodyNode : public MultibodyElement<T> {
374382
const VelocityKinematicsCache<T>* vc, const T* accelerations,
375383
std::vector<SpatialAcceleration<T>>* A_WB_array) const = 0;
376384

385+
virtual void CalcSpatialAccelerationInM_BaseToTip(
386+
const T* positions, const PositionKinematicsCacheInM<T>& pcm,
387+
const T* velocities, const VelocityKinematicsCacheInM<T>& vcm,
388+
const T* accelerations,
389+
std::vector<SpatialAcceleration<T>>* A_WM_M_array) const = 0;
390+
377391
// Computes the generalized forces `tau` for a single BodyNode.
378392
// This method is used by MultibodyTree within a tip-to-base loop to compute
379393
// the vector of generalized forces `tau` that would correspond with a known
@@ -433,6 +447,17 @@ class BodyNode : public MultibodyElement<T> {
433447
std::vector<SpatialForce<T>>* F_BMo_W_array,
434448
EigenPtr<VectorX<T>> tau_array) const = 0;
435449

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

0 commit comments

Comments
 (0)