44 #ifndef ILQGAMES_SOLVER_GAME_SOLVER_H    45 #define ILQGAMES_SOLVER_GAME_SOLVER_H    47 #include <ilqgames/dynamics/multi_player_dynamical_system.h>    48 #include <ilqgames/dynamics/multi_player_integrable_system.h>    49 #include <ilqgames/solver/lq_feedback_solver.h>    50 #include <ilqgames/solver/lq_open_loop_solver.h>    51 #include <ilqgames/solver/lq_solver.h>    52 #include <ilqgames/solver/problem.h>    53 #include <ilqgames/solver/solver_params.h>    54 #include <ilqgames/utils/linear_dynamics_approximation.h>    55 #include <ilqgames/utils/loop_timer.h>    56 #include <ilqgames/utils/operating_point.h>    57 #include <ilqgames/utils/quadratic_cost_approximation.h>    58 #include <ilqgames/utils/solver_log.h>    59 #include <ilqgames/utils/strategy.h>    60 #include <ilqgames/utils/types.h>    62 #include <glog/logging.h>    74 static constexpr 
size_t kMaxLoopTimesToRecord = 10;
    83   virtual std::shared_ptr<SolverLog> Solve(
    84       bool* success = 
nullptr, Time max_runtime = constants::kInfinity) = 0;
    87   Problem& GetProblem() { 
return *problem_; }
    90   GameSolver(
const std::shared_ptr<Problem>& problem,
    92       : problem_(problem), params_(params), timer_(kMaxLoopTimesToRecord) {
    93     CHECK_NOTNULL(problem_.get());
    94     CHECK_NOTNULL(problem_->Dynamics().get());
    99   virtual std::shared_ptr<SolverLog> CreateNewLog()
 const {
   100     return std::make_shared<SolverLog>();
   104   const std::shared_ptr<Problem> problem_;