RobotLocomotion / drake

Model-based design and verification for robotics.
https://drake.mit.edu
Other
3.26k stars 1.26k forks source link

const symbolic::Polynomial p{monomial_basis.dot(Q_poly * monomial_basis)}; is slow #10200

Open hongkai-dai opened 5 years ago

hongkai-dai commented 5 years ago

I tried to create a sum-of-squares polynomial by calling MathematicalProgram::NewSosPolynomial(m), where m is a vector of monomials (monomial basis) of size 578. It took 180 seconds to create this Sos polynomial. Most of the time is spent on the line https://github.com/RobotLocomotion/drake/blob/c63627ee938d9273767fede9cba10bddfa8248a0/solvers/mathematical_program.cc#L201 where it computes mᵀ * Q * m.

On the other hand, I changed that line to

symbolic::Polynomial p{};
  for (int i = 0; i < Q_poly.rows(); ++i) {
    p.AddProduct(Q(i, i), pow(monomial_basis(i), 2));
    for (int j = i + 1; j < Q_poly.cols(); ++j) {
      p.AddProduct(2 * Q(i, j), monomial_basis(i) * monomial_basis(j));
    }
  }

i.e., to do the matrix multiplication by hand, and now the computation takes about 3s.

@soonho-tri and I try to investigated into this. He finds the slow version created way too many polynomial instances. Also I suspect we have incurred a lot of overhead to copy a polynomial. We will keep investigating into the issue. Ideally we like the simplicity to write m.dot(Q * m), rather than the double for loop to compute matrix multiplication.

hongkai-dai commented 5 years ago

To reproduce the behavior, there is a branch https://github.com/hongkai-dai/drake/tree/slow_symbolic_polynomial, and the bazel target

$ bazel build //multibody/rational_forward_kinematics:symbolic_polynomial_slow_test
$ ./bazel-bin/multibody/rational_forward_kinematics/symbolic_polynomial_slow_test
hongkai-dai commented 5 years ago

Updates, since #10201 calling NewSosPolynomial is fast, but the problem still pertains, that calling const symbolic::Polynomial p{monomial_basis.dot(Q_poly * monomial_basis)}; is slow.