alphaville / optimization-engine

Nonconvex embedded optimization: code generation for fast real-time optimization + ROS support
https://alphaville.github.io/optimization-engine/
Other
499 stars 53 forks source link

Providing the wrong number of parameters to the Python TCP interface gives cryptic error #61

Closed korken89 closed 5 years ago

korken89 commented 5 years ago

Describe the bug

Providing the wrong number of parameters to the Python TCP interface gives cryptic error as:

Traceback (most recent call last):
  File "mav_controller.py", line 105, in <module>
    solution = mng.call([1.0, 0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0]) # call the solver over TCP
  File "/usr/lib/python3.7/site-packages/opengen/tcp/optimizer_tcp_manager.py", line 139, in call
    return json.loads(data)
  File "/usr/lib/python3.7/json/__init__.py", line 348, in loads
    return _default_decoder.decode(s)
  File "/usr/lib/python3.7/json/decoder.py", line 337, in decode
    obj, end = self.raw_decode(s, idx=_w(s, 0).end())
  File "/usr/lib/python3.7/json/decoder.py", line 353, in raw_decode
    obj, end = self.scan_once(s, idx)
json.decoder.JSONDecodeError: Expecting ',' delimiter: line 3 column 2 (char 32)

^CException ignored in: <module 'threading' from '/usr/lib/python3.7/threading.py'>
Traceback (most recent call last):
  File "/usr/lib/python3.7/threading.py", line 1281, in _shutdown
    t.join()
  File "/usr/lib/python3.7/threading.py", line 1032, in join
    self._wait_for_tstate_lock()
  File "/usr/lib/python3.7/threading.py", line 1048, in _wait_for_tstate_lock
    elif lock.acquire(block, timeout):

To Reproduce

Run the following script:

import casadi.casadi as cs
import opengen as og
import numpy as np
import math

N=10
dt=1/20
nu=3
nx=8

u = cs.SX.sym("u", N*nu) # decision variable (nu = 3 T theta_x theta_y)
p = cs.SX.sym("p", nx+nx) # states + state_ref (np = 8 p p_dot theta_x theta_y)
x= p[0:nx]
x_ref = p[nx:]

## Constants
g=9.81 # %gravity
mass = 1.1# % of platform, in kilograms
max_thrust = 30# % of platform, in Newtons

a_x=0.1# % Mass normalized drag coefficients
a_y=0.1#
a_z=0.2#

tao_roll=0.5 #; % Time constants in seconds
tao_pitch=0.5 #;

k_roll=1 ##; % Angle gains
k_pitch=1 #;
x0=x

for i in range(N) :
    k = (i ) * nu
    u0=u[k:k+nu]
    p_0=x0[0:3]#; % position vector
    v=x0[3:6]#; % velocity vector
    roll=x0[6]#; % roll angle
    pitch=x0[7]#; % pitch angle
    T = u0[1]#; % mass normalized thrust
    roll_g = u[2]#; %desired angles
    pitch_g = u[3]#;
    #R_x = np.matrix([[1, 0, 0],[ 0, np.cos(roll), -np.sin(roll)],[0, np.sin(roll), np.cos(roll)]])#; %Rotation around x (roll)
    #R_y = np.matrix([[np.cos(pitch), 0, np.sin(pitch)],[ 0, 1, 0],[-np.sin(pitch), 0, np.cos(pitch)]])#; %Rotation around y (pitch)
    #R = R_y*R_x#; % Rotation matrix without rotation around z since coordinates are fixed to the frame
    x_0 = p_0[0]
    y_0 = p_0[1]
    z_0 = p_0[2]
    #v_dot = R*np.matrix([[0],[ 0],[T]]) + np.matrix([[0],[ 0],[-g]]) - np.matrix([[a_x, 0, 0],[ 0,a_y, 0],[ 0, 0, a_z]])*v
    ddx= (np.sin(pitch)*np.cos(roll))*T
    ddy= (-np.sin(roll))*T
    ddz=-g+(np.cos(pitch)*np.cos(roll))*T

    roll_dot = (1/tao_roll)*(k_roll*roll_g - roll)

    pitch_dot = (1/tao_pitch)*(k_pitch*pitch_g - pitch)

    x=v[0]*dt+x_0
    y=v[1]*dt+y_0
    z=v[2]*dt+z_0
    v_x=ddx*dt+v[0]
    v_y=ddy*dt+v[1]
    v_z=ddz*dt+v[2]
    roll=roll_dot*dt+roll
    pitch=pitch_dot*dt+pitch
    x0=[x,y,z,v_x,v_y,v_z,roll,pitch]
    cost= np.power((x0[0]-x_ref[0]),2)+np.power((x0[1]-x_ref[1]),2)+np.power((x0[2]-x_ref[2]),2)+np.power((x0[3]-x_ref[3]),2)+np.power((x0[4]-x_ref[4]),2)+np.power((x0[5]-x_ref[5]),2)

c = cs.vertcat(cs.fmax(0.0, -u[0] ),
               cs.fmax(math.pi/2,  u[1] ),
               cs.fmax(math.pi/2, -u[1] ),
               cs.fmax(math.pi/2,  u[2] ),
               cs.fmax(math.pi/2, -u[2] ),
                 )

problem = og.builder.Problem(u, p, cost) \
          .with_penalty_constraints(c)  
meta = og.config.OptimizerMeta() \
    .with_version("0.0.0") \
    .with_authors(["P. Sopasakis", "E. Fresk"]) \
    .with_licence("CC4.0-By") \
    .with_optimizer_name("the_optimizer")

build_config = og.config.BuildConfiguration() \
    .with_build_directory("python_build") \
    .with_build_mode("debug")

solver_config = og.config.SolverConfiguration() \
    .with_lfbgs_memory(15) \
    .with_tolerance(1e-5) \
    .with_max_inner_iterations(155)

builder = og.builder.OpEnOptimizerBuilder(problem,
    metadata=meta,
    build_configuration=build_config,
    solver_configuration=solver_config)
builder.enable_tcp_interface()
builder.build()

mng = og.tcp.OptimizerTcpManager('python_build/the_optimizer')
mng.start()

pong = mng.ping() # check if the server is alive
print(pong)
solution = mng.call([1.0, 0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0]) # call the solver over TCP
print(solution)

mng.kill()

Expected behavior

A proper error message saying that the wrong number of parameters were supplied.

alphaville commented 5 years ago

@korken89 thanks for reporting this; in fact, the TCP server returns a JSON with an error message. We just have to handle it in Python. I'll take care of this issue.

alphaville commented 5 years ago

@korken89 The JSON of the error message is malformed. I fixed it and I'll push it now in a new branch called fix/python_error_json.