Skip to content

Commit

Permalink
Renamed 'has_batch' to 'model_expects_batch_dim'.
Browse files Browse the repository at this point in the history
  • Loading branch information
Tim-Salzmann committed Jul 31, 2023
1 parent 4d528a7 commit 8642f2a
Show file tree
Hide file tree
Showing 8 changed files with 29 additions and 17 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ On MacOS with M1 chip you will have to compile [tera_renderer](https://github.co
and place the binary in `l4casadi/template_generation/bin`. For other platforms it will be downloaded automatically.

## Example
https://github.com/Tim-Salzmann/l4casadi/blob/d800ca7bea785a22b05c64f4aecd7554ba5093d3/examples/readme.py#L28-L40
https://github.com/Tim-Salzmann/l4casadi/blob/23e07380e214f70b8932578317aa373d2216b57e/examples/readme.py#L28-L40

Please note that only `casadi.MX` symbolic variables are supported as input.

Expand Down
2 changes: 1 addition & 1 deletion examples/acados.py
Original file line number Diff line number Diff line change
Expand Up @@ -174,7 +174,7 @@ def acados_model(self, model):

def run():
N = 10
learned_dyn_model = l4c.L4CasADi(MultiLayerPerceptron(), has_batch=True, name='learned_dyn')
learned_dyn_model = l4c.L4CasADi(MultiLayerPerceptron(), model_expects_batch_dim=True, name='learned_dyn')

model = DoubleIntegratorWithLearnedDynamics(learned_dyn_model)
solver = MPC(model=model.model(), N=N,
Expand Down
2 changes: 1 addition & 1 deletion examples/readme.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ def forward(self, x):


pyTorch_model = MultiLayerPerceptron()
l4c_model = l4c.L4CasADi(pyTorch_model, has_batch=True, device='cpu') # device='cuda' for GPU
l4c_model = l4c.L4CasADi(pyTorch_model, model_expects_batch_dim=True, device='cpu') # device='cuda' for GPU

x_sym = cs.MX.sym('x', 2, 1)
y_sym = l4c_model(x_sym)
Expand Down
18 changes: 14 additions & 4 deletions l4casadi/l4casadi.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,15 +19,25 @@ def dynamic_lib_file_ending():


class L4CasADi(object):
def __init__(self, model: Callable[[torch.Tensor], torch.Tensor],
has_batch: bool = False, device: Union[torch.device, Text] = "cpu", name: Text = "l4casadi_f"):
def __init__(self,
model: Callable[[torch.Tensor], torch.Tensor],
model_expects_batch_dim: bool = False,
device: Union[torch.device, Text] = "cpu",
name: Text = "l4casadi_f"):
"""
:param model: PyTorch model.
:param model_expects_batch_dim: True if the PyTorch model expects a batch dimension.
:param device: Device on which the PyTorch model is executed.
:param name: Unique name of the generated L4CasADi model. This name is used for autogenerated files.
Creating two L4CasADi models with the same name will result in overwriting the files of the first model.
"""
self.model = model
if isinstance(self.model, torch.nn.Module):
self.model.eval().to(device)
for parameters in self.model.parameters():
parameters.requires_grad = False
self.name = name
self.has_batch = has_batch
self.has_batch = model_expects_batch_dim
self.device = device if isinstance(device, str) else f'{device.type}:{device.index}'

self.generation_path = pathlib.Path('./_l4c_generated')
Expand Down Expand Up @@ -100,7 +110,7 @@ def generate_cpp_function_template(self, rows: int, cols: int, has_jac: bool, ha
'cols_out': cols_out,
'has_jac': has_jac,
'has_hess': has_hess,
'has_batch': self.has_batch
'model_expects_batch_dim': self.has_batch
}
with open(self.generation_path / f'{self.name}.json', 'w') as f:
json.dump(gen_params, f)
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include <l4casadi.hpp>

L4CasADi l4casadi("{{ model_path }}", "{{ name }}", {{ has_batch }}, "{{ device }}", {{ has_jac }}, {{ has_hess }});
L4CasADi l4casadi("{{ model_path }}", "{{ name }}", {{ model_expects_batch_dim }}, "{{ device }}", {{ has_jac }}, {{ has_hess }});

#ifdef __cplusplus
extern "C" {
Expand Down
4 changes: 2 additions & 2 deletions libl4casadi/include/l4casadi.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,9 @@
class L4CasADi
{
private:
bool has_batch;
bool model_expects_batch_dim;
public:
L4CasADi(std::string, std::string, bool has_batch = false, std::string = "cpu", bool = false, bool = false);
L4CasADi(std::string, std::string, bool = false, std::string = "cpu", bool = false, bool = false);
~L4CasADi();
void forward(const double*, int, int, double*);
void jac(const double*, int, int, double*);
Expand Down
10 changes: 5 additions & 5 deletions libl4casadi/src/l4casadi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,14 +79,14 @@ class L4CasADi::L4CasADiImpl
}
};

L4CasADi::L4CasADi(std::string model_path, std::string model_prefix, bool has_batch, std::string device,
L4CasADi::L4CasADi(std::string model_path, std::string model_prefix, bool model_expects_batch_dim, std::string device,
bool has_jac, bool has_hess):
pImpl{std::make_unique<L4CasADiImpl>(model_path, model_prefix, device, has_jac, has_hess)},
has_batch{has_batch} {}
model_expects_batch_dim{model_expects_batch_dim} {}

void L4CasADi::forward(const double* in, int rows, int cols, double* out) {
torch::Tensor in_tensor;
if (this->has_batch) {
if (this->model_expects_batch_dim) {
in_tensor = torch::from_blob(( void * )in, {1, rows}, at::kDouble).to(torch::kFloat);
} else {
in_tensor = torch::from_blob(( void * )in, {rows, cols}, at::kDouble).to(torch::kFloat);
Expand All @@ -98,7 +98,7 @@ void L4CasADi::forward(const double* in, int rows, int cols, double* out) {

void L4CasADi::jac(const double* in, int rows, int cols, double* out) {
torch::Tensor in_tensor;
if (this->has_batch) {
if (this->model_expects_batch_dim) {
in_tensor = torch::from_blob(( void * )in, {1, rows}, at::kDouble).to(torch::kFloat);
} else {
in_tensor = torch::from_blob(( void * )in, {rows, cols}, at::kDouble).to(torch::kFloat);
Expand All @@ -110,7 +110,7 @@ void L4CasADi::jac(const double* in, int rows, int cols, double* out) {

void L4CasADi::hess(const double* in, int rows, int cols, double* out) {
torch::Tensor in_tensor;
if (this->has_batch) {
if (this->model_expects_batch_dim) {
in_tensor = torch::from_blob(( void * )in, {1, rows}, at::kDouble).to(torch::kFloat);
} else {
in_tensor = torch::from_blob(( void * )in, {rows, cols}, at::kDouble).to(torch::kFloat);
Expand Down
6 changes: 4 additions & 2 deletions tests/test_l4casadi.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ def test_l4casadi_deep_model(self, deep_model):
rand_inp = torch.rand((1, deep_model.input_layer.in_features))
torch_out = deep_model(rand_inp)

l4c_out = l4c.L4CasADi(deep_model, has_batch=True)(rand_inp.transpose(-2, -1).detach().numpy())
l4c_out = l4c.L4CasADi(deep_model, model_expects_batch_dim=True)(rand_inp.transpose(-2, -1).detach().numpy())

np.allclose(l4c_out, torch_out.transpose(-2, -1).detach().numpy())

Expand All @@ -68,7 +68,9 @@ def test_l4casadi_deep_model_jac(self, deep_model):

mx_inp = cs.MX.sym('x', deep_model.input_layer.in_features, 1)

jac_fun = cs.Function('f_jac', [mx_inp], [cs.jacobian(l4c.L4CasADi(deep_model, has_batch=True)(mx_inp), mx_inp)])
jac_fun = cs.Function('f_jac',
[mx_inp],
[cs.jacobian(l4c.L4CasADi(deep_model, model_expects_batch_dim=True)(mx_inp), mx_inp)])

l4c_out = jac_fun(rand_inp.transpose(-2, -1).detach().numpy())

Expand Down

0 comments on commit 8642f2a

Please sign in to comment.