Simple-Robotics / aligator

A versatile and efficient framework for constrained trajectory optimization

Home Page:https://simple-robotics.github.io/aligator/

Geek Repo:Geek Repo

Github PK Tool:Github PK Tool

Segfault setting a problem with no nodes

stephane-caron opened this issue · comments

The API says we can setup a solver for a problem. This makes me immediately want to try setting up different problems in succession 😜

    solver.setup(problem)  # sneaky line
    for i in range(nb_nodes):
        stage = proxddp.StageModel(running_cost, integrator)
        problem.addStage(stage)
    solver.setup(problem)

On my machine this leads to:

$ python example.py  # with sneaky line
[1]    87811 segmentation fault (core dumped)  python trajopt.py

$ python example.py  # without sneaky line
iter|  alpha   |inner_crit| prim_err | dual_err |   xreg   |  dphi0   |  merit   | delta_M  |al_iter
Successfully converged.

→ Suggested unit test.

Reproduction code

Just a part of the cartpole.py example. Sorry this is not minimal:

import numpy as np
import pinocchio as pin
import proxddp
import proxnlp
from robot_descriptions.loaders.pinocchio import load_robot_description

if __name__ == "__main__":
    full_robot = load_robot_description(
        "upkie_description",
        root_joint=pin.JointModelFreeFlyer(),
    )
    robot = full_robot.buildReducedRobot(
        list_of_joints_to_lock=[
            f"{side}_{joint}"
            for side in ("left", "right")
            for joint in ("hip", "knee")
        ]
    )

    model = robot.model
    timestep = 0.01  # [s]
    control_dim = 1
    actuation_matrix = np.array([0.0] * 6 + [+1.0, -1.0]).reshape(
        (model.nv, control_dim)
    )

    phase_space = proxnlp.manifolds.MultibodyPhaseSpace(model)
    continuous_dynamics = proxddp.dynamics.MultibodyFreeFwdDynamics(
        phase_space, actuation_matrix
    )
    integrator = proxddp.dynamics.IntegratorSemiImplEuler(
        continuous_dynamics, timestep
    )

    # Control running cost
    wu = 1e-4 * np.ones(control_dim)
    control_reg_cost = proxddp.QuadraticResidualCost(
        proxddp.ControlErrorResidual(phase_space.ndx, np.zeros(control_dim)),
        timestep * np.diag(wu),
    )

    # Target running cost
    target = pin.SE3.Identity()
    target.translation = np.array([0.5, 0.0, 0.0])
    target_weights = np.zeros(6)
    target_weights[:3] = np.ones(3) * 1.0
    frame_residual = proxddp.FramePlacementResidual(
        phase_space.ndx,
        control_dim,
        model,
        target,
        model.getFrameId("chassis"),
    )
    target_cost = proxddp.QuadraticResidualCost(
        frame_residual,
        np.diag(target_weights) * timestep,
    )

    # Running cost stack
    running_cost = proxddp.CostStack(phase_space.ndx, control_dim)
    running_cost.addCost(control_reg_cost)
    running_cost.addCost(target_cost)

    # Terminal cost
    # XXX: warning, re-using target cost here! If it breaks start there
    terminal_cost = proxddp.CostStack(phase_space.ndx, control_dim)
    terminal_cost.addCost(target_cost)

    nb_nodes = 100
    initial_state = phase_space.neutral()
    problem = proxddp.TrajOptProblem(
        initial_state, control_dim, phase_space, terminal_cost
    )

    mu_init = 4e-2
    rho_init = 1e-2
    verbose = proxddp.VerboseLevel.VERBOSE
    TOL = 1e-4
    MAX_ITER = 200
    solver = proxddp.SolverProxDDP(
        TOL, mu_init, rho_init=rho_init, max_iters=MAX_ITER, verbose=verbose
    )

    solver.setup(problem)
    for i in range(nb_nodes):
        stage = proxddp.StageModel(running_cost, integrator)
        problem.addStage(stage)
    solver.setup(problem)

    u0 = np.zeros(control_dim)
    controls = [u0] * nb_nodes
    states = proxddp.rollout(integrator, initial_state, controls)
    solver.run(problem, states, controls)
commented

Nice catch ! What do you get in debug mode ? Is it the first setup() which produces the segfault? That would be my guess since the problem is "empty" (e.g. has no other nodes)

commented

Also, you're welcome to add the example to the repo in a PR :)

Is it the first setup() which produces the segfault?

Whoops, my bad issue description. You're 🎯, the first setup() is the segfault-guilty one.

Also, you're welcome to add the example to the repo in a PR :)

Way to go 👍 #47