RobotLocomotion / drake

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

IpoptSolver crashes on this kinematic trajectory optimization instance #18398

Open RussTedrake opened 1 year ago

RussTedrake commented 1 year ago

Reported by a student. I've reduced it down to this minimal example:

import numpy as np

from pydrake.all import (BsplineTrajectory, KinematicTrajectoryOptimization,
                         IpoptSolver)

t_duration = 0.782
q_Catch = np.array([-0.74, 0.58, 0, -1.79, 0, -0.79, 0])
q_Throw = np.array([-0.54, 0.58, 0, -1.79, 0, -0.79, 0])
v_Catch = np.array([[-0.151], [3.974], [-0.121], [-0.673], [0.039], [1.305],
                    [-0.000]])
v_Throw = np.array([[-0.151], [-4.050], [-0.121], [0.559], [0.039], [-1.322],
                    [0.000]])

# Initialize KinTrajOpt
num_positions = 7
num_control_points = 21
trajopt = KinematicTrajectoryOptimization(num_positions, num_control_points)
prog = trajopt.get_mutable_prog()

# Add Position and Velocity Bounds based on iiwa
#trajopt.AddPositionBounds(
#    [-2.96706, -2.0944, -2.96706, -2.0944, -2.96706, -2.0944, -3.05433],
#    [2.96706, 2.0944, 2.96706, 2.0944, 2.96706, 2.0944, 3.05433])
trajopt.AddVelocityBounds([-10] * 7, [10] * 7)

# Constrain duration to be exact duration
trajopt.AddDurationConstraint(2 * t_duration, 2 * t_duration)

# Constrain positions in joint angles
trajopt.AddPathPositionConstraint(q_Catch, q_Catch, 0)
trajopt.AddPathPositionConstraint(q_Throw, q_Throw, 0.5)
trajopt.AddPathPositionConstraint(q_Catch, q_Catch, 1)

trajopt.AddPathVelocityConstraint(v_Catch, v_Catch, 0)
trajopt.AddPathVelocityConstraint(v_Throw, v_Throw, 0.5)
trajopt.AddPathVelocityConstraint(v_Catch, v_Catch, 1)

solver = IpoptSolver()
result = solver.Solve(prog)

if not result.is_success():
    print("Trajectory optimization failed!")
    print(result.get_solver_id().name())
else:
    print("Trajectory optimization succeeded!")

Using SnoptSolver, the optimization succeeds. But with IpoptSolver, it fails.

I'm opening this issue to track; will try reproducing in c++ and capturing it in the debugger.

RussTedrake commented 1 year ago

Here is the c++ reproduction, which can be dropped into kinematic_trajectory_optimization_test.cc

// Confirms that we've resolved issue #18398.
GTEST_TEST(KinTrajOptTest, Issue18398) {
  const double kDuration = 0.782;
  VectorXd q_catch(7), q_throw(7), v_catch(7), v_throw(7);
  q_catch << -0.74, 0.58, 0, -1.79, 0, -0.79, 0;
  q_throw << -0.54, 0.58, 0, -1.79, 0, -0.79, 0;
  v_catch << -0.151, 3.974, -0.121, -0.673, 0.039, 1.305, 0; 
  v_throw << -0.151, -4.050, -0.121, 0.559, 0.039, -1.322, 0;

  const int kNumPositions = 7;
  const int kNumControlPoints = 21;
  KinematicTrajectoryOptimization trajopt(kNumPositions, kNumControlPoints);

  trajopt.AddVelocityBounds(VectorXd::Constant(7, -10),
                            VectorXd::Constant(7, 10));

  trajopt.AddDurationConstraint(2 * kDuration, 2 * kDuration);

  trajopt.AddPathPositionConstraint(q_catch, q_catch, 0);
  trajopt.AddPathPositionConstraint(q_throw, q_throw, 0.5);
  trajopt.AddPathPositionConstraint(q_catch, q_catch, 1);

  trajopt.AddPathVelocityConstraint(v_catch, v_catch, 0);
  trajopt.AddPathVelocityConstraint(v_throw, v_throw, 0.5);
  trajopt.AddPathVelocityConstraint(v_catch, v_catch, 1);

  std::cout << trajopt.prog() << std::endl;

  solvers::IpoptSolver solver;
  auto result = solver.Solve(trajopt.prog());

  EXPECT_TRUE(result.is_success());
}

I spent some time with it (@hongkai-dai did, too). But didn't pinpoint the failure yet.

@sammy-tri -- i believe you were the original author of this interface and might be more familiar. Hope it's ok to pass this one over to you.

RussTedrake commented 1 year ago

Since I didn't mention it specifically, this program has ONLY linear and bounding box constraints (and no objectives). So it's pretty simple.

sammy-tri commented 1 year ago

Will take a look.

sammy-tri commented 1 year ago

I'm going to need to timebox this for today, but here's what I've learned so far.

There doesn't seem to be anything obviously wrong with the (few) calls that Ipopt makes back into our interface before the segfault (no weird lengths or pointers, anyway), at least after a quick glance.

If run in valgrind, there are some bad memory accesses deep inside mumps (like, it looks like inside the fortran code) before the final bad memory access and the segfault.

It's possible to make the test arrive at a solution by adding/subtracting a tiny epsilon to the upper and lower bounds passed to AddDurationConstraint. This also makes the valgrind complaints inside mumps go away.

So I'm thinking that the structure of the problem isn't itself causing the problem (number of constraints, number of variables, etc). I'm not sure I can get any further without rebuilding from source and digging around inside of mumps though, which I don't think I'm going to get to in the near future.