ilqgames
A new real-time solver for large-scale differential games.
problem.h
1 /*
2  * Copyright (c) 2019, The Regents of the University of California (Regents).
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are
7  * met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  *
12  * 2. Redistributions in binary form must reproduce the above
13  * copyright notice, this list of conditions and the following
14  * disclaimer in the documentation and/or other materials provided
15  * with the distribution.
16  *
17  * 3. Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS AS IS
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
25  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
26  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
27  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
28  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
29  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
30  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  * Please contact the author(s) of this library if you have any questions.
34  * Authors: David Fridovich-Keil ( dfk@eecs.berkeley.edu )
35  */
36 
37 ///////////////////////////////////////////////////////////////////////////////
38 //
39 // Base class specifying the problem interface for managing calls to the core
40 // ILQGame solver. Specific examples will be derived from this class.
41 //
42 ///////////////////////////////////////////////////////////////////////////////
43 
44 #ifndef ILQGAMES_SOLVER_PROBLEM_H
45 #define ILQGAMES_SOLVER_PROBLEM_H
46 
47 #include <ilqgames/cost/player_cost.h>
48 #include <ilqgames/dynamics/multi_player_dynamical_system.h>
49 #include <ilqgames/dynamics/multi_player_flat_system.h>
50 #include <ilqgames/dynamics/multi_player_integrable_system.h>
51 #include <ilqgames/utils/solver_log.h>
52 #include <ilqgames/utils/strategy.h>
53 #include <ilqgames/utils/types.h>
54 
55 #include <limits>
56 #include <memory>
57 #include <vector>
58 
59 namespace ilqgames {
60 
61 class Problem {
62  public:
63  virtual ~Problem() {}
64 
65  // Initialize this object.
66  virtual void Initialize() {
67  ConstructDynamics();
68  ConstructPlayerCosts();
69  ConstructInitialState();
70  ConstructInitialOperatingPoint();
71  ConstructInitialStrategies();
72  initialized_ = true;
73  }
74 
75  // Reset the initial time and change nothing else.
76  void ResetInitialTime(Time t0) {
77  CHECK(initialized_);
78  operating_point_->t0 = t0;
79  }
80 
81  void ResetInitialState(const VectorXf& x0) {
82  CHECK(initialized_);
83  x0_ = x0;
84  }
85 
86  // Update initial state and modify previous strategies and operating
87  // points to start at the specified runtime after the current time t0.
88  // Since time is continuous and we will want to maintain the same fixed
89  // discretization, we will integrate x0 forward from t0 by approximately
90  // planner_runtime, then find the nearest state in the existing plan to that
91  // state, and start from there. By default, extends operating points and
92  // strategies as follows:
93  // 1. new controls are zero
94  // 2. new states are those that result from zero control
95  // 3. new strategies are also zero
96  virtual void SetUpNextRecedingHorizon(const VectorXf& x0, Time t0,
97  Time planner_runtime = 0.1);
98 
99  // Overwrite existing solution with the given operating point and strategies.
100  // Truncates to fit in the same memory.
101  virtual void OverwriteSolution(const OperatingPoint& operating_point,
102  const std::vector<Strategy>& strategies);
103 
104  // Accessors.
105  bool IsConstrained() const;
106  virtual Time InitialTime() const { return operating_point_->t0; }
107  const VectorXf& InitialState() const { return x0_; }
108  // size_t NumTimeSteps() const { return num_time_steps_; }
109  // Time TimeStep() const { return time_step_; }
110  // Time TimeHorizon() const { return time_horizon_; }
111  std::vector<PlayerCost>& PlayerCosts() { return player_costs_; }
112  const std::vector<PlayerCost>& PlayerCosts() const { return player_costs_; }
113  const std::shared_ptr<const MultiPlayerIntegrableSystem>& Dynamics() const {
114  return dynamics_;
115  }
116  const MultiPlayerDynamicalSystem& NormalDynamics() const {
117  CHECK(!dynamics_->TreatAsLinear());
118  return *static_cast<const MultiPlayerDynamicalSystem*>(dynamics_.get());
119  }
120  const MultiPlayerFlatSystem& FlatDynamics() const {
121  CHECK(dynamics_->TreatAsLinear());
122  return *static_cast<const MultiPlayerFlatSystem*>(dynamics_.get());
123  }
124  virtual const OperatingPoint& CurrentOperatingPoint() const {
125  return *operating_point_;
126  }
127  virtual const std::vector<Strategy>& CurrentStrategies() const {
128  return *strategies_;
129  }
130 
131  protected:
132  Problem();
133 
134  // Functions for initialization. By default, operating point and strategies
135  // are initialized to zero.
136  virtual void ConstructDynamics() = 0;
137  virtual void ConstructPlayerCosts() = 0;
138  virtual void ConstructInitialState() = 0;
139  virtual void ConstructInitialOperatingPoint() {
140  operating_point_.reset(
141  new OperatingPoint(time::kNumTimeSteps, 0.0, dynamics_));
142  }
143  virtual void ConstructInitialStrategies() {
144  strategies_.reset(new std::vector<Strategy>());
145  for (PlayerIndex ii = 0; ii < dynamics_->NumPlayers(); ii++)
146  strategies_->emplace_back(time::kNumTimeSteps, dynamics_->XDim(),
147  dynamics_->UDim(ii));
148  }
149 
150  // Utility used by SetUpNextRecedingHorizon. Integrate the given state
151  // forward, set the new initial state and time, and return the first timestep
152  // in the new problem.
153  size_t SyncToExistingProblem(const VectorXf& x0, Time t0,
154  Time planner_runtime, OperatingPoint& op);
155 
156  // // Time horizon (s), time step (s), and number of time steps.
157  // const Time time_horizon_;
158  // const Time time_step_;
159  // const size_t num_time_steps_;
160 
161  // Dynamical system.
162  std::shared_ptr<const MultiPlayerIntegrableSystem> dynamics_;
163 
164  // Player costs. These will not change during operation of this solver.
165  std::vector<PlayerCost> player_costs_;
166 
167  // Initial condition.
168  VectorXf x0_;
169 
170  // Strategies and operating points for all players.
171  std::unique_ptr<OperatingPoint> operating_point_;
172  std::unique_ptr<std::vector<Strategy>> strategies_;
173 
174  // Has this object been initialized?
175  bool initialized_;
176 }; // class Problem
177 
178 } // namespace ilqgames
179 
180 #endif