Skip to content

Commit b771fdf

Browse files
committed
Effort limits for Kinematic Trajectory Optimization
Resolves #22500.
1 parent f048d9a commit b771fdf

File tree

7 files changed

+278
-5
lines changed

7 files changed

+278
-5
lines changed

bindings/pydrake/planning/BUILD.bazel

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -105,6 +105,9 @@ drake_py_unittest(
105105

106106
drake_py_unittest(
107107
name = "trajectory_optimization_test",
108+
data = [
109+
"//examples/multibody/cart_pole:models",
110+
],
108111
deps = [
109112
":planning",
110113
"//bindings/pydrake/examples",

bindings/pydrake/planning/planning_py_trajectory_optimization.cc

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -332,6 +332,11 @@ void DefinePlanningTrajectoryOptimization(py::module m) {
332332
py::arg("lb"), py::arg("ub"), cls_doc.AddAccelerationBounds.doc)
333333
.def("AddJerkBounds", &Class::AddJerkBounds, py::arg("lb"),
334334
py::arg("ub"), cls_doc.AddJerkBounds.doc)
335+
.def("AddEffortBoundsAtNormalizedTimes",
336+
&Class::AddEffortBoundsAtNormalizedTimes, py::arg("plant"),
337+
py::arg("s"), py::arg("lb") = std::nullopt,
338+
py::arg("ub") = std::nullopt, py::arg("plant_context") = nullptr,
339+
cls_doc.AddEffortBoundsAtNormalizedTimes.doc)
335340
.def("AddDurationCost", &Class::AddDurationCost,
336341
py::arg("weight") = 1.0, cls_doc.AddDurationCost.doc)
337342
.def("AddPathLengthCost", &Class::AddPathLengthCost,

bindings/pydrake/planning/test/trajectory_optimization_test.py

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,7 @@
3232
ExpressionConstraint
3333
)
3434
from pydrake.multibody.plant import MultibodyPlant
35+
from pydrake.multibody.parsing import Parser
3536
import pydrake.solvers as mp
3637
from pydrake.symbolic import Variable
3738
from pydrake.systems.framework import InputPortSelection
@@ -254,6 +255,16 @@ def test_kinematic_trajectory_optimization(self):
254255
trajopt.AddAccelerationBounds(lb=b, ub=b)
255256
trajopt.AddJerkBounds(lb=b, ub=b)
256257

258+
plant = MultibodyPlant(time_step=0.0)
259+
Parser(plant).AddModelsFromUrl(
260+
url="package://drake/examples/multibody/cart_pole/cart_pole.sdf")
261+
plant.Finalize()
262+
plant_context = plant.CreateDefaultContext()
263+
trajopt.AddEffortBoundsAtNormalizedTimes(
264+
plant=plant, s=[0.1, 0.9],
265+
lb=[-1, -2], ub=[3, 4],
266+
plant_context=plant_context)
267+
257268
trajopt.AddDurationCost(weight=1)
258269
trajopt.AddPathLengthCost(weight=1)
259270
trajopt.AddPathEnergyCost(weight=1)

planning/trajectory_optimization/BUILD.bazel

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -97,6 +97,7 @@ drake_cc_library(
9797
"//math:bspline_basis",
9898
"//math:gradient",
9999
"//math:matrix_util",
100+
"//multibody/plant",
100101
"//solvers:mathematical_program",
101102
"//solvers:mathematical_program_result",
102103
],
@@ -194,6 +195,7 @@ drake_cc_googletest(
194195
deps = [
195196
":kinematic_trajectory_optimization",
196197
"//common/test_utilities:eigen_matrix_compare",
198+
"//multibody/benchmarks/pendulum",
197199
"//solvers:constraint",
198200
"//solvers:ipopt_solver",
199201
"//solvers:osqp_solver",

planning/trajectory_optimization/kinematic_trajectory_optimization.cc

Lines changed: 119 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,8 @@ using math::EigenToStdVector;
2828
using math::ExtractValue;
2929
using math::InitializeAutoDiff;
3030
using math::StdVectorToEigen;
31+
using multibody::MultibodyForces;
32+
using multibody::MultibodyPlant;
3133
using solvers::Binding;
3234
using solvers::BoundingBoxConstraint;
3335
using solvers::Constraint;
@@ -187,12 +189,82 @@ class DerivativeConstraint : public Constraint {
187189
const int derivative_order_;
188190
};
189191

192+
// Constraint of the form tau_lb <= InverseDynamics(q, v, a) <= tau_ub. The
193+
// constraint should be bound to the duration followed by all of the control
194+
// points in the bspline. TODO(russt): The constraint actually only depends on
195+
// a subset of the control points, depending on s, so we could consider
196+
// optimizing this aspect.
197+
class EffortConstraint : public Constraint {
198+
public:
199+
EffortConstraint(const std::shared_ptr<MultibodyPlant<AutoDiffXd>>& plant,
200+
std::shared_ptr<systems::Context<AutoDiffXd>> plant_context,
201+
const Eigen::VectorXd& lb, const Eigen::VectorXd& ub,
202+
const BsplineTrajectory<double>& bspline, double s)
203+
: Constraint(lb.size(), 1 + bspline.num_control_points() * bspline.rows(),
204+
lb, ub),
205+
plant_(plant),
206+
plant_context_(std::move(plant_context)),
207+
num_control_points_(bspline.num_control_points()),
208+
s_(s) {
209+
// Note: consistency checks on the input arguments already happened in
210+
// AddEffortBoundsAtNormalizedTimes().
211+
M_q_ = bspline.EvaluateLinearInControlPoints(s, 0).cast<AutoDiffXd>();
212+
M_v_ = bspline.EvaluateLinearInControlPoints(s, 1).cast<AutoDiffXd>();
213+
M_vdot_ = bspline.EvaluateLinearInControlPoints(s, 2).cast<AutoDiffXd>();
214+
}
215+
216+
void DoEval(const Eigen::Ref<const Eigen::VectorXd>& x,
217+
Eigen::VectorXd* y) const override {
218+
AutoDiffVecXd y_t;
219+
Eval(InitializeAutoDiff(x), &y_t);
220+
*y = ExtractValue(y_t);
221+
}
222+
223+
void DoEval(const Eigen::Ref<const AutoDiffVecXd>& x,
224+
AutoDiffVecXd* y) const override {
225+
y->resize(plant_->num_positions());
226+
AutoDiffXd duration = x[0];
227+
MatrixX<AutoDiffXd> control_points =
228+
x.tail(plant_->num_positions() * num_control_points_)
229+
.reshaped(plant_->num_positions(), num_control_points_);
230+
plant_context_->SetTime(s_ * duration);
231+
plant_->SetPositions(plant_context_.get(), control_points * M_q_);
232+
plant_->SetVelocities(plant_context_.get(),
233+
control_points * M_v_ / duration);
234+
VectorX<AutoDiffXd> vdot = control_points * M_vdot_ / pow(duration, 2);
235+
drake::log()->info("q: {}", fmt_eigen(control_points * M_q_));
236+
drake::log()->info("v: {}", fmt_eigen(control_points * M_v_ / duration));
237+
drake::log()->info("vdot: {}", fmt_eigen(vdot.transpose()));
238+
MultibodyForces<AutoDiffXd> forces_(*plant_);
239+
plant_->CalcForceElementsContribution(*plant_context_, &forces_);
240+
*y = plant_->CalcInverseDynamics(*plant_context_, vdot, forces_);
241+
}
242+
243+
void DoEval(const Eigen::Ref<const VectorX<symbolic::Variable>>&,
244+
VectorX<symbolic::Expression>*) const override {
245+
throw std::runtime_error(
246+
"EffortConstraint does not support evaluation with Expression.");
247+
}
248+
249+
private:
250+
const std::shared_ptr<MultibodyPlant<AutoDiffXd>> plant_;
251+
std::shared_ptr<systems::Context<AutoDiffXd>> plant_context_;
252+
// M_q_, M_v_, M_vdot_ are matrices such that by multiplying control_points
253+
// with these matrices, we get the position q, dqds, and d²qds² respectively.
254+
VectorX<AutoDiffXd> M_q_;
255+
VectorX<AutoDiffXd> M_v_;
256+
VectorX<AutoDiffXd> M_vdot_;
257+
int num_control_points_;
258+
double s_;
259+
};
260+
190261
// solvers::LinearConstraint stores linear constraints in the form A*x <= b.
191-
// When constraints are naturally expressed in the form X*a <= b (the decision
192-
// variables on the left), it is still a vector constraint, but we must do some
193-
// work to rewrite it as A*x, and the result is a big sparse A. This method
194-
// does precisely that. For MatrixXDecisionVariable X and VectorXd a, returns
195-
// SparseMatrix A and VectorXDecisionVariable x such that Ax == Xa.
262+
// When constraints are naturally expressed in the form X*a <= b (the
263+
// decision variables on the left), it is still a vector constraint, but we
264+
// must do some work to rewrite it as A*x, and the result is a big sparse A.
265+
// This method does precisely that. For MatrixXDecisionVariable X and
266+
// VectorXd a, returns SparseMatrix A and VectorXDecisionVariable x such that
267+
// Ax == Xa.
196268
std::pair<SparseMatrix<double>, VectorXDecisionVariable> RewriteXa(
197269
const MatrixXDecisionVariable& X, const VectorXd& a) {
198270
const int num_nonzeros = (a.array() != 0).count();
@@ -497,6 +569,48 @@ std::vector<Binding<Constraint>> KinematicTrajectoryOptimization::AddJerkBounds(
497569
return bindings;
498570
}
499571

572+
std::vector<Binding<Constraint>>
573+
KinematicTrajectoryOptimization::AddEffortBoundsAtNormalizedTimes(
574+
const MultibodyPlant<double>& plant,
575+
const Eigen::Ref<const Eigen::VectorXd>& s,
576+
const std::optional<Eigen::Ref<const Eigen::VectorXd>>& lb,
577+
const std::optional<Eigen::Ref<const Eigen::VectorXd>>& ub,
578+
const systems::Context<double>* plant_context) {
579+
DRAKE_THROW_UNLESS(s.array().minCoeff() >= 0 && s.array().maxCoeff() <= 1);
580+
const MatrixXd B = plant.MakeActuationMatrix();
581+
const VectorXd B_tau_lb = B * (lb.value_or(plant.GetEffortLowerLimits()));
582+
const VectorXd B_tau_ub = B * (ub.value_or(plant.GetEffortUpperLimits()));
583+
DRAKE_THROW_UNLESS(B_tau_lb.size() == num_positions());
584+
DRAKE_THROW_UNLESS(B_tau_ub.size() == num_positions());
585+
DRAKE_THROW_UNLESS((B_tau_lb.array() <= B_tau_ub.array()).all());
586+
if (plant_context != nullptr) {
587+
plant.ValidateContext(plant_context);
588+
}
589+
590+
VectorXDecisionVariable vars(1 + num_control_points_ * num_positions_);
591+
vars << duration_, control_points_.reshaped(control_points_.size(), 1);
592+
std::shared_ptr<MultibodyPlant<AutoDiffXd>> plant_ad(
593+
systems::System<double>::ToAutoDiffXd(plant));
594+
std::vector<Binding<Constraint>> bindings;
595+
for (int i = 0; i < ssize(s); ++i) {
596+
// Note: we choose to make a separate context for each s so that the
597+
// constraints are thread-safe.
598+
std::shared_ptr<systems::Context<AutoDiffXd>> plant_context_ad(
599+
plant_ad->CreateDefaultContext());
600+
if (plant_context != nullptr) {
601+
plant_context_ad->SetTimeStateAndParametersFrom(*plant_context);
602+
}
603+
bindings.emplace_back(prog_.AddConstraint(
604+
std::make_shared<EffortConstraint>(plant_ad,
605+
std::move(plant_context_ad),
606+
B_tau_lb, B_tau_ub, bspline_, s[i]),
607+
vars));
608+
bindings.back().evaluator()->set_description(
609+
fmt::format("effort bound at s={}", s[i]));
610+
}
611+
return bindings;
612+
}
613+
500614
Binding<LinearCost> KinematicTrajectoryOptimization::AddDurationCost(
501615
double weight) {
502616
auto binding = prog_.AddLinearCost(weight * duration_);

planning/trajectory_optimization/kinematic_trajectory_optimization.h

Lines changed: 36 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99

1010
#include "drake/common/copyable_unique_ptr.h"
1111
#include "drake/common/trajectories/bspline_trajectory.h"
12+
#include "drake/multibody/plant/multibody_plant.h"
1213
#include "drake/solvers/binding.h"
1314
#include "drake/solvers/mathematical_program.h"
1415
#include "drake/solvers/mathematical_program_result.h"
@@ -204,6 +205,38 @@ class KinematicTrajectoryOptimization {
204205
const Eigen::Ref<const Eigen::VectorXd>& lb,
205206
const Eigen::Ref<const Eigen::VectorXd>& ub);
206207

208+
/** Adds generic (nonlinear) constraints to enforce the effort limits defined
209+
in the plant at a sequence of normalized times, `s`:
210+
@verbatim
211+
B lb ≤ M(q)v̇ + C(q, v)v - τ_g(q) - τ_app ≤ B ub
212+
@endverbatim
213+
where q, v, and v̇ are evaluated at s. B is the plant's actuation matrix, and
214+
M, C, τ_g, and τ_app are the plant's mass matrix, Coriolis force, gravity,
215+
and applied force, respectively. `ub` and `lb` are the upper and lower effort
216+
bounds, respectively; if they are not provided then
217+
plant.GetEffortLowerLimits() and plant.GetEffortUpperLimits() are used.
218+
219+
Pass `plant_context` if you have non-default parameters in the context. Note
220+
that there are no lifetime requirements on `plant` nsor `plant_context`.
221+
222+
Note that the convex hull property of the B-splines is not guaranteed to hold
223+
here -- effort limits maybe be violated away from the normalized times `s`.
224+
225+
@pre plant.is_finalized()
226+
@pre plant.num_positions() == num_positions()
227+
@pre s[i] ∈ [0, 1] for all i
228+
@pre B lb ≤ B ub
229+
230+
@returns A vector of bindings with one effort limit constraint for each `s`.
231+
*/
232+
std::vector<solvers::Binding<solvers::Constraint>>
233+
AddEffortBoundsAtNormalizedTimes(
234+
const multibody::MultibodyPlant<double>& plant,
235+
const Eigen::Ref<const Eigen::VectorXd>& s,
236+
const std::optional<Eigen::Ref<const Eigen::VectorXd>>& lb = std::nullopt,
237+
const std::optional<Eigen::Ref<const Eigen::VectorXd>>& ub = std::nullopt,
238+
const systems::Context<double>* plant_context = nullptr);
239+
207240
/** Adds a linear cost on the duration of the trajectory. */
208241
solvers::Binding<solvers::LinearCost> AddDurationCost(double weight = 1.0);
209242

@@ -234,6 +267,9 @@ class KinematicTrajectoryOptimization {
234267

235268
/* TODO(russt):
236269
- Support additional (non-convex) costs/constraints on q(t) directly.
270+
- AddMultibodyPlantConstraints which adds joint, velocity, acceleration, and
271+
effort limits + multibody constraints. Presumably we can't have quaternions
272+
in a fully-actuated system.
237273
*/
238274

239275
private:

planning/trajectory_optimization/test/kinematic_trajectory_optimization_test.cc

Lines changed: 102 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,11 +10,13 @@
1010
#include "drake/common/test_utilities/eigen_matrix_compare.h"
1111
#include "drake/common/text_logging.h"
1212
#include "drake/math/matrix_util.h"
13+
#include "drake/multibody/benchmarks/pendulum/make_pendulum_plant.h"
1314
#include "drake/solvers/ipopt_solver.h"
1415
#include "drake/solvers/osqp_solver.h"
1516
#include "drake/solvers/solve.h"
1617

1718
using Eigen::MatrixXd;
19+
using Eigen::Vector2d;
1820
using Eigen::Vector3d;
1921
using Eigen::VectorXd;
2022
using std::nullopt;
@@ -359,6 +361,106 @@ TEST_F(KinematicTrajectoryOptimizationTest, AddJerkBounds) {
359361
}
360362
}
361363

364+
GTEST_TEST(KinematicTrajectoryOptimizationMultibodyTest,
365+
AddEffortBoundsAtNormalizedTimes) {
366+
multibody::benchmarks::pendulum::PendulumParameters parameters;
367+
auto plant = multibody::benchmarks::pendulum::MakePendulumPlant(parameters);
368+
const int num_control_points = 10;
369+
KinematicTrajectoryOptimization trajopt(plant->num_positions(),
370+
num_control_points);
371+
372+
const Vector1d tau_lb(-1.0), tau_ub(1.0);
373+
auto bindings = trajopt.AddEffortBoundsAtNormalizedTimes(*plant, Vector1d(0),
374+
tau_lb, tau_ub);
375+
EXPECT_EQ(bindings.size(), 1);
376+
EXPECT_EQ(bindings[0].evaluator()->num_constraints(), 1);
377+
EXPECT_EQ(bindings[0].evaluator()->lower_bound(), tau_lb);
378+
EXPECT_EQ(bindings[0].evaluator()->upper_bound(), tau_ub);
379+
380+
// Use a small traj opt to compute the (normalized) control points.
381+
auto MakeNormalizedTrajectory = [&](double duration, double q0, double v0,
382+
double vdot0) {
383+
KinematicTrajectoryOptimization kto(plant->num_positions(),
384+
num_control_points);
385+
// The spline should be normalized (duration = 1).
386+
kto.AddDurationConstraint(1, 1);
387+
// We have to undo the time scaling.
388+
v0 *= duration;
389+
vdot0 *= duration * duration;
390+
kto.AddPathPositionConstraint(Vector1d(q0), Vector1d(q0), /* s= */ 0);
391+
kto.AddPathVelocityConstraint(Vector1d(v0), Vector1d(v0), /* s= */ 0);
392+
kto.AddPathAccelerationConstraint(Vector1d(vdot0), Vector1d(vdot0),
393+
/* s= */ 0);
394+
auto result = Solve(kto.prog());
395+
return kto.ReconstructTrajectory(result);
396+
};
397+
398+
// Variables for the constraint are [duration, control_points]
399+
VectorXd x(1 + num_control_points);
400+
const double duration = 4.23;
401+
auto vdot_ulimit = [&](double q, double v) {
402+
// ml^2vdot + b*v + mglsin(q) <= tau_ub
403+
return (tau_ub[0] - parameters.damping() * v -
404+
parameters.m() * parameters.g() * parameters.l() * std::sin(q)) /
405+
parameters.m() / parameters.l() / parameters.l();
406+
};
407+
408+
// Initial acceleration below the limit.
409+
double q0 = 0, v0 = 0;
410+
auto traj = MakeNormalizedTrajectory(duration, q0, v0,
411+
/* vdot0 = */ 0.9 * vdot_ulimit(q0, v0));
412+
x << duration,
413+
math::StdVectorToEigen<double>(traj.control_points()).row(0).transpose();
414+
EXPECT_TRUE(bindings[0].evaluator()->CheckSatisfied(x));
415+
416+
// Initial acceleration above the limit.
417+
traj = MakeNormalizedTrajectory(duration, q0, v0,
418+
/* vdot0 = */ 1.1 * vdot_ulimit(q0, v0));
419+
x << duration,
420+
math::StdVectorToEigen<double>(traj.control_points()).row(0).transpose();
421+
EXPECT_FALSE(bindings[0].evaluator()->CheckSatisfied(x));
422+
423+
// Confirm that the damping is also considered by setting a (large) non-zero
424+
// velocity.
425+
v0 = -100;
426+
traj = MakeNormalizedTrajectory(duration, q0, v0,
427+
/* vdot0 = */ 0.9 * vdot_ulimit(q0, v0));
428+
x << duration,
429+
math::StdVectorToEigen<double>(traj.control_points()).row(0).transpose();
430+
EXPECT_TRUE(bindings[0].evaluator()->CheckSatisfied(x));
431+
traj = MakeNormalizedTrajectory(duration, q0, v0,
432+
/* vdot0 = */ 1.1 * vdot_ulimit(q0, v0));
433+
x << duration,
434+
math::StdVectorToEigen<double>(traj.control_points()).row(0).transpose();
435+
EXPECT_FALSE(bindings[0].evaluator()->CheckSatisfied(x));
436+
437+
// Set the damping to zero in the context.
438+
auto context = plant->CreateDefaultContext();
439+
plant->get_joint(multibody::JointIndex(0))
440+
.SetDampingVector(context.get(), Vector1d::Zero());
441+
bindings = trajopt.AddEffortBoundsAtNormalizedTimes(
442+
*plant, Vector1d(0.5), tau_lb, tau_ub, context.get());
443+
EXPECT_EQ(bindings.size(), 1);
444+
EXPECT_EQ(bindings[0].evaluator()->num_constraints(), 1);
445+
EXPECT_EQ(bindings[0].evaluator()->lower_bound(), tau_lb);
446+
EXPECT_EQ(bindings[0].evaluator()->upper_bound(), tau_ub);
447+
// The torque that tripped do to high damping is now satisfied.
448+
EXPECT_TRUE(bindings[0].evaluator()->CheckSatisfied(x));
449+
450+
// Multiple normalized times.
451+
bindings = trajopt.AddEffortBoundsAtNormalizedTimes(
452+
*plant, Vector2d(0.5, 1.0), tau_lb, tau_ub);
453+
EXPECT_EQ(bindings.size(), 2);
454+
455+
// Default bounds.
456+
bindings = trajopt.AddEffortBoundsAtNormalizedTimes(*plant, Vector1d(0.25));
457+
EXPECT_EQ(bindings.size(), 1);
458+
EXPECT_TRUE(CompareMatrices(bindings[0].evaluator()->lower_bound(),
459+
plant->GetEffortLowerLimits(), 1e-14));
460+
EXPECT_TRUE(CompareMatrices(bindings[0].evaluator()->upper_bound(),
461+
plant->GetEffortUpperLimits(), 1e-14));
462+
}
463+
362464
TEST_F(KinematicTrajectoryOptimizationTest, AddDurationCost) {
363465
EXPECT_EQ(trajopt_.prog().linear_costs().size(), 0);
364466
auto binding = trajopt_.AddDurationCost(1.0);

0 commit comments

Comments
 (0)