@@ -28,6 +28,8 @@ using math::EigenToStdVector;
28
28
using math::ExtractValue;
29
29
using math::InitializeAutoDiff;
30
30
using math::StdVectorToEigen;
31
+ using multibody::MultibodyForces;
32
+ using multibody::MultibodyPlant;
31
33
using solvers::Binding;
32
34
using solvers::BoundingBoxConstraint;
33
35
using solvers::Constraint;
@@ -187,12 +189,82 @@ class DerivativeConstraint : public Constraint {
187
189
const int derivative_order_;
188
190
};
189
191
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
+
190
261
// 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.
196
268
std::pair<SparseMatrix<double >, VectorXDecisionVariable> RewriteXa (
197
269
const MatrixXDecisionVariable& X, const VectorXd& a) {
198
270
const int num_nonzeros = (a.array () != 0 ).count ();
@@ -497,6 +569,48 @@ std::vector<Binding<Constraint>> KinematicTrajectoryOptimization::AddJerkBounds(
497
569
return bindings;
498
570
}
499
571
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
+
500
614
Binding<LinearCost> KinematicTrajectoryOptimization::AddDurationCost (
501
615
double weight) {
502
616
auto binding = prog_.AddLinearCost (weight * duration_);
0 commit comments