casadi / casadi

CasADi is a symbolic framework for numeric optimization implementing automatic differentiation in forward and reverse modes on sparse matrix-valued computational graphs. It supports self-contained C-code generation and interfaces state-of-the-art codes such as SUNDIALS, IPOPT etc. It can be used from C++, Python or Matlab/Octave.
http://casadi.org
GNU Lesser General Public License v3.0
1.75k stars 391 forks source link

The parametrized bspline conundrum #2561

Open jgillis opened 4 years ago

jgillis commented 4 years ago

Goal: have parametrically settable B-spline in codegen that evaluates in O(log(N)) N: size of grid (let's say 1D) Should not be differentiable wrt to grid or coeff

jgillis commented 4 years ago

User input:

conf = Configuration()
p = conf.parameter()
p2 = sqrt(p)
x = MX.sym("x")
y = sin(p2*x)
f = Function('f',[x],[y])
p1 = conf.parameter()
z = 2*y+cos(p2+p1)
g = Function('g',[x],[z])

In virtual machine:

conf = Configuration()

p = conf.parameter()
p2 = sqrt(p)
x = MX.sym("x")
y = sin(ConfigurationOutput(p2)*x) # (*)
f = Function('f',[x],[y])
p1 = conf.parameter()
z = 2*y+ConfigurationOutput(cos(p2+p1))
g = Function('g',[x],[z])

f(1) # Error: parameter not set 

#Creates:
F = Function('F',[p,p1],[p2,cos(p2+p1)])

conf.set_value(p, 1)
conf.set_value(p1, 2)

conf.compute()
# Evaluates F

(*) at MX manipulation time, or at MX Function construction time? Probably latter, since you can then make use of mutable temp of MXnode to detect dependencies efficiently

Codegen

cg = CodeGenerator()
cg.add(f)
cg.add(g)
cg.add(conf)

C code

static double i1[1] = {nan}; // order defined by calls to conf,parameter()
static double i2[1] = {nan};
static double r1[1] = {nan}; // corresponds to p2
static double r2[1] = {nan}; // correspnds to cos(p2+p1)

set_parameter(id, value) {
   casadi_copy();
}

compute() {
  arg[0] = i1;
  arg[1] = i2;
  res[0] = r1;
  res[1] = r2;
   F(arg,res);

}

/* f:(i0,i1)->(o0) */
static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) {
  casadi_real w0, w1;
  w0 = r1;
  w1 = arg[0] ? arg[0][0] : 0;
  w0 *= w1;
  w0 = sin( w0 );
  if (res[0]) res[0][0] = w0;
  return 0;
}

Serialization

Start Serializer with a dump of Configuration

Why not caching?

Alternative to hashes: timestamp

jgillis commented 4 years ago

Context, value

Do we want evaluation to be possible in different contexts? no

Allow cyclic dependencies between variables of different contexts? no

Who holds the values? The context or the node? If it's the context, then the node should contain a reference to the context -> SharedObject

Who creates output nodes? The user, the MX logic, the MX Function? In the two latter cases, the node needs a reference to the context. How else can the Context end up with a Function? Instead of a reference, can't we work with an index into a global ContextTable? -> difficult to work with serialize/deserialize: what if you deserialize two functions with different Contexts?

Should Context have a 'subcontext' method that only works once?

jgillis commented 4 years ago

Each Context defines a computation.

jgillis commented 4 years ago

New approach, with prototype implementation. No Context, values stored in MXNode called Gate. Gate automatically inserted as soon as MX.sym becomes part of the graph.

from casadi import *
import subprocess

p = MX.par("p")

p2 = sqrt(p)

x = MX.sym("x")
y = sin(p2*x) # Gate node inserted after p2, right before multiplication

print(y)

f = Function('f',[x],[y])
print(f(3))  # defaults to nan

f.disp(True)
print()

g = Function.conf("g",[p])

print(g(9))
print(f(3)) # Now the nan is gone
print(g(16))
print(f(3)) # Another number

g.disp(True)
print()

cg = CodeGenerator("foo")
cg.add(f)
cg.add(g)
cg.generate()

commands = "gcc -pedantic -std=c89 -fPIC -shared -Wall -Werror -Wno-unknown-pragmas -Wno-long-long -Wno-unused-parameter -Wextra {name}.c -o {name}.so".format(name='foo')

p = subprocess.Popen(commands,shell=True).wait()

F = external(f.name(), "./foo.so")
G = external(g.name(), "./foo.so")

print("codegen start")

print(F(3))
print(G(16))
print(F(3))
print(G(9))
print(F(3))

print("codegen stop")

fs = FileSerializer("test.casadi")
fs.pack(f)
fs.pack(g)
fs = None

fs = FileDeserializer("test.casadi")
ff = fs.unpack()
gg = fs.unpack()

print(ff(3))
print(gg(16))
print(ff(3))
print(gg(9))
print(ff(3))
sin((gate()*x))
nan
f:(i0)->(o0) MXFunction
Algorithm:
@0 = gate()
@1 = input[0][0]
@0 = (@0*@1)
@0 = sin(@0)
output[0][0] = @0
3
0.412118
4
-0.536573
g:(i0)->(o0) MXFunction
Algorithm:
@0 = input[0][0]
@0 = sqrt(@0)
@1 = gate()
output[0][0] = @1
codegen start
0
4
-0.536573
3
0.412118
codegen stop
-0.536573
4
-0.536573
3
0.412118

foo.c:


static casadi_real casadi_rwd0[1];

/* f:(i0)->(o0) */
static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) {
  casadi_real w0, w1;
  /* #0: @0 = gate() */
  casadi_copy(casadi_rwd0, 1, (&w0));
  /* #1: @1 = input[0][0] */
  w1 = arg[0] ? arg[0][0] : 0;
  /* #2: @0 = (@0*@1) */
  w0 *= w1;
  /* #3: @0 = sin(@0) */
  w0 = sin( w0 );
  /* #4: output[0][0] = @0 */
  if (res[0]) res[0][0] = w0;
  return 0;
}

/* g:(i0)->(o0) */
static int casadi_f1(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) {
  casadi_real w0, w1;
  /* #0: @0 = input[0][0] */
  w0 = arg[0] ? arg[0][0] : 0;
  /* #1: @0 = sqrt(@0) */
  w0 = sqrt( w0 );
  /* #2: @1 = gate() */
  casadi_copy((&w0), 1, casadi_rwd0);
  casadi_copy(casadi_rwd0, 1, (&w1));
  /* #3: output[0][0] = @1 */
  if (res[0]) res[0][0] = w1;
  return 0;
}

Todo: swap in Gate node

jgillis commented 4 years ago
jgillis commented 3 years ago

New take.

mem = MemoryPool()

foo = mem.add("foo",DM([1,2,3]))

mem.set("foo",DM([2,3,4]))