RobotLocomotion / drake

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

mathematical program: zeros in the cost function can not be updated #11863

Closed sadraddini closed 5 years ago

sadraddini commented 5 years ago

I found a problem when using UpdateCoefficients in the mathematical program, which is useful when we want to solve a program with a new linear cost function without the need to setting up the program from scratch. The only requirement is that the new cost vector should have the same dimensions as the old one, otherwise we get RuntimeError: Can't change the number of decision variable.

There exists a small bug here: when the old cost vector contains zeros, then the mathematical program removes them and shrinks the size of the cost vector. Then, when we give a new cost vector, it by mistake gives the error that the number of variables can not change.

As an example, consider the following toy problem:

import numpy as np

import pydrake.symbolic as sym
import pydrake.solvers.mathematicalprogram as MP
import pydrake.solvers.gurobi as Gurobi_drake
import pydrake.solvers.osqp as OSQP_drake

# use Gurobi solver
gurobi_solver=Gurobi_drake.GurobiSolver()
solver=gurobi_solver

prog=MP.MathematicalProgram()
x=prog.NewContinuousVariables(2,1,"x")
prog.AddLinearConstraint(A=np.eye(2),ub=np.ones((2,1)),lb=np.ones((2,1))*-1,vars=x)
c=np.array([1,0]).reshape(2,1)
J=prog.AddLinearCost(np.dot(c.T,x)[0,0])
result=solver.Solve(prog,None,None)
print "x=",result.GetSolution(x)
print "c=",J.evaluator().a()," and its shape is",J.evaluator().a().shape
# Now let's change the cost vector
c_new=np.array([-1,1]).reshape(2,1)
J.evaluator().UpdateCoefficients(c_new)
result=solver.Solve(prog,None,None)
print result.GetSolution(x)

Executing this piece of code will generate the mentioned runtime error:

x=[-1. -1.]
c= [1.]  and its shape is (1,)
Traceback (most recent call last):
... # *these lines are omitted* 
    J.evaluator().UpdateCoefficients(c_new)

RuntimeError: Can't change the number of decision variables

As you see the, the cost vector's size has been shrunk to 1. If we replace the zero in the old cost vector by 0.01, or any non-zero number, this problem will vanish:

x= [-1. -1.]
c= [0.01 1.  ]  and its shape is (2,)
[ 1. -1.]

Currently our (me and @wualbert) solution to this is replacing the zeros with small epsilons. But still we should have pointed out this issue.

SeanCurtis-TRI commented 5 years ago

@hongkai-dai I've assigned this to you -- feel free to pass it along if you feel there's someone more appropriate.

mpetersen94 commented 5 years ago

The problem comes from the fact that when the program evaluates np.dot(c.T,x)[0,0] the result is x(0). As a result the cost added is only on one variable not both. To fix it you either need to first initialize the cost with both variables or use the vector constructor method to add the cost (although that method seems to be missing a binding...).

sadraddini commented 5 years ago

The problem comes from the fact that when the program evaluates np.dot(c.T,x)[0,0] the result is x(0). As a result the cost added is only on one variable not both. To fix it you either need to first initialize the cost with both variables or use the vector constructor method to add the cost (although that method seems to be missing a binding...).

No the problem is not there. np.dot(c.T,x) is by construction a 1*1 matrix, so [0,0] returns its only entry. I can change the code as follows:

prog=MP.MathematicalProgram()
x=prog.NewContinuousVariables(2,1,"x")
prog.AddLinearConstraint(A=np.eye(2),ub=np.ones((2,1)),lb=np.ones((2,1))*-1,vars=x)
c=np.array([1,0.00]).reshape(2,1)
J=prog.AddLinearCost(c[0,0]*x[0,0]+c[1,0]*x[1,0])
result=solver.Solve(prog,None,None)
print "x=",result.GetSolution(x)
print "c=",J.evaluator().a()," and its shape is",J.evaluator().a().shape
# Now let's change the cost vector
c_new=np.array([-1,1]).reshape(2,1)
J.evaluator().UpdateCoefficients(c_new)
result=solver.Solve(prog,None,None)
print result.GetSolution(x)

And still the following is observed:

x= [-1. -1.]
c= [1.]  and its shape is (1,)
... 
RuntimeError: Can't change the number of decision variables
mpetersen94 commented 5 years ago

c[0,0]*x[0,0]+c[1,0]*x[1,0] will still evaluate to x[0,0] so both formulations are equivalent to J=prog.AddLinearCost(x[0,0]) The expression is simplified to remove the variables multiplied by zero before being passed to the AddLinearCost method so it only ever sees a cost on one variable.

sadraddini commented 5 years ago

c[0,0]*x[0,0]+c[1,0]*x[1,0] will still evaluate to x[0,0] so both formulations are equivalent to J=prog.AddLinearCost(x[0,0]) The expression is simplified to remove the variables multiplied by zero before being passed to the AddLinearCost method so it only ever sees a cost on one variable.

Makes sense but then this can be viewed as a bug since it does not keep the cost vector with zeros. Therefore, when we ask it to change the cost vector to some non-zero values, it wrongly thinks that the number of decision variables is changed.

hongkai-dai commented 5 years ago

Hi Sadra,

I agree it is a bug in our code, as we strip the term with 0 coefficient in the linear expression. In C++, I can avoid this problem by calling AddLinearCost(Eigen::Vector2d(0, 0), 0, x), which still keeps the 0 coefficient. This C++ function doesn't have a python binding yet. I can add that python binding. Would that be good with you?

Best, Hongkai

hongkai-dai commented 5 years ago

@mpetersen94 as you mentioned there is one missing python binding. I added that python binding in #11870, could you review it? Thanks!

hongkai-dai commented 5 years ago

@sadraddini , even if we don't have the zero coefficient issue, I wouldn't recommend to add the linear cost by calling AddLinearCost(expression), and then change the coefficient by UpdateCoefficient. The reason is that when you call UpdateCoefficient, you implicitly assume the order of the variables, which is not guaranteed when adding the cost. Here is an example

cost = prog.AddLinearCost( x[0] + x[1])
cost.evaluator().UpdateCoefficients([2, 3])

You would not know if the updated cost is 2 * x(0) + 3 * x(1) or 2 * x(1) + 3 * x(0). Our API don't guarantee that cost.variables() is sorted in any order, so both costs are possible.

I would recommend to call cost = AddLinearCost([1, 1], 0, [x[0], x[1]]) instead. This guarantees that the order of cost.variables() is [x[0], x[1]] as in the input argument, an then if you call cost.evaluator().UpdateCoefficients([2, 3]), it is guaranteed that the updated cost is 2 * x[0] + 3 * x[1].

sadraddini commented 5 years ago

Hi Sadra,

I agree it is a bug in our code, as we strip the term with 0 coefficient in the linear expression. In C++, I can avoid this problem by calling AddLinearCost(Eigen::Vector2d(0, 0), 0, x), which still keeps the 0 coefficient. This C++ function doesn't have a python binding yet. I can add that python binding. Would that be good with you?

Best, Hongkai

This should solve the problem. It is also faster to construct the linear cost like that rather than evaluating a symbolic expression. Thanks!