forked from RobotLocomotion/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
/
symbolic_expression_cell.cc
2351 lines (2039 loc) · 75.8 KB
/
symbolic_expression_cell.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
#define DRAKE_COMMON_SYMBOLIC_DETAIL_HEADER
#include "drake/common/symbolic_expression_cell.h"
#undef DRAKE_COMMON_SYMBOLIC_DETAIL_HEADER
#include <algorithm>
#include <cmath>
#include <functional>
#include <iomanip>
#include <limits>
#include <map>
#include <memory>
#include <numeric>
#include <ostream>
#include <sstream>
#include <stdexcept>
#include <string>
#include <utility>
#include "drake/common/drake_assert.h"
#include "drake/common/hash.h"
#include "drake/common/symbolic.h"
namespace drake {
namespace symbolic {
using std::accumulate;
using std::all_of;
using std::domain_error;
using std::endl;
using std::equal;
using std::lexicographical_compare;
using std::make_shared;
using std::map;
using std::numeric_limits;
using std::ostream;
using std::ostringstream;
using std::pair;
using std::runtime_error;
using std::shared_ptr;
using std::static_pointer_cast;
using std::string;
using std::vector;
bool is_integer(const double v) {
// v should be in [int_min, int_max].
if (!((numeric_limits<int>::lowest() <= v) &&
(v <= numeric_limits<int>::max()))) {
return false;
}
double intpart; // dummy variable
return modf(v, &intpart) == 0.0;
}
bool is_positive_integer(const double v) { return (v > 0) && is_integer(v); }
bool is_non_negative_integer(const double v) {
return (v >= 0) && is_integer(v);
}
namespace {
// Determines if the summation represented by term_to_coeff_map is
// polynomial-convertible or not. This function is used in the
// constructor of ExpressionAdd.
bool determine_polynomial(
const std::map<Expression, double>& term_to_coeff_map) {
return all_of(term_to_coeff_map.begin(), term_to_coeff_map.end(),
[](const pair<const Expression, double>& p) {
return p.first.is_polynomial();
});
}
// Determines if the product represented by term_to_coeff_map is
// polynomial-convertible or not. This function is used in the
// constructor of ExpressionMul.
bool determine_polynomial(
const std::map<Expression, Expression>& base_to_exponent_map) {
return all_of(base_to_exponent_map.begin(), base_to_exponent_map.end(),
[](const pair<const Expression, Expression>& p) {
// For each base^exponent, it has to satisfy the following
// conditions:
// - base is polynomial-convertible.
// - exponent is a non-negative integer.
const Expression& base{p.first};
const Expression& exponent{p.second};
if (!base.is_polynomial() || !is_constant(exponent)) {
return false;
}
const double e{get_constant_value(exponent)};
return is_non_negative_integer(e);
});
}
// Determines if pow(base, exponent) is polynomial-convertible or not. This
// function is used in constructor of ExpressionPow.
bool determine_polynomial(const Expression& base, const Expression& exponent) {
// base ^ exponent is polynomial-convertible if the following hold:
// - base is polynomial-convertible.
// - exponent is a non-negative integer.
if (!(base.is_polynomial() && is_constant(exponent))) {
return false;
}
const double e{get_constant_value(exponent)};
return is_non_negative_integer(e);
}
Expression ExpandMultiplication(const Expression& e1, const Expression& e2,
const Expression& e3);
// Helper function expanding (e1 * e2). It assumes that both of e1 and e2 are
// already expanded.
Expression ExpandMultiplication(const Expression& e1, const Expression& e2) {
// Precondition: e1 and e2 are already expanded.
DRAKE_ASSERT(e1.EqualTo(e1.Expand()));
DRAKE_ASSERT(e2.EqualTo(e2.Expand()));
if (is_addition(e1)) {
// (c0 + c1 * e_{1,1} + ... + c_n * e_{1, n}) * e2
// = c0 * e2 + c1 * e_{1,1} * e2 + ... + c_n * e_{1,n} * e2
const double c0{get_constant_in_addition(e1)};
const map<Expression, double>& m1{get_expr_to_coeff_map_in_addition(e1)};
ExpressionAddFactory fac;
fac.AddExpression(ExpandMultiplication(c0, e2));
for (const pair<const Expression, double>& p : m1) {
fac.AddExpression(ExpandMultiplication(p.second, p.first, e2));
}
return fac.GetExpression();
}
if (is_addition(e2)) {
// e1 * (c0 + c1 * e_{2,1} + ... + c_n * e_{2, n})
// = e1 * c0 + e1 * c1 * e_{2,1} + ... + e1 * c_n * e_{2,n}
const double c0{get_constant_in_addition(e2)};
const map<Expression, double>& m1{get_expr_to_coeff_map_in_addition(e2)};
ExpressionAddFactory fac;
fac.AddExpression(ExpandMultiplication(e1, c0));
for (const pair<const Expression, double>& p : m1) {
fac.AddExpression(ExpandMultiplication(e1, p.second, p.first));
}
return fac.GetExpression();
}
return e1 * e2;
}
Expression ExpandMultiplication(const Expression& e1, const Expression& e2,
const Expression& e3) {
return ExpandMultiplication(ExpandMultiplication(e1, e2), e3);
}
// Helper function expanding pow(base, n). It assumes that base is expanded.
Expression ExpandPow(const Expression& base, const int n) {
// Precondition: base is already expanded.
DRAKE_ASSERT(base.EqualTo(base.Expand()));
DRAKE_ASSERT(n >= 1);
if (n == 1) {
return base;
}
const Expression pow_half{ExpandPow(base, n / 2)};
if (n % 2 == 1) {
// pow(base, n) = base * pow(base, n / 2) * pow(base, n / 2)
return ExpandMultiplication(base, pow_half, pow_half);
}
// pow(base, n) = pow(base, n / 2) * pow(base, n / 2)
return ExpandMultiplication(pow_half, pow_half);
}
// Helper function expanding pow(base, exponent). It assumes that both of base
// and exponent are already expanded.
Expression ExpandPow(const Expression& base, const Expression& exponent) {
// Precondition: base and exponent are already expanded.
DRAKE_ASSERT(base.EqualTo(base.Expand()));
DRAKE_ASSERT(exponent.EqualTo(exponent.Expand()));
if (is_multiplication(base)) {
// pow(c * ∏ᵢ pow(e₁ᵢ, e₂ᵢ), exponent)
// = pow(c, exponent) * ∏ᵢ pow(e₁ᵢ, e₂ᵢ * exponent)
const double c{get_constant_in_multiplication(base)};
auto map = get_base_to_exponent_map_in_multiplication(base);
for (pair<const Expression, Expression>& p : map) {
p.second = p.second * exponent;
}
return pow(c, exponent) * ExpressionMulFactory{1.0, map}.GetExpression();
}
// Expand if
// 1) base is an addition expression and
// 2) exponent is a positive integer.
if (!is_addition(base) || !is_constant(exponent)) {
return pow(base, exponent);
}
const double e{get_constant_value(exponent)};
if (e <= 0 || !is_integer(e)) {
return pow(base, exponent);
}
const int n{static_cast<int>(e)};
return ExpandPow(base, n);
}
} // anonymous namespace
ExpressionCell::ExpressionCell(const ExpressionKind k, const bool is_poly)
: kind_{k}, is_polynomial_{is_poly} {}
UnaryExpressionCell::UnaryExpressionCell(const ExpressionKind k,
const Expression& e,
const bool is_poly)
: ExpressionCell{k, is_poly}, e_{e} {}
void UnaryExpressionCell::HashAppendDetail(DelegatingHasher* hasher) const {
DRAKE_ASSERT(hasher);
using drake::hash_append;
hash_append(*hasher, e_);
}
Variables UnaryExpressionCell::GetVariables() const {
return e_.GetVariables();
}
bool UnaryExpressionCell::EqualTo(const ExpressionCell& e) const {
// Expression::EqualTo guarantees the following assertion.
DRAKE_ASSERT(get_kind() == e.get_kind());
const auto& unary_e = static_cast<const UnaryExpressionCell&>(e);
return e_.EqualTo(unary_e.e_);
}
bool UnaryExpressionCell::Less(const ExpressionCell& e) const {
// Expression::Less guarantees the following assertion.
DRAKE_ASSERT(get_kind() == e.get_kind());
const auto& unary_e = static_cast<const UnaryExpressionCell&>(e);
return e_.Less(unary_e.e_);
}
double UnaryExpressionCell::Evaluate(const Environment& env) const {
const double v{e_.Evaluate(env)};
return DoEvaluate(v);
}
BinaryExpressionCell::BinaryExpressionCell(const ExpressionKind k,
const Expression& e1,
const Expression& e2,
const bool is_poly)
: ExpressionCell{k, is_poly}, e1_{e1}, e2_{e2} {}
void BinaryExpressionCell::HashAppendDetail(DelegatingHasher* hasher) const {
DRAKE_ASSERT(hasher);
using drake::hash_append;
hash_append(*hasher, e1_);
hash_append(*hasher, e2_);
}
Variables BinaryExpressionCell::GetVariables() const {
Variables ret{e1_.GetVariables()};
ret.insert(e2_.GetVariables());
return ret;
}
bool BinaryExpressionCell::EqualTo(const ExpressionCell& e) const {
// Expression::EqualTo guarantees the following assertion.
DRAKE_ASSERT(get_kind() == e.get_kind());
const auto& binary_e = static_cast<const BinaryExpressionCell&>(e);
return e1_.EqualTo(binary_e.e1_) && e2_.EqualTo(binary_e.e2_);
}
bool BinaryExpressionCell::Less(const ExpressionCell& e) const {
// Expression::Less guarantees the following assertion.
DRAKE_ASSERT(get_kind() == e.get_kind());
const auto& binary_e = static_cast<const BinaryExpressionCell&>(e);
if (e1_.Less(binary_e.e1_)) {
return true;
}
if (binary_e.e1_.Less(e1_)) {
return false;
}
// e1_ equals to binary_e.e1_, compare e2_ and binary_e.e2_
return e2_.Less(binary_e.e2_);
}
double BinaryExpressionCell::Evaluate(const Environment& env) const {
const double v1{e1_.Evaluate(env)};
const double v2{e2_.Evaluate(env)};
return DoEvaluate(v1, v2);
}
ExpressionVar::ExpressionVar(const Variable& v)
: ExpressionCell{ExpressionKind::Var, true}, var_{v} {
// Dummy symbolic variable (ID = 0) should not be used in constructing
// symbolic expressions.
DRAKE_DEMAND(!var_.is_dummy());
// Boolean symbolic variable should not be used in constructing symbolic
// expressions.
DRAKE_DEMAND(var_.get_type() != Variable::Type::BOOLEAN);
}
void ExpressionVar::HashAppendDetail(DelegatingHasher* hasher) const {
DRAKE_ASSERT(hasher);
using drake::hash_append;
hash_append(*hasher, var_);
}
Variables ExpressionVar::GetVariables() const { return {get_variable()}; }
bool ExpressionVar::EqualTo(const ExpressionCell& e) const {
// Expression::EqualTo guarantees the following assertion.
DRAKE_ASSERT(get_kind() == e.get_kind());
return var_.equal_to(static_cast<const ExpressionVar&>(e).var_);
}
bool ExpressionVar::Less(const ExpressionCell& e) const {
// Expression::Less guarantees the following assertion.
DRAKE_ASSERT(get_kind() == e.get_kind());
// Note the below is using the overloaded operator< between ExpressionVar
// which is based on variable IDs.
return var_.less(static_cast<const ExpressionVar&>(e).var_);
}
Polynomiald ExpressionVar::ToPolynomial() const {
return Polynomiald(1.0, var_.get_id());
}
double ExpressionVar::Evaluate(const Environment& env) const {
Environment::const_iterator const it{env.find(var_)};
if (it != env.cend()) {
DRAKE_ASSERT(!std::isnan(it->second));
return it->second;
}
ostringstream oss;
oss << "The following environment does not have an entry for the "
"variable "
<< var_ << endl;
oss << env << endl;
throw runtime_error{oss.str()};
}
Expression ExpressionVar::Expand() const { return Expression{var_}; }
Expression ExpressionVar::Substitute(const Substitution& s) const {
const Substitution::const_iterator it{s.find(var_)};
if (it != s.end()) {
return it->second;
}
return Expression{var_};
}
Expression ExpressionVar::Differentiate(const Variable& x) const {
if (x.equal_to(var_)) {
return Expression::One();
}
return Expression::Zero();
}
ostream& ExpressionVar::Display(ostream& os) const { return os << var_; }
ExpressionConstant::ExpressionConstant(const double v)
: ExpressionCell{ExpressionKind::Constant, true}, v_{v} {
DRAKE_ASSERT(!std::isnan(v));
}
void ExpressionConstant::HashAppendDetail(DelegatingHasher* hasher) const {
using drake::hash_append;
hash_append(*hasher, v_);
}
Variables ExpressionConstant::GetVariables() const { return Variables{}; }
bool ExpressionConstant::EqualTo(const ExpressionCell& e) const {
// Expression::EqualTo guarantees the following assertion.
DRAKE_ASSERT(get_kind() == e.get_kind());
return v_ == static_cast<const ExpressionConstant&>(e).v_;
}
bool ExpressionConstant::Less(const ExpressionCell& e) const {
// Expression::Less guarantees the following assertion.
DRAKE_ASSERT(get_kind() == e.get_kind());
return v_ < static_cast<const ExpressionConstant&>(e).v_;
}
Polynomiald ExpressionConstant::ToPolynomial() const { return Polynomiald(v_); }
double ExpressionConstant::Evaluate(const Environment&) const {
DRAKE_DEMAND(!std::isnan(v_));
return v_;
}
Expression ExpressionConstant::Expand() const { return Expression{v_}; }
Expression ExpressionConstant::Substitute(const Substitution&) const {
DRAKE_DEMAND(!std::isnan(v_));
return Expression{v_};
}
Expression ExpressionConstant::Differentiate(const Variable&) const {
return Expression::Zero();
}
ostream& ExpressionConstant::Display(ostream& os) const { return os << v_; }
ExpressionNaN::ExpressionNaN() : ExpressionCell{ExpressionKind::NaN, false} {}
void ExpressionNaN::HashAppendDetail(DelegatingHasher*) const {}
Variables ExpressionNaN::GetVariables() const { return Variables{}; }
bool ExpressionNaN::EqualTo(const ExpressionCell& e) const {
// Expression::EqualTo guarantees the following assertion.
DRAKE_ASSERT(get_kind() == e.get_kind());
return true;
}
bool ExpressionNaN::Less(const ExpressionCell& e) const {
// Expression::Less guarantees the following assertion.
DRAKE_ASSERT(get_kind() == e.get_kind());
return false;
}
Polynomiald ExpressionNaN::ToPolynomial() const {
throw runtime_error("NaN is detected while converting to Polynomial.");
}
double ExpressionNaN::Evaluate(const Environment&) const {
throw runtime_error("NaN is detected during Symbolic computation.");
}
Expression ExpressionNaN::Expand() const {
throw runtime_error("NaN is detected during expansion.");
}
Expression ExpressionNaN::Substitute(const Substitution&) const {
throw runtime_error("NaN is detected during substitution.");
}
Expression ExpressionNaN::Differentiate(const Variable&) const {
throw runtime_error("NaN is detected during differentiation.");
}
ostream& ExpressionNaN::Display(ostream& os) const { return os << "NaN"; }
ExpressionAdd::ExpressionAdd(const double constant,
const map<Expression, double>& expr_to_coeff_map)
: ExpressionCell{ExpressionKind::Add,
determine_polynomial(expr_to_coeff_map)},
constant_(constant),
expr_to_coeff_map_(expr_to_coeff_map) {
DRAKE_ASSERT(!expr_to_coeff_map_.empty());
}
void ExpressionAdd::HashAppendDetail(DelegatingHasher* hasher) const {
using drake::hash_append;
hash_append(*hasher, constant_);
hash_append(*hasher, expr_to_coeff_map_);
}
Variables ExpressionAdd::GetVariables() const {
Variables ret{};
for (const auto& p : expr_to_coeff_map_) {
ret.insert(p.first.GetVariables());
}
return ret;
}
bool ExpressionAdd::EqualTo(const ExpressionCell& e) const {
// Expression::EqualTo guarantees the following assertion.
DRAKE_ASSERT(get_kind() == e.get_kind());
const ExpressionAdd& add_e{static_cast<const ExpressionAdd&>(e)};
// Compare constant.
if (constant_ != add_e.constant_) {
return false;
}
return equal(expr_to_coeff_map_.cbegin(), expr_to_coeff_map_.cend(),
add_e.expr_to_coeff_map_.cbegin(),
add_e.expr_to_coeff_map_.cend(),
[](const pair<const Expression, double>& p1,
const pair<const Expression, double>& p2) {
return p1.first.EqualTo(p2.first) && p1.second == p2.second;
});
}
bool ExpressionAdd::Less(const ExpressionCell& e) const {
// Expression::Less guarantees the following assertion.
DRAKE_ASSERT(get_kind() == e.get_kind());
const ExpressionAdd& add_e{static_cast<const ExpressionAdd&>(e)};
// Compare the constants.
if (constant_ < add_e.constant_) {
return true;
}
if (add_e.constant_ < constant_) {
return false;
}
// Compare the two maps.
return lexicographical_compare(
expr_to_coeff_map_.cbegin(), expr_to_coeff_map_.cend(),
add_e.expr_to_coeff_map_.cbegin(), add_e.expr_to_coeff_map_.cend(),
[](const pair<const Expression, double>& p1,
const pair<const Expression, double>& p2) {
const Expression& term1{p1.first};
const Expression& term2{p2.first};
if (term1.Less(term2)) {
return true;
}
if (term2.Less(term1)) {
return false;
}
const double coeff1{p1.second};
const double coeff2{p2.second};
return coeff1 < coeff2;
});
}
Polynomiald ExpressionAdd::ToPolynomial() const {
DRAKE_ASSERT(is_polynomial());
return accumulate(expr_to_coeff_map_.begin(), expr_to_coeff_map_.end(),
Polynomiald(constant_),
[](const Polynomiald& polynomial,
const pair<const Expression, double>& p) {
return polynomial + p.first.ToPolynomial() * p.second;
});
}
double ExpressionAdd::Evaluate(const Environment& env) const {
return accumulate(
expr_to_coeff_map_.begin(), expr_to_coeff_map_.end(), constant_,
[&env](const double init, const pair<const Expression, double>& p) {
return init + p.first.Evaluate(env) * p.second;
});
}
Expression ExpressionAdd::Expand() const {
// (c0 + c1 * e_1 + ... + c_n * e_n).Expand()
// = c0 + c1 * e_1.Expand() + ... + c_n * e_n.Expand()
ExpressionAddFactory fac{constant_, {}};
for (const pair<const Expression, double>& p : expr_to_coeff_map_) {
fac.AddExpression(ExpandMultiplication(p.first.Expand(), p.second));
}
return fac.GetExpression();
}
Expression ExpressionAdd::Substitute(const Substitution& s) const {
return accumulate(
expr_to_coeff_map_.begin(), expr_to_coeff_map_.end(),
Expression{constant_},
[&s](const Expression& init, const pair<const Expression, double>& p) {
return init + p.first.Substitute(s) * p.second;
});
}
Expression ExpressionAdd::Differentiate(const Variable& x) const {
// ∂/∂x (c_0 + c_1 * f_1 + ... + c_n * f_n)
// = (∂/∂x c_0) + (∂/∂x c_1 * f_1) + ... + (∂/∂x c_n * f_n)
// = 0.0 + c_1 * (∂/∂x f_1) + ... + c_n * (∂/∂x f_n)
ExpressionAddFactory fac;
for (const pair<const Expression, double>& p : expr_to_coeff_map_) {
fac.AddExpression(p.second * p.first.Differentiate(x));
}
return fac.GetExpression();
}
ostream& ExpressionAdd::Display(ostream& os) const {
DRAKE_ASSERT(!expr_to_coeff_map_.empty());
bool print_plus{false};
os << "(";
if (constant_ != 0.0) {
os << constant_;
print_plus = true;
}
for (auto& p : expr_to_coeff_map_) {
DisplayTerm(os, print_plus, p.second, p.first);
print_plus = true;
}
os << ")";
return os;
}
ostream& ExpressionAdd::DisplayTerm(ostream& os, const bool print_plus,
const double coeff,
const Expression& term) const {
DRAKE_ASSERT(coeff != 0.0);
if (coeff > 0.0) {
if (print_plus) {
os << " + ";
}
// Do not print "1 * t"
if (coeff != 1.0) {
os << coeff << " * ";
}
} else {
// Instead of printing "+ (- E)", just print "- E".
os << " - ";
if (coeff != -1.0) {
os << (-coeff) << " * ";
}
}
os << term;
return os;
}
ExpressionAddFactory::ExpressionAddFactory(
const double constant, map<Expression, double> expr_to_coeff_map)
: constant_{constant}, expr_to_coeff_map_{std::move(expr_to_coeff_map)} {}
ExpressionAddFactory::ExpressionAddFactory(
const std::shared_ptr<const ExpressionAdd>& ptr)
: ExpressionAddFactory{ptr->get_constant(), ptr->get_expr_to_coeff_map()} {}
void ExpressionAddFactory::AddExpression(const Expression& e) {
if (is_constant(e)) {
const double v{get_constant_value(e)};
return AddConstant(v);
}
if (is_addition(e)) {
// Flattening
return Add(to_addition(e));
}
if (is_multiplication(e)) {
const double constant{get_constant_in_multiplication(e)};
DRAKE_ASSERT(constant != 0.0);
if (constant != 1.0) {
// Instead of adding (1.0 * (constant * b1^t1 ... bn^tn)),
// add (constant, 1.0 * b1^t1 ... bn^tn).
return AddTerm(constant,
ExpressionMulFactory(
1.0, get_base_to_exponent_map_in_multiplication(e))
.GetExpression());
}
}
return AddTerm(1.0, e);
}
void ExpressionAddFactory::Add(const shared_ptr<const ExpressionAdd>& ptr) {
AddConstant(ptr->get_constant());
AddMap(ptr->get_expr_to_coeff_map());
}
ExpressionAddFactory& ExpressionAddFactory::operator=(
const std::shared_ptr<const ExpressionAdd>& ptr) {
constant_ = ptr->get_constant();
expr_to_coeff_map_ = ptr->get_expr_to_coeff_map();
return *this;
}
ExpressionAddFactory& ExpressionAddFactory::Negate() {
constant_ = -constant_;
for (auto& p : expr_to_coeff_map_) {
p.second = -p.second;
}
return *this;
}
Expression ExpressionAddFactory::GetExpression() const {
if (expr_to_coeff_map_.empty()) {
return Expression{constant_};
}
if (constant_ == 0.0 && expr_to_coeff_map_.size() == 1u) {
// 0.0 + c1 * t1 -> c1 * t1
const auto it(expr_to_coeff_map_.cbegin());
return it->first * it->second;
}
return Expression{
make_shared<const ExpressionAdd>(constant_, expr_to_coeff_map_)};
}
void ExpressionAddFactory::AddConstant(const double constant) {
constant_ += constant;
}
void ExpressionAddFactory::AddTerm(const double coeff, const Expression& term) {
DRAKE_ASSERT(!is_constant(term));
DRAKE_ASSERT(coeff != 0.0);
const auto it(expr_to_coeff_map_.find(term));
if (it != expr_to_coeff_map_.end()) {
// Case1: term is already in the map
double& this_coeff{it->second};
this_coeff += coeff;
if (this_coeff == 0.0) {
// If the coefficient becomes zero, remove the entry.
// TODO(soonho-tri): The following operation is not sound since it cancels
// `term` which might contain 0/0 problems.
expr_to_coeff_map_.erase(it);
}
} else {
// Case2: term is not found in expr_to_coeff_map_.
// Add the entry (term, coeff).
expr_to_coeff_map_.emplace(term, coeff);
}
}
void ExpressionAddFactory::AddMap(
const map<Expression, double>& expr_to_coeff_map) {
for (const auto& p : expr_to_coeff_map) {
AddTerm(p.second, p.first);
}
}
ExpressionMul::ExpressionMul(
const double constant,
const map<Expression, Expression>& base_to_exponent_map)
: ExpressionCell{ExpressionKind::Mul,
determine_polynomial(base_to_exponent_map)},
constant_(constant),
base_to_exponent_map_(base_to_exponent_map) {
DRAKE_ASSERT(!base_to_exponent_map_.empty());
}
void ExpressionMul::HashAppendDetail(DelegatingHasher* hasher) const {
using drake::hash_append;
hash_append(*hasher, constant_);
hash_append(*hasher, base_to_exponent_map_);
}
Variables ExpressionMul::GetVariables() const {
Variables ret{};
for (const auto& p : base_to_exponent_map_) {
ret.insert(p.first.GetVariables());
ret.insert(p.second.GetVariables());
}
return ret;
}
bool ExpressionMul::EqualTo(const ExpressionCell& e) const {
// Expression::EqualTo guarantees the following assertion.
DRAKE_ASSERT(get_kind() == e.get_kind());
const ExpressionMul& mul_e{static_cast<const ExpressionMul&>(e)};
// Compare constant.
if (constant_ != mul_e.constant_) {
return false;
}
// Check each (term, coeff) pairs in two maps.
return equal(
base_to_exponent_map_.cbegin(), base_to_exponent_map_.cend(),
mul_e.base_to_exponent_map_.cbegin(), mul_e.base_to_exponent_map_.cend(),
[](const pair<const Expression, Expression>& p1,
const pair<const Expression, Expression>& p2) {
return p1.first.EqualTo(p2.first) && p1.second.EqualTo(p2.second);
});
}
bool ExpressionMul::Less(const ExpressionCell& e) const {
// Expression::Less guarantees the following assertion.
DRAKE_ASSERT(get_kind() == e.get_kind());
const ExpressionMul& mul_e{static_cast<const ExpressionMul&>(e)};
// Compare the constants.
if (constant_ < mul_e.constant_) {
return true;
}
if (mul_e.constant_ < constant_) {
return false;
}
// Compare the two maps.
return lexicographical_compare(
base_to_exponent_map_.cbegin(), base_to_exponent_map_.cend(),
mul_e.base_to_exponent_map_.cbegin(), mul_e.base_to_exponent_map_.cend(),
[](const pair<const Expression, Expression>& p1,
const pair<const Expression, Expression>& p2) {
const Expression& base1{p1.first};
const Expression& base2{p2.first};
if (base1.Less(base2)) {
return true;
}
if (base2.Less(base1)) {
return false;
}
const Expression& exp1{p1.second};
const Expression& exp2{p2.second};
return exp1.Less(exp2);
});
}
Polynomiald ExpressionMul::ToPolynomial() const {
DRAKE_ASSERT(is_polynomial());
return accumulate(
base_to_exponent_map_.begin(), base_to_exponent_map_.end(),
Polynomiald{constant_},
[](const Polynomiald& polynomial,
const pair<const Expression, Expression>& p) {
const Expression& base{p.first};
const Expression& exponent{p.second};
DRAKE_ASSERT(base.is_polynomial());
DRAKE_ASSERT(is_constant(exponent));
return polynomial * pow(base.ToPolynomial(),
static_cast<int>(get_constant_value(exponent)));
});
}
double ExpressionMul::Evaluate(const Environment& env) const {
return accumulate(
base_to_exponent_map_.begin(), base_to_exponent_map_.end(), constant_,
[&env](const double init, const pair<const Expression, Expression>& p) {
return init * std::pow(p.first.Evaluate(env), p.second.Evaluate(env));
});
}
Expression ExpressionMul::Expand() const {
// (c * ∏ᵢ pow(bᵢ, eᵢ)).Expand()
// = c * ExpandMultiplication(∏ ExpandPow(bᵢ.Expand(), eᵢ.Expand()))
return accumulate(
base_to_exponent_map_.begin(), base_to_exponent_map_.end(),
Expression{constant_},
[](const Expression& init, const pair<const Expression, Expression>& p) {
return ExpandMultiplication(
init, ExpandPow(p.first.Expand(), p.second.Expand()));
});
}
Expression ExpressionMul::Substitute(const Substitution& s) const {
return accumulate(base_to_exponent_map_.begin(), base_to_exponent_map_.end(),
Expression{constant_},
[&s](const Expression& init,
const pair<const Expression, Expression>& p) {
return init *
pow(p.first.Substitute(s), p.second.Substitute(s));
});
}
// Computes ∂/∂x pow(f, g).
Expression DifferentiatePow(const Expression& f, const Expression& g,
const Variable& x) {
if (is_constant(g)) {
const Expression& n{g}; // alias n = g
// Special case where exponent is a constant:
// ∂/∂x pow(f, n) = n * pow(f, n - 1) * ∂/∂x f
return n * pow(f, n - 1) * f.Differentiate(x);
}
if (is_constant(f)) {
const Expression& n{f}; // alias n = f
// Special case where base is a constant:
// ∂/∂x pow(n, g) = log(n) * pow(n, g) * ∂/∂x g
return log(n) * pow(n, g) * g.Differentiate(x);
}
// General case:
// ∂/∂x pow(f, g)
// = ∂/∂f pow(f, g) * ∂/∂x f + ∂/∂g pow(f, g) * ∂/∂x g
// = g * pow(f, g - 1) * ∂/∂x f + log(f) * pow(f, g) * ∂/∂x g
// = pow(f, g - 1) * (g * ∂/∂x f + log(f) * f * ∂/∂x g)
return pow(f, g - 1) *
(g * f.Differentiate(x) + log(f) * f * g.Differentiate(x));
}
Expression ExpressionMul::Differentiate(const Variable& x) const {
// ∂/∂x (c * f₁^g₁ * f₂^g₂ * ... * fₙ^gₙ
//= c * [expr * (∂/∂x f₁^g₁) / f₁^g₁ +
// expr * (∂/∂x f₂^g₂) / f₂^g₂ +
// ... +
// expr * (∂/∂x fₙ^gₙ) / fₙ^gₙ]
// = c * expr * (∑ᵢ (∂/∂x fᵢ^gᵢ) / fᵢ^gᵢ)
//
// where expr = (f₁^g₁ * f₂^g₂ * ... * fₙn^gₙ).
// This factory will form the expression that we will return.
ExpressionMulFactory mul_fac{constant_, base_to_exponent_map_};
// This factory will form (∑ᵢ (∂/∂x fᵢ^gᵢ) / fᵢ^gᵢ).
ExpressionAddFactory add_fac;
for (const pair<const Expression, Expression>& term : base_to_exponent_map_) {
const Expression& base{term.first};
const Expression& exponent{term.second};
add_fac.AddExpression(DifferentiatePow(base, exponent, x) *
pow(base, -exponent));
}
mul_fac.AddExpression(add_fac.GetExpression());
return mul_fac.GetExpression();
}
ostream& ExpressionMul::Display(ostream& os) const {
DRAKE_ASSERT(!base_to_exponent_map_.empty());
bool print_mul{false};
os << "(";
if (constant_ != 1.0) {
os << constant_;
print_mul = true;
}
for (auto& p : base_to_exponent_map_) {
DisplayTerm(os, print_mul, p.first, p.second);
print_mul = true;
}
os << ")";
return os;
}
ostream& ExpressionMul::DisplayTerm(ostream& os, const bool print_mul,
const Expression& base,
const Expression& exponent) const {
// Print " * pow(base, exponent)" if print_mul is true
// Print "pow(base, exponent)" if print_mul is false
// Print "base" instead of "pow(base, exponent)" if exponent == 1.0
if (print_mul) {
os << " * ";
}
if (is_one(exponent)) {
os << base;
} else {
os << "pow(" << base << ", " << exponent << ")";
}
return os;
}
ExpressionMulFactory::ExpressionMulFactory(
const double constant, map<Expression, Expression> base_to_exponent_map)
: constant_{constant},
base_to_exponent_map_{std::move(base_to_exponent_map)} {}
ExpressionMulFactory::ExpressionMulFactory(
const std::shared_ptr<const ExpressionMul>& ptr)
: ExpressionMulFactory{ptr->get_constant(),
ptr->get_base_to_exponent_map()} {}
void ExpressionMulFactory::AddExpression(const Expression& e) {
if (constant_ == 0.0) {
return; // Do nothing if it already represented 0.
}
if (is_zero(e)) {
// X * 0 => 0. So clear the constant and the map.
return SetZero();
}
if (is_constant(e)) {
return AddConstant(get_constant_value(e));
}
if (is_multiplication(e)) {
// Flattening
return Add(to_multiplication(e));
}
// Add e^1
return AddTerm(e, Expression{1.0});
}
void ExpressionMulFactory::Add(const shared_ptr<const ExpressionMul>& ptr) {
if (constant_ == 0.0) {
return; // Do nothing if it already represented 0.
}
AddConstant(ptr->get_constant());
AddMap(ptr->get_base_to_exponent_map());
}
void ExpressionMulFactory::SetZero() {
constant_ = 0.0;
base_to_exponent_map_.clear();
}
ExpressionMulFactory& ExpressionMulFactory::operator=(
const std::shared_ptr<const ExpressionMul>& ptr) {
constant_ = ptr->get_constant();
base_to_exponent_map_ = ptr->get_base_to_exponent_map();
return *this;
}
ExpressionMulFactory& ExpressionMulFactory::Negate() {
constant_ = -constant_;
return *this;
}
Expression ExpressionMulFactory::GetExpression() const {
if (base_to_exponent_map_.empty()) {
return Expression{constant_};
}
if (constant_ == 1.0 && base_to_exponent_map_.size() == 1u) {
// 1.0 * c1^t1 -> c1^t1
const auto it(base_to_exponent_map_.cbegin());
return pow(it->first, it->second);
}
return Expression{
make_shared<const ExpressionMul>(constant_, base_to_exponent_map_)};
}
void ExpressionMulFactory::AddConstant(const double constant) {
if (constant == 0.0) {
return SetZero();
}
constant_ *= constant;
}
void ExpressionMulFactory::AddTerm(const Expression& base,
const Expression& exponent) {
// The following assertion holds because of
// ExpressionMulFactory::AddExpression.
DRAKE_ASSERT(!(is_constant(base) && is_constant(exponent)));
if (is_pow(base)) {
// If (base, exponent) = (pow(e1, e2), exponent)), then add (e1, e2 *
// exponent)
// Example: (x^2)^3 => x^(2 * 3)
return AddTerm(get_first_argument(base),
get_second_argument(base) * exponent);
}
const auto it(base_to_exponent_map_.find(base));
if (it != base_to_exponent_map_.end()) {
// base is already in map.
// (= b1^e1 * ... * (base^this_exponent) * ... * en^bn).
// Update it to be (... * (base^(this_exponent + exponent)) * ...)
// Example: x^3 * x^2 => x^5
Expression& this_exponent = it->second;
this_exponent += exponent;
if (is_zero(this_exponent)) {
// If it ends up with base^0 (= 1.0) then remove this entry from the map.
// TODO(soonho-tri): The following operation is not sound since it can
// cancels `base` which might include 0/0 problems.
base_to_exponent_map_.erase(it);
}
} else {
// Product is not found in base_to_exponent_map_. Add the entry (base,
// exponent).
base_to_exponent_map_.emplace(base, exponent);
}
}
void ExpressionMulFactory::AddMap(
const map<Expression, Expression>& base_to_exponent_map) {