[
  {
    "path": ".gitignore",
    "content": "## MATLAB files to ignore ##\n\n# Windows default autosave extension\n*.asv\n\n# OSX / *nix default autosave extension\n*.m~\n\n# Compiled MEX binaries (all platforms)\n*.mex*\n\n# Packaged app and toolbox files\n*.mlappinstall\n*.mltbx\n\n# Generated helpsearch folders\nhelpsearch*/\n\n# Simulink code generation folders\nslprj/\nsccprj/\n\n# Matlab code generation folders\ncodegen/\n\n# Simulink autosave extension\n*.autosave\n\n# Simulink cache files\n*.slxc\n\n# Octave session info\noctave-workspace\n"
  },
  {
    "path": "LICENSE",
    "content": "MIT License\n\nCopyright (c) 2021 Jun Zeng\n\nPermission is hereby granted, free of charge, to any person obtaining a copy\nof this software and associated documentation files (the \"Software\"), to deal\nin the Software without restriction, including without limitation the rights\nto use, copy, modify, merge, publish, distribute, sublicense, and/or sell\ncopies of the Software, and to permit persons to whom the Software is\nfurnished to do so, subject to the following conditions:\n\nThe above copyright notice and this permission notice shall be included in all\ncopies or substantial portions of the Software.\n\nTHE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR\nIMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,\nFITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE\nAUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER\nLIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,\nOUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE\nSOFTWARE.\n"
  },
  {
    "path": "README.md",
    "content": "**Status**: The implementation code for corresponding papers will be merged here and new papers will be added in an inverse order of submission.\n\n### Introduction\n\nIn this repository, a collection of our work is presented where nonlinear model predictive control (NMPC) with control Lyapunov functions (CLFs) and control barrier functions (CBFs) are applied.\n\n### Dependencies\nThe packages needed for running the code are [Yalmip](https://yalmip.github.io/) and [IPOPT](https://projects.coin-or.org/Ipopt/wiki/MatlabInterface).\n\nWe also provide the zipped version of precompiled .mex files for IPOPT in the folder `packages` in case you don't have it. Unzip the file based on the operating system and add those .mex files into your MATLAB path.\n\n### Citing\n\n#### Theoretical Publications\n\nIf you find this project useful in your work, please consider citing following work:\n\n* S. Liu, J. Zeng, K. Sreenath and C. Belta. \"Iterative Convex Optimization for Model Predictive Control with Discrete-Time High-Order Control Barrier Functions.\" *2023 IEEE American Control Conference (ACC)*. [[arXiv]](https://arxiv.org/abs/2210.04361) [[Docs]](matlab/acc2023/README.md) [[Code]](matlab/acc2023) [[BibTex]](bibtex/acc2023_impc_dhocbf.md)\n\n* A. Thirugnanam, J. Zeng, K. Sreenath. \"Safety-Critical Control and Planning for Obstacle Avoidance between Polytopes with Control Barrier Functions.\" *2022 IEEE International Conference on Robotics and Automation (ICRA)*. [[IEEE]](https://ieeexplore.ieee.org/document/9812334) [[arXiv]](https://arxiv.org/abs/2109.12313) [[Video]](https://youtu.be/wucophROPRY) [[BibTex]](bibtex/icra2022_nmpc_dcbf_polytope.md)\n\n* J. Zeng, Z. Li, K. Sreenath. \"Enhancing Feasibility and Safety of Nonlinear Model Predictive Control with Discrete-Time Control Barrier Functions.\" *2021 IEEE Conference on Decision and Control (CDC)*. [[IEEE]](https://ieeexplore.ieee.org/document/9683174) [[arXiv]](https://arxiv.org/abs/2105.10596) [[Docs]](matlab/cdc2021/README.md) [[Code]](matlab/cdc2021) [[BibTex]](bibtex/cdc2022_nmpc_dcbf_feasibility.md)\n\n* J. Zeng, B. Zhang and K. Sreenath. \"Safety-Critical Model Predictive Control with Discrete-Time Control Barrier Function.\" *2021 IEEE American Control Conference (ACC)*. [[IEEE]](https://ieeexplore.ieee.org/document/9483029) [[arXiv]](https://arxiv.org/abs/2007.11718) [[Docs]](matlab/acc2021/README.md) [[Code]](matlab/acc2021) [[BibTex]](bibtex/acc2021_nmpc_dcbf.md)\n\n#### Applicational Publications\n\n* Z. Li, J. Zeng, A. Thirugnanam, K. Sreenath. \"Bridging Model-based Safety and Model-free Reinforcement Learning through System Identification of Low Dimensional Linear Models.\" *2022 Proceedings of Robotics: Science and Systems (RSS)*. [[RSS]](http://www.roboticsproceedings.org/rss18/p033.html) [[arXiv]](https://arxiv.org/abs/2205.05787) [[BibTex]](bibtex/rss2022_nmpc_dcbf_legged_robots.md) [[Webpage]](https://sites.google.com/berkeley.edu/rl-sysid-rss2022/home)\n"
  },
  {
    "path": "bibtex/acc2021_nmpc_dcbf.md",
    "content": "```\n@inproceedings{zeng2021mpccbf,\n  title={Safety-critical model predictive control with discrete-time control barrier function},\n  author={Zeng, Jun and Zhang, Bike and Sreenath, Koushil},\n  booktitle={2021 American Control Conference (ACC)},\n  year={2021},\n  volume={},\n  number={},\n  pages={3882-3889}\n}\n```"
  },
  {
    "path": "bibtex/acc2023_impc_dhocbf.md",
    "content": "```\n@inproceedings{liu2023iterative,\n  title={Iterative Convex Optimization for Model Predictive Control with Discrete-Time High-Order Control Barrier Functions},\n  author={Liu, Shuo and Zeng, Jun and Sreenath, Koushil and Belta, Calin A},\n  booktitle={2023 American Control Conference (ACC)},\n  year={2023}\n}\n```"
  },
  {
    "path": "bibtex/cdc2022_nmpc_dcbf_feasibility.md",
    "content": "```\n@inproceedings{zeng2021mpccbf-feasibility,\n  title={Enhancing feasibility and safety of nonlinear model predictive control with discrete-time control barrier functions},\n  author={Zeng, Jun and Li, Zhongyu and Sreenath, Koushil},\n  booktitle={2021 Conference on Decision and Control (CDC)},\n  year={2021},\n  volume={},\n  number={},\n  pages={6137-6144}\n}\n``` "
  },
  {
    "path": "bibtex/icra2022_nmpc_dcbf_polytope.md",
    "content": "```\n@inproceedings{thirugnanam2021safetycritical,\n  author={Thirugnanam, Akshay and Zeng, Jun and Sreenath, Koushil},\n  booktitle={2022 International Conference on Robotics and Automation (ICRA)}, \n  title={Safety-Critical Control and Planning for Obstacle Avoidance between Polytopes with Control Barrier Functions}, \n  year={2022},\n  volume={},\n  number={},\n  pages={286-292},\n}\n```"
  },
  {
    "path": "bibtex/rss2022_nmpc_dcbf_legged_robots.md",
    "content": "```\n@inproceedings{li2022bridging, \n    author = {Li, Zhongyu and Zeng, Jun and Thirugnanam, Akshay and Sreenath, Koushil}, \n    title = {{Bridging Model-based Safety and Model-free Reinforcement Learning through System Identification of Low Dimensional Linear Models}}, \n    booktitle = {Proceedings of Robotics: Science and Systems}, \n    year = {2022}, \n    address = {New York City, NY, USA}, \n    month = {June}, \n}\n```"
  },
  {
    "path": "matlab/acc2021/DCLFDCBF.m",
    "content": "classdef DCLFDCBF < handle\n    properties\n        system\n        params\n        x0\n        x_curr\n        time_curr = 0.0\n        xlog = []\n        ulog = []\n        u_cost = 0\n        obs\n    end\n    \n    methods\n        function self = DCLFDCBF(x0, system, params)\n            % Define DCLF-DCBF controller\n            self.x0 = x0;\n            self.x_curr = x0;\n            self.system = system;\n            self.params = params;\n        end\n        \n        function sim(self, time)\n            % Simulate the system until a given time\n            xk = self.x_curr;\n            while self.time_curr <= time\n                % Solve DCLF-DCBF\n                uk = self.solveDCLFDCBF();\n                xk = self.system.A * xk + self.system.B * uk;\n                % update system\n                self.x_curr = xk;\n                self.time_curr = self.time_curr + self.system.dt;\n                self.xlog = [self.xlog, xk];\n                self.ulog = [self.ulog, uk];\n                self.u_cost = self.u_cost + uk'*uk*self.system.dt;\n            end\n        end\n        \n        function uopt = solveDCLFDCBF(self)\n            % Solve DCLF-DCBF\n            x = self.x_curr;\n            u = sdpvar(2,1);\n            delta = sdpvar(1,1);\n            constraints = [];\n            % add DCLF constraints\n            x_next = self.system.A * x + self.system.B * u;\n            v = x' * self.params.P * x;\n            v_next = x_next' * self.params.P * x_next;\n            constraints = [constraints; v_next - v + self.params.alpha * v <= delta];\n            % add DCBF constraints\n            pos = self.obs.pos;\n            r = self.obs.r;\n            b = (x(1:2)-pos)'*(x(1:2)-pos) - r^2;\n            b_next = (x_next(1:2)-pos)'*(x_next(1:2)-pos) - r^2;\n            constraints = [constraints; b_next - b + self.params.gamma*b >= 0];\n            % input constraints\n            constraints = [constraints; self.system.ul <= u <= self.system.uu];\n            % cost\n            cost = u'*self.params.H*u + delta'*self.params.p*delta;\n            % solve optimization\n            ops = sdpsettings('solver','ipopt','verbose',0);\n            diagnostics = optimize(constraints, cost, ops);\n            if diagnostics.problem == 0\n                feas = true;\n                uopt = value(u);\n            else\n                feas = false;\n                uopt = [];\n            end\n            fprintf('solver time: %f\\n', diagnostics.solvertime);\n        end\n        \n        function plot(self,figure_name)\n            % Plot simulation\n            figure('Renderer', 'painters', 'Position', [0 0 400 400]);\n            set(gca,'LooseInset',get(gca,'TightInset'));\n            hold on;\n            % plot trajectory\n            plot(self.xlog(1,:), self.xlog(2,:), 'ko-',...\n                'LineWidth', 1.0,'MarkerSize',4);\n            % plot obstacle\n            pos = self.obs.pos;\n            r = self.obs.r;\n            th = linspace(0,2*pi*100);\n            x = cos(th) ; y = sin(th) ;\n            plot(pos(1) + r*x, pos(2) + r*y, 'Color', [0.8500, 0.3250, 0.0980], 'LineWidth', 2);\n            plot(pos(1), pos(2), 'Color', [0.8500, 0.3250, 0.0980], 'MarkerSize', 5, 'LineWidth', 2);\n            % plot target position\n            plot(self.x0(1), self.x0(2), 'db', 'LineWidth', 1);\n            plot(0.0, 0.0, 'dr', 'LineWidth', 1);\n            h=get(gca,'Children');\n            h_legend = legend(h([end]), {'DCLF-DCBF'}, 'Location', 'SouthEast');\n            set(h_legend, 'Interpreter','latex');\n            set(gca,'LineWidth', 0.2, 'FontSize', 15);\n            grid on\n            xlabel('$x (m)$','interpreter','latex','FontSize',20);\n            ylabel('$y (m)$','interpreter','latex','FontSize',20);\n            xticks(-5:0);\n            yticks(-5:0);\n            xlim([-5,0.2]);\n            ylim([-5,0.2]);\n            print(gcf,strcat('figures/',figure_name), '-depsc');\n        end\n    end\nend"
  },
  {
    "path": "matlab/acc2021/MPCCBF.m",
    "content": "classdef MPCCBF < handle\n    % MPC with distance constraints\n    properties\n        system\n        params\n        x0\n        x_curr\n        time_curr = 0.0\n        xlog = []\n        ulog = []\n        distlog = []\n        solvertime = []\n        xopenloop = {}\n        uopenloop = {}\n        u_cost = 0\n        obs\n    end\n    methods\n        function self = MPCCBF(x0, system, params)\n            % Define MPC_CBF controller\n            self.x0 = x0;\n            self.x_curr = x0;\n            self.system = system;\n            self.params = params;\n        end\n        \n        function sim(self, time)\n            % Simulate the system until a given time\n            xk = self.x_curr;\n            while self.time_curr <= time\n                % Solve CFTOC\n                [~, uk] = self.solveMPCCBF(self.x_curr);\n                xk = self.system.A * xk + self.system.B * uk;\n                % update system\n                self.x_curr = xk;\n                self.time_curr = self.time_curr + self.system.dt;\n                self.xlog = [self.xlog, xk];\n                self.ulog = [self.ulog, uk];\n                self.u_cost = self.u_cost + uk'*uk*self.system.dt;\n            end\n        end\n        \n        function [xopt, uopt] = solveMPCCBF(self, xk)\n            % Solve MPC-CBF\n            [feas, x, u, J] = self.solve_cftoc(xk);\n            if ~feas\n                xopt = [];\n                uopt = [];\n                return\n            else\n                xopt = x(:,2);\n                uopt = u(:,1);\n            end\n        end\n        \n        function [feas, xopt, uopt, Jopt] = solve_cftoc(self, xk)\n            % Solve CFTOC\n            % extract variables\n            N = self.params.N;\n            % define variables and cost\n            x = sdpvar(4, N+1);\n            u = sdpvar(2, N);\n            constraints = [];\n            cost = 0;\n            % initial constraint\n            constraints = [constraints; x(:,1) == xk];\n            % add constraints and costs\n            for i = 1:N\n                constraints = [constraints;\n                    self.system.xl <= x(:,i) <= self.system.xu;\n                    self.system.ul <= u(:,i) <= self.system.uu\n                    x(:,i+1) == self.system.A * x(:,i) + self.system.B * u(:,i)];\n                cost = cost + x(:,i)'*self.params.Q*x(:,i) + u(:,i)'*self.params.R*u(:,i);\n            end\n            % add CBF constraints\n            for i = 1:N\n                pos = self.obs.pos;\n                r = self.obs.r ;\n                b = (x([1:2],i)-pos)'*((x([1:2],i)-pos)) - r^2;\n                b_next = (x([1:2],i+1)-pos)'*((x([1:2],i+1)-pos)) - r^2;\n                constraints = [constraints; b_next - b + self.params.gamma * b >= 0];\n            end\n            % add terminal cost\n            cost = cost + x(:,N+1)'*self.params.P*x(:,N+1);\n            ops = sdpsettings('solver','ipopt','verbose',0);\n            % solve optimization\n            diagnostics = optimize(constraints, cost, ops);\n            if diagnostics.problem == 0\n                feas = true;\n                xopt = value(x);\n                uopt = value(u);\n                Jopt = value(cost);\n            else\n                feas = false;\n                xopt = [];\n                uopt = [];\n                Jopt = [];\n            end\n            self.distlog = [self.distlog, sqrt((xk(1:2)-pos)'*(xk(1:2)-pos)-r^2)];\n            self.xopenloop{size(self.xopenloop,2)+1} = xopt;\n            self.uopenloop{size(self.uopenloop,2)+1} = uopt;\n            self.solvertime = [self.solvertime, diagnostics.solvertime];\n            fprintf('solver time: %f\\n', diagnostics.solvertime);\n        end\n        \n        function plot(self, figure_name)\n            % Plot simulation\n            figure('Renderer', 'painters', 'Position', [0 0 400 400]);\n            set(gca,'LooseInset',get(gca,'TightInset'));\n            hold on;\n            % plot closed-loop trajectory\n            plot(self.xlog(1,:), self.xlog(2,:), 'ko-',...\n                'LineWidth', 1.0, 'MarkerSize', 4);\n            % plot open-loop trajectory\n            for i = 1:size(self.xopenloop, 2)\n                plot(self.xopenloop{i}(1,:), self.xopenloop{i}(2,:),...\n                    'k*-.', 'LineWidth', 0.5,'MarkerSize',0.5)\n            end\n            % plot obstacle\n            pos = self.obs.pos;\n            r = self.obs.r;\n            th = linspace(0,2*pi*100);\n            x = cos(th) ; y = sin(th) ;\n            plot(pos(1) + r*x, pos(2) + r*y, 'Color', [0.8500, 0.3250, 0.0980],...\n                'LineWidth', 2);\n            plot(pos(1), pos(2), 'Color', [0.8500, 0.3250, 0.0980],...\n                'MarkerSize', 5, 'LineWidth', 2);\n            % plot target position\n            plot(self.x0(1), self.x0(2), 'db', 'LineWidth', 1);\n            plot(0.0, 0.0, 'dr', 'LineWidth', 1);\n            h=get(gca,'Children');\n            h_legend = legend(h([end]), {'MPC-CBF'}, 'Location', 'SouthEast');\n            set(h_legend, 'Interpreter','latex');\n            set(gca,'LineWidth', 0.2, 'FontSize', 15);\n            grid on\n            xlabel('$x (m)$','interpreter','latex','FontSize',20);\n            ylabel('$y (m)$','interpreter','latex','FontSize',20);\n            xticks(-5:0);\n            yticks(-5:0);\n            xlim([-5,0.2]);\n            ylim([-5,0.2]);\n            print(gcf,strcat('figures/',figure_name), '-depsc');\n        end\n    end\nend"
  },
  {
    "path": "matlab/acc2021/MPCDC.m",
    "content": "classdef MPCDC < handle\n    % MPC with distance constraints\n    properties\n        system\n        params\n        x0\n        x_curr\n        time_curr = 0.0\n        xlog = []\n        ulog = []\n        distlog = []\n        solvertime = []\n        xopenloop = {}\n        uopenloop = {}\n        u_cost = 0\n        obs\n    end\n    methods\n        function self = MPCDC(x0, system, params)\n            % Define MPC_DC controller\n            self.x0 = x0;\n            self.x_curr = x0;\n            self.system = system;\n            self.params = params;\n        end\n        \n        function sim(self, time)\n            % Simulate the system until a given time\n            xk = self.x_curr;\n            while self.time_curr <= time\n                % Solve CFTOC\n                [~, uk] = self.solveMPCDC(self.x_curr);\n                xk = self.system.A * xk + self.system.B * uk;\n                % update system\n                self.x_curr = xk;\n                self.time_curr = self.time_curr + self.system.dt;\n                self.xlog = [self.xlog, xk];\n                self.ulog = [self.ulog, uk];\n                self.u_cost = self.u_cost + uk'*uk*self.system.dt;\n            end\n        end\n        \n        function [xopt, uopt] = solveMPCDC(self, xk)\n            % Solve MPC-DC\n            [feas, x, u, J] = self.solve_cftoc(xk);\n            if ~feas\n                xopt = [];\n                uopt = [];\n                return\n            else\n                xopt = x(:,2);\n                uopt = u(:,1);\n            end\n        end\n        \n        function [feas, xopt, uopt, Jopt] = solve_cftoc(self, xk)\n            % Solve CFTOC\n            % extract variables\n            N = self.params.N;\n            % define variables and cost\n            x = sdpvar(4, N+1);\n            u = sdpvar(2, N);\n            constraints = [];\n            cost = 0;\n            % initial constraint\n            constraints = [constraints; x(:,1) == xk];\n            % add constraints and costs\n            for i = 1:N\n                constraints = [constraints;\n                    self.system.xl <= x(:,i) <= self.system.xu;\n                    self.system.ul <= u(:,i) <= self.system.uu\n                    x(:,i+1) == self.system.A * x(:,i) + self.system.B * u(:,i)];\n                cost = cost + x(:,i)'*self.params.Q*x(:,i) + u(:,i)'*self.params.R*u(:,i);\n            end\n            % add CBF constraints\n            for i = 1:N\n                pos = self.obs.pos;\n                r = self.obs.r ;\n                b = (x([1:2],i)-pos)'*((x([1:2],i)-pos)) - r^2;\n                constraints = [constraints; b >= 0];\n            end\n            % add terminal cost\n            cost = cost + x(:,N+1)'*self.params.P*x(:,N+1);\n            ops = sdpsettings('solver','ipopt','verbose',0);\n            % solve optimization\n            diagnostics = optimize(constraints, cost, ops);\n            if diagnostics.problem == 0\n                feas = true;\n                xopt = value(x);\n                uopt = value(u);\n                Jopt = value(cost);\n            else\n                feas = false;\n                xopt = [];\n                uopt = [];\n                Jopt = [];\n            end\n            self.distlog = [self.distlog, sqrt((xk(1:2)-pos)'*(xk(1:2)-pos)-r^2)];\n            self.xopenloop{size(self.xopenloop,2)+1} = xopt;\n            self.uopenloop{size(self.uopenloop,2)+1} = uopt;\n            self.solvertime = [self.solvertime, diagnostics.solvertime];\n            fprintf('solver time: %f\\n', diagnostics.solvertime);\n        end\n        \n        function plot(self, figure_name)\n            % Plot simulation\n            figure('Renderer', 'painters', 'Position', [0 0 400 400]);\n            set(gca,'LooseInset',get(gca,'TightInset'));\n            hold on;\n            % plot closed-loop trajectory\n            plot(self.xlog(1,:), self.xlog(2,:), 'ko-',...\n                'LineWidth', 1.0, 'MarkerSize', 4);\n            % plot open-loop trajectory\n            for i = 1:size(self.xopenloop, 2)\n                plot(self.xopenloop{i}(1,:), self.xopenloop{i}(2,:),...\n                    'k*-.', 'LineWidth', 0.5,'MarkerSize',0.5)\n            end\n            % plot obstacle\n            pos = self.obs.pos;\n            r = self.obs.r;\n            th = linspace(0,2*pi*100);\n            x = cos(th) ; y = sin(th) ;\n            plot(pos(1) + r*x, pos(2) + r*y, 'Color', [0.8500, 0.3250, 0.0980],...\n                'LineWidth', 2);\n            plot(pos(1), pos(2), 'Color', [0.8500, 0.3250, 0.0980],...\n                'MarkerSize', 5, 'LineWidth', 2);\n            % plot target position\n            plot(self.x0(1), self.x0(2), 'db', 'LineWidth', 1);\n            plot(0.0, 0.0, 'dr', 'LineWidth', 1);\n            h=get(gca,'Children');\n            h_legend = legend(h([end]), {'MPC-DC'}, 'Location', 'SouthEast');\n            set(h_legend, 'Interpreter','latex');\n            set(gca,'LineWidth', 0.2, 'FontSize', 15);\n            grid on\n            xlabel('$x (m)$','interpreter','latex','FontSize',20);\n            ylabel('$y (m)$','interpreter','latex','FontSize',20);\n            xticks(-5:0);\n            yticks(-5:0);\n            xlim([-5,0.2]);\n            ylim([-5,0.2]);\n            print(gcf,strcat('figures/',figure_name), '-depsc');\n        end\n    end\nend"
  },
  {
    "path": "matlab/acc2021/README.md",
    "content": "## MPC-CBF-ACC2021\nWe propose a control framework which unifies the model predictive control and control barrier functions, where terminal cost function serves as control Lyapunov functions for stability. This is the reference implementation of our paper:\n\nIf you find this project useful in your work, please consider citing following work:\n```\n@inproceedings{zeng2021mpccbf,\n  title={Safety-critical model predictive control with discrete-time control barrier function},\n  author={Zeng, Jun and Zhang, Bike and Sreenath, Koushil},\n  booktitle={2021 American Control Conference (ACC)},\n  year={2021}\n}\n```\n\n### Instructions\nThe 2D double integrator is assigned to reach the target position at origin while avoiding obstacles. We have three classes for different controllers: `DCLFDCBF.m` (DCLF-DCBF), `MPCCBF.m` (MPC-CBF) and `MPCDC` (MPC-DC), respectively.\n\nMoreover, to illustrate the performance among them, we have:\n* `test.m`: Run DCLF-DCBF/MPC-CBF/MPC-DC respectively.\n* `testGamma.m`: Run analysis for different hyperparameter $\\gamma$.\n* `testHorizon.m`: Run analysis for different horizon.\n* `testBenchmark.m`: Run analysis for some benchmark."
  },
  {
    "path": "matlab/acc2021/figures/.gitignore",
    "content": "*.eps\n"
  },
  {
    "path": "matlab/acc2021/test.m",
    "content": "close all\nclear\n\n%% General Flags\nrun_dclf_dcbf = true;\ndisplay_dclf_dcbf = true;\nrun_mpc_cbf_one = true;\ndisplay_mpc_cbf_one = true;\nrun_mpc_cbf_multiple = true;\nrun_mpc_cbf_multiple = true;\nrun_mpc_dc = true;\ndisplay_mpc_dc = true;\n\n%% Setup and Parameters\nx0 = [-5; -5; 0; 0];\ntime_total = 30.0;\ndt = 0.2;\nP = 100*eye(4);\nQ = 10*eye(4);\nR = eye(2);\nN = 8;\nxmin = [-5; -5; -5; -5];\nxmax = [5; 5; 5; 5];\numin = [-1; -1];\numax = [1; 1];\n\n%% Discrete-time double integrator 2D\nsystem.dt = dt;\nsystem.A = [1 0 dt 0;\n    0 1 0 dt;\n    0 0 1 0;\n    0 0 0 1];\nsystem.B = [0.5*dt^2 0;\n    0 0.5*dt^2;\n    dt 0;\n    0 dt];\nsystem.xl = xmin;\nsystem.xu = xmax;\nsystem.ul = umin;\nsystem.uu = umax;\n\n%% DCLF-DCBF parameters\np = 1e3;\nparams_dclf_dcbf.P = P;\nparams_dclf_dcbf.H = R;\nparams_dclf_dcbf.p = p;\nparams_dclf_dcbf.alpha = 1.0;\nparams_dclf_dcbf.gamma = 0.4;\n\n%% MPC-CBF parameters\nparams_mpc_cbf.Q = Q;\nparams_mpc_cbf.R = R;\nparams_mpc_cbf.P = P;\nparams_mpc_cbf.N = N;\nparams_mpc_cbf.gamma = 0.4;\n\n%% MPC-DC parameters\nparams_mpc_dc.Q = Q;\nparams_mpc_dc.R = R;\nparams_mpc_dc.P = P;\nparams_mpc_dc.N = N;\n\n%% Obstacle\nobs.pos = [-2; -2.25];\nobs.r = 1.5;\n\n%% Simulate DCLF-DCBF\nif run_dclf_dcbf\n    fprintf('Run DCLF-DCBF\\n');\n    controller_dclf_dcbf = DCLFDCBF(x0, system, params_dclf_dcbf);\n    controller_dclf_dcbf.obs = obs;\n    controller_dclf_dcbf.sim(time_total);\nend\n\n%% Display DCLF-DCBF simulation\nif display_dclf_dcbf\n    % Plot simulation\n    figure('Renderer', 'painters', 'Position', [0 0 400 400]);\n    set(gca,'LooseInset',get(gca,'TightInset'));\n    hold on;\n    % plot trajectory\n    plot(controller_dclf_dcbf.xlog(1,:), controller_dclf_dcbf.xlog(2,:), 'ko-',...\n        'LineWidth', 1.0,'MarkerSize',4);\n    % plot obstacle\n    pos = controller_dclf_dcbf.obs.pos;\n    r = controller_dclf_dcbf.obs.r;\n    th = linspace(0,2*pi*100);\n    x = cos(th) ; y = sin(th) ;\n    plot(pos(1) + r*x, pos(2) + r*y, 'Color', [0.8500, 0.3250, 0.0980], 'LineWidth', 2);\n    plot(pos(1), pos(2), 'Color', [0.8500, 0.3250, 0.0980], 'MarkerSize', 5, 'LineWidth', 2);\n    % plot target position\n    plot(controller_dclf_dcbf.x0(1), controller_dclf_dcbf.x0(2), 'db', 'LineWidth', 1);\n    plot(0.0, 0.0, 'dr', 'LineWidth', 1);\n    h=get(gca,'Children');\n    h_legend = legend(h([end]), {'DCLF-DCBF'}, 'Location', 'SouthEast');\n    set(h_legend, 'Interpreter','latex');\n    set(gca,'LineWidth', 0.2, 'FontSize', 15);\n    grid on\n    xlabel('$x (m)$','interpreter','latex','FontSize',20);\n    ylabel('$y (m)$','interpreter','latex','FontSize',20);\n    xticks(-5:0);\n    yticks(-5:0);\n    xlim([-5,0.2]);\n    ylim([-5,0.2]);\n    print(gcf,'figures/dclf-dcbf-avoidance.eps', '-depsc');\n    print(gcf,'figures/dclf-dcbf-avoidance.png', '-dpng', '-r800');\nend\n\n%% Simulate MPC-CBF with N=1;\nparams_mpc_cbf.N = 1;\nif run_mpc_cbf_one\n    fprintf('Run MPC-CBF\\n');\n    controller_mpc_cbf_one = MPCCBF(x0, system, params_mpc_cbf);\n    controller_mpc_cbf_one.obs = obs;\n    controller_mpc_cbf_one.sim(time_total);\nend\n\n%% Display MPC-CBF simulation with N=1\nif display_mpc_cbf_one\n    % Plot simulation\n    figure('Renderer', 'painters', 'Position', [0 0 400 400]);\n    set(gca,'LooseInset',get(gca,'TightInset'));\n    hold on;\n    % plot trajectory\n    plot(controller_mpc_cbf_one.xlog(1,:), controller_mpc_cbf_one.xlog(2,:), 'ko-',...\n        'LineWidth', 1.0,'MarkerSize',4);\n    % plot obstacle\n    pos = controller_mpc_cbf_one.obs.pos;\n    r = controller_mpc_cbf_one.obs.r;\n    th = linspace(0,2*pi*100);\n    x = cos(th) ; y = sin(th) ;\n    plot(pos(1) + r*x, pos(2) + r*y, 'Color', [0.8500, 0.3250, 0.0980], 'LineWidth', 2);\n    plot(pos(1), pos(2), 'Color', [0.8500, 0.3250, 0.0980], 'MarkerSize', 5, 'LineWidth', 2);\n    % plot target position\n    plot(controller_mpc_cbf_one.x0(1), controller_mpc_cbf_one.x0(2), 'db', 'LineWidth', 1);\n    plot(0.0, 0.0, 'dr', 'LineWidth', 1);\n    h=get(gca,'Children');\n    h_legend = legend(h([end]), {'MPC-CBF ($N=1$)'}, 'Location', 'SouthEast');\n    set(h_legend, 'Interpreter','latex');\n    set(gca,'LineWidth', 0.2, 'FontSize', 15);\n    grid on\n    xlabel('$x (m)$','interpreter','latex','FontSize',20);\n    ylabel('$y (m)$','interpreter','latex','FontSize',20);\n    xticks(-5:0);\n    yticks(-5:0);\n    xlim([-5,0.2]);\n    ylim([-5,0.2]);\n    print(gcf, 'figures/mpc-cbf-avoidance-one-step.eps', '-depsc');\n    print(gcf, 'figures/mpc-cbf-avoidance-one-step.png', '-dpng', '-r800');\nend\n\n%% Simulate MPC-CBF with other N\nparams_mpc_cbf.N = 8;\nif run_mpc_cbf_one\n    fprintf('Run MPC-CBF\\n');\n    controller_mpc_cbf_multiple = MPCCBF(x0, system, params_mpc_cbf);\n    controller_mpc_cbf_multiple.obs = obs;\n    controller_mpc_cbf_multiple.sim(time_total);\nend\n\n%% Display MPC-CBF simulation with other N\nif display_mpc_cbf_one\n    % Plot simulation\n    figure('Renderer', 'painters', 'Position', [0 0 400 400]);\n    set(gca,'LooseInset',get(gca,'TightInset'));\n    hold on;\n    % plot trajectory\n    plot(controller_mpc_cbf_multiple.xlog(1,:), controller_mpc_cbf_multiple.xlog(2,:), 'ko-',...\n        'LineWidth', 1.0,'MarkerSize',4);\n    % plot obstacle\n    pos = controller_mpc_cbf_multiple.obs.pos;\n    r = controller_mpc_cbf_multiple.obs.r;\n    th = linspace(0,2*pi*100);\n    x = cos(th) ; y = sin(th) ;\n    plot(pos(1) + r*x, pos(2) + r*y, 'Color', [0.8500, 0.3250, 0.0980], 'LineWidth', 2);\n    plot(pos(1), pos(2), 'Color', [0.8500, 0.3250, 0.0980], 'MarkerSize', 5, 'LineWidth', 2);\n    % plot target position\n    plot(controller_mpc_cbf_multiple.x0(1), controller_mpc_cbf_multiple.x0(2), 'db', 'LineWidth', 1);\n    plot(0.0, 0.0, 'dr', 'LineWidth', 1);\n    h=get(gca,'Children');\n    h_legend = legend(h([end]), {'MPC-CBF ($N=8$)'}, 'Location', 'SouthEast');\n    set(h_legend, 'Interpreter','latex');\n    set(gca,'LineWidth', 0.2, 'FontSize', 15);\n    grid on\n    xlabel('$x (m)$','interpreter','latex','FontSize',20);\n    ylabel('$y (m)$','interpreter','latex','FontSize',20);\n    xticks(-5:0);\n    yticks(-5:0);\n    xlim([-5,0.2]);\n    ylim([-5,0.2]);\n    print(gcf, 'figures/mpc-cbf-avoidance-several-steps.eps', '-depsc');\n    print(gcf, 'figures/mpc-cbf-avoidance-several-steps.png', '-dpng', '-r800');\nend\n\n%% Simulate MPC-DC\nif run_mpc_dc\n    fprintf('Run MPC-DC\\n');\n    controller_mpc_dc = MPCDC(x0, system, params_mpc_dc);\n    controller_mpc_dc.obs = obs;\n    controller_mpc_dc.sim(time_total);\nend\n\n%% Display MPC-DC simulation\nif display_mpc_dc\n    % Plot simulation\n    figure('Renderer', 'painters', 'Position', [0 0 400 400]);\n    set(gca,'LooseInset',get(gca,'TightInset'));\n    hold on;\n    % plot trajectory\n    plot(controller_mpc_dc.xlog(1,:), controller_mpc_dc.xlog(2,:), 'ko-',...\n        'LineWidth', 1.0,'MarkerSize',4);\n    % plot obstacle\n    pos = controller_mpc_dc.obs.pos;\n    r = controller_mpc_dc.obs.r;\n    th = linspace(0,2*pi*100);\n    x = cos(th) ; y = sin(th) ;\n    plot(pos(1) + r*x, pos(2) + r*y, 'Color', [0.8500, 0.3250, 0.0980], 'LineWidth', 2);\n    plot(pos(1), pos(2), 'Color', [0.8500, 0.3250, 0.0980], 'MarkerSize', 5, 'LineWidth', 2);\n    % plot target position\n    plot(controller_mpc_dc.x0(1), controller_mpc_dc.x0(2), 'db', 'LineWidth', 1);\n    plot(0.0, 0.0, 'dr', 'LineWidth', 1);\n    h=get(gca,'Children');\n    h_legend = legend(h([end]), {'MPC-DC ($N=8$)'}, 'Location', 'SouthEast');\n    set(h_legend, 'Interpreter','latex');\n    set(gca,'LineWidth', 0.2, 'FontSize', 15);\n    grid on\n    xlabel('$x (m)$','interpreter','latex','FontSize',20);\n    ylabel('$y (m)$','interpreter','latex','FontSize',20);\n    xticks(-5:0);\n    yticks(-5:0);\n    xlim([-5,0.2]);\n    ylim([-5,0.2]);\n    print(gcf, 'figures/mpc-dc-avoidance.eps', '-depsc');\n    print(gcf, 'figures/mpc-dc-avoidance.png', '-dpng', '-r800');\nend"
  },
  {
    "path": "matlab/acc2021/testBenchmark.m",
    "content": "close all\nclear\n\n%% Setup and Parameters\nx0 = [-5; -5; 0; 0];\ntime_total = 20.0;\ndt = 0.2;\nP = 100*eye(4);\nQ = 10*eye(4);\nR = eye(2);\nN = 8;\nxmin = [-5; -5; -5; -5];\nxmax = [5; 5; 5; 5];\numin = [-1; -1];\numax = [1; 1];\n\n%% Discrete-time double integrator 2D\nsystem.dt = dt;\nsystem.A = [1 0 dt 0;\n    0 1 0 dt;\n    0 0 1 0;\n    0 0 0 1];\nsystem.B = [0.5*dt^2 0;\n    0 0.5*dt^2;\n    dt 0;\n    0 dt];\nsystem.xl = xmin;\nsystem.xu = xmax;\nsystem.ul = umin;\nsystem.uu = umax;\n\n%% MPC-CBF parameters\nparams.Q = Q;\nparams.R = R;\nparams.P = P;\nparams.N = N;\nparams.gamma = 0.5;\n\n%% Obstacle\nobs.pos = [-2; -2.25];\nobs.r = 1.5;\n\n%% Simulate MPC-CBF\ngamma_list = linspace(0.1, 0.5, 5);\ncontroller_mpc_cbf_list = {};\nfor i = 1:size(gamma_list, 2)\n    new_params = params;\n    new_params.N = 5;\n    new_params.gamma = gamma_list(i);\n    controller_mpc_cbf = MPCCBF(x0, system, new_params);\n    controller_mpc_cbf.obs = obs;\n    controller_mpc_cbf.sim(time_total);\n    controller_mpc_cbf_list{i} = controller_mpc_cbf;\nend\n\n%% Computational time benchmark\nfor i = 1:size(gamma_list, 2)\n    controller_mpc_cbf = controller_mpc_cbf_list{i};\n    fprintf('Computational time for MPC-CBF3: mean %.3f, std %.3f, min %.3f, max %.3f, input cost %.3f, min dist %f\\n',...\n    [mean(controller_mpc_cbf.solvertime),...\n    std(controller_mpc_cbf.solvertime),...\n    min(controller_mpc_cbf.solvertime),...\n    max(controller_mpc_cbf.solvertime),...\n    controller_mpc_cbf.u_cost,...\n    min(controller_mpc_cbf.distlog)]);\nend"
  },
  {
    "path": "matlab/acc2021/testGamma.m",
    "content": "close all\nclear\n\n%% Setup and Parameters\nx0 = [-5; -5; 0; 0];\ntime_total = 20.0;\ndt = 0.2;\nP = 100*eye(4);\nQ = 10*eye(4);\nR = eye(2);\nN = 8;\nxmin = [-5; -5; -5; -5];\nxmax = [5; 5; 5; 5];\numin = [-1; -1];\numax = [1; 1];\n\n%% Discrete-time double integrator 2D\nsystem.dt = dt;\nsystem.A = [1 0 dt 0;\n    0 1 0 dt;\n    0 0 1 0;\n    0 0 0 1];\nsystem.B = [0.5*dt^2 0;\n    0 0.5*dt^2;\n    dt 0;\n    0 dt];\nsystem.xl = xmin;\nsystem.xu = xmax;\nsystem.ul = umin;\nsystem.uu = umax;\n\n%% MPC-CBF parameters\nparams_mpc_cbf.Q = Q;\nparams_mpc_cbf.R = R;\nparams_mpc_cbf.P = P;\nparams_mpc_cbf.N = N;\nparams_mpc_cbf.gamma = 0.5;\n\n%% Obstacle\nobs.pos = [-2; -2.25];\nobs.r = 1.5;\n\n%% Simulate MPC-CBF\ngamma_list = [0.1, 0.2, 0.3, 1.0]; \nfor ind = 1:size(gamma_list, 2)\n    fprintf('Run MPC-CBF with gamma %f\\n', gamma_list(ind));\n    params_mpc_cbf.gamma = gamma_list(ind);\n    controller_mpc_cbf_list{ind} = MPCCBF(x0, system, params_mpc_cbf);\n    controller_mpc_cbf_list{ind}.obs = obs;\n    controller_mpc_cbf_list{ind}.sim(time_total);\nend\n\n%% Simulate MPC-DC\nparams_mpc_dc = params_mpc_cbf;\ncontroller_mpc_dc = MPCDC(x0, system, params_mpc_cbf);\ncontroller_mpc_dc.obs = obs;\ncontroller_mpc_dc.sim(time_total);\n\n%% Visualization benchmark\nfigure('Renderer', 'painters', 'Position', [0 0 400 400]);\nset(gca,'LooseInset',get(gca,'TightInset'));\nhold on\nfor ind = 1:size(gamma_list, 2)\n    plot(controller_mpc_cbf_list{ind}.xlog(1,:), controller_mpc_cbf_list{ind}.xlog(2,:),...\n        '-', 'LineWidth', 1.0, 'MarkerSize', 4);\nend\nplot(controller_mpc_dc.xlog(1,:), controller_mpc_dc.xlog(2,:),...\n    'k--', 'LineWidth', 1.0, 'MarkerSize', 4);\n% plot obstacle\npos = obs.pos;\nr = obs.r;\nth = linspace(0,2*pi*100);\nx = cos(th) ; y = sin(th) ;\nplot(pos(1) + r*x, pos(2) + r*y, 'Color', [0.8500, 0.3250, 0.0980],...\n    'LineWidth', 2);\nplot(pos(1), pos(2), 'Color', [0.8500, 0.3250, 0.0980],...\n    'MarkerSize', 5, 'LineWidth', 2);\n% plot target position\nplot(x0(1), x0(2), 'db', 'LineWidth', 1);\nplot(0.0, 0.0, 'dr', 'LineWidth', 1);\nh=get(gca,'Children');\nh_legend = legend(h([end, end-1, end-2, end-3, end-4]),...\n    {'MPC-CBF ($\\gamma=0.1$)', 'MPC-CBF ($\\gamma=0.2$)',...\n    'MPC-CBF ($\\gamma=0.3$)', 'MPC-CBF ($\\gamma=1.0$)', 'MPC-DC'}, 'Location', 'SouthEast');\nset(h_legend, 'Interpreter','latex');\nset(gca,'LineWidth', 0.2, 'FontSize', 15);\ngrid on\nxlabel('$x (m)$','interpreter','latex','FontSize',20);\nylabel('$y (m)$','interpreter','latex','FontSize',20);\nxticks(-5:1);\nyticks(-5:1);\nxlim([-5,0.2]);\nylim([-5,0.2]);\nprint(gcf,'figures/benchmark-gamma.eps', '-depsc');\nprint(gcf,'figures/benchmark-gamma.png', '-dpng', '-r800');"
  },
  {
    "path": "matlab/acc2021/testHorizon.m",
    "content": "close all\nclear\n\n%% Setup and Parameters\nx0 = [-5; -5; 0; 0];\ntime_total = 20.0;\ndt = 0.2;\nP = 100*eye(4);\nQ = 10*eye(4);\nR = eye(2);\nN = 8;\nxmin = [-5; -5; -5; -5];\nxmax = [5; 5; 5; 5];\numin = [-1; -1];\numax = [1; 1];\n\n%% Discrete-time double integrator 2D\nsystem.dt = dt;\nsystem.A = [1 0 dt 0;\n    0 1 0 dt;\n    0 0 1 0;\n    0 0 0 1];\nsystem.B = [0.5*dt^2 0;\n    0 0.5*dt^2;\n    dt 0;\n    0 dt];\nsystem.xl = xmin;\nsystem.xu = xmax;\nsystem.ul = umin;\nsystem.uu = umax;\n\n%% MPC-CBF parameters\nparams.Q = Q;\nparams.R = R;\nparams.P = P;\nparams.N = N;\nparams.gamma = 0.5;\n\n%% Obstacle\nobs.pos = [-2; -2.25];\nobs.r = 1.5;\n\n%% Simulate MPC-CBF\nparams.N = 5;\nparams.gamma = 0.25;\ncontroller_mpc_cbf_1 = MPCCBF(x0, system, params);\ncontroller_mpc_cbf_1.obs = obs;\ncontroller_mpc_cbf_1.sim(time_total);\n\n%% Simulate MPC-CBF with lower gamma\nparams.gamma = 0.20;\ncontroller_mpc_cbf_2 = MPCCBF(x0, system, params);\ncontroller_mpc_cbf_2.obs = obs;\ncontroller_mpc_cbf_2.sim(time_total);\n\nparams.gamma = 0.15;\ncontroller_mpc_cbf_3 = MPC_CBF(x0, system, params);\ncontroller_mpc_cbf_3.obs = obs;\ncontroller_mpc_cbf_3.sim(time_total);\n\n%% Simulate MPC-DC\n\n% The problem is infeasible at N=5\n% params.N = 5;\n% controller_mpc_dc_0 = MPCDC(x0, system, params);\n% controller_mpc_dc_0.obs = obs;\n% controller_mpc_dc_0.sim(time_total);\n\nparams.N = 7;\ncontroller_mpc_dc_1 = MPCDC(x0, system, params);\ncontroller_mpc_dc_1.obs = obs;\ncontroller_mpc_dc_1.sim(time_total);\n\nparams.N = 15;\ncontroller_mpc_dc_2 = MPCDC(x0, system, params);\ncontroller_mpc_dc_2.obs = obs;\ncontroller_mpc_dc_2.sim(time_total);\n\n%%\nparams.N = 30;\ncontroller_mpc_dc_3 = MPCDC(x0, system, params);\ncontroller_mpc_dc_3.obs = obs;\ncontroller_mpc_dc_3.sim(time_total);\n\n%% Visualization benchmark\nfigure('Renderer', 'painters', 'Position', [0 0 400 400]);\nset(gca,'LooseInset',get(gca,'TightInset'));\nhold on\nplot(controller_mpc_cbf_3.xlog(1,:), controller_mpc_cbf_3.xlog(2,:),...\n    '-', 'Color', [0, 0.4470, 0.7410], 'LineWidth', 1.0, 'MarkerSize', 4);\nplot(controller_mpc_cbf_2.xlog(1,:), controller_mpc_cbf_2.xlog(2,:),...\n    '-', 'Color', [0.8500, 0.3250, 0.0980], 'LineWidth', 1.0, 'MarkerSize', 4);\nplot(controller_mpc_cbf_1.xlog(1,:), controller_mpc_cbf_1.xlog(2,:),...\n    '-', 'Color', [0.9290, 0.6940, 0.1250], 'LineWidth', 1.0, 'MarkerSize', 4);\nplot(controller_mpc_dc_1.xlog(1,:), controller_mpc_dc_1.xlog(2,:),...\n    '--', 'Color', [0.4940, 0.1840, 0.5560], 'LineWidth', 1.0, 'MarkerSize', 4);\nplot(controller_mpc_dc_2.xlog(1,:), controller_mpc_dc_2.xlog(2,:),...\n    '--', 'Color', [0.4660, 0.6740, 0.1880], 'LineWidth', 1.0, 'MarkerSize', 4);\nplot(controller_mpc_dc_3.xlog(1,:), controller_mpc_dc_3.xlog(2,:),...\n    '--', 'Color', [0.3010, 0.7450, 0.9330], 'LineWidth', 1.0, 'MarkerSize', 4);\n% plot obstacle\npos = obs.pos;\nr = obs.r;\nth = linspace(0,2*pi*100);\nx = cos(th) ; y = sin(th) ;\nplot(pos(1) + r*x, pos(2) + r*y, 'Color', [0.8500, 0.3250, 0.0980],...\n    'LineWidth', 2);\nplot(pos(1), pos(2), 'Color', [0.8500, 0.3250, 0.0980],...\n    'MarkerSize', 5, 'LineWidth', 2);\n% plot target position\nplot(x0(1), x0(2), 'db', 'LineWidth', 1);\nplot(0.0, 0.0, 'dr', 'LineWidth', 1);\nh=get(gca,'Children');\nh_legend = legend(h([end, end-1, end-2, end-3, end-4, end-5]),...\n    {'MPC-CBF ($N = 5, \\gamma = 0.15$)', 'MPC-CBF ($N = 5, \\gamma = 0.20$)',...\n    'MPC-CBF ($N = 5, \\gamma = 0.25$)', 'MPC-DC ($N = 7$)', 'MPC-DC ($N = 15$)',...\n    'MPC-DC ($N = 30$)'}, 'Location', 'SouthEast');\nset(h_legend, 'Interpreter','latex', 'FontSize', 10);\nset(gca,'LineWidth', 0.2, 'FontSize', 15);\ngrid on\nxlabel('$x (m)$','interpreter','latex','FontSize',20);\nylabel('$y (m)$','interpreter','latex','FontSize',20);\nxticks(-5:0);\nyticks(-5:0);\nxlim([-5,0.2]);\nylim([-5,0.2]);\nprint(gcf,'figures/benchmark-horizon.eps', '-depsc');\nprint(gcf,'figures/benchmark-horizon.png', '-dpng', '-r800');\n\n%% Computational time benchmark\nfigure('Renderer', 'painters', 'Position', [0 0 800 400]);\nxlabel('Computational time (s)', 'interpreter', 'latex', 'FontSize', 16);\nylabel('Percentage', 'interpreter', 'latex', 'FontSize', 16);\nhold on\n% [N_mpc_3, edges_mpc_3] = histcounts(controller_mpc_cbf_3.solvertime, 10, 'Normalization', 'probability');\n% plot(edges_mpc_3(1:end-1), N_mpc_3, '-', 'Color', [0, 0.4470, 0.7410], 'LineWidth', 1);\n% [N_mpc_2, edges_mpc_2] = histcounts(controller_mpc_cbf_2.solvertime, 10, 'Normalization', 'probability');\n% plot(edges_mpc_2(1:end-1), N_mpc_2, '-', 'Color', [0.8500, 0.3250, 0.0980], 'LineWidth', 1);\n[N_mpc_1, edges_mpc_1] = histcounts(controller_mpc_cbf_1.solvertime, 10, 'Normalization', 'probability');\nplot(edges_mpc_1(1:end-1), N_mpc_1, '-', 'Color', [0.9290, 0.6940, 0.1250], 'LineWidth', 1);\n[N_dc_1, edges_dc_1] = histcounts(controller_mpc_dc_1.solvertime, 10, 'Normalization', 'probability');\nplot(edges_dc_1(1:end-1), N_dc_1, '--', 'Color', [0.4940, 0.1840, 0.5560], 'LineWidth', 1);\n[N_dc_2, edges_dc_2] = histcounts(controller_mpc_dc_2.solvertime, 10, 'Normalization', 'probability');\nplot(edges_dc_2(1:end-1), N_dc_2, '--', 'Color', [0.4660, 0.6740, 0.1880], 'LineWidth', 1);\n[N_dc_3, edges_dc_3] = histcounts(controller_mpc_dc_3.solvertime, 10, 'Normalization', 'probability');\nplot(edges_dc_3(1:end-1), N_dc_3, '--', 'Color', [0.3010, 0.7450, 0.9330], 'LineWidth', 1);\nh=get(gca,'Children');\nh_legend = legend(h([end, end-1, end-2, end-3]),...\n    {'MPC-CBF ($N = 5, \\gamma = 0.25$)',...\n    'MPC-DC ($N = 7$)',...\n    'MPC-DC ($N = 15$)',...\n    'MPC-DC ($N = 30$)'}, 'Location', 'NorthEast');\nset(h_legend, 'Interpreter','latex');\nset(gca,'LineWidth', 0.2, 'FontSize', 15);\nprint(gcf,'figures/benchmark-horizon-computational-time.eps', '-depsc');\nprint(gcf,'figures/benchmark-horizon-computational-time.png', '-dpng', '-r800');\n%% Computational time table\nfprintf('Computational time for MPC-CBF3: mean %.3f, std %.3f, min %.3f, max %.3f, input cost %.3f, min dist %f\\n',...\n    [mean(controller_mpc_cbf_3.solvertime),...\n    std(controller_mpc_cbf_3.solvertime),...\n    min(controller_mpc_cbf_3.solvertime),...\n    max(controller_mpc_cbf_3.solvertime),...\n    controller_mpc_cbf_3.u_cost,...\n    min(controller_mpc_cbf_3.distlog)]);\n\nfprintf('Computational time for MPC-CBF2: mean %.3f, std %.3f, min %.3f, max %.3f, input cost %.3f, min dist %f\\n',...\n    [mean(controller_mpc_cbf_2.solvertime),...\n    std(controller_mpc_cbf_2.solvertime),...\n    min(controller_mpc_cbf_2.solvertime),...\n    max(controller_mpc_cbf_2.solvertime),...\n    controller_mpc_cbf_2.u_cost,...\n    min(controller_mpc_cbf_2.distlog)]);\n\nfprintf('Computational time for MPC-CBF1: mean %.3f, std %.3f, min %.3f, max %.3f, input cost %.3f, min dist %f\\n',...\n    [mean(controller_mpc_cbf_1.solvertime),...\n    std(controller_mpc_cbf_1.solvertime),...\n    min(controller_mpc_cbf_1.solvertime),...\n    max(controller_mpc_cbf_1.solvertime),...\n    controller_mpc_cbf_1.u_cost,...\n    min(controller_mpc_cbf_1.distlog)]);\n\n% fprintf('Computational time for MPC-DC0: mean %.3f, std %.3f, min %.3f, max %.3f, input cost %.3f, min dist %f\\n',...\n%     [mean(controller_mpc_dc_0.solvertime),...\n%     std(controller_mpc_dc_0.solvertime),...\n%     min(controller_mpc_dc_0.solvertime),...\n%     max(controller_mpc_dc_0.solvertime),...\n%     controller_mpc_dc_0.u_cost,...\n%     min(controller_mpc_dc_0.distlog)]);\n\nfprintf('Computational time for MPC-DC1: mean %.3f, std %.3f, min %.3f, max %.3f, input cost %.3f, min dist %f\\n',...\n    [mean(controller_mpc_dc_1.solvertime),...\n    std(controller_mpc_dc_1.solvertime),...\n    min(controller_mpc_dc_1.solvertime),...\n    max(controller_mpc_dc_1.solvertime),...\n    controller_mpc_dc_1.u_cost,...\n    min(controller_mpc_dc_1.distlog)]);\n\nfprintf('Computational time for MPC-DC2: mean %.3f, std %.3f, min %.3f, max %.3f, input cost %.3f, min dist %f\\n',...\n    [mean(controller_mpc_dc_2.solvertime),...\n    std(controller_mpc_dc_2.solvertime),...\n    min(controller_mpc_dc_2.solvertime),...\n    max(controller_mpc_dc_2.solvertime),...\n    controller_mpc_dc_2.u_cost,...\n    min(controller_mpc_dc_2.distlog)]);\n\nfprintf('Computational time for MPC-DC3: mean %.3f, std %.3f, min %.3f, max %.3f, input cost %.3f, min dist %f\\n',...\n    [mean(controller_mpc_dc_3.solvertime),...\n    std(controller_mpc_dc_3.solvertime),...\n    min(controller_mpc_dc_3.solvertime),...\n    max(controller_mpc_dc_3.solvertime),...\n    controller_mpc_dc_3.u_cost,...\n    min(controller_mpc_dc_3.distlog)]);"
  },
  {
    "path": "matlab/acc2023/README.md",
    "content": "# Iterative-MPC-DHOCBF\nMatlab code for the paper *\"Iterative Convex Optimization for Model Predictive Control with Discrete-Time High-Order Control Barrier Functions\"*, accepted by IEEE American Control Conference (ACC) 2023, Authors: *Shuo Liu, Jun Zeng,  Koushil Sreenath and Calin Belta* [[PDF]](https://arxiv.org/pdf/2210.04361.pdf)\n\nIn this paper, we propose a framework that solves the safety critical MPC problem in an iterative optimization, which is applicable for any relative-degree control barrier functions. In the proposed formulation, the nonlinear system dynamics as well as the safety constraints modeled as discrete-time high order control barrier functions (DHOCBF) are linearized at each time step. Our formulation is generally valid for any control barrier function with an arbitrary relative-degree. The advantages of fast computational performance with safety guarantee are analyzed and validated with numerical results.\n\n## Citing\nIf you find this project useful in your work, please consider citing following work:\n```\n@inproceedings{liu2023iterative,\n  title={Iterative Convex Optimization for Model Predictive Control with Discrete-Time High-Order Control Barrier Functions},\n  author={Liu, Shuo and Zeng, Jun and Sreenath, Koushil and Belta, Calin A},\n  booktitle={2023 American Control Conference (ACC)},\n  year={2023}\n}\n```\n\n## Instruction\nThere are two subfolders `closedloop_performance` and `benchmark`. `closedloop_performance` contains all information to generate figure 2, 3, 4 in paper and `benchmark` conatins code to generate data for table 1,2 in paper.\n\n## Subfolder `closedloop_performance`\n\n### Code Descriptions\n* `Closedloop_Trajectories_Hyperparameters.m` includes codes to generate necessary data for figure 2-a and figure 3; *\"Iterative_Convergence\"* includes codes to generate necessary data for figure 2-b,c,d.\n* `Maximum_Iterations.m` includes codes to generate necessary data for figure 4.   \n* `NMPCDCBF1.m` and `NMPCDCBF2.m` include codes related to NMPC-DHOCBF with `mcbf=1` and `mcbf=2` respectively and `FigureGenerate.m` includes codes to transfer the data into figures in paper.\n\n### Usage\n* Run `Closedloop_Trajectories_Hyperparameters.m`, `Iterative_Convergence.m` and `Maximum_Iterations.m` and the data files are generated as MATLAB mat files.  \n* Run `FigureGenerate.m` to generate all figures in paper, which will be saved in folder `closedloop_performance/figures`.\n\n## Subfolder `benchmark`\n\n### Code Descriptions\nThere are four folders including the codes to generate necessary dada for table 1,2 in paper.   \n* `gamma1_0p4gamma2_0p4` includes the codes for iMPC-DHOCBF and NMPC-DHOCBF with decay rate parameters `gamma1=0.4, gamma2=0.4, mcbf=2`.\n* `gamma1_0p4` includes the codes for iMPC-DHOCBF and NMPC-DHOCBF with decay rate parameters `gamma1=0.4, mcbf=1`.\n* `gamma1_0p6gamma2_0p6` includes the codes for iMPC-DHOCBF and NMPC-DHOCBF with decay rate parameters `gamma1=0.6, gamma2=0.6, mcbf=2`.\n* `gamma1_0p6` includes the codes for iMPC-DHOCBF and NMPC-DHOCBF with decay rate parameters `gamma1=0.6, mcbf=1`.\n### Usage\n* Run `InitialState.m` first to generate 1000 random initial states in the mat file `InitialStateData.mat`, then copy it to each folder.\n* In each folder, run the file `test_comprehensive.m` and you will see corresponding data files generated as MATLAB mat files `feasibility_N.mat` and `timecom_N.mat` which includes the information about infeasible rate and mean/variance of computing time (stored in matrices `nmpcdata` and `impcdata`) in paper from generating one time-step trajectories for iMPC-DHOCBF and NMPC-DHOCBF.\n\n### Warnings\n* It may take a long time to run the file `test_comprehensive.m` (several hours to a day depending on your computer when the number of horizon reaches large). Instead, if you want to run the file for different number of horizon parallelly to speed up the running process, in folder `test_each_horizon.m`, there are six files called `test_N4.m`, `test_N8.m`, `test_N12.m`, `test_N16.m`, `test_N20.m`,`test_N24.m` which correspond to the number of horizon 4, 8, 12, 16, 20, 24 for iMPC-DHOCBF and NMPC-DHOCBF. By copying `InitialStateData.mat` to this folder then you can run these 6 files parallely, in order to generate same MATLAB mat files `feasibility_N.mat` and `timecom_N.mat` which  includes the information about infeasible rate and mean/variance of computing time in paper from generating one time-step trajectories for iMPC-DHOCBF and NMPC-DHOCBF. You should run the file `tabledata.m` next and all useful data in table are stored in matrices `nmpcdata` and `impcdata`.\n\n## Post Analysis\n1. For comparison of capability of generating safe optimal trajectories for different numbers of horizon and hyperparameters, please see the figure below:\n![image](https://github.com/ShockLeo/Iterative-MPC-DHOCBF/blob/main/closedloop_performance/performance2.png)\n2. For comparison of infeasible rate and mean/variance of computing time from generating one time-step trajectories, please see the figure below:\n![image](https://github.com/ShockLeo/Iterative-MPC-DHOCBF/blob/main/benchmark/performance1.png) \nFor other figures please refer to the paper.\n\n## Dependencies\nThe packages needed for running the code are [Yalmip](https://yalmip.github.io/) and [IPOPT](https://github.com/coin-or/Ipopt) for NMPC-DHOCBF and [OSQP](https://github.com/osqp/osqp) for iMPC-DHOCBF.\n"
  },
  {
    "path": "matlab/acc2023/benchmark/InitialState.m",
    "content": "samplen=1000;%Total number of initial states\r\nInitialMat=zeros(4,samplen);%Store initialized x, y, theta, v into each row by sequence\r\nfor i=1:samplen\r\nrr=0;\r\nwhile rr<=1\r\nxini1=(-10+rand(1)*(20));%-10~10\r\nyini1=(-10+rand(1)*(20));%-10~10\r\nrr = (xini1)^2+(yini1)^2;%Initialize location states which are inside safe region\r\nend\r\nthetaini1=(-10+rand(1)*(20));%-10~10\r\nvini1=(-10+rand(1)*(20));%-10~10\r\nInitialMat(1,i)=xini1;\r\nInitialMat(2,i)=yini1;\r\nInitialMat(3,i)=thetaini1;\r\nInitialMat(4,i)=vini1;\r\nend\r\nsave('InitialStateData','InitialMat');"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1-0p6/NMPCDCBF1.m",
    "content": "classdef NMPCDCBF1 < handle\r\n    % MPC with distance constraints\r\n    properties\r\n        system\r\n        params\r\n        x0\r\n        x_curr\r\n        time_curr = 0.0\r\n        xlog = []\r\n        ulog = []\r\n        tt = 0\r\n        distlog = []\r\n        solvertime = []\r\n        xopenloop = {}\r\n        uopenloop = {}\r\n        u_cost = 0\r\n        obs\r\n    end\r\n    methods\r\n        function self = NMPCDCBF1(x0, system, params)\r\n            % Define MPC_CBF controller\r\n            self.x0 = x0;\r\n            self.x_curr = x0;\r\n            self.system = system;\r\n            self.params = params;\r\n        end\r\n        \r\n        function sim(self, time)\r\n            % Simulate the system until a given time\r\n            tic;\r\n            xk = self.x_curr;\r\n            while self.time_curr < time\r\n                [~, uk, tt] = self.solveNMPCDCBF1(self.x_curr);\r\n                if tt == -1 %if infeasiblility happens, stop\r\n                    self.tt = tt;\r\n                    return\r\n                end\r\n                xk = self.system.A * xk + [xk(4,1) * cos(xk(3,1))*self.system.dt;xk(4,1) * sin(xk(3,1))*self.system.dt;0;0] + self.system.C * uk;\r\n                % update system\r\n                self.x_curr = xk;\r\n                self.time_curr = self.time_curr + self.system.dt;\r\n                self.xlog = [self.xlog, xk];\r\n                self.ulog = [self.ulog, uk];\r\n                self.u_cost = self.u_cost + uk'*uk;\r\n                tt = tt + toc;%record computing time for each time-step\r\n                self.tt = tt;\r\n                return\r\n            end\r\n            \r\n        end\r\n        \r\n        function [xopt, uopt,tt] = solveNMPCDCBF1(self, xk)\r\n            % Solve NMPC-DCBF\r\n            [feas, x, u, J] = self.solve_cftoc1(xk);\r\n            if ~feas\r\n                xopt = [];\r\n                uopt = [];\r\n                tt = -1;\r\n                return\r\n            else\r\n                xopt = x(:,2);\r\n                uopt = u(:,1);\r\n                tt = 0;\r\n            end\r\n        end\r\n        \r\n        function [feas, xopt, uopt, Jopt] = solve_cftoc1(self, xk)\r\n            % Solve CFTOC\r\n            % extract variables\r\n            N = self.params.N;\r\n            % define variables and cost\r\n            x = sdpvar(4, N+1);\r\n            u = sdpvar(4, N);\r\n            constraints = [];\r\n            cost = 0;\r\n            % initial constraint\r\n            constraints = [constraints; x(:,1) == xk];\r\n            % add constraints and costs\r\n            AA=self.system.A;\r\n            BB=self.system.B;\r\n            CC=self.system.C;\r\n            constraints = [constraints;\r\n                    self.system.xl <= x(:,1) <= self.system.xu;\r\n                    self.system.ul <= u(:,1) <= self.system.uu;\r\n                    x(:,2) == AA * x(:,1) + [x(4,1)*cos(x(3,1))*self.system.dt;x(4,1)*sin(x(3,1))*self.system.dt;0; 0] + CC * u(:,1)];\r\n                cost = cost + (x(:,1)-[3;0.01;0;0])'*self.params.Q*(x(:,1)-[3;0.01;0;0]) + (u(:,1)-[0;0;1;1])'*self.params.R*(u(:,1)-[0;0;1;1]); % self.params.S*(w(:,1)-1)^2;\r\n            for i = 2:1:N\r\n                constraints = [constraints;\r\n                    self.system.xl <= x(:,i) <= self.system.xu;\r\n                    self.system.ul <= u(:,i) <= self.system.uu;\r\n                    x(:,i+1) == AA * x(:,i) + [x(4,i)*cos(x(3,i))*self.system.dt;x(4,i)*sin(x(3,i))*self.system.dt;0; 0] + CC * u(:,i)];\r\n                cost = cost + (x(:,i)-[3;0.01;0;0])'*self.params.Q*(x(:,i)-[3;0.01;0;0]) + (u(:,i)-[0;0;1;1])'*self.params.R*(u(:,i)-[0;0;1;1]);% self.params.S*(w(:,i)-1)^2;\r\n            end\r\n            % add CBF constraints\r\n            for i = 1:N-1\r\n                pos = self.obs.pos1;\r\n                r = self.obs.r1 ;\r\n                b = (x([1:2],i)-pos)'*((x([1:2],i)-pos))-r^2;\r\n                b_next = (x([1:2],i+1)-pos)'*((x([1:2],i+1)-pos))-r^2;\r\n                constraints = [constraints; b_next  >= u(3,i)*(1-self.params.gamma1)*b];%Highest order mcbf=1\r\n            end\r\n            % add terminal cost\r\n            cost = cost + (x(:,N+1)-[3;0.01;0;0])'*self.params.P*(x(:,N+1)-[3;0.01;0;0]);\r\n            ops = sdpsettings('solver','ipopt','verbose',0);\r\n            % solve optimization\r\n            diagnostics = optimize(constraints, cost, ops);\r\n            if diagnostics.problem == 0\r\n                feas = true;\r\n                xopt = value(x);\r\n                uopt = value(u);\r\n                Jopt = value(cost);\r\n            else\r\n                feas = false;\r\n                xopt = [];\r\n                uopt = [];\r\n                Jopt = [];\r\n            end\r\n            pos = self.obs.pos1;\r\n            r = self.obs.r1 ;\r\n            self.distlog = [self.distlog, (r^2-(xk(1:2)-pos)'*(xk(1:2)-pos))];\r\n            self.xopenloop{size(self.xopenloop,2)+1} = xopt;\r\n            self.uopenloop{size(self.uopenloop,2)+1} = uopt;\r\n            self.solvertime = [self.solvertime, diagnostics.solvertime];\r\n            fprintf('solver time: %f\\n', diagnostics.solvertime);\r\n        end\r\n    end\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1-0p6/test_comprehensive.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnmpcdata=zeros(3,6);%Store data in matrix for nmpc and impc, first row: mean of computing time; second row: standard deviation of computing time; third row: infeasible rate\r\nimpcdata=zeros(3,6);\r\nfor ii = 1:6\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=ii*4;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p6\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nfilenm1 = ['timecom' num2str(i) '.mat'];\r\nfilenm2 = ['feasibility' num2str(i) '.mat'];\r\nsave(filenm1,'nmpcplot1','impcplot1');\r\nsave(filenm2,'nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\nnmpcdata(1,ii)=mu1;\r\nimpcdata(1,ii)=mu2;\r\nnmpcdata(2,ii)=sigma1;\r\nimpcdata(2,ii)=sigma2;\r\nnmpcdata(3,ii)=nmpcinf;\r\nimpcdata(3,ii)=impcinf;\r\nend\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.6;\r\nparams_nmpc_dcbf.gamma2 = 0.6;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-4\\n');\r\n    controller_nmpc_dcbf_multiple4 = NMPCDCBF1(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple4.obs = obs;\r\n    controller_nmpc_dcbf_multiple4.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple4.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 6;\r\ngamma2 = 6;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1-0p6/test_each_horizon/NMPCDCBF1.m",
    "content": "classdef NMPCDCBF1 < handle\r\n    % MPC with distance constraints\r\n    properties\r\n        system\r\n        params\r\n        x0\r\n        x_curr\r\n        time_curr = 0.0\r\n        xlog = []\r\n        ulog = []\r\n        tt = 0\r\n        distlog = []\r\n        solvertime = []\r\n        xopenloop = {}\r\n        uopenloop = {}\r\n        u_cost = 0\r\n        obs\r\n    end\r\n    methods\r\n        function self = NMPCDCBF1(x0, system, params)\r\n            % Define MPC_CBF controller\r\n            self.x0 = x0;\r\n            self.x_curr = x0;\r\n            self.system = system;\r\n            self.params = params;\r\n        end\r\n        \r\n        function sim(self, time)\r\n            % Simulate the system until a given time\r\n            tic;\r\n            xk = self.x_curr;\r\n            while self.time_curr < time\r\n                [~, uk, tt] = self.solveNMPCDCBF1(self.x_curr);\r\n                if tt == -1 %if infeasiblility happens, stop\r\n                    self.tt = tt;\r\n                    return\r\n                end\r\n                xk = self.system.A * xk + [xk(4,1) * cos(xk(3,1))*self.system.dt;xk(4,1) * sin(xk(3,1))*self.system.dt;0;0] + self.system.C * uk;\r\n                % update system\r\n                self.x_curr = xk;\r\n                self.time_curr = self.time_curr + self.system.dt;\r\n                self.xlog = [self.xlog, xk];\r\n                self.ulog = [self.ulog, uk];\r\n                self.u_cost = self.u_cost + uk'*uk;\r\n                tt = tt + toc;%record computing time for each time-step\r\n                self.tt = tt;\r\n                return\r\n            end\r\n            \r\n        end\r\n        \r\n        function [xopt, uopt,tt] = solveNMPCDCBF1(self, xk)\r\n            % Solve NMPC-DCBF\r\n            [feas, x, u, J] = self.solve_cftoc1(xk);\r\n            if ~feas\r\n                xopt = [];\r\n                uopt = [];\r\n                tt = -1;\r\n                return\r\n            else\r\n                xopt = x(:,2);\r\n                uopt = u(:,1);\r\n                tt = 0;\r\n            end\r\n        end\r\n        \r\n        function [feas, xopt, uopt, Jopt] = solve_cftoc1(self, xk)\r\n            % Solve CFTOC\r\n            % extract variables\r\n            N = self.params.N;\r\n            % define variables and cost\r\n            x = sdpvar(4, N+1);\r\n            u = sdpvar(4, N);\r\n            constraints = [];\r\n            cost = 0;\r\n            % initial constraint\r\n            constraints = [constraints; x(:,1) == xk];\r\n            % add constraints and costs\r\n            AA=self.system.A;\r\n            BB=self.system.B;\r\n            CC=self.system.C;\r\n            constraints = [constraints;\r\n                    self.system.xl <= x(:,1) <= self.system.xu;\r\n                    self.system.ul <= u(:,1) <= self.system.uu;\r\n                    x(:,2) == AA * x(:,1) + [x(4,1)*cos(x(3,1))*self.system.dt;x(4,1)*sin(x(3,1))*self.system.dt;0; 0] + CC * u(:,1)];\r\n                cost = cost + (x(:,1)-[3;0.01;0;0])'*self.params.Q*(x(:,1)-[3;0.01;0;0]) + (u(:,1)-[0;0;1;1])'*self.params.R*(u(:,1)-[0;0;1;1]); % self.params.S*(w(:,1)-1)^2;\r\n            for i = 2:1:N\r\n                constraints = [constraints;\r\n                    self.system.xl <= x(:,i) <= self.system.xu;\r\n                    self.system.ul <= u(:,i) <= self.system.uu;\r\n                    x(:,i+1) == AA * x(:,i) + [x(4,i)*cos(x(3,i))*self.system.dt;x(4,i)*sin(x(3,i))*self.system.dt;0; 0] + CC * u(:,i)];\r\n                cost = cost + (x(:,i)-[3;0.01;0;0])'*self.params.Q*(x(:,i)-[3;0.01;0;0]) + (u(:,i)-[0;0;1;1])'*self.params.R*(u(:,i)-[0;0;1;1]);% self.params.S*(w(:,i)-1)^2;\r\n            end\r\n            % add CBF constraints\r\n            for i = 1:N-1\r\n                pos = self.obs.pos1;\r\n                r = self.obs.r1 ;\r\n                b = (x([1:2],i)-pos)'*((x([1:2],i)-pos))-r^2;\r\n                b_next = (x([1:2],i+1)-pos)'*((x([1:2],i+1)-pos))-r^2;\r\n                constraints = [constraints; b_next  >= u(3,i)*(1-self.params.gamma1)*b];%Highest order mcbf=1\r\n            end\r\n            % add terminal cost\r\n            cost = cost + (x(:,N+1)-[3;0.01;0;0])'*self.params.P*(x(:,N+1)-[3;0.01;0;0]);\r\n            ops = sdpsettings('solver','ipopt','verbose',0);\r\n            % solve optimization\r\n            diagnostics = optimize(constraints, cost, ops);\r\n            if diagnostics.problem == 0\r\n                feas = true;\r\n                xopt = value(x);\r\n                uopt = value(u);\r\n                Jopt = value(cost);\r\n            else\r\n                feas = false;\r\n                xopt = [];\r\n                uopt = [];\r\n                Jopt = [];\r\n            end\r\n            pos = self.obs.pos1;\r\n            r = self.obs.r1 ;\r\n            self.distlog = [self.distlog, (r^2-(xk(1:2)-pos)'*(xk(1:2)-pos))];\r\n            self.xopenloop{size(self.xopenloop,2)+1} = xopt;\r\n            self.uopenloop{size(self.uopenloop,2)+1} = uopt;\r\n            self.solvertime = [self.solvertime, diagnostics.solvertime];\r\n            fprintf('solver time: %f\\n', diagnostics.solvertime);\r\n        end\r\n    end\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1-0p6/test_each_horizon/tabledata.m",
    "content": "nmpcdata=zeros(3,6);%Store data in matrix for nmpc and impc, first row: mean of computing time; second row: standard deviation of computing time; third row: infeasible rate\r\nimpcdata=zeros(3,6);\r\nfor ii = 1:6\r\ni=ii*4;\r\nfilenm1 = ['timecom' num2str(i) '.mat'];\r\nfilenm2 = ['feasibility' num2str(i) '.mat'];\r\nload(filenm1);\r\nload(filenm2);\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\nnmpcdata(1,ii)=mu1;\r\nimpcdata(1,ii)=mu2;\r\nnmpcdata(2,ii)=sigma1;\r\nimpcdata(2,ii)=sigma2;\r\nnmpcdata(3,ii)=nmpcinf;\r\nimpcdata(3,ii)=impcinf;\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1-0p6/test_each_horizon/test_N12.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=12;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p6\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom12','nmpcplot1','impcplot1');\r\nsave('feasibility12','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.6;\r\nparams_nmpc_dcbf.gamma2 = 0.6;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-12\\n');\r\n    controller_nmpc_dcbf_multiple12 = NMPCDCBF1(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple12.obs = obs;\r\n    controller_nmpc_dcbf_multiple12.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple12.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 6;\r\ngamma2 = 6;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1-0p6/test_each_horizon/test_N16.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=16;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p6\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom16','nmpcplot1','impcplot1');\r\nsave('feasibility16','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.6;\r\nparams_nmpc_dcbf.gamma2 = 0.6;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-16\\n');\r\n    controller_nmpc_dcbf_multiple16 = NMPCDCBF1(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple16.obs = obs;\r\n    controller_nmpc_dcbf_multiple16.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple16.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 6;\r\ngamma2 = 6;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1-0p6/test_each_horizon/test_N20.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=20;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p6\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom20','nmpcplot1','impcplot1');\r\nsave('feasibility20','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.6;\r\nparams_nmpc_dcbf.gamma2 = 0.6;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-20\\n');\r\n    controller_nmpc_dcbf_multiple20 = NMPCDCBF1(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple20.obs = obs;\r\n    controller_nmpc_dcbf_multiple20.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple20.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 6;\r\ngamma2 = 6;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1-0p6/test_each_horizon/test_N24.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=24;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p6\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom24','nmpcplot1','impcplot1');\r\nsave('feasibility24','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.6;\r\nparams_nmpc_dcbf.gamma2 = 0.6;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-24\\n');\r\n    controller_nmpc_dcbf_multiple24 = NMPCDCBF1(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple24.obs = obs;\r\n    controller_nmpc_dcbf_multiple24.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple24.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 6;\r\ngamma2 = 6;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1-0p6/test_each_horizon/test_N4.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=4;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p6\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom4','nmpcplot1','impcplot1');\r\nsave('feasibility4','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.6;\r\nparams_nmpc_dcbf.gamma2 = 0.6;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-4\\n');\r\n    controller_nmpc_dcbf_multiple4 = NMPCDCBF1(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple4.obs = obs;\r\n    controller_nmpc_dcbf_multiple4.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple4.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 6;\r\ngamma2 = 6;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1-0p6/test_each_horizon/test_N8.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=8;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p6\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom8','nmpcplot1','impcplot1');\r\nsave('feasibility8','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.6;\r\nparams_nmpc_dcbf.gamma2 = 0.6;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-8\\n');\r\n    controller_nmpc_dcbf_multiple8 = NMPCDCBF1(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple8.obs = obs;\r\n    controller_nmpc_dcbf_multiple8.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple8.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 6;\r\ngamma2 = 6;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1-0p6gamma2-0p6/NMPCDCBF2.m",
    "content": "classdef NMPCDCBF2 < handle\r\n    % MPC with distance constraints\r\n    properties\r\n        system\r\n        params\r\n        x0\r\n        x_curr\r\n        time_curr = 0.0\r\n        xlog = []\r\n        ulog = []\r\n        tt = 0\r\n        distlog = []\r\n        solvertime = []\r\n        xopenloop = {}\r\n        uopenloop = {}\r\n        u_cost = 0\r\n        obs\r\n    end\r\n    methods\r\n        function self = NMPCDCBF2(x0, system, params)\r\n            % Define MPC_CBF controller\r\n            self.x0 = x0;\r\n            self.x_curr = x0;\r\n            self.system = system;\r\n            self.params = params;\r\n        end\r\n        \r\n        function sim(self, time)\r\n            % Simulate the system until a given time\r\n            tic;\r\n            xk = self.x_curr;\r\n            while self.time_curr < time\r\n                [~, uk, tt] = self.solveNMPCDCBF1(self.x_curr);%if infeasiblility happens, stop\r\n                if tt == -1\r\n                    self.tt = tt;%record computing time for each time-step\r\n                    return\r\n                end\r\n                xk = self.system.A * xk + [xk(4,1) * cos(xk(3,1))*self.system.dt;xk(4,1) * sin(xk(3,1))*self.system.dt;0;0] + self.system.C * uk;\r\n                % update system\r\n                self.x_curr = xk;\r\n                self.time_curr = self.time_curr + self.system.dt;\r\n                self.xlog = [self.xlog, xk];\r\n                self.ulog = [self.ulog, uk];\r\n                self.u_cost = self.u_cost + uk'*uk;\r\n                tt = tt + toc;\r\n                self.tt = tt;\r\n                return\r\n            end\r\n            \r\n        end\r\n        \r\n        function [xopt, uopt,tt] = solveNMPCDCBF1(self, xk)\r\n            % Solve NMPC-DCBF\r\n            [feas, x, u, J] = self.solve_cftoc1(xk);\r\n            if ~feas\r\n                xopt = [];\r\n                uopt = [];\r\n                tt = -1;\r\n                return\r\n            else\r\n                xopt = x(:,2);\r\n                uopt = u(:,1);\r\n                tt = 0;\r\n            end\r\n        end\r\n        \r\n        function [feas, xopt, uopt, Jopt] = solve_cftoc1(self, xk)\r\n            % Solve CFTOC\r\n            % extract variables\r\n            N = self.params.N;\r\n            % define variables and cost\r\n            x = sdpvar(4, N+1);%%%%%%%%%%%%%%%%%%%%%%%%%%%%\r\n            u = sdpvar(4, N);\r\n            constraints = [];\r\n            cost = 0;\r\n            % initial constraint\r\n            constraints = [constraints; x(:,1) == xk];\r\n            % add constraints and costs\r\n            AA=self.system.A;\r\n            BB=self.system.B;\r\n            CC=self.system.C;\r\n            constraints = [constraints;\r\n                    self.system.xl <= x(:,1) <= self.system.xu;\r\n                    self.system.ul <= u(:,1) <= self.system.uu;\r\n                    x(:,2) == AA * x(:,1) + [x(4,1)*cos(x(3,1))*self.system.dt;x(4,1)*sin(x(3,1))*self.system.dt;0; 0] + CC * u(:,1)];\r\n                cost = cost + (x(:,1)-[3;0.01;0;0])'*self.params.Q*(x(:,1)-[3;0.01;0;0]) + (u(:,1)-[0;0;1;1])'*self.params.R*(u(:,1)-[0;0;1;1]); % self.params.S*(w(:,1)-1)^2;\r\n            for i = 2:1:N\r\n                constraints = [constraints;\r\n                    self.system.xl <= x(:,i) <= self.system.xu;\r\n                    self.system.ul <= u(:,i) <= self.system.uu;\r\n                    x(:,i+1) == AA * x(:,i) + [x(4,i)*cos(x(3,i))*self.system.dt;x(4,i)*sin(x(3,i))*self.system.dt;0; 0] + CC * u(:,i)];\r\n                cost = cost + (x(:,i)-[3;0.01;0;0])'*self.params.Q*(x(:,i)-[3;0.01;0;0]) + (u(:,i)-[0;0;1;1])'*self.params.R*(u(:,i)-[0;0;1;1]);% self.params.S*(w(:,i)-1)^2;\r\n            end\r\n            % add CBF constraints\r\n            for i = 1:N-1\r\n                pos = self.obs.pos1;\r\n                r = self.obs.r1 ;\r\n                b = (x([1:2],i)-pos)'*((x([1:2],i)-pos))-r^2;\r\n                b_next = (x([1:2],i+1)-pos)'*((x([1:2],i+1)-pos))-r^2;\r\n                b_next_next = (x([1:2],i+2)-pos)'*((x([1:2],i+2)-pos))-r^2;                \r\n                b1 = (b_next - b)/self.system.dt + self.params.gamma1/self.system.dt * (b);\r\n                b1_next = (b_next_next - b_next)/self.system.dt + self.params.gamma1/self.system.dt * (b_next);\r\n                constraints = [constraints; b1_next  >=u(4,i)*(1-self.params.gamma2)*b1;b_next  >= u(3,i)*(1-self.params.gamma1)*b];%Highest order mcbf=2\r\n            end\r\n            % add terminal cost\r\n            cost = cost + (x(:,N+1)-[3;0.01;0;0])'*self.params.P*(x(:,N+1)-[3;0.01;0;0]);\r\n            ops = sdpsettings('solver','ipopt','verbose',0);\r\n            % solve optimization\r\n            diagnostics = optimize(constraints, cost, ops);\r\n            if diagnostics.problem == 0\r\n                feas = true;\r\n                xopt = value(x);\r\n                uopt = value(u);\r\n                Jopt = value(cost);\r\n            else\r\n                feas = false;\r\n                xopt = [];\r\n                uopt = [];\r\n                Jopt = [];\r\n            end\r\n            pos = self.obs.pos1;\r\n            r = self.obs.r1 ;\r\n            self.distlog = [self.distlog, (r^2-(xk(1:2)-pos)'*(xk(1:2)-pos))];\r\n            self.xopenloop{size(self.xopenloop,2)+1} = xopt;\r\n            self.uopenloop{size(self.uopenloop,2)+1} = uopt;\r\n            self.solvertime = [self.solvertime, diagnostics.solvertime];\r\n            fprintf('solver time: %f\\n', diagnostics.solvertime);\r\n        end\r\n    end\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1-0p6gamma2-0p6/test_comprehensive.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnmpcdata=zeros(3,6);%Store data in matrix for nmpc and impc, first row: mean of computing time; second row: standard deviation of computing time; third row: infeasible rate\r\nimpcdata=zeros(3,6);\r\nfor ii = 1:6\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=ii*4;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p6gamma2_0p6\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nfilenm1 = ['timecom' num2str(i) '.mat'];\r\nfilenm2 = ['feasibility' num2str(i) '.mat'];\r\nsave(filenm1,'nmpcplot1','impcplot1');\r\nsave(filenm2,'nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\nnmpcdata(1,ii)=mu1;\r\nimpcdata(1,ii)=mu2;\r\nnmpcdata(2,ii)=sigma1;\r\nimpcdata(2,ii)=sigma2;\r\nnmpcdata(3,ii)=nmpcinf;\r\nimpcdata(3,ii)=impcinf;\r\nend\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.6;\r\nparams_nmpc_dcbf.gamma2 = 0.6;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-4\\n');\r\n    controller_nmpc_dcbf_multiple4 = NMPCDCBF2(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple4.obs = obs;\r\n    controller_nmpc_dcbf_multiple4.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple4.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 6;\r\ngamma2 = 6;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1-0p6gamma2-0p6/test_each_horizon/NMPCDCBF2.m",
    "content": "classdef NMPCDCBF2 < handle\r\n    % MPC with distance constraints\r\n    properties\r\n        system\r\n        params\r\n        x0\r\n        x_curr\r\n        time_curr = 0.0\r\n        xlog = []\r\n        ulog = []\r\n        tt = 0\r\n        distlog = []\r\n        solvertime = []\r\n        xopenloop = {}\r\n        uopenloop = {}\r\n        u_cost = 0\r\n        obs\r\n    end\r\n    methods\r\n        function self = NMPCDCBF2(x0, system, params)\r\n            % Define MPC_CBF controller\r\n            self.x0 = x0;\r\n            self.x_curr = x0;\r\n            self.system = system;\r\n            self.params = params;\r\n        end\r\n        \r\n        function sim(self, time)\r\n            % Simulate the system until a given time\r\n            tic;\r\n            xk = self.x_curr;\r\n            while self.time_curr < time\r\n                [~, uk, tt] = self.solveNMPCDCBF1(self.x_curr);%if infeasiblility happens, stop\r\n                if tt == -1\r\n                    self.tt = tt;%record computing time for each time-step\r\n                    return\r\n                end\r\n                xk = self.system.A * xk + [xk(4,1) * cos(xk(3,1))*self.system.dt;xk(4,1) * sin(xk(3,1))*self.system.dt;0;0] + self.system.C * uk;\r\n                % update system\r\n                self.x_curr = xk;\r\n                self.time_curr = self.time_curr + self.system.dt;\r\n                self.xlog = [self.xlog, xk];\r\n                self.ulog = [self.ulog, uk];\r\n                self.u_cost = self.u_cost + uk'*uk;\r\n                tt = tt + toc;\r\n                self.tt = tt;\r\n                return\r\n            end\r\n            \r\n        end\r\n        \r\n        function [xopt, uopt,tt] = solveNMPCDCBF1(self, xk)\r\n            % Solve NMPC-DCBF\r\n            [feas, x, u, J] = self.solve_cftoc1(xk);\r\n            if ~feas\r\n                xopt = [];\r\n                uopt = [];\r\n                tt = -1;\r\n                return\r\n            else\r\n                xopt = x(:,2);\r\n                uopt = u(:,1);\r\n                tt = 0;\r\n            end\r\n        end\r\n        \r\n        function [feas, xopt, uopt, Jopt] = solve_cftoc1(self, xk)\r\n            % Solve CFTOC\r\n            % extract variables\r\n            N = self.params.N;\r\n            % define variables and cost\r\n            x = sdpvar(4, N+1);%%%%%%%%%%%%%%%%%%%%%%%%%%%%\r\n            u = sdpvar(4, N);\r\n            constraints = [];\r\n            cost = 0;\r\n            % initial constraint\r\n            constraints = [constraints; x(:,1) == xk];\r\n            % add constraints and costs\r\n            AA=self.system.A;\r\n            BB=self.system.B;\r\n            CC=self.system.C;\r\n            constraints = [constraints;\r\n                    self.system.xl <= x(:,1) <= self.system.xu;\r\n                    self.system.ul <= u(:,1) <= self.system.uu;\r\n                    x(:,2) == AA * x(:,1) + [x(4,1)*cos(x(3,1))*self.system.dt;x(4,1)*sin(x(3,1))*self.system.dt;0; 0] + CC * u(:,1)];\r\n                cost = cost + (x(:,1)-[3;0.01;0;0])'*self.params.Q*(x(:,1)-[3;0.01;0;0]) + (u(:,1)-[0;0;1;1])'*self.params.R*(u(:,1)-[0;0;1;1]); % self.params.S*(w(:,1)-1)^2;\r\n            for i = 2:1:N\r\n                constraints = [constraints;\r\n                    self.system.xl <= x(:,i) <= self.system.xu;\r\n                    self.system.ul <= u(:,i) <= self.system.uu;\r\n                    x(:,i+1) == AA * x(:,i) + [x(4,i)*cos(x(3,i))*self.system.dt;x(4,i)*sin(x(3,i))*self.system.dt;0; 0] + CC * u(:,i)];\r\n                cost = cost + (x(:,i)-[3;0.01;0;0])'*self.params.Q*(x(:,i)-[3;0.01;0;0]) + (u(:,i)-[0;0;1;1])'*self.params.R*(u(:,i)-[0;0;1;1]);% self.params.S*(w(:,i)-1)^2;\r\n            end\r\n            % add CBF constraints\r\n            for i = 1:N-1\r\n                pos = self.obs.pos1;\r\n                r = self.obs.r1 ;\r\n                b = (x([1:2],i)-pos)'*((x([1:2],i)-pos))-r^2;\r\n                b_next = (x([1:2],i+1)-pos)'*((x([1:2],i+1)-pos))-r^2;\r\n                b_next_next = (x([1:2],i+2)-pos)'*((x([1:2],i+2)-pos))-r^2;                \r\n                b1 = (b_next - b)/self.system.dt + self.params.gamma1/self.system.dt * (b);\r\n                b1_next = (b_next_next - b_next)/self.system.dt + self.params.gamma1/self.system.dt * (b_next);\r\n                constraints = [constraints; b1_next  >=u(4,i)*(1-self.params.gamma2)*b1;b_next  >= u(3,i)*(1-self.params.gamma1)*b];%Highest order mcbf=2\r\n            end\r\n            % add terminal cost\r\n            cost = cost + (x(:,N+1)-[3;0.01;0;0])'*self.params.P*(x(:,N+1)-[3;0.01;0;0]);\r\n            ops = sdpsettings('solver','ipopt','verbose',0);\r\n            % solve optimization\r\n            diagnostics = optimize(constraints, cost, ops);\r\n            if diagnostics.problem == 0\r\n                feas = true;\r\n                xopt = value(x);\r\n                uopt = value(u);\r\n                Jopt = value(cost);\r\n            else\r\n                feas = false;\r\n                xopt = [];\r\n                uopt = [];\r\n                Jopt = [];\r\n            end\r\n            pos = self.obs.pos1;\r\n            r = self.obs.r1 ;\r\n            self.distlog = [self.distlog, (r^2-(xk(1:2)-pos)'*(xk(1:2)-pos))];\r\n            self.xopenloop{size(self.xopenloop,2)+1} = xopt;\r\n            self.uopenloop{size(self.uopenloop,2)+1} = uopt;\r\n            self.solvertime = [self.solvertime, diagnostics.solvertime];\r\n            fprintf('solver time: %f\\n', diagnostics.solvertime);\r\n        end\r\n    end\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1-0p6gamma2-0p6/test_each_horizon/tabledata.m",
    "content": "nmpcdata=zeros(3,6);%Store data in matrix for nmpc and impc, first row: mean of computing time; second row: standard deviation of computing time; third row: infeasible rate\r\nimpcdata=zeros(3,6);\r\nfor ii = 1:6\r\ni=ii*4;\r\nfilenm1 = ['timecom' num2str(i) '.mat'];\r\nfilenm2 = ['feasibility' num2str(i) '.mat'];\r\nload(filenm1);\r\nload(filenm2);\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\nnmpcdata(1,ii)=mu1;\r\nimpcdata(1,ii)=mu2;\r\nnmpcdata(2,ii)=sigma1;\r\nimpcdata(2,ii)=sigma2;\r\nnmpcdata(3,ii)=nmpcinf;\r\nimpcdata(3,ii)=impcinf;\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1-0p6gamma2-0p6/test_each_horizon/test_N12.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=12;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p6gamma2_0p6\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom12','nmpcplot1','impcplot1');\r\nsave('feasibility12','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.6;\r\nparams_nmpc_dcbf.gamma2 = 0.6;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-12\\n');\r\n    controller_nmpc_dcbf_multiple12 = NMPCDCBF2(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple12.obs = obs;\r\n    controller_nmpc_dcbf_multiple12.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple12.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 6;\r\ngamma2 = 6;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1-0p6gamma2-0p6/test_each_horizon/test_N16.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=16;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p6gamma2_0p6\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom16','nmpcplot1','impcplot1');\r\nsave('feasibility16','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.6;\r\nparams_nmpc_dcbf.gamma2 = 0.6;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-16\\n');\r\n    controller_nmpc_dcbf_multiple16 = NMPCDCBF2(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple16.obs = obs;\r\n    controller_nmpc_dcbf_multiple16.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple16.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 6;\r\ngamma2 = 6;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1-0p6gamma2-0p6/test_each_horizon/test_N20.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=20;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p6gamma2_0p6\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom20','nmpcplot1','impcplot1');\r\nsave('feasibility20','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.6;\r\nparams_nmpc_dcbf.gamma2 = 0.6;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-20\\n');\r\n    controller_nmpc_dcbf_multiple20 = NMPCDCBF2(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple20.obs = obs;\r\n    controller_nmpc_dcbf_multiple20.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple20.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 6;\r\ngamma2 = 6;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1-0p6gamma2-0p6/test_each_horizon/test_N24.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=24;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p6gamma2_0p6\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom24','nmpcplot1','impcplot1');\r\nsave('feasibility24','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.6;\r\nparams_nmpc_dcbf.gamma2 = 0.6;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-24\\n');\r\n    controller_nmpc_dcbf_multiple24 = NMPCDCBF2(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple24.obs = obs;\r\n    controller_nmpc_dcbf_multiple24.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple24.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 6;\r\ngamma2 = 6;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1-0p6gamma2-0p6/test_each_horizon/test_N4.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=4;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p6gamma2_0p6\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom4','nmpcplot1','impcplot1');\r\nsave('feasibility4','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.6;\r\nparams_nmpc_dcbf.gamma2 = 0.6;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-4\\n');\r\n    controller_nmpc_dcbf_multiple4 = NMPCDCBF2(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple4.obs = obs;\r\n    controller_nmpc_dcbf_multiple4.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple4.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 6;\r\ngamma2 = 6;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1-0p6gamma2-0p6/test_each_horizon/test_N8.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=8;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p6gamma2_0p6\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom8','nmpcplot1','impcplot1');\r\nsave('feasibility8','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.6;\r\nparams_nmpc_dcbf.gamma2 = 0.6;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-8\\n');\r\n    controller_nmpc_dcbf_multiple8 = NMPCDCBF2(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple8.obs = obs;\r\n    controller_nmpc_dcbf_multiple8.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple8.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 6;\r\ngamma2 = 6;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1_0p4/NMPCDCBF1.m",
    "content": "classdef NMPCDCBF1 < handle\r\n    % MPC with distance constraints\r\n    properties\r\n        system\r\n        params\r\n        x0\r\n        x_curr\r\n        time_curr = 0.0\r\n        xlog = []\r\n        ulog = []\r\n        tt = 0\r\n        distlog = []\r\n        solvertime = []\r\n        xopenloop = {}\r\n        uopenloop = {}\r\n        u_cost = 0\r\n        obs\r\n    end\r\n    methods\r\n        function self = NMPCDCBF1(x0, system, params)\r\n            % Define MPC_CBF controller\r\n            self.x0 = x0;\r\n            self.x_curr = x0;\r\n            self.system = system;\r\n            self.params = params;\r\n        end\r\n        \r\n        function sim(self, time)\r\n            % Simulate the system until a given time\r\n            tic;\r\n            xk = self.x_curr;\r\n            while self.time_curr < time\r\n                [~, uk, tt] = self.solveNMPCDCBF1(self.x_curr);\r\n                if tt == -1 %if infeasiblility happens, stop\r\n                    self.tt = tt;\r\n                    return\r\n                end\r\n                xk = self.system.A * xk + [xk(4,1) * cos(xk(3,1))*self.system.dt;xk(4,1) * sin(xk(3,1))*self.system.dt;0;0] + self.system.C * uk;\r\n                % update system\r\n                self.x_curr = xk;\r\n                self.time_curr = self.time_curr + self.system.dt;\r\n                self.xlog = [self.xlog, xk];\r\n                self.ulog = [self.ulog, uk];\r\n                self.u_cost = self.u_cost + uk'*uk;\r\n                tt = tt + toc;%record computing time for each time-step\r\n                self.tt = tt;\r\n                return\r\n            end\r\n            \r\n        end\r\n        \r\n        function [xopt, uopt,tt] = solveNMPCDCBF1(self, xk)\r\n            % Solve NMPC-DCBF\r\n            [feas, x, u, J] = self.solve_cftoc1(xk);\r\n            if ~feas\r\n                xopt = [];\r\n                uopt = [];\r\n                tt = -1;\r\n                return\r\n            else\r\n                xopt = x(:,2);\r\n                uopt = u(:,1);\r\n                tt = 0;\r\n            end\r\n        end\r\n        \r\n        function [feas, xopt, uopt, Jopt] = solve_cftoc1(self, xk)\r\n            % Solve CFTOC\r\n            % extract variables\r\n            N = self.params.N;\r\n            % define variables and cost\r\n            x = sdpvar(4, N+1);\r\n            u = sdpvar(4, N);\r\n            constraints = [];\r\n            cost = 0;\r\n            % initial constraint\r\n            constraints = [constraints; x(:,1) == xk];\r\n            % add constraints and costs\r\n            AA=self.system.A;\r\n            BB=self.system.B;\r\n            CC=self.system.C;\r\n            constraints = [constraints;\r\n                    self.system.xl <= x(:,1) <= self.system.xu;\r\n                    self.system.ul <= u(:,1) <= self.system.uu;\r\n                    x(:,2) == AA * x(:,1) + [x(4,1)*cos(x(3,1))*self.system.dt;x(4,1)*sin(x(3,1))*self.system.dt;0; 0] + CC * u(:,1)];\r\n                cost = cost + (x(:,1)-[3;0.01;0;0])'*self.params.Q*(x(:,1)-[3;0.01;0;0]) + (u(:,1)-[0;0;1;1])'*self.params.R*(u(:,1)-[0;0;1;1]); % self.params.S*(w(:,1)-1)^2;\r\n            for i = 2:1:N\r\n                constraints = [constraints;\r\n                    self.system.xl <= x(:,i) <= self.system.xu;\r\n                    self.system.ul <= u(:,i) <= self.system.uu;\r\n                    x(:,i+1) == AA * x(:,i) + [x(4,i)*cos(x(3,i))*self.system.dt;x(4,i)*sin(x(3,i))*self.system.dt;0; 0] + CC * u(:,i)];\r\n                cost = cost + (x(:,i)-[3;0.01;0;0])'*self.params.Q*(x(:,i)-[3;0.01;0;0]) + (u(:,i)-[0;0;1;1])'*self.params.R*(u(:,i)-[0;0;1;1]);% self.params.S*(w(:,i)-1)^2;\r\n            end\r\n            % add CBF constraints\r\n            for i = 1:N-1\r\n                pos = self.obs.pos1;\r\n                r = self.obs.r1 ;\r\n                b = (x([1:2],i)-pos)'*((x([1:2],i)-pos))-r^2;\r\n                b_next = (x([1:2],i+1)-pos)'*((x([1:2],i+1)-pos))-r^2;\r\n                constraints = [constraints; b_next  >= u(3,i)*(1-self.params.gamma1)*b];%Highest order mcbf=1\r\n            end\r\n            % add terminal cost\r\n            cost = cost + (x(:,N+1)-[3;0.01;0;0])'*self.params.P*(x(:,N+1)-[3;0.01;0;0]);\r\n            ops = sdpsettings('solver','ipopt','verbose',0);\r\n            % solve optimization\r\n            diagnostics = optimize(constraints, cost, ops);\r\n            if diagnostics.problem == 0\r\n                feas = true;\r\n                xopt = value(x);\r\n                uopt = value(u);\r\n                Jopt = value(cost);\r\n            else\r\n                feas = false;\r\n                xopt = [];\r\n                uopt = [];\r\n                Jopt = [];\r\n            end\r\n            pos = self.obs.pos1;\r\n            r = self.obs.r1 ;\r\n            self.distlog = [self.distlog, (r^2-(xk(1:2)-pos)'*(xk(1:2)-pos))];\r\n            self.xopenloop{size(self.xopenloop,2)+1} = xopt;\r\n            self.uopenloop{size(self.uopenloop,2)+1} = uopt;\r\n            self.solvertime = [self.solvertime, diagnostics.solvertime];\r\n            fprintf('solver time: %f\\n', diagnostics.solvertime);\r\n        end\r\n    end\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1_0p4/test_comprehensive.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnmpcdata=zeros(3,6);%Store data in matrix for nmpc and impc, first row: mean of computing time; second row: standard deviation of computing time; third row: infeasible rate\r\nimpcdata=zeros(3,6);\r\nfor ii = 1:6\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=ii*4;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p4\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nfilenm1 = ['timecom' num2str(i) '.mat'];\r\nfilenm2 = ['feasibility' num2str(i) '.mat'];\r\nsave(filenm1,'nmpcplot1','impcplot1');\r\nsave(filenm2,'nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\nnmpcdata(1,ii)=mu1;\r\nimpcdata(1,ii)=mu2;\r\nnmpcdata(2,ii)=sigma1;\r\nimpcdata(2,ii)=sigma2;\r\nnmpcdata(3,ii)=nmpcinf;\r\nimpcdata(3,ii)=impcinf;\r\nend\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.4;\r\nparams_nmpc_dcbf.gamma2 = 0.4;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-4\\n');\r\n    controller_nmpc_dcbf_multiple4 = NMPCDCBF1(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple4.obs = obs;\r\n    controller_nmpc_dcbf_multiple4.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple4.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 4;\r\ngamma2 = 4;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1_0p4/test_each_horizon/NMPCDCBF1.m",
    "content": "classdef NMPCDCBF1 < handle\r\n    % MPC with distance constraints\r\n    properties\r\n        system\r\n        params\r\n        x0\r\n        x_curr\r\n        time_curr = 0.0\r\n        xlog = []\r\n        ulog = []\r\n        tt = 0\r\n        distlog = []\r\n        solvertime = []\r\n        xopenloop = {}\r\n        uopenloop = {}\r\n        u_cost = 0\r\n        obs\r\n    end\r\n    methods\r\n        function self = NMPCDCBF1(x0, system, params)\r\n            % Define MPC_CBF controller\r\n            self.x0 = x0;\r\n            self.x_curr = x0;\r\n            self.system = system;\r\n            self.params = params;\r\n        end\r\n        \r\n        function sim(self, time)\r\n            % Simulate the system until a given time\r\n            tic;\r\n            xk = self.x_curr;\r\n            while self.time_curr < time\r\n                [~, uk, tt] = self.solveNMPCDCBF1(self.x_curr);\r\n                if tt == -1 %if infeasiblility happens, stop\r\n                    self.tt = tt;\r\n                    return\r\n                end\r\n                xk = self.system.A * xk + [xk(4,1) * cos(xk(3,1))*self.system.dt;xk(4,1) * sin(xk(3,1))*self.system.dt;0;0] + self.system.C * uk;\r\n                % update system\r\n                self.x_curr = xk;\r\n                self.time_curr = self.time_curr + self.system.dt;\r\n                self.xlog = [self.xlog, xk];\r\n                self.ulog = [self.ulog, uk];\r\n                self.u_cost = self.u_cost + uk'*uk;\r\n                tt = tt + toc;%record computing time for each time-step\r\n                self.tt = tt;\r\n                return\r\n            end\r\n            \r\n        end\r\n        \r\n        function [xopt, uopt,tt] = solveNMPCDCBF1(self, xk)\r\n            % Solve NMPC-DCBF\r\n            [feas, x, u, J] = self.solve_cftoc1(xk);\r\n            if ~feas\r\n                xopt = [];\r\n                uopt = [];\r\n                tt = -1;\r\n                return\r\n            else\r\n                xopt = x(:,2);\r\n                uopt = u(:,1);\r\n                tt = 0;\r\n            end\r\n        end\r\n        \r\n        function [feas, xopt, uopt, Jopt] = solve_cftoc1(self, xk)\r\n            % Solve CFTOC\r\n            % extract variables\r\n            N = self.params.N;\r\n            % define variables and cost\r\n            x = sdpvar(4, N+1);\r\n            u = sdpvar(4, N);\r\n            constraints = [];\r\n            cost = 0;\r\n            % initial constraint\r\n            constraints = [constraints; x(:,1) == xk];\r\n            % add constraints and costs\r\n            AA=self.system.A;\r\n            BB=self.system.B;\r\n            CC=self.system.C;\r\n            constraints = [constraints;\r\n                    self.system.xl <= x(:,1) <= self.system.xu;\r\n                    self.system.ul <= u(:,1) <= self.system.uu;\r\n                    x(:,2) == AA * x(:,1) + [x(4,1)*cos(x(3,1))*self.system.dt;x(4,1)*sin(x(3,1))*self.system.dt;0; 0] + CC * u(:,1)];\r\n                cost = cost + (x(:,1)-[3;0.01;0;0])'*self.params.Q*(x(:,1)-[3;0.01;0;0]) + (u(:,1)-[0;0;1;1])'*self.params.R*(u(:,1)-[0;0;1;1]); % self.params.S*(w(:,1)-1)^2;\r\n            for i = 2:1:N\r\n                constraints = [constraints;\r\n                    self.system.xl <= x(:,i) <= self.system.xu;\r\n                    self.system.ul <= u(:,i) <= self.system.uu;\r\n                    x(:,i+1) == AA * x(:,i) + [x(4,i)*cos(x(3,i))*self.system.dt;x(4,i)*sin(x(3,i))*self.system.dt;0; 0] + CC * u(:,i)];\r\n                cost = cost + (x(:,i)-[3;0.01;0;0])'*self.params.Q*(x(:,i)-[3;0.01;0;0]) + (u(:,i)-[0;0;1;1])'*self.params.R*(u(:,i)-[0;0;1;1]);% self.params.S*(w(:,i)-1)^2;\r\n            end\r\n            % add CBF constraints\r\n            for i = 1:N-1\r\n                pos = self.obs.pos1;\r\n                r = self.obs.r1 ;\r\n                b = (x([1:2],i)-pos)'*((x([1:2],i)-pos))-r^2;\r\n                b_next = (x([1:2],i+1)-pos)'*((x([1:2],i+1)-pos))-r^2;\r\n                constraints = [constraints; b_next  >= u(3,i)*(1-self.params.gamma1)*b];%Highest order mcbf=1\r\n            end\r\n            % add terminal cost\r\n            cost = cost + (x(:,N+1)-[3;0.01;0;0])'*self.params.P*(x(:,N+1)-[3;0.01;0;0]);\r\n            ops = sdpsettings('solver','ipopt','verbose',0);\r\n            % solve optimization\r\n            diagnostics = optimize(constraints, cost, ops);\r\n            if diagnostics.problem == 0\r\n                feas = true;\r\n                xopt = value(x);\r\n                uopt = value(u);\r\n                Jopt = value(cost);\r\n            else\r\n                feas = false;\r\n                xopt = [];\r\n                uopt = [];\r\n                Jopt = [];\r\n            end\r\n            pos = self.obs.pos1;\r\n            r = self.obs.r1 ;\r\n            self.distlog = [self.distlog, (r^2-(xk(1:2)-pos)'*(xk(1:2)-pos))];\r\n            self.xopenloop{size(self.xopenloop,2)+1} = xopt;\r\n            self.uopenloop{size(self.uopenloop,2)+1} = uopt;\r\n            self.solvertime = [self.solvertime, diagnostics.solvertime];\r\n            fprintf('solver time: %f\\n', diagnostics.solvertime);\r\n        end\r\n    end\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1_0p4/test_each_horizon/tabledata.m",
    "content": "nmpcdata=zeros(3,6);%Store data in matrix for nmpc and impc, first row: mean of computing time; second row: standard deviation of computing time; third row: infeasible rate\r\nimpcdata=zeros(3,6);\r\nfor ii = 1:6\r\ni=ii*4;\r\nfilenm1 = ['timecom' num2str(i) '.mat'];\r\nfilenm2 = ['feasibility' num2str(i) '.mat'];\r\nload(filenm1);\r\nload(filenm2);\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\nnmpcdata(1,ii)=mu1; \r\nimpcdata(1,ii)=mu2;\r\nnmpcdata(2,ii)=sigma1;\r\nimpcdata(2,ii)=sigma2;\r\nnmpcdata(3,ii)=nmpcinf;\r\nimpcdata(3,ii)=impcinf;\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1_0p4/test_each_horizon/test_N12.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=12;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p4\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom12','nmpcplot1','impcplot1');\r\nsave('feasibility12','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.4;\r\nparams_nmpc_dcbf.gamma2 = 0.4;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-12\\n');\r\n    controller_nmpc_dcbf_multiple12 = NMPCDCBF1(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple12.obs = obs;\r\n    controller_nmpc_dcbf_multiple12.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple12.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 4;\r\ngamma2 = 4;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1_0p4/test_each_horizon/test_N16.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=16;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p4\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom16','nmpcplot1','impcplot1');\r\nsave('feasibility16','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.4;\r\nparams_nmpc_dcbf.gamma2 = 0.4;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-16\\n');\r\n    controller_nmpc_dcbf_multiple16 = NMPCDCBF1(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple16.obs = obs;\r\n    controller_nmpc_dcbf_multiple16.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple16.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 4;\r\ngamma2 = 4;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1_0p4/test_each_horizon/test_N20.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=20;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p4\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom20','nmpcplot1','impcplot1');\r\nsave('feasibility20','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.4;\r\nparams_nmpc_dcbf.gamma2 = 0.4;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-20\\n');\r\n    controller_nmpc_dcbf_multiple20 = NMPCDCBF1(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple20.obs = obs;\r\n    controller_nmpc_dcbf_multiple20.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple20.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 4;\r\ngamma2 = 4;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1_0p4/test_each_horizon/test_N24.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=24;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p4\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom24','nmpcplot1','impcplot1');\r\nsave('feasibility24','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.4;\r\nparams_nmpc_dcbf.gamma2 = 0.4;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-24\\n');\r\n    controller_nmpc_dcbf_multiple24 = NMPCDCBF1(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple24.obs = obs;\r\n    controller_nmpc_dcbf_multiple24.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple24.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 4;\r\ngamma2 = 4;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1_0p4/test_each_horizon/test_N4.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=4;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p4\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom4','nmpcplot1','impcplot1');\r\nsave('feasibility4','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.4;\r\nparams_nmpc_dcbf.gamma2 = 0.4;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-4\\n');\r\n    controller_nmpc_dcbf_multiple4 = NMPCDCBF1(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple4.obs = obs;\r\n    controller_nmpc_dcbf_multiple4.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple4.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 4;\r\ngamma2 = 4;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1_0p4/test_each_horizon/test_N8.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=8;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p4\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom8','nmpcplot1','impcplot1');\r\nsave('feasibility8','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.4;\r\nparams_nmpc_dcbf.gamma2 = 0.4;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-8\\n');\r\n    controller_nmpc_dcbf_multiple8 = NMPCDCBF1(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple8.obs = obs;\r\n    controller_nmpc_dcbf_multiple8.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple8.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 4;\r\ngamma2 = 4;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1_0p4gamma2_0p4/NMPCDCBF2.m",
    "content": "classdef NMPCDCBF2 < handle\r\n    % MPC with distance constraints\r\n    properties\r\n        system\r\n        params\r\n        x0\r\n        x_curr\r\n        time_curr = 0.0\r\n        xlog = []\r\n        ulog = []\r\n        tt = 0\r\n        distlog = []\r\n        solvertime = []\r\n        xopenloop = {}\r\n        uopenloop = {}\r\n        u_cost = 0\r\n        obs\r\n    end\r\n    methods\r\n        function self = NMPCDCBF2(x0, system, params)\r\n            % Define MPC_CBF controller\r\n            self.x0 = x0;\r\n            self.x_curr = x0;\r\n            self.system = system;\r\n            self.params = params;\r\n        end\r\n        \r\n        function sim(self, time)\r\n            % Simulate the system until a given time\r\n            tic;\r\n            xk = self.x_curr;\r\n            while self.time_curr < time\r\n                [~, uk, tt] = self.solveNMPCDCBF1(self.x_curr);%if infeasiblility happens, stop\r\n                if tt == -1\r\n                    self.tt = tt;%record computing time for each time-step\r\n                    return\r\n                end\r\n                xk = self.system.A * xk + [xk(4,1) * cos(xk(3,1))*self.system.dt;xk(4,1) * sin(xk(3,1))*self.system.dt;0;0] + self.system.C * uk;\r\n                % update system\r\n                self.x_curr = xk;\r\n                self.time_curr = self.time_curr + self.system.dt;\r\n                self.xlog = [self.xlog, xk];\r\n                self.ulog = [self.ulog, uk];\r\n                self.u_cost = self.u_cost + uk'*uk;\r\n                tt = tt + toc;\r\n                self.tt = tt;\r\n                return\r\n            end\r\n            \r\n        end\r\n        \r\n        function [xopt, uopt,tt] = solveNMPCDCBF1(self, xk)\r\n            % Solve NMPC-DCBF\r\n            [feas, x, u, J] = self.solve_cftoc1(xk);\r\n            if ~feas\r\n                xopt = [];\r\n                uopt = [];\r\n                tt = -1;\r\n                return\r\n            else\r\n                xopt = x(:,2);\r\n                uopt = u(:,1);\r\n                tt = 0;\r\n            end\r\n        end\r\n        \r\n        function [feas, xopt, uopt, Jopt] = solve_cftoc1(self, xk)\r\n            % Solve CFTOC\r\n            % extract variables\r\n            N = self.params.N;\r\n            % define variables and cost\r\n            x = sdpvar(4, N+1);%%%%%%%%%%%%%%%%%%%%%%%%%%%%\r\n            u = sdpvar(4, N);\r\n            constraints = [];\r\n            cost = 0;\r\n            % initial constraint\r\n            constraints = [constraints; x(:,1) == xk];\r\n            % add constraints and costs\r\n            AA=self.system.A;\r\n            BB=self.system.B;\r\n            CC=self.system.C;\r\n            constraints = [constraints;\r\n                    self.system.xl <= x(:,1) <= self.system.xu;\r\n                    self.system.ul <= u(:,1) <= self.system.uu;\r\n                    x(:,2) == AA * x(:,1) + [x(4,1)*cos(x(3,1))*self.system.dt;x(4,1)*sin(x(3,1))*self.system.dt;0; 0] + CC * u(:,1)];\r\n                cost = cost + (x(:,1)-[3;0.01;0;0])'*self.params.Q*(x(:,1)-[3;0.01;0;0]) + (u(:,1)-[0;0;1;1])'*self.params.R*(u(:,1)-[0;0;1;1]); % self.params.S*(w(:,1)-1)^2;\r\n            for i = 2:1:N\r\n                constraints = [constraints;\r\n                    self.system.xl <= x(:,i) <= self.system.xu;\r\n                    self.system.ul <= u(:,i) <= self.system.uu;\r\n                    x(:,i+1) == AA * x(:,i) + [x(4,i)*cos(x(3,i))*self.system.dt;x(4,i)*sin(x(3,i))*self.system.dt;0; 0] + CC * u(:,i)];\r\n                cost = cost + (x(:,i)-[3;0.01;0;0])'*self.params.Q*(x(:,i)-[3;0.01;0;0]) + (u(:,i)-[0;0;1;1])'*self.params.R*(u(:,i)-[0;0;1;1]);% self.params.S*(w(:,i)-1)^2;\r\n            end\r\n            % add CBF constraints\r\n            for i = 1:N-1\r\n                pos = self.obs.pos1;\r\n                r = self.obs.r1 ;\r\n                b = (x([1:2],i)-pos)'*((x([1:2],i)-pos))-r^2;\r\n                b_next = (x([1:2],i+1)-pos)'*((x([1:2],i+1)-pos))-r^2;\r\n                b_next_next = (x([1:2],i+2)-pos)'*((x([1:2],i+2)-pos))-r^2;                \r\n                b1 = (b_next - b)/self.system.dt + self.params.gamma1/self.system.dt * (b);\r\n                b1_next = (b_next_next - b_next)/self.system.dt + self.params.gamma1/self.system.dt * (b_next);\r\n                constraints = [constraints; b1_next  >=u(4,i)*(1-self.params.gamma2)*b1;b_next  >= u(3,i)*(1-self.params.gamma1)*b];%Highest order mcbf=2\r\n            end\r\n            % add terminal cost\r\n            cost = cost + (x(:,N+1)-[3;0.01;0;0])'*self.params.P*(x(:,N+1)-[3;0.01;0;0]);\r\n            ops = sdpsettings('solver','ipopt','verbose',0);\r\n            % solve optimization\r\n            diagnostics = optimize(constraints, cost, ops);\r\n            if diagnostics.problem == 0\r\n                feas = true;\r\n                xopt = value(x);\r\n                uopt = value(u);\r\n                Jopt = value(cost);\r\n            else\r\n                feas = false;\r\n                xopt = [];\r\n                uopt = [];\r\n                Jopt = [];\r\n            end\r\n            pos = self.obs.pos1;\r\n            r = self.obs.r1 ;\r\n            self.distlog = [self.distlog, (r^2-(xk(1:2)-pos)'*(xk(1:2)-pos))];\r\n            self.xopenloop{size(self.xopenloop,2)+1} = xopt;\r\n            self.uopenloop{size(self.uopenloop,2)+1} = uopt;\r\n            self.solvertime = [self.solvertime, diagnostics.solvertime];\r\n            fprintf('solver time: %f\\n', diagnostics.solvertime);\r\n        end\r\n    end\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1_0p4gamma2_0p4/test_comprehensive.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnmpcdata=zeros(3,6);%Store data in matrix for nmpc and impc, first row: mean of computing time; second row: standard deviation of computing time; third row: infeasible rate\r\nimpcdata=zeros(3,6);\r\nfor ii = 1:6\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=ii*4;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p4gamma2_0p4\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nfilenm1 = ['timecom' num2str(i) '.mat'];\r\nfilenm2 = ['feasibility' num2str(i) '.mat'];\r\nsave(filenm1,'nmpcplot1','impcplot1');\r\nsave(filenm2,'nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\nnmpcdata(1,ii)=mu1;\r\nimpcdata(1,ii)=mu2;\r\nnmpcdata(2,ii)=sigma1;\r\nimpcdata(2,ii)=sigma2;\r\nnmpcdata(3,ii)=nmpcinf;\r\nimpcdata(3,ii)=impcinf;\r\nend\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.4;\r\nparams_nmpc_dcbf.gamma2 = 0.4;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-4\\n');\r\n    controller_nmpc_dcbf_multiple4 = NMPCDCBF2(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple4.obs = obs;\r\n    controller_nmpc_dcbf_multiple4.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple4.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 4;\r\ngamma2 = 4;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1_0p4gamma2_0p4/test_each_horizon/NMPCDCBF2.m",
    "content": "classdef NMPCDCBF2 < handle\r\n    % MPC with distance constraints\r\n    properties\r\n        system\r\n        params\r\n        x0\r\n        x_curr\r\n        time_curr = 0.0\r\n        xlog = []\r\n        ulog = []\r\n        tt = 0\r\n        distlog = []\r\n        solvertime = []\r\n        xopenloop = {}\r\n        uopenloop = {}\r\n        u_cost = 0\r\n        obs\r\n    end\r\n    methods\r\n        function self = NMPCDCBF2(x0, system, params)\r\n            % Define MPC_CBF controller\r\n            self.x0 = x0;\r\n            self.x_curr = x0;\r\n            self.system = system;\r\n            self.params = params;\r\n        end\r\n        \r\n        function sim(self, time)\r\n            % Simulate the system until a given time\r\n            tic;\r\n            xk = self.x_curr;\r\n            while self.time_curr < time\r\n                [~, uk, tt] = self.solveNMPCDCBF1(self.x_curr);%if infeasiblility happens, stop\r\n                if tt == -1\r\n                    self.tt = tt;%record computing time for each time-step\r\n                    return\r\n                end\r\n                xk = self.system.A * xk + [xk(4,1) * cos(xk(3,1))*self.system.dt;xk(4,1) * sin(xk(3,1))*self.system.dt;0;0] + self.system.C * uk;\r\n                % update system\r\n                self.x_curr = xk;\r\n                self.time_curr = self.time_curr + self.system.dt;\r\n                self.xlog = [self.xlog, xk];\r\n                self.ulog = [self.ulog, uk];\r\n                self.u_cost = self.u_cost + uk'*uk;\r\n                tt = tt + toc;\r\n                self.tt = tt;\r\n                return\r\n            end\r\n            \r\n        end\r\n        \r\n        function [xopt, uopt,tt] = solveNMPCDCBF1(self, xk)\r\n            % Solve NMPC-DCBF\r\n            [feas, x, u, J] = self.solve_cftoc1(xk);\r\n            if ~feas\r\n                xopt = [];\r\n                uopt = [];\r\n                tt = -1;\r\n                return\r\n            else\r\n                xopt = x(:,2);\r\n                uopt = u(:,1);\r\n                tt = 0;\r\n            end\r\n        end\r\n        \r\n        function [feas, xopt, uopt, Jopt] = solve_cftoc1(self, xk)\r\n            % Solve CFTOC\r\n            % extract variables\r\n            N = self.params.N;\r\n            % define variables and cost\r\n            x = sdpvar(4, N+1);%%%%%%%%%%%%%%%%%%%%%%%%%%%%\r\n            u = sdpvar(4, N);\r\n            constraints = [];\r\n            cost = 0;\r\n            % initial constraint\r\n            constraints = [constraints; x(:,1) == xk];\r\n            % add constraints and costs\r\n            AA=self.system.A;\r\n            BB=self.system.B;\r\n            CC=self.system.C;\r\n            constraints = [constraints;\r\n                    self.system.xl <= x(:,1) <= self.system.xu;\r\n                    self.system.ul <= u(:,1) <= self.system.uu;\r\n                    x(:,2) == AA * x(:,1) + [x(4,1)*cos(x(3,1))*self.system.dt;x(4,1)*sin(x(3,1))*self.system.dt;0; 0] + CC * u(:,1)];\r\n                cost = cost + (x(:,1)-[3;0.01;0;0])'*self.params.Q*(x(:,1)-[3;0.01;0;0]) + (u(:,1)-[0;0;1;1])'*self.params.R*(u(:,1)-[0;0;1;1]); % self.params.S*(w(:,1)-1)^2;\r\n            for i = 2:1:N\r\n                constraints = [constraints;\r\n                    self.system.xl <= x(:,i) <= self.system.xu;\r\n                    self.system.ul <= u(:,i) <= self.system.uu;\r\n                    x(:,i+1) == AA * x(:,i) + [x(4,i)*cos(x(3,i))*self.system.dt;x(4,i)*sin(x(3,i))*self.system.dt;0; 0] + CC * u(:,i)];\r\n                cost = cost + (x(:,i)-[3;0.01;0;0])'*self.params.Q*(x(:,i)-[3;0.01;0;0]) + (u(:,i)-[0;0;1;1])'*self.params.R*(u(:,i)-[0;0;1;1]);% self.params.S*(w(:,i)-1)^2;\r\n            end\r\n            % add CBF constraints\r\n            for i = 1:N-1\r\n                pos = self.obs.pos1;\r\n                r = self.obs.r1 ;\r\n                b = (x([1:2],i)-pos)'*((x([1:2],i)-pos))-r^2;\r\n                b_next = (x([1:2],i+1)-pos)'*((x([1:2],i+1)-pos))-r^2;\r\n                b_next_next = (x([1:2],i+2)-pos)'*((x([1:2],i+2)-pos))-r^2;                \r\n                b1 = (b_next - b)/self.system.dt + self.params.gamma1/self.system.dt * (b);\r\n                b1_next = (b_next_next - b_next)/self.system.dt + self.params.gamma1/self.system.dt * (b_next);\r\n                constraints = [constraints; b1_next  >=u(4,i)*(1-self.params.gamma2)*b1;b_next  >= u(3,i)*(1-self.params.gamma1)*b];%Highest order mcbf=2\r\n            end\r\n            % add terminal cost\r\n            cost = cost + (x(:,N+1)-[3;0.01;0;0])'*self.params.P*(x(:,N+1)-[3;0.01;0;0]);\r\n            ops = sdpsettings('solver','ipopt','verbose',0);\r\n            % solve optimization\r\n            diagnostics = optimize(constraints, cost, ops);\r\n            if diagnostics.problem == 0\r\n                feas = true;\r\n                xopt = value(x);\r\n                uopt = value(u);\r\n                Jopt = value(cost);\r\n            else\r\n                feas = false;\r\n                xopt = [];\r\n                uopt = [];\r\n                Jopt = [];\r\n            end\r\n            pos = self.obs.pos1;\r\n            r = self.obs.r1 ;\r\n            self.distlog = [self.distlog, (r^2-(xk(1:2)-pos)'*(xk(1:2)-pos))];\r\n            self.xopenloop{size(self.xopenloop,2)+1} = xopt;\r\n            self.uopenloop{size(self.uopenloop,2)+1} = uopt;\r\n            self.solvertime = [self.solvertime, diagnostics.solvertime];\r\n            fprintf('solver time: %f\\n', diagnostics.solvertime);\r\n        end\r\n    end\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1_0p4gamma2_0p4/test_each_horizon/tabledata.m",
    "content": "nmpcdata=zeros(3,6);%Store data in matrix for nmpc and impc, first row: mean of computing time; second row: standard deviation of computing time; third row: infeasible rate\r\nimpcdata=zeros(3,6);\r\nfor ii = 1:6\r\ni=ii*4;\r\nfilenm1 = ['timecom' num2str(i) '.mat'];\r\nfilenm2 = ['feasibility' num2str(i) '.mat'];\r\nload(filenm1);\r\nload(filenm2);\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\nnmpcdata(1,ii)=mu1;\r\nimpcdata(1,ii)=mu2;\r\nnmpcdata(2,ii)=sigma1;\r\nimpcdata(2,ii)=sigma2;\r\nnmpcdata(3,ii)=nmpcinf;\r\nimpcdata(3,ii)=impcinf;\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1_0p4gamma2_0p4/test_each_horizon/test_N12.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=12;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p4gamma2_0p4\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom12','nmpcplot1','impcplot1');\r\nsave('feasibility12','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.4;\r\nparams_nmpc_dcbf.gamma2 = 0.4;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-12\\n');\r\n    controller_nmpc_dcbf_multiple12 = NMPCDCBF2(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple12.obs = obs;\r\n    controller_nmpc_dcbf_multiple12.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple12.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 4;\r\ngamma2 = 4;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1_0p4gamma2_0p4/test_each_horizon/test_N16.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=16;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p4gamma2_0p4\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom16','nmpcplot1','impcplot1');\r\nsave('feasibility16','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.4;\r\nparams_nmpc_dcbf.gamma2 = 0.4;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-16\\n');\r\n    controller_nmpc_dcbf_multiple16 = NMPCDCBF2(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple16.obs = obs;\r\n    controller_nmpc_dcbf_multiple16.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple16.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 4;\r\ngamma2 = 4;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1_0p4gamma2_0p4/test_each_horizon/test_N20.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=20;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p4gamma2_0p4\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom20','nmpcplot1','impcplot1');\r\nsave('feasibility20','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.4;\r\nparams_nmpc_dcbf.gamma2 = 0.4;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-20\\n');\r\n    controller_nmpc_dcbf_multiple20 = NMPCDCBF2(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple20.obs = obs;\r\n    controller_nmpc_dcbf_multiple20.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple20.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 4;\r\ngamma2 = 4;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1_0p4gamma2_0p4/test_each_horizon/test_N24.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=24;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p4gamma2_0p4\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom24','nmpcplot1','impcplot1');\r\nsave('feasibility24','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.4;\r\nparams_nmpc_dcbf.gamma2 = 0.4;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-24\\n');\r\n    controller_nmpc_dcbf_multiple24 = NMPCDCBF2(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple24.obs = obs;\r\n    controller_nmpc_dcbf_multiple24.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple24.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 4;\r\ngamma2 = 4;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1_0p4gamma2_0p4/test_each_horizon/test_N4.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=4;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p4gamma2_0p4\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom4','nmpcplot1','impcplot1');\r\nsave('feasibility4','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.4;\r\nparams_nmpc_dcbf.gamma2 = 0.4;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-4\\n');\r\n    controller_nmpc_dcbf_multiple4 = NMPCDCBF2(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple4.obs = obs;\r\n    controller_nmpc_dcbf_multiple4.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple4.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 4;\r\ngamma2 = 4;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/benchmark/gamma1_0p4gamma2_0p4/test_each_horizon/test_N8.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------------------------------------------------------\r\nnb = 1000;%Total number of initial states\r\nnmpcd=zeros(1,nb);%Store computing time for one time-step for NMPC-DCBF\r\nimpcd=zeros(1,nb);%Store computing time for one time-step for iMPC-DCBF\r\nnmpcinf=zeros(1,1);%Store infeasible rate for one time-step for NMPC-DCBF\r\nimpcinf=zeros(1,1);%Store infeasible rate for one time-step for iMPC-DCBF\r\ni=8;%i is number of horozon\r\nts = 1;%Total time steps\r\nload(gamma1_0p4gamma2_0p4\\InitialStateData');%Load the generated 1000 initial states\r\n[a, b, c, d]=compare(i,ts,nb,InitialMat);%Involves NMPC-DCBF and iMPC-DCBF\r\nnmpcd(1,:)=a;\r\nimpcd(1,:)=b;\r\nnmpcinf(1,1)=c;\r\nimpcinf(1,1)=d;\r\nnmpcplot1=nmpcd(1,:);\r\nnmpcplot1(nmpcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\nimpcplot1=impcd(1,:);\r\nimpcplot1(impcplot1==-1)=[];%Eliminate infeasible one time-step trajectories\r\n\r\nsave('timecom8','nmpcplot1','impcplot1');\r\nsave('feasibility8','nmpcinf','impcinf');\r\n\r\ndistnmpc = fitdist(nmpcplot1','Normal');\r\ndistimpc = fitdist(impcplot1','Normal');\r\nmu1=distnmpc.mu;%Get mean of sample of computing time for NMPC-DCBF\r\nmu2=distimpc.mu;%Get mean of sample of computing time for iMPC-DCBF\r\nsigma1=distnmpc.sigma;%Get variance of sample of computing time for NMPC-DCBF\r\nsigma2=distimpc.sigma;%Get variance of sample of computing time for iMPC-DCBF\r\n\r\n\r\n%Initialize atmosphere parameters\r\nfunction [tnmpc, timpc, ratiotnmpc, ratiotimpc]=compare(N11,ttsim,samplen,InitialMat)\r\ntnmpc=[];\r\ntimpc=[];\r\nfor i=1:samplen\r\nN1=N11;\r\ntsim=ttsim;\r\nxini1=InitialMat(1,i);\r\nyini1=InitialMat(2,i);\r\nthetaini1=InitialMat(3,i);\r\nvini1=InitialMat(4,i);\r\nx01=[xini1;yini1;thetaini1;vini1];\r\nx02=[xini1 yini1 thetaini1 vini1];\r\nt1 = nmpcdcbf(x01, N1, tsim);\r\nt2 = impcdcbf(x02, N1, tsim);\r\ntindex=[N11 i];\r\ndisp(tindex);\r\ntnmpc=[tnmpc t1];%Computing time for NMPC-DCBF\r\ntimpc=[timpc t2];%Computing time for iMPC-DCBF\r\nend\r\nnnmpc1 = length(tnmpc);\r\nnimpc1 = length(timpc);\r\ntnmpcs = tnmpc;\r\ntimpcs = timpc;\r\ntnmpcs(tnmpcs==-1)=[];\r\ntimpcs(timpcs==-1)=[];\r\nnnmpc2 = length(tnmpcs);\r\nnimpc2 = length(timpcs);\r\nratiotnmpc = (nnmpc1-nnmpc2)/nnmpc1;%Infeasible rate for NMPC-DCBF\r\nratiotimpc = (nimpc1-nimpc2)/nimpc1;%Infeasible rate for iMPC-DCBF\r\nend\r\n\r\n\r\n\r\n\r\nfunction t1 = nmpcdcbf(x00, N1, ttsim)\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = x00;\r\ndt = 0.1;\r\ntime_total = ttsim *dt;\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time unicycle model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% NMPC-DCBF parameters\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.4;\r\nparams_nmpc_dcbf.gamma2 = 0.4;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n\r\n\r\n%% Simulate NMPC-DCBF with other N\r\nparams_nmpc_dcbf.N = N1;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-8\\n');\r\n    controller_nmpc_dcbf_multiple8 = NMPCDCBF2(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple8.obs = obs;\r\n    controller_nmpc_dcbf_multiple8.sim(time_total);\r\nend\r\nt1=controller_nmpc_dcbf_multiple8.tt;\r\nend\r\n\r\n\r\nfunction t2=impcdcbf(x00, N1, ttsim)\r\nt2=0;\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 4;\r\ngamma2 = 4;\r\nnsim = ttsim;\r\n\r\ntic;\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = x00;\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n%    error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nt2=t2+toc;\r\nreturn\r\n\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n%        error('OSQP did not solve the problem!')\r\n        t2=-1;\r\n        return\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    testx0 = [testx0 x0];\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/closedloop_performance/Closedloop_Trajectories_Hyperparameters.m",
    "content": "close all\r\nclear\r\n\r\n%------------------------------------------NMPC-DCBF---------------------------------------------\r\n\r\n%% General Flags\r\nrun_nmpc_dcbf_one = true;\r\nrun_nmpc_dcbf_multiple = true;\r\n\r\n%% Setup and Parameters\r\nx0 = [-3; 0; 0; 0];%Initial Condition\r\ntime_total = 4.5;%Time for the total steps, equal to tsim\r\ndt = 0.1;%One time-step\r\nP = zeros(4,4);%Weight matrix P\r\nP(1,1) = 10; P(2,2) = 10; P(3,3) = 10;P(4,4) = 10;\r\nQ = zeros(4,4);%Weight matrix Q\r\nQ(1,1) = 10; Q(2,2) = 10; Q(3,3) = 10;Q(4,4) = 10;\r\nR = zeros(4,4);%Weight matrix R\r\nR(1,1) = 1; R(2,2) = 1;R(3,3) = 1000;R(4,4) = 1000;\r\n%Variables range as below\r\nxmin = [-10; -10; -10;-10];\r\nxmax = [10; 10; 10;10];\r\numin = [-7; -5;-inf;-inf];\r\numax = [7; 5;inf;inf];\r\n\r\n%% Discrete-time Unicycle Model\r\nsystem.dt = dt;\r\nsystem.A = [1 0 0 0;\r\n    0 1 0 0;\r\n    0 0 1 0;\r\n    0 0 0 1];\r\nsystem.B = [x0(4,1)*cos(x0(3,1))*dt;\r\n    x0(4,1)*sin(x0(3,1))*dt;\r\n    0;\r\n    0];\r\nsystem.C =[0 0 0 0;\r\n    0 0 0 0;\r\n    1*dt 0 0 0;\r\n    0 1*dt 0 0];\r\nsystem.xl = xmin;\r\nsystem.xu = xmax;\r\nsystem.ul = umin;\r\nsystem.uu = umax;\r\n\r\n%% Obstacle\r\nobs.pos1 = [0; 0];\r\nobs.r1 = 1;\r\n\r\n%% NMPC-DCBF parameters set 1\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.4;\r\nparams_nmpc_dcbf.gamma2 = 0.4;\r\n%% Simulate NMPC-DCBF with Number of Horizon N\r\nparams_nmpc_dcbf.N = 24;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-11\\n');\r\n    controller_nmpc_dcbf_multiple11 = NMPCDCBF1(x0, system, params_nmpc_dcbf);%Highest order mcbf=1\r\n    controller_nmpc_dcbf_multiple11.obs = obs;\r\n    controller_nmpc_dcbf_multiple11.sim(time_total);\r\nend\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-12\\n');\r\n    controller_nmpc_dcbf_multiple12 = NMPCDCBF2(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple12.obs = obs;\r\n    controller_nmpc_dcbf_multiple12.sim(time_total);\r\nend\r\n\r\n%% NMPC-DCBF parameters set 2\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.6;%\r\nparams_nmpc_dcbf.gamma2 = 0.6;\r\n%% Simulate NMPC-DCBF with Number of Horizon N\r\nparams_nmpc_dcbf.N = 24;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-21\\n');\r\n    controller_nmpc_dcbf_multiple21 = NMPCDCBF1(x0, system, params_nmpc_dcbf);%Highest order mcbf=1\r\n    controller_nmpc_dcbf_multiple21.obs = obs;\r\n    controller_nmpc_dcbf_multiple21.sim(time_total);\r\nend\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-22\\n');\r\n    controller_nmpc_dcbf_multiple22 = NMPCDCBF2(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple22.obs = obs;\r\n    controller_nmpc_dcbf_multiple22.sim(time_total);\r\nend\r\n\r\n%% NMPC-DCBF parameters set 3\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.4;%\r\nparams_nmpc_dcbf.gamma2 = 0.4;\r\n%% Simulate NMPC-DCBF with Number of Horizon N\r\nparams_nmpc_dcbf.N = 16;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-31\\n');\r\n    controller_nmpc_dcbf_multiple31 = NMPCDCBF1(x0, system, params_nmpc_dcbf);%Highest order mcbf=1\r\n    controller_nmpc_dcbf_multiple31.obs = obs;\r\n    controller_nmpc_dcbf_multiple31.sim(time_total);\r\nend\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-32\\n');\r\n    controller_nmpc_dcbf_multiple32 = NMPCDCBF2(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple32.obs = obs;\r\n    controller_nmpc_dcbf_multiple32.sim(time_total);\r\nend\r\n\r\n%% NMPC-DCBF parameters set 4\r\nparams_nmpc_dcbf.Q = Q;\r\nparams_nmpc_dcbf.R = R;\r\nparams_nmpc_dcbf.P = P;\r\nparams_nmpc_dcbf.gamma1 = 0.6;%\r\nparams_nmpc_dcbf.gamma2 = 0.6;\r\n%% Simulate NMPC-DCBF with Number of Horizon N\r\nparams_nmpc_dcbf.N = 16;\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-41\\n');\r\n    controller_nmpc_dcbf_multiple41 = NMPCDCBF1(x0, system, params_nmpc_dcbf);%Highest order mcbf=1\r\n    controller_nmpc_dcbf_multiple41.obs = obs;\r\n    controller_nmpc_dcbf_multiple41.sim(time_total);\r\nend\r\nif run_nmpc_dcbf_one\r\n    fprintf('Run NMPC-DCBF-42\\n');\r\n    controller_nmpc_dcbf_multiple42 = NMPCDCBF2(x0, system, params_nmpc_dcbf);%Highest order mcbf=2\r\n    controller_nmpc_dcbf_multiple42.obs = obs;\r\n    controller_nmpc_dcbf_multiple42.sim(time_total);\r\nend\r\n%% Initialize atmosphere parameters\r\nimpc1 = impcdcbf2(4,4,24);%Highest order mcbf=2\r\nimpc2 = impcdcbf2(6,6,24);\r\nimpc3 = impcdcbf2(4,4,16);\r\nimpc4 = impcdcbf2(6,6,16);\r\nimpc5 = impcdcbf1(4,24);%Highest order mcbf=1\r\nimpc6 = impcdcbf1(6,24);\r\n\r\n\r\nsave('impc_N24_Gamma4_4','impc1');%impc-solid lines\r\nsave('impc_N24_Gamma6_6','impc2');\r\nsave('impc_N16_Gamma4_4','impc3');\r\nsave('impc_N16_Gamma6_6','impc4');\r\nsave('impc_N24_Gamma4','impc5');\r\nsave('impc_N24_Gamma6','impc6');\r\n\r\ncontroller_nmpc_dcbf_multiple1=controller_nmpc_dcbf_multiple12.xlog;%Highest order mcbf=2\r\ncontroller_nmpc_dcbf_multiple2=controller_nmpc_dcbf_multiple22.xlog;\r\ncontroller_nmpc_dcbf_multiple3=controller_nmpc_dcbf_multiple32.xlog;\r\ncontroller_nmpc_dcbf_multiple4=controller_nmpc_dcbf_multiple42.xlog;\r\ncontroller_nmpc_dcbf_multiple5=controller_nmpc_dcbf_multiple11.xlog;%Highest order mcbf=1\r\ncontroller_nmpc_dcbf_multiple6=controller_nmpc_dcbf_multiple21.xlog;\r\n\r\nsave('nmpc_N24_Gamma4_4','controller_mpc_cbf_multiple1');%nmpc-dashed lines\r\nsave('nmpc_N24_Gamma6_6','controller_mpc_cbf_multiple2');\r\nsave('nmpc_N16_Gamma4_4','controller_mpc_cbf_multiple3');\r\nsave('nmpc_N16_Gamma6_6','controller_mpc_cbf_multiple4');\r\nsave('nmpc_N24_Gamma4','controller_mpc_cbf_multiple5');\r\nsave('nmpc_N24_Gamma6','controller_mpc_cbf_multiple6');\r\n\r\n\r\n%--------------------------------------iMPC-DCBF------------------------------------------------\r\nfunction impc=impcdcbf2(gamma1, gamma2, N1)\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = gamma1;\r\ngamma2 = gamma2;\r\nnsim = 45;%Total time steps, corresponding to time_total in NMPC-DCBF\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = [-3 0 0 0];\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);%First order CBF constraints\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);%Second order CBF constraints\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\n\r\nA = [Aeq; Aineq; Acbf; A2cbf];\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n   error('OSQP did not solve the problem!')\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step\r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n       error('OSQP did not solve the problem!')\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n       error('OSQP did not solve the problem!')\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\nfunction impc=impcdcbf1(gamma1, N1)\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = N1;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = gamma1;\r\nnsim = 45;%Total time steps, corresponding to time_total in NMPC-DCBF\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = [-3 0 0 0];\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);%First order CBF constraints\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf];\r\nl = [leq; lineq; lcbf];\r\nu = [ueq; uineq; ucbf];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n   error('OSQP did not solve the problem!')\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)%Iterations for the first time-step \r\n    storagex = ctrlx;%store the state variables and inputs in order to compare them with the next iteration\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    \r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf];\r\n    l = [leq; lineq; lcbf];\r\n    u = [ueq; uineq; ucbf];\r\n\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n       error('OSQP did not solve the problem!')\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break \r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)%Iterations for the left time steps\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf];\r\n    l = [leq; lineq; lcbf];\r\n    u = [ueq; uineq; ucbf];\r\n\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n       error('OSQP did not solve the problem!')\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break \r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/closedloop_performance/FigureGenerate.m",
    "content": "close all\r\nclear\r\n\r\n%--------------------------------------------------------------------------------------\r\nnsim=100;%Total time-steps for the trajectory\r\nxo = 0;%Obstacle parameters\r\nyo = 0;\r\nr = 1;\r\nN=24;%Number of iteration\r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\trajectory');%For the location address, please change it later based on where you download the files\r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\iteration_x');\r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\iteration_y');\r\nfigure(1)%Figure 2-a of paper\r\nset(0,'defaultfigurecolor','w'); \r\nset(gca,'LooseInset',get(gca,'TightInset'));\r\nhold on;\r\nth = linspace(0,2*pi*100);\r\nx = cos(th) ; y = sin(th) ;\r\nplot(xo + r*x, yo + r*y, 'k-', 'LineWidth', 2);\r\nfill(xo + r*x, yo + r*y, [1 0.5 0]);\r\naxis square\r\nplot(impctra(1,1), impctra(2,1), 'db', 'LineWidth', 1);\r\nplot(3, 0, 'dr', 'LineWidth', 1);\r\nh = plot(impctra(1,:), impctra(2,:), 'ko-',...\r\n        'LineWidth', 1.0,'MarkerSize',4);\r\nh1 = plot(Itera_x(1,:), Itera_y(1,:),'c', 'LineWidth', 1);%\r\nh2 =plot(Itera_x(3,:), Itera_y(3,:),'g', 'LineWidth', 1);\r\nh3 =plot(Itera_x(5,:), Itera_y(5,:),'m', 'LineWidth', 1);\r\nh4 =plot(Itera_x(10,:), Itera_y(10,:),'r', 'LineWidth', 1);\r\nh5 =plot(Itera_x(32,:), Itera_y(32,:),'b', 'LineWidth', 1);\r\n\r\nh_legend = legend([h,h1,h2,h3,h4,h5], {'Closed-loop ($t_{\\mathrm{sim}}=100$)','Open-loop ($j=1$)','Open-loop ($j=3$)','Open-loop ($j=5$)',...\r\n    'Open-loop ($j=10$)','Open-loop ($j=32$)'}, 'Location', 'SouthEast');\r\nset(h_legend, 'Interpreter','latex');\r\nset(gca,'LineWidth', 0.2, 'FontSize', 19);\r\ngrid on\r\naxis equal\r\nxlim([-3,3]);\r\nylim([-2,2]);\r\nxlabel('$x(m)$','interpreter','latex','FontSize',20);\r\nylabel('$y(m)$','interpreter','latex','FontSize',20);\r\ntext('Interpreter','latex','String','$t=6$','Position',[-2.45 0.9],'FontSize',18);\r\nannotation('arrow',[0.21 0.21],[0.70 0.60],'LineStyle', '-','color',[0 0 0]);\r\nprint(gcf,'figures/openloop-snapshots', '-depsc');\r\nprint(gcf,'figures/openloop-snapshots.png', '-dpng', '-r800');\r\n\r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\impc_N24_Gamma4_4');%impc-24-4-4\r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\impc_N24_Gamma6_6');%impc-24-6-6\r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\impc_N16_Gamma4_4');%impc-16-4-4\r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\impc_N16_Gamma6_6');%impc-16-6-6\r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\nmpc_N24_Gamma4_4');%nmpc-24-6-6\r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\nmpc_N24_Gamma6_6');%nmpc-24-4-4\r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\nmpc_N16_Gamma4_4');%nmpc-16-6-6\r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\nmpc_N16_Gamma6_6');%nmpc-16-4-4\r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\impc_N24_Gamma4');%impc-24-4\r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\impc_N24_Gamma6');%impc-24-6\r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\nmpc_N24_Gamma4');%nmpc-24-4\r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\nmpc_N24_Gamma6');%nmpc-24-6\r\n\r\nfigure(2)%Figure 2-b of paper\r\n%Draw the figure\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nxr = [3;0.01;0;0];\r\nset(0,'defaultfigurecolor','w'); \r\nset(gca,'LooseInset',get(gca,'TightInset'));\r\nhold on;\r\nth = linspace(0,2*pi*100);\r\nx = cos(th) ; y = sin(th) ;\r\nplot(xo + r*x, yo + r*y, 'k-', 'LineWidth', 2);\r\nfill(xo + r*x, yo + r*y, [1 0.5 0]);\r\naxis square\r\nplot(impc1(1,1), impc2(2,1), 'db', 'LineWidth', 1);\r\nplot(xr(1), xr(2), 'dr', 'LineWidth', 1);\r\nh1 = plot(impc1(1,:), impc1(2,:), 'k',...\r\n        'LineWidth', 2.0,'MarkerSize',4);\r\nh2 = plot(impc2(1,:), impc2(2,:), 'r',...\r\n        'LineWidth', 2.0,'MarkerSize',4);\r\nh3 = plot(impc3(1,:), impc3(2,:), 'b',...\r\n        'LineWidth', 2.0,'MarkerSize',4);\r\nh4 = plot(impc4(1,:), impc4(2,:), 'm',...\r\n        'LineWidth', 2.0,'MarkerSize',4);\r\n\r\nh_legend1 = legend([h1,h2,h3,h4], {'$N=24,\\gamma_{1}=0.4,\\gamma_{2}=0.4$','$N=24,\\gamma_{1}=0.6,\\gamma_{2}=0.6$','$N=16,\\gamma_{1}=0.4,\\gamma_{2}=0.4$','$N=16,\\gamma_{1}=0.6,\\gamma_{2}=0.6$'}, 'Location', 'SouthEast');\r\nset(h_legend1, 'Interpreter','latex');\r\nset(gca,'LineWidth', 0.2, 'FontSize', 18);\r\ngrid on\r\naxis equal\r\nxlim([-3,3]);\r\nylim([-2,2]);\r\nxlabel('$x(m)$','interpreter','latex','FontSize',20);\r\nylabel('$y(m)$','interpreter','latex','FontSize',20);\r\nprint(gcf,'figures/closedloop-snapshots1', '-depsc');\r\nprint(gcf,'figures/closedloop-snapshots1.png', '-dpng', '-r800');\r\n\r\nfigure(3)%Figure 2-c of paper\r\n% Draw the figure\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nxr = [3;0.01;0;0];\r\nset(0,'defaultfigurecolor','w'); \r\nset(gca,'LooseInset',get(gca,'TightInset'));\r\nhold on;\r\nth = linspace(0,2*pi*100);\r\nx = cos(th) ; y = sin(th) ;\r\nplot(xo + r*x, yo + r*y, 'k-', 'LineWidth', 2);\r\nfill(xo + r*x, yo + r*y, [1 0.5 0]);\r\naxis square\r\nplot(impc1(1,1), impc2(2,1), 'db', 'LineWidth', 1);\r\nplot(xr(1), xr(2), 'dr', 'LineWidth', 1);\r\nh5 = plot(controller_nmpc_dcbf_multiple1(1,:), controller_nmpc_dcbf_multiple1(2,:), 'k--',...\r\n        'LineWidth', 2.0,'MarkerSize',4);\r\nh6 = plot(controller_nmpc_dcbf_multiple2(1,:), controller_nmpc_dcbf_multiple2(2,:), 'r--',...\r\n        'LineWidth', 2.0,'MarkerSize',4);\r\nh7 = plot(controller_nmpc_dcbf_multiple3(1,:), controller_nmpc_dcbf_multiple3(2,:), 'b--',...\r\n        'LineWidth', 2.0,'MarkerSize',4);\r\nh8 = plot(controller_nmpc_dcbf_multiple4(1,:), controller_nmpc_dcbf_multiple4(2,:), 'm--',...\r\n        'LineWidth', 2.0,'MarkerSize',4);\r\nh_legend2 = legend([h5,h6,h7,h8], {'$N=24,\\gamma_{1}=0.4,\\gamma_{2}=0.4$','$N=24,\\gamma_{1}=0.6,\\gamma_{2}=0.6$','$N=16,\\gamma_{1}=0.4,\\gamma_{2}=0.4$','$N=16,\\gamma_{1}=0.6,\\gamma_{2}=0.6$'}, 'Location', 'SouthEast');\r\nset(h_legend2, 'Interpreter','latex');\r\nset(gca,'LineWidth', 0.2, 'FontSize', 16);\r\ngrid on\r\naxis equal\r\nxlim([-3,3]);\r\nylim([-2,2]);\r\nxlabel('$x(m)$','interpreter','latex','FontSize',20);\r\nylabel('$y(m)$','interpreter','latex','FontSize',20);\r\ntext('Interpreter','latex','String','$t=13$','Position',[-2 -1.1],'FontSize',18);\r\nannotation('arrow',[0.37 0.47],[0.33 0.38],'LineStyle', '-','color',[0 0 0]);\r\ntext('Interpreter','latex','String','$t=33$','Position',[1 0.1],'FontSize',18);\r\nannotation('arrow',[0.78 0.88],[0.53 0.48],'LineStyle', '-','color',[0 0 0]);\r\nprint(gcf,'figures/closedloop-snapshots2', '-depsc');\r\nprint(gcf,'figures/closedloop-snapshots2.png', '-dpng', '-r800');\r\n\r\nfigure(4)%Figure 2-d of paper\r\n% Draw the figure\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nxr = [3;0.01;0;0];\r\nset(0,'defaultfigurecolor','w'); \r\nset(gca,'FontSize',20)\r\nset(gca,'LooseInset',get(gca,'TightInset'));\r\nhold on;\r\nth = linspace(0,2*pi*100);\r\nx = cos(th) ; y = sin(th) ;\r\nplot(xo + r*x, yo + r*y, 'k-', 'LineWidth', 2);\r\nfill(xo + r*x, yo + r*y, [1 0.5 0]);\r\naxis square\r\nplot(impc1(1,1), impc2(2,1), 'db', 'LineWidth', 1);\r\nplot(xr(1), xr(2), 'dr', 'LineWidth', 1);\r\nh9 = plot(impc5(1,1:46), impc5(2,1:46), 'k',...\r\n        'LineWidth', 2.0,'MarkerSize',4);\r\nh10 = plot(impc6(1,1:46), impc6(2,1:46), 'r',...\r\n        'LineWidth', 2.0,'MarkerSize',4);\r\nh11 = plot(controller_nmpc_dcbf_multiple5(1,:), controller_nmpc_dcbf_multiple5(2,:), 'b--',...\r\n        'LineWidth', 2.0,'MarkerSize',4);\r\nh12 = plot(controller_nmpc_dcbf_multiple6(1,:), controller_nmpc_dcbf_multiple6(2,:), 'm--',...\r\n        'LineWidth', 2.0,'MarkerSize',4);\r\nh_legend3 = legend([h9,h10,h11,h12], {'$N=24,\\gamma_{1}=0.4$','$N=24,\\gamma_{1}=0.6$','$N=24,\\gamma_{1}=0.4$','$N=24,\\gamma_{1}=0.6$'}, 'Location', 'SouthEast');\r\nset(h_legend3, 'Interpreter','latex');\r\nset(gca,'LineWidth', 0.2, 'FontSize', 18);\r\ngrid on\r\naxis equal\r\nxlim([-3,3]);\r\nylim([-2,2]);\r\nxlabel('$x(m)$','interpreter','latex','FontSize',20);\r\nylabel('$y(m)$','interpreter','latex','FontSize',20);\r\nprint(gcf,'figures/closedloop-snapshots3', '-depsc');\r\nprint(gcf,'figures/closedloop-snapshots3.png', '-dpng', '-r800');\r\n\r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\jtconv_Gamma4_4');\r\nfigure(5)%Figure 4-a of paper\r\nkk = 0:1:(nsim-1);\r\nhk = plot(kk, kk44(1,:), 'ko-',...\r\n        'LineWidth', 1.0,'MarkerSize',4);\r\nxlim([0,99]);\r\nylim([0,1000]);\r\nset(gca,'FontSize',18)\r\nxlabel('$t$','interpreter','latex','FontSize',20);\r\nylabel('$j_{t,\\mathrm{conv}}$','interpreter','latex','FontSize',20);\r\nset(gca, 'YScale', 'log')\r\nprint(gcf,'figures/J-converge-1', '-depsc');\r\nprint(gcf,'figures/J-converge-1.png', '-dpng', '-r400');\r\n\r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\jtconv_Gamma4_6'); \r\n\r\nfigure(6)%Figure 4-b of paper\r\nkk = 0:1:(nsim-1);\r\nhk = plot(kk, kk46(1,:), 'ko-',...\r\n        'LineWidth', 1.0,'MarkerSize',4);\r\nxlim([0,99]);\r\nylim([0,1000]);\r\nxlabel('$t$','interpreter','latex','FontSize',20);\r\nylabel('$j_{t,\\mathrm{conv}}$','interpreter','latex','FontSize',20);\r\nset(gca,'FontSize',18)\r\nset(gca, 'YScale', 'log')\r\nprint(gcf,'figures/J-converge-2', '-depsc');\r\nprint(gcf,'figures/J-converge-2.png', '-dpng', '-r400');\r\n\r\n\r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\jtconv_Gamma6_4');\r\n\r\nfigure(7)%Figure 4-c of paper\r\nkk = 0:1:(nsim-1);\r\nhk = plot(kk, kk64(1,:), 'ko-',...\r\n        'LineWidth', 1.0,'MarkerSize',4);\r\nxlim([0,99]);\r\nxlabel('$t$','interpreter','latex','FontSize',20);\r\nylabel('$j_{t,\\mathrm{conv}}$','interpreter','latex','FontSize',20);\r\nset(gca,'FontSize',18)\r\nset(gca, 'YScale', 'log')\r\nprint(gcf,'figures/J-converge-3', '-depsc');\r\nprint(gcf,'figures/J-converge-3.png', '-dpng', '-r400');\r\n\r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\jtconv_Gamma6_6');\r\n\r\nfigure(8)%Figure 4-d of paper\r\nkk = 0:1:(nsim-1);\r\nhk = plot(kk, kk66(1,:), 'ko-',...\r\n        'LineWidth', 1.0,'MarkerSize',4);\r\nxlim([0,99]);\r\nxlabel('$t$','interpreter','latex','FontSize',20);\r\nylabel('$j_{t,\\mathrm{conv}}$','interpreter','latex','FontSize',20);\r\nset(gca,'FontSize',18)\r\nset(gca, 'YScale', 'log')\r\nprint(gcf,'figures/J-converge-4', '-depsc');\r\nprint(gcf,'figures/J-converge-4.png', '-dpng', '-r400');\r\n\r\n \r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\iteration_theta');\r\nload('D:\\onedri\\OneDrive\\Desktop\\shuo\\Github\\Figure2_3_4\\iteration_v');\r\n\r\nfigure(9)%Figure 3-a of paper\r\nkk1 = 0:1:N;\r\nhh = plot(kk1, Itera_x(32,:),'r', 'LineWidth', 1);\r\nhh1 = plot(kk1, Itera_x(1,:),'r', 'LineWidth', 1);\r\nhold on \r\nfor i=2:1:32\r\nif i<=20\r\nhh1= plot(kk1, Itera_x(i,:),'r', 'LineWidth', 1);\r\nelse\r\nhh=plot(kk1, Itera_x(i,:),'b', 'LineWidth', 2);\r\nhold on \r\nxlim([0,24]);\r\nend\r\nend\r\nhh_legend = legend([hh,hh1], {'Converged ($j=32$)','Converging ($1\\le j<32$)'}, 'Location', 'SouthEast');\r\nset(hh_legend, 'Interpreter','latex','FontSize',18);\r\ntext('Interpreter','latex','String','$j=1$','Position',[19 0.55],'FontSize',18);\r\nannotation('arrow',[0.75 0.7],[0.62 0.71],'LineStyle', '-','color',[0 0 0]);\r\ntext('Interpreter','latex','String','$j=2$','Position',[5.3 0.6],'FontSize',18);\r\nannotation('arrow',[0.3 0.4],[0.6 0.55],'LineStyle', '-','color',[0 0 0]);\r\nset(gca,'FontSize',18)\r\nxlabel('$k$','interpreter','latex','FontSize',20);\r\nylabel('$x(m)$','interpreter','latex','FontSize',20);\r\nprint(gcf,'figures/state-converge-1', '-depsc');\r\nprint(gcf,'figures/state-converge-1.png', '-dpng', '-r400');\r\n \r\nfigure(10)%Figure 3-b of paper\r\nkk1 = 0:1:N;\r\nhh = plot(kk1, Itera_y(32,:),'r', 'LineWidth', 1);\r\nhh1 = plot(kk1, Itera_y(1,:),'r', 'LineWidth', 1);\r\nhold on \r\nfor i=2:1:32\r\nif i<=20\r\nhh1= plot(kk1, Itera_y(i,:),'r', 'LineWidth', 1);\r\nelse\r\nhh=plot(kk1, Itera_y(i,:),'b', 'LineWidth', 2);\r\nhold on \r\nxlim([0,24]);\r\nend\r\nend\r\nhh_legend = legend([hh,hh1], {'Converged ($j=32$)','Converging ($1\\le j<32$)'}, 'Location', 'SouthEast');\r\nset(hh_legend, 'Interpreter','latex','FontSize',18);\r\ntext('Interpreter','latex','String','$j=1$','Position',[16.5 1],'FontSize',18);\r\nannotation('arrow',[0.7 0.75],[0.75 0.66],'LineStyle', '-','color',[0 0 0]);\r\ntext('Interpreter','latex','String','$j=2$','Position',[1.9 0.90],'FontSize',18);\r\nannotation('arrow',[0.2 0.27],[0.68 0.6],'LineStyle', '-','color',[0 0 0]);\r\nset(gca,'FontSize',18)\r\nxlabel('$k$','interpreter','latex','FontSize',20);\r\nylabel('$y(m)$','interpreter','latex','FontSize',20);\r\nprint(gcf,'figures/state-converge-2', '-depsc');\r\nprint(gcf,'figures/state-converge-2.png', '-dpng', '-r400');\r\n\r\n\r\nfigure(11)%Figure 3-c of paper\r\nkk1 = 0:1:N;\r\nhh = plot(kk1, Itera_theta(32,:),'r', 'LineWidth', 1);\r\nhh1 = plot(kk1, Itera_theta(1,:),'r', 'LineWidth', 1);\r\nhold on \r\nfor i=2:1:32\r\nif i<=20\r\nhh1= plot(kk1, Itera_theta(i,:),'r', 'LineWidth', 1);\r\nelse\r\nhh=plot(kk1, Itera_theta(i,:),'b', 'LineWidth', 2);\r\nhold on \r\nxlim([0,24]);\r\nend\r\nend\r\nhh_legend = legend([hh,hh1], {'Converged ($j=32$)','Converging ($1\\le j<32$)'}, 'Location', 'SouthEast');\r\nset(hh_legend, 'Interpreter','latex','FontSize',18);\r\ntext('Interpreter','latex','String','$j=1$','Position',[13.5 0],'FontSize',18);\r\nannotation('arrow',[0.58 0.48],[0.55 0.5],'LineStyle', '-','color',[0 0 0]);\r\ntext('Interpreter','latex','String','$j=2$','Position',[5.4 -0.17],'FontSize',18);\r\nannotation('arrow',[0.37 0.44],[0.43 0.35],'LineStyle', '-','color',[0 0 0]);\r\nset(gca,'FontSize',18)\r\nxlabel('$k$','interpreter','latex','FontSize',20);\r\nylabel('$\\theta(rad)$','interpreter','latex','FontSize',20);\r\nprint(gcf,'figures/state-converge-3', '-depsc');\r\nprint(gcf,'figures/state-converge-3.png', '-dpng', '-r400');\r\n\r\n \r\nfigure(12)%Figure 3-d of paper\r\nkk1 = 0:1:N;\r\nhh = plot(kk1, Itera_v(32,:),'r', 'LineWidth', 1);\r\nhh1 = plot(kk1, Itera_v(1,:),'r', 'LineWidth', 1);\r\nhold on \r\nfor i=2:1:32\r\nif i<=20\r\nhh1= plot(kk1, Itera_v(i,:),'r', 'LineWidth', 1);\r\nelse\r\nhh=plot(kk1, Itera_v(i,:),'b', 'LineWidth', 2);\r\nhold on \r\nxlim([0,24]);\r\nend\r\nend\r\nhh_legend = legend([hh,hh1], {'Converged ($j=32$)','Converging ($1\\le j<32$)'}, 'Location', 'SouthEast');\r\nset(hh_legend, 'Interpreter','latex','FontSize',18);\r\ntext('Interpreter','latex','String','$j=1$','Position',[17.5 1.7],'FontSize',18);\r\nannotation('arrow',[0.74 0.64],[0.55 0.5],'LineStyle', '-','color',[0 0 0]);\r\ntext('Interpreter','latex','String','$j=2$','Position',[8.5 2.7],'FontSize',18);\r\nannotation('arrow',[0.42 0.32],[0.83 0.88],'LineStyle', '-','color',[0 0 0]);\r\nset(gca,'FontSize',18)\r\nxlabel('$k$','interpreter','latex','FontSize',20);\r\nylabel('$v(m\\cdot s^{-1})$','interpreter','latex','FontSize',20);\r\nprint(gcf,'figures/state-converge-4', '-depsc');\r\nprint(gcf,'figures/state-converge-4.png', '-dpng', '-r400');\r\n"
  },
  {
    "path": "matlab/acc2023/closedloop_performance/Iterative_Convergence.m",
    "content": "close all\r\nclear\r\n\r\n%--------------------------------------iMPC-DCBF------------------------------------------------\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = 24;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = 4;\r\ngamma2 = 4;\r\nnsim = 100;%Total time steps\r\nItera_x = [];%This is to store iterative convergence of location x\r\nItera_y = [];%This is to store iterative convergence of location y\r\nItera_theta = [];%This is to store iterative convergence of orientation theta\r\nItera_v = [];%This is to store iterative convergence of speed v\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = [-3 0 0 0];\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];%Highest order mcbf=2\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n   error('OSQP did not solve the problem!')\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];%Highest order mcbf=2\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n       error('OSQP did not solve the problem!')\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];%Highest order mcbf=2\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n       error('OSQP did not solve the problem!')\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    if i == 6 %Get several open-loop trajectories at different iterations predicted at t = 6\r\n     Itera_x = [Itera_x; ctrlx(1:4:(N*nx)+1)'];\r\n     Itera_y = [Itera_y; ctrlx(2:4:(N*nx)+2)'];\r\n     Itera_theta = [Itera_theta; ctrlx(3:4:(N*nx)+3)'];\r\n     Itera_v = [Itera_v; ctrlx(4:4:(N*nx)+4)'];\r\n    end\r\n    x0 = ctrlx(1:nx);\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      break\r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\n\r\nsave('trajectory','impctra');%Close-loop 2D-trajectory where tsim=100\r\nsave('iteration_x','Itera_x');\r\nsave('iteration_y','Itera_y');\r\nsave('iteration_theta','Itera_theta');\r\nsave('iteration_v','Itera_v');\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/closedloop_performance/Maximum_Iterations.m",
    "content": "close all\r\nclear\r\n\r\n%--------------------------------------iMPC-DCBF------------------------------------------------\r\nkk44=getkk(4,4);\r\nkk46=getkk(4,6);\r\nkk64=getkk(6,4);\r\nkk66=getkk(6,6);\r\nsave('jtconv_Gamma4_4','kk44');%44 corrsponds to gamma1=0.4 and gamma2=0.4 in paper\r\nsave('jtconv_Gamma4_6','kk46');%46 corrsponds to gamma1=0.4 and gamma2=0.6 in paper\r\nsave('jtconv_Gamma6_4','kk64');%64 corrsponds to gamma1=0.6 and gamma2=0.4 in paper\r\nsave('jtconv_Gamma6_6','kk66');%66 corrsponds to gamma1=0.6 and gamma2=0.6 in paper\r\n\r\nfunction kk = getkk(gamma1,gamma2)\r\nxo = 0;\r\nyo = 0;\r\nr = 1;\r\nN = 24;%Number of horizon\r\nK1 = 1000;%Maximum iteration times, jmax\r\nK = 1000;%Maximum iteration times, jmax\r\ndt = 0.1;\r\ngamma1 = gamma1;\r\ngamma2 = gamma2;\r\nnsim = 100;%Total time steps\r\nkk = [];%This is for you to see the convergence interation jt,conv for every time step\r\n\r\n% Constraints\r\n\r\numin = [-7; -5; -inf; -inf;];\r\numax = [7; 5; Inf; Inf];\r\nxmin = [-10; -10; -10; -10];\r\nxmax = [ 10;  10;  10;  10];\r\n\r\n% Objective function\r\nQ = diag([10 10 10 10]);\r\nQN = Q;\r\nR = 1 * eye(4);\r\nR(3,3) = 1000;\r\nR(4,4) = 1000;\r\n% Initial and reference states\r\nx0 = [-3 0 0 0];\r\nxr = [3; 0.01; 0; 0];\r\nur = [0; 0; 1; 1];\r\n\r\n% Dynamic system initialization\r\nBB = [0 0 0 0;0 0 0 0;dt 0 0 0;0 dt 0 0];\r\n\r\n% Convex MPC frame\r\n[nx, nu] = size(BB);\r\n% Initialize states set (x00,x01,,,x0N）\r\nx_0 = [];\r\nx0 = x0';\r\nu_0 = zeros(nu, N);\r\nu0 = zeros(nu, 1);% we may need to change this for a better warm-up start\r\nimpc = zeros(nx, nsim + 1);\r\nimpc(:, 1) = x0;\r\nx0new = x0;\r\nfor i=1 : (N+1)\r\n    x_0 = [x_0 x0new];\r\n    x0new = [dt*x0new(4)*cos(x0new(3))+x0new(1);dt*x0new(4)*sin(x0new(3))+x0new(2);dt*u0(1)+x0new(3);dt*u0(2)+x0new(4)];\r\nend\r\n\r\nabc = tangentline(x_0, r);\r\nAcbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\nlcbf = -abc(3, :);\r\nlcbf(1) = [];\r\nlcbf = lcbf';\r\nucbf = inf * ones(N, 1);\r\nA2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\nlcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\nucbf2 = inf * ones(N-1, 1);\r\n\r\n% Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n% - quadratic objective\r\nP = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n% - linear objective\r\nq = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n% - linear dynamics\r\nAx = getax(x_0, dt, N, nx);\r\nBu = kron([sparse(1, N); speye(N)], BB);\r\nCx = getcx(x_0, u_0, dt, N, nx);\r\nAeq = [Ax, Bu];\r\nleq = [-x0; -Cx];\r\nueq = leq;\r\n% - input and state constraints\r\nAineq = speye((N+1)*nx + N*nu);\r\nlineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\nuineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n% - OSQP constraints\r\nA = [Aeq; Aineq; Acbf; A2cbf];%Highest order mcbf=2\r\nl = [leq; lineq; lcbf; lcbf2];\r\nu = [ueq; uineq; ucbf; ucbf2];\r\n\r\n% Create an OSQP object\r\nprob = osqp;\r\n% Setup workspace\r\nprob.setup(P, q, A, l, u, 'warm_start', true);\r\n% Solve\r\nres = prob.solve();\r\n\r\n% Check solver status\r\nif ~strcmp(res.info.status, 'solved')\r\n   error('OSQP did not solve the problem!')\r\nend\r\nctrlx = res.x(1:(N+1)*nx);\r\nctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n\r\nfor j = 1 : (K1-1)\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];%Highest order mcbf=2\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n       error('OSQP did not solve the problem!')\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      kk = [kk j];%If convergence criterion is satisfied, stop and record jt,conv\r\n      break\r\n    elseif j == K1-1\r\n      kk = [kk j];%If convergence criterion is not satisfied, stop at jmax and record it as jt,conv  \r\n    end\r\nend % Move for the first step\r\nctrl = ctrlu(1:nu);\r\nx0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\nctrlu = rewrite(ctrlu, nu, N);\r\nx_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\nu_0 = transu(ctrlu, nu, N);\r\nimpc(:, 2) = x0;\r\nstoragex = ctrlx;\r\nstorageu = ctrlu;\r\n\r\nfor i = 1 : (nsim-1)\r\n\r\n   for j = 1 : K\r\n    abc = tangentline(x_0, r);\r\n    Acbf = cbfmat(abc, nx, nu, dt, gamma1, x0);\r\n    lcbf = -abc(3, :);\r\n    lcbf(1) = [];\r\n    lcbf = lcbf';\r\n    ucbf = inf * ones(N, 1);\r\n    A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0);\r\n    lcbf2 = getlcbf2(abc, dt, gamma1, gamma2);\r\n    ucbf2 = inf * ones(N-1, 1);\r\n    % Cast MPC problem to a QP: x = (x(0),x(1),...,x(N),u(0),...,u(N-1))\r\n    % - quadratic objective\r\n    P = blkdiag( kron(speye(N), Q), QN, kron(speye(N), R) );\r\n    % - linear objective\r\n    q = [repmat(-Q*xr, N, 1); -QN*xr; repmat(-R*ur, N, 1)];\r\n    % - linear dynamics\r\n    Ax = getax(x_0, dt, N, nx);\r\n    Bu = kron([sparse(1, N); speye(N)], BB);\r\n    Cx = getcx(x_0, u_0, dt, N, nx);\r\n    Aeq = [Ax, Bu];\r\n    leq = [-x0; -Cx];\r\n    ueq = leq;\r\n    % - input and state constraints\r\n    Aineq = speye((N+1)*nx + N*nu);\r\n    lineq = [repmat(xmin, N+1, 1); repmat(umin, N, 1)];\r\n    uineq = [repmat(xmax, N+1, 1); repmat(umax, N, 1)];\r\n\r\n    % - OSQP constraints\r\n    A = [Aeq; Aineq; Acbf; A2cbf];%Highest order mcbf=2\r\n    l = [leq; lineq; lcbf; lcbf2];\r\n    u = [ueq; uineq; ucbf; ucbf2];\r\n    % Create an OSQP object\r\n    prob = osqp;\r\n    % Setup workspace\r\n    prob.setup(P, q, A, l, u, 'warm_start', true);\r\n    % Solve\r\n    res = prob.solve();\r\n\r\n    % Check solver status\r\n    if ~strcmp(res.info.status, 'solved')\r\n       error('OSQP did not solve the problem!')\r\n    end\r\n    ctrlx = res.x(1:(N+1)*nx);\r\n    ctrlu = res.x((N+1)*nx+1:(N+1)*nx+N*nu);\r\n    x0 = ctrlx(1:nx);\r\n    x_0 = trans(x0, ctrlx, nx, N+1);\r\n    u_0 = transu(ctrlu, nu, N);\r\n    testx = (storagex - ctrlx)'*(storagex - ctrlx);\r\n    testu = (storageu - ctrlu)'*(storageu - ctrlu);\r\n    test = (testx)/(storagex'*storagex);\r\n    if (test)^(0.5)<=10^(-2)&& (testx/((N+1)*nx))^(0.5)<=10^(-4)%Convergence criterion\r\n      kk = [kk j];%If convergence criterion is satisfied, stop and record jt,conv\r\n      break\r\n    elseif j == K\r\n      kk = [kk j];%If convergence criterion is not satisfied, stop at jmax and record it as jt,conv   \r\n    end\r\n    storagex = ctrlx;\r\n    storageu = ctrlu;\r\n   end\r\n   ctrl = ctrlu(1:nu);\r\n   x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*ctrl(1)+x0(3);dt*ctrl(2)+x0(4)];\r\n   ctrlu = rewrite(ctrlu, nu, N);\r\n   x_0 = newinit(x0, ctrlu, nx, nu, N, dt);\r\n   u_0 = transu(ctrlu, nu, N);\r\n   impc(:, i+2) = x0;\r\nend\r\nend\r\n\r\n% Linerize the CBF constraints (get a, b, c for lines)\r\nfunction abc = tangentline(xy, r)% x and y from initialize states set, abc are coeeficients for linear equation a*x+b*y+c=0\r\n[xx, ~] = size(xy);%xx=2,yy=N+1\r\nxy(xx,:) = []; % this part should be changed for other case\r\nxy((xx-1),:) = []; % this part should be changed other case\r\n[xx, yy] = size(xy);%xx=2,yy=N+1\r\nxyjiao = zeros(xx, yy);%intersection points\r\nfor i = 1 : xx\r\n    for j = 1 : yy\r\n        xyjiao(i, j) = r * xy(i, j) * (1 / (xy(:, j)' * xy(:, j)))^(0.5);%calculate coordinates of intersection points\r\n    end\r\nend\r\ncc = -r^2 * ones(1, yy);\r\nabc = [xyjiao; cc];\r\nend\r\n\r\n% Get CBF constraints matrix \r\nfunction Acbf = cbfmat(abc, nx, nu, dt, gamma, x0)\r\n[~, yy] = size(abc);\r\nAcbfx = zeros((yy-1), yy*nx);\r\nAcbfu = zeros((yy-1), (yy-1)*nu);\r\nfor i = 1 : (yy-1)\r\n    Acbfx(i, (i*nx)+1) = abc(1, (i+1));\r\n    Acbfx(i, (i*nx)+2) = abc(2, (i+1));\r\nend\r\nfor i = 1 : (yy-1)\r\n    Acbfu(i, ((i-1)*nu+3)) = - (1 - dt * gamma)^(i) * (abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nAcbf = [Acbfx Acbfu];\r\nend\r\n\r\n% Transfer vector x into matrix \r\nfunction res = trans(x0, vector, nxx, nyy)%nxx=nx,nyy=N+1\r\n res = zeros(nxx, nyy);\r\n res(:,1) = x0;\r\n for i = 1 : (nyy -1)\r\n     res(:,i+1)= vector(((i)*nxx+1):(i+1)*nxx);\r\n end   \r\nend\r\n\r\n% Transfer vector u into matrix \r\nfunction resu = transu(vector, nxx, nyy)%nxx=nu,nyy=N\r\n resu = zeros(nxx, nyy);\r\n for i = 1 : (nyy)\r\n     resu(:,i)= vector(((i-1)*nxx+1):(i)*nxx);\r\n end   \r\nend\r\n\r\n% Rewrite u vector\r\nfunction reu = rewrite(vector, nu, N)\r\nappend = vector((N-1)*nu+1:N*nu);\r\nvector(1:nu) = [];\r\nreu = [vector;append];\r\nend\r\n\r\n% Get new x_0\r\nfunction x_0 = newinit(x0, ctrlu, nx, nu, N, dt)\r\n x_0 = zeros(nx, N+1);\r\n x_0(:, 1) = x0;\r\n for i=1 : N\r\n    u0 = ctrlu((i-1)*nu+1:i*nu);\r\n    x0 = [dt*x0(4)*cos(x0(3))+x0(1);dt*x0(4)*sin(x0(3))+x0(2);dt*u0(1)+x0(3);dt*u0(2)+x0(4)];\r\n    x_0(:, i + 1) = x0;\r\n end\r\nend\r\n\r\n% Get AA matrix\r\nfunction AA = getaa(x0, dt)\r\n AA = [1 0 -x0(4)*sin(x0(3))*dt cos(x0(3))*dt;0 1 x0(4)*cos(x0(3))*dt sin(x0(3))*dt;0 0 1 0;0 0 0 1];\r\nend\r\n% Get CC matrix\r\nfunction CC = getcc(x0, x1, u0, dt)\r\n CC = [x0(4)*sin(x0(3))*x0(3)*dt-x0(4)*cos(x0(3))*dt+x1(1)-x0(1);-x0(4)*cos(x0(3))*x0(3)*dt-x0(4)*sin(x0(3))*dt+x1(2)-x0(2);-u0(1)*dt+x1(3)-x0(3);-u0(2)*dt+x1(4)-x0(4)];\r\nend\r\n% Get Ax matrix\r\nfunction Ax = getax(x_0, dt, N, nx)\r\nx0 = x_0(:,1);\r\nAA = getaa(x0, dt);\r\nAx = kron(speye(N+1), -speye(nx)) + kron(sparse(diag(ones(N, 1), -1)), AA);\r\nfor i = 1 : (N-1)\r\n   x0 = x_0(:,i+1);\r\n   AA = getaa(x0, dt);\r\n   Ax(nx*(i+1)+1:nx*(i+1)+nx,nx*i+1:nx*i+nx) = AA;\r\nend\r\nend\r\n% Get Cx matrix\r\nfunction Cx = getcx(x_0, u_0, dt, N, nx)\r\nCx = zeros(N*nx, 1);\r\nfor i = 1 : N\r\n    u0 = u_0(:,i);\r\n    x0 = x_0(:,i);\r\n    x1 = x_0(:,i+1);\r\n    CC = getcc(x0, x1, u0, dt);\r\n    Cx((i-1)*nx+1:(i-1)*nx+nx) = CC;\r\nend\r\nend\r\n% Get A2cbf\r\nfunction A2cbf = cbfmat2(abc, nx, nu, dt, gamma1, gamma2, x0)\r\n[~, yy] = size(abc);\r\nAcbfx2 = zeros((yy-2), yy*nx);\r\nAcbfx22 = zeros((yy-2), yy*nx);\r\nAcbfu2 = zeros((yy-2), (yy-1)*nu);\r\nfor i = 1 : (yy-2)\r\n    Acbfx2(i, (i*nx)+1) = (gamma1-1/dt)*abc(1, (i+1));\r\n    Acbfx2(i, (i*nx)+2) = (gamma1-1/dt)*abc(2, (i+1));\r\n    Acbfx2(i, ((i+1)*nx)+1) = (1/dt)*abc(1, (i+2));\r\n    Acbfx2(i, ((i+1)*nx)+2) = (1/dt)*abc(2, (i+2));\r\nend\r\nfor i = 1 : (yy-2)\r\n    Acbfx22(i, (1*nx)+1) = -(1-dt*gamma2)^(i)/dt*abc(1, (1+1));\r\n    Acbfx22(i, (1*nx)+2) = -(1-dt*gamma2)^(i)/dt*abc(2, (1+1));\r\nend\r\nAcbfx2 = Acbfx2 + Acbfx22;\r\nfor i = 1 : (yy-2)\r\n    Acbfu2(i, ((i-1)*nu+4)) = - (1 - dt * gamma2)^(i)*(gamma1-1/dt)*(abc(1, 1) * x0(1, 1) + abc(2, 1) * x0(2, 1) + abc(3, 1));\r\nend\r\nA2cbf = [Acbfx2 Acbfu2];\r\nend\r\n% Get lcbf2\r\nfunction lcbf2 = getlcbf2(abc, dt, gamma1, gamma2)\r\n[~, yy] = size(abc);\r\nlcbf2 = zeros((yy-2),1);\r\nfor i = 1 : (yy-2)\r\n    lcbf2(i, 1) = -abc(3, (i+2))/dt-(gamma1-1/dt)*abc(3, (i+1))+(1 - dt * gamma2)^(i)*abc(3, (1+1))/dt;\r\nend\r\nend"
  },
  {
    "path": "matlab/acc2023/closedloop_performance/NMPCDCBF1.m",
    "content": "classdef NMPCDCBF1 < handle\r\n    % MPC with distance constraints\r\n    properties\r\n        system\r\n        params\r\n        x0\r\n        x_curr\r\n        time_curr = 0.0\r\n        xlog = []\r\n        ulog = []\r\n        tt = 0\r\n        distlog = []\r\n        solvertime = []\r\n        xopenloop = {}\r\n        uopenloop = {}\r\n        u_cost = 0\r\n        obs\r\n    end\r\n    methods\r\n        function self = NMPCDCBF1(x0, system, params)\r\n            % Define MPC_CBF controller\r\n            self.x0 = x0;\r\n            self.x_curr = x0;\r\n            self.system = system;\r\n            self.params = params;\r\n        end\r\n        \r\n        function sim(self, time)\r\n            % Simulate the system until a given time\r\n            tic;\r\n            xk = self.x_curr;\r\n            while self.time_curr < time\r\n                [~, uk, tt] = self.solveNMPCDCBF1(self.x_curr);\r\n                if tt == -1 %if infeasiblility happens, stop\r\n                    self.tt = tt;\r\n                    return\r\n                end\r\n                xk = self.system.A * xk + [xk(4,1) * cos(xk(3,1))*self.system.dt;xk(4,1) * sin(xk(3,1))*self.system.dt;0;0] + self.system.C * uk;\r\n                % update system\r\n                self.x_curr = xk;\r\n                self.time_curr = self.time_curr + self.system.dt;\r\n                self.xlog = [self.xlog, xk];\r\n                self.ulog = [self.ulog, uk];\r\n                self.u_cost = self.u_cost + uk'*uk;\r\n                tt = tt + toc;%record computing time for each time-step\r\n                self.tt = tt;\r\n                return\r\n            end\r\n            \r\n        end\r\n        \r\n        function [xopt, uopt,tt] = solveNMPCDCBF1(self, xk)\r\n            % Solve NMPC-DCBF\r\n            [feas, x, u, J] = self.solve_cftoc1(xk);\r\n            if ~feas\r\n                xopt = [];\r\n                uopt = [];\r\n                tt = -1;\r\n                return\r\n            else\r\n                xopt = x(:,2);\r\n                uopt = u(:,1);\r\n                tt = 0;\r\n            end\r\n        end\r\n        \r\n        function [feas, xopt, uopt, Jopt] = solve_cftoc1(self, xk)\r\n            % Solve CFTOC\r\n            % extract variables\r\n            N = self.params.N;\r\n            % define variables and cost\r\n            x = sdpvar(4, N+1);\r\n            u = sdpvar(4, N);\r\n            constraints = [];\r\n            cost = 0;\r\n            % initial constraint\r\n            constraints = [constraints; x(:,1) == xk];\r\n            % add constraints and costs\r\n            AA=self.system.A;\r\n            BB=self.system.B;\r\n            CC=self.system.C;\r\n            constraints = [constraints;\r\n                    self.system.xl <= x(:,1) <= self.system.xu;\r\n                    self.system.ul <= u(:,1) <= self.system.uu;\r\n                    x(:,2) == AA * x(:,1) + [x(4,1)*cos(x(3,1))*self.system.dt;x(4,1)*sin(x(3,1))*self.system.dt;0; 0] + CC * u(:,1)];\r\n                cost = cost + (x(:,1)-[3;0.01;0;0])'*self.params.Q*(x(:,1)-[3;0.01;0;0]) + (u(:,1)-[0;0;1;1])'*self.params.R*(u(:,1)-[0;0;1;1]); % self.params.S*(w(:,1)-1)^2;\r\n            for i = 2:1:N\r\n                constraints = [constraints;\r\n                    self.system.xl <= x(:,i) <= self.system.xu;\r\n                    self.system.ul <= u(:,i) <= self.system.uu;\r\n                    x(:,i+1) == AA * x(:,i) + [x(4,i)*cos(x(3,i))*self.system.dt;x(4,i)*sin(x(3,i))*self.system.dt;0; 0] + CC * u(:,i)];\r\n                cost = cost + (x(:,i)-[3;0.01;0;0])'*self.params.Q*(x(:,i)-[3;0.01;0;0]) + (u(:,i)-[0;0;1;1])'*self.params.R*(u(:,i)-[0;0;1;1]);% self.params.S*(w(:,i)-1)^2;\r\n            end\r\n            % add CBF constraints\r\n            for i = 1:N-1\r\n                pos = self.obs.pos1;\r\n                r = self.obs.r1 ;\r\n                b = (x([1:2],i)-pos)'*((x([1:2],i)-pos))-r^2;\r\n                b_next = (x([1:2],i+1)-pos)'*((x([1:2],i+1)-pos))-r^2;\r\n                constraints = [constraints; b_next  >= u(3,i)*(1-self.params.gamma1)*b];%Highest order mcbf=1\r\n            end\r\n            % add terminal cost\r\n            cost = cost + (x(:,N+1)-[3;0.01;0;0])'*self.params.P*(x(:,N+1)-[3;0.01;0;0]);\r\n            ops = sdpsettings('solver','ipopt','verbose',0);\r\n            % solve optimization\r\n            diagnostics = optimize(constraints, cost, ops);\r\n            if diagnostics.problem == 0\r\n                feas = true;\r\n                xopt = value(x);\r\n                uopt = value(u);\r\n                Jopt = value(cost);\r\n            else\r\n                feas = false;\r\n                xopt = [];\r\n                uopt = [];\r\n                Jopt = [];\r\n            end\r\n            pos = self.obs.pos1;\r\n            r = self.obs.r1 ;\r\n            self.distlog = [self.distlog, (r^2-(xk(1:2)-pos)'*(xk(1:2)-pos))];\r\n            self.xopenloop{size(self.xopenloop,2)+1} = xopt;\r\n            self.uopenloop{size(self.uopenloop,2)+1} = uopt;\r\n            self.solvertime = [self.solvertime, diagnostics.solvertime];\r\n            fprintf('solver time: %f\\n', diagnostics.solvertime);\r\n        end\r\n    end\r\nend"
  },
  {
    "path": "matlab/acc2023/closedloop_performance/NMPCDCBF2.m",
    "content": "classdef NMPCDCBF2 < handle\r\n    % MPC with distance constraints\r\n    properties\r\n        system\r\n        params\r\n        x0\r\n        x_curr\r\n        time_curr = 0.0\r\n        xlog = []\r\n        ulog = []\r\n        tt = 0\r\n        distlog = []\r\n        solvertime = []\r\n        xopenloop = {}\r\n        uopenloop = {}\r\n        u_cost = 0\r\n        obs\r\n    end\r\n    methods\r\n        function self = NMPCDCBF2(x0, system, params)\r\n            % Define MPC_CBF controller\r\n            self.x0 = x0;\r\n            self.x_curr = x0;\r\n            self.system = system;\r\n            self.params = params;\r\n        end\r\n        \r\n        function sim(self, time)\r\n            % Simulate the system until a given time\r\n            tic;\r\n            xk = self.x_curr;\r\n            while self.time_curr < time\r\n                [~, uk, tt] = self.solveNMPCDCBF1(self.x_curr);%if infeasiblility happens, stop\r\n                if tt == -1\r\n                    self.tt = tt;%record computing time for each time-step\r\n                    return\r\n                end\r\n                xk = self.system.A * xk + [xk(4,1) * cos(xk(3,1))*self.system.dt;xk(4,1) * sin(xk(3,1))*self.system.dt;0;0] + self.system.C * uk;\r\n                % update system\r\n                self.x_curr = xk;\r\n                self.time_curr = self.time_curr + self.system.dt;\r\n                self.xlog = [self.xlog, xk];\r\n                self.ulog = [self.ulog, uk];\r\n                self.u_cost = self.u_cost + uk'*uk;\r\n                tt = tt + toc;\r\n                self.tt = tt;\r\n                return\r\n            end\r\n            \r\n        end\r\n        \r\n        function [xopt, uopt,tt] = solveNMPCDCBF1(self, xk)\r\n            % Solve NMPC-DCBF\r\n            [feas, x, u, J] = self.solve_cftoc1(xk);\r\n            if ~feas\r\n                xopt = [];\r\n                uopt = [];\r\n                tt = -1;\r\n                return\r\n            else\r\n                xopt = x(:,2);\r\n                uopt = u(:,1);\r\n                tt = 0;\r\n            end\r\n        end\r\n        \r\n        function [feas, xopt, uopt, Jopt] = solve_cftoc1(self, xk)\r\n            % Solve CFTOC\r\n            % extract variables\r\n            N = self.params.N;\r\n            % define variables and cost\r\n            x = sdpvar(4, N+1);%%%%%%%%%%%%%%%%%%%%%%%%%%%%\r\n            u = sdpvar(4, N);\r\n            constraints = [];\r\n            cost = 0;\r\n            % initial constraint\r\n            constraints = [constraints; x(:,1) == xk];\r\n            % add constraints and costs\r\n            AA=self.system.A;\r\n            BB=self.system.B;\r\n            CC=self.system.C;\r\n            constraints = [constraints;\r\n                    self.system.xl <= x(:,1) <= self.system.xu;\r\n                    self.system.ul <= u(:,1) <= self.system.uu;\r\n                    x(:,2) == AA * x(:,1) + [x(4,1)*cos(x(3,1))*self.system.dt;x(4,1)*sin(x(3,1))*self.system.dt;0; 0] + CC * u(:,1)];\r\n                cost = cost + (x(:,1)-[3;0.01;0;0])'*self.params.Q*(x(:,1)-[3;0.01;0;0]) + (u(:,1)-[0;0;1;1])'*self.params.R*(u(:,1)-[0;0;1;1]); % self.params.S*(w(:,1)-1)^2;\r\n            for i = 2:1:N\r\n                constraints = [constraints;\r\n                    self.system.xl <= x(:,i) <= self.system.xu;\r\n                    self.system.ul <= u(:,i) <= self.system.uu;\r\n                    x(:,i+1) == AA * x(:,i) + [x(4,i)*cos(x(3,i))*self.system.dt;x(4,i)*sin(x(3,i))*self.system.dt;0; 0] + CC * u(:,i)];\r\n                cost = cost + (x(:,i)-[3;0.01;0;0])'*self.params.Q*(x(:,i)-[3;0.01;0;0]) + (u(:,i)-[0;0;1;1])'*self.params.R*(u(:,i)-[0;0;1;1]);% self.params.S*(w(:,i)-1)^2;\r\n            end\r\n            % add CBF constraints\r\n            for i = 1:N-1\r\n                pos = self.obs.pos1;\r\n                r = self.obs.r1 ;\r\n                b = (x([1:2],i)-pos)'*((x([1:2],i)-pos))-r^2;\r\n                b_next = (x([1:2],i+1)-pos)'*((x([1:2],i+1)-pos))-r^2;\r\n                b_next_next = (x([1:2],i+2)-pos)'*((x([1:2],i+2)-pos))-r^2;                \r\n                b1 = (b_next - b)/self.system.dt + self.params.gamma1/self.system.dt * (b);\r\n                b1_next = (b_next_next - b_next)/self.system.dt + self.params.gamma1/self.system.dt * (b_next);\r\n                constraints = [constraints; b1_next  >=u(4,i)*(1-self.params.gamma2)*b1;b_next  >= u(3,i)*(1-self.params.gamma1)*b];%Highest order mcbf=2\r\n            end\r\n            % add terminal cost\r\n            cost = cost + (x(:,N+1)-[3;0.01;0;0])'*self.params.P*(x(:,N+1)-[3;0.01;0;0]);\r\n            ops = sdpsettings('solver','ipopt','verbose',0);\r\n            % solve optimization\r\n            diagnostics = optimize(constraints, cost, ops);\r\n            if diagnostics.problem == 0\r\n                feas = true;\r\n                xopt = value(x);\r\n                uopt = value(u);\r\n                Jopt = value(cost);\r\n            else\r\n                feas = false;\r\n                xopt = [];\r\n                uopt = [];\r\n                Jopt = [];\r\n            end\r\n            pos = self.obs.pos1;\r\n            r = self.obs.r1 ;\r\n            self.distlog = [self.distlog, (r^2-(xk(1:2)-pos)'*(xk(1:2)-pos))];\r\n            self.xopenloop{size(self.xopenloop,2)+1} = xopt;\r\n            self.uopenloop{size(self.uopenloop,2)+1} = uopt;\r\n            self.solvertime = [self.solvertime, diagnostics.solvertime];\r\n            fprintf('solver time: %f\\n', diagnostics.solvertime);\r\n        end\r\n    end\r\nend"
  },
  {
    "path": "matlab/acc2023/closedloop_performance/figures/J-converge-1.eps",
    "content": "%!PS-Adobe-3.0 EPSF-3.0\r\n%%Creator: (MATLAB, The Mathworks, Inc. Version 9.10.0.1649659 \\(R2021a\\) Update 1. Operating System: Windows 10)\r\n%%Title: figures/J-converge-1.eps\r\n%%CreationDate: 2023-01-31T03:11:51\r\n%%Pages: (atend)\r\n%%BoundingBox:     3     7   383   301\r\n%%LanguageLevel: 3\r\n%%EndComments\r\n%%BeginProlog\r\n%%BeginResource: procset (Apache XML Graphics Std ProcSet) 1.2 0\r\n%%Version: 1.2 0\r\n%%Copyright: (Copyright 2001-2003,2010 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/bd{bind def}bind def\r\n/ld{load def}bd\r\n/GR/grestore ld\r\n/GS/gsave ld\r\n/RM/rmoveto ld\r\n/C/curveto ld\r\n/t/show ld\r\n/L/lineto ld\r\n/ML/setmiterlimit ld\r\n/CT/concat ld\r\n/f/fill ld\r\n/N/newpath ld\r\n/S/stroke ld\r\n/CC/setcmykcolor ld\r\n/A/ashow ld\r\n/cp/closepath ld\r\n/RC/setrgbcolor ld\r\n/LJ/setlinejoin ld\r\n/GC/setgray ld\r\n/LW/setlinewidth ld\r\n/M/moveto ld\r\n/re {4 2 roll M\r\n1 index 0 rlineto\r\n0 exch rlineto\r\nneg 0 rlineto\r\ncp } bd\r\n/_ctm matrix def\r\n/_tm matrix def\r\n/BT { _ctm currentmatrix pop matrix _tm copy pop 0 0 moveto } bd\r\n/ET { _ctm setmatrix } bd\r\n/iTm { _ctm setmatrix _tm concat } bd\r\n/Tm { _tm astore pop iTm 0 0 moveto } bd\r\n/ux 0.0 def\r\n/uy 0.0 def\r\n/F {\r\n  /Tp exch def\r\n  /Tf exch def\r\n  Tf findfont Tp scalefont setfont\r\n  /cf Tf def  /cs Tp def\r\n} bd\r\n/ULS {currentpoint /uy exch def /ux exch def} bd\r\n/ULE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add moveto  Tcx uy To add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/OLE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs add moveto Tcx uy To add cs add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/SOE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs 10 mul 26 idiv add moveto Tcx uy To add cs 10 mul 26 idiv add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/QT {\r\n/Y22 exch store\r\n/X22 exch store\r\n/Y21 exch store\r\n/X21 exch store\r\ncurrentpoint\r\n/Y21 load 2 mul add 3 div exch\r\n/X21 load 2 mul add 3 div exch\r\n/X21 load 2 mul /X22 load add 3 div\r\n/Y21 load 2 mul /Y22 load add 3 div\r\n/X22 load /Y22 load curveto\r\n} bd\r\n/SSPD {\r\ndup length /d exch dict def\r\n{\r\n/v exch def\r\n/k exch def\r\ncurrentpagedevice k known {\r\n/cpdv currentpagedevice k get def\r\nv cpdv ne {\r\n/upd false def\r\n/nullv v type /nulltype eq def\r\n/nullcpdv cpdv type /nulltype eq def\r\nnullv nullcpdv or\r\n{\r\n/upd true def\r\n} {\r\n/sametype v type cpdv type eq def\r\nsametype {\r\nv type /arraytype eq {\r\n/vlen v length def\r\n/cpdvlen cpdv length def\r\nvlen cpdvlen eq {\r\n0 1 vlen 1 sub {\r\n/i exch def\r\n/obj v i get def\r\n/cpdobj cpdv i get def\r\nobj cpdobj ne {\r\n/upd true def\r\nexit\r\n} if\r\n} for\r\n} {\r\n/upd true def\r\n} ifelse\r\n} {\r\nv type /dicttype eq {\r\nv {\r\n/dv exch def\r\n/dk exch def\r\n/cpddv cpdv dk get def\r\ndv cpddv ne {\r\n/upd true def\r\nexit\r\n} if\r\n} forall\r\n} {\r\n/upd true def\r\n} ifelse\r\n} ifelse\r\n} if\r\n} ifelse\r\nupd true eq {\r\nd k v put\r\n} if\r\n} if\r\n} if\r\n} forall\r\nd length 0 gt {\r\nd setpagedevice\r\n} if\r\n} bd\r\n/RE { % /NewFontName [NewEncodingArray] /FontName RE -\r\n  findfont dup length dict begin\r\n  {\r\n    1 index /FID ne\r\n    {def} {pop pop} ifelse\r\n  } forall\r\n  /Encoding exch def\r\n  /FontName 1 index def\r\n  currentdict definefont pop\r\n  end\r\n} bind def\r\n%%EndResource\r\n%%BeginResource: procset (Apache XML Graphics EPS ProcSet) 1.0 0\r\n%%Version: 1.0 0\r\n%%Copyright: (Copyright 2002-2003 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/BeginEPSF { %def\r\n/b4_Inc_state save def         % Save state for cleanup\r\n/dict_count countdictstack def % Count objects on dict stack\r\n/op_count count 1 sub def      % Count objects on operand stack\r\nuserdict begin                 % Push userdict on dict stack\r\n/showpage { } def              % Redefine showpage, { } = null proc\r\n0 setgray 0 setlinecap         % Prepare graphics state\r\n1 setlinewidth 0 setlinejoin\r\n10 setmiterlimit [ ] 0 setdash newpath\r\n/languagelevel where           % If level not equal to 1 then\r\n{pop languagelevel             % set strokeadjust and\r\n1 ne                           % overprint to their defaults.\r\n{false setstrokeadjust false setoverprint\r\n} if\r\n} if\r\n} bd\r\n/EndEPSF { %def\r\ncount op_count sub {pop} repeat            % Clean up stacks\r\ncountdictstack dict_count sub {end} repeat\r\nb4_Inc_state restore\r\n} bd\r\n%%EndResource\r\n%FOPBeginFontDict\r\n%%IncludeResource: font Courier-Oblique\r\n%%IncludeResource: font Courier-BoldOblique\r\n%%IncludeResource: font Courier-Bold\r\n%%IncludeResource: font ZapfDingbats\r\n%%IncludeResource: font Symbol\r\n%%IncludeResource: font Helvetica\r\n%%IncludeResource: font Helvetica-Oblique\r\n%%IncludeResource: font Helvetica-Bold\r\n%%IncludeResource: font Helvetica-BoldOblique\r\n%%IncludeResource: font Times-Roman\r\n%%IncludeResource: font Times-Italic\r\n%%IncludeResource: font Times-Bold\r\n%%IncludeResource: font Times-BoldItalic\r\n%%IncludeResource: font Courier\r\n%FOPEndFontDict\r\n%%BeginResource: encoding WinAnsiEncoding\r\n/WinAnsiEncoding [\r\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /space /exclam /quotedbl\n/numbersign /dollar /percent /ampersand /quotesingle\n/parenleft /parenright /asterisk /plus /comma\n/hyphen /period /slash /zero /one\n/two /three /four /five /six\n/seven /eight /nine /colon /semicolon\n/less /equal /greater /question /at\n/A /B /C /D /E\n/F /G /H /I /J\n/K /L /M /N /O\n/P /Q /R /S /T\n/U /V /W /X /Y\n/Z /bracketleft /backslash /bracketright /asciicircum\n/underscore /quoteleft /a /b /c\n/d /e /f /g /h\n/i /j /k /l /m\n/n /o /p /q /r\n/s /t /u /v /w\n/x /y /z /braceleft /bar\n/braceright /asciitilde /bullet /Euro /bullet\n/quotesinglbase /florin /quotedblbase /ellipsis /dagger\n/daggerdbl /circumflex /perthousand /Scaron /guilsinglleft\n/OE /bullet /Zcaron /bullet /bullet\n/quoteleft /quoteright /quotedblleft /quotedblright /bullet\n/endash /emdash /asciitilde /trademark /scaron\n/guilsinglright /oe /bullet /zcaron /Ydieresis\n/space /exclamdown /cent /sterling /currency\n/yen /brokenbar /section /dieresis /copyright\n/ordfeminine /guillemotleft /logicalnot /sfthyphen /registered\n/macron /degree /plusminus /twosuperior /threesuperior\n/acute /mu /paragraph /middot /cedilla\n/onesuperior /ordmasculine /guillemotright /onequarter /onehalf\n/threequarters /questiondown /Agrave /Aacute /Acircumflex\n/Atilde /Adieresis /Aring /AE /Ccedilla\n/Egrave /Eacute /Ecircumflex /Edieresis /Igrave\n/Iacute /Icircumflex /Idieresis /Eth /Ntilde\n/Ograve /Oacute /Ocircumflex /Otilde /Odieresis\n/multiply /Oslash /Ugrave /Uacute /Ucircumflex\n/Udieresis /Yacute /Thorn /germandbls /agrave\n/aacute /acircumflex /atilde /adieresis /aring\n/ae /ccedilla /egrave /eacute /ecircumflex\n/edieresis /igrave /iacute /icircumflex /idieresis\n/eth /ntilde /ograve /oacute /ocircumflex\n/otilde /odieresis /divide /oslash /ugrave\n/uacute /ucircumflex /udieresis /yacute /thorn\n/ydieresis\n] def\r\n%%EndResource\r\n%FOPBeginFontReencode\r\n/Courier-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Oblique exch definefont pop\r\n/Courier-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-BoldOblique exch definefont pop\r\n/Courier-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Bold exch definefont pop\r\n/Helvetica findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica exch definefont pop\r\n/Helvetica-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Oblique exch definefont pop\r\n/Helvetica-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Bold exch definefont pop\r\n/Helvetica-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-BoldOblique exch definefont pop\r\n/Times-Roman findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Roman exch definefont pop\r\n/Times-Italic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Italic exch definefont pop\r\n/Times-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Bold exch definefont pop\r\n/Times-BoldItalic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-BoldItalic exch definefont pop\r\n/Courier findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier exch definefont pop\r\n%FOPEndFontReencode\r\n%%EndProlog\r\n%%Page: 1 1\r\n%%PageBoundingBox: 0 0 420 315\r\n%%BeginPageSetup\r\n[1 0 0 -1 0 315] CT\r\n%%EndPageSetup\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n163 698 M\n1014 698 L\n1014 63 L\n163 63 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 698 M\n1014 698 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 63 M\n1014 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 698 M\n163 689.49 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n334.919 698 M\n334.919 689.49 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n506.838 698 M\n506.838 689.49 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n678.758 698 M\n678.758 689.49 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n850.677 698 M\n850.677 689.49 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 63 M\n163 71.51 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n334.919 63 M\n334.919 71.51 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n506.838 63 M\n506.838 71.51 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n678.758 63 M\n678.758 71.51 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n850.677 63 M\n850.677 71.51 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 61.125 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-13.5 49 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 125.5947 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(20) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 190.06439 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(40) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 254.53409 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(60) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 319.00378 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(80) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.68766 290.84999] CT\r\n0.149 GC\r\nN\r\n-6.348 40.503 M\n-6.348 39.722 -6.192 39.034 QT\n-2.364 23.815 L\n-7.927 23.815 L\n-8.458 23.815 -8.458 23.112 QT\n-8.255 21.956 -7.77 21.956 QT\n-1.895 21.956 L\n0.23 13.3 L\n0.433 12.612 1.058 12.12 QT\n1.683 11.628 2.448 11.628 QT\n3.136 11.628 3.589 12.026 QT\n4.042 12.425 4.042 13.097 QT\n4.042 13.253 4.027 13.347 QT\n4.011 13.44 3.98 13.534 QT\n1.855 21.956 L\n7.323 21.956 L\n7.87 21.956 7.87 22.644 QT\n7.839 22.784 7.761 23.089 QT\n7.683 23.394 7.55 23.604 QT\n7.417 23.815 7.167 23.815 QT\n1.402 23.815 L\n-2.411 39.128 L\n-2.802 40.628 -2.802 41.722 QT\n-2.802 44.003 -1.239 44.003 QT\n1.089 44.003 2.886 41.815 QT\n4.683 39.628 5.636 37.003 QT\n5.839 36.706 6.058 36.706 QT\n6.698 36.706 L\n6.902 36.706 7.034 36.847 QT\n7.167 36.987 7.167 37.159 QT\n7.167 37.269 7.12 37.315 QT\n5.948 40.534 3.722 42.964 QT\n1.495 45.394 -1.38 45.394 QT\n-3.473 45.394 -4.911 44.026 QT\n-6.348 42.659 -6.348 40.503 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 698 M\n163 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 698 M\n1014 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 698 M\n171.51 698 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 486.333 M\n171.51 486.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 274.667 M\n171.51 274.667 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 63 M\n171.51 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 698 M\n1005.49 698 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 486.333 M\n1005.49 486.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 274.667 M\n1005.49 274.667 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 63 M\n1005.49 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 698 M\n167.255 698 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 634.282 M\n167.255 634.282 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 597.009 M\n167.255 597.009 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 570.564 M\n167.255 570.564 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 550.051 M\n167.255 550.051 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 533.291 M\n167.255 533.291 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 519.121 M\n167.255 519.121 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 506.846 M\n167.255 506.846 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 496.019 M\n167.255 496.019 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 486.333 M\n167.255 486.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 422.615 M\n167.255 422.615 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 385.343 M\n167.255 385.343 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 358.897 M\n167.255 358.897 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 338.385 M\n167.255 338.385 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 321.625 M\n167.255 321.625 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 307.454 M\n167.255 307.454 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 295.179 M\n167.255 295.179 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 284.352 M\n167.255 284.352 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 274.667 M\n167.255 274.667 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 210.949 M\n167.255 210.949 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 173.676 M\n167.255 173.676 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 147.231 M\n167.255 147.231 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 126.718 M\n167.255 126.718 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 109.958 M\n167.255 109.958 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 95.788 M\n167.255 95.788 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 83.513 M\n167.255 83.513 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 72.685 M\n167.255 72.685 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n163 63 M\n167.255 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 698 M\n1009.745 698 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 634.282 M\n1009.745 634.282 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 597.009 M\n1009.745 597.009 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 570.564 M\n1009.745 570.564 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 550.051 M\n1009.745 550.051 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 533.291 M\n1009.745 533.291 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 519.121 M\n1009.745 519.121 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 506.846 M\n1009.745 506.846 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 496.019 M\n1009.745 496.019 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 486.333 M\n1009.745 486.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 422.615 M\n1009.745 422.615 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 385.343 M\n1009.745 385.343 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 358.897 M\n1009.745 358.897 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 338.385 M\n1009.745 338.385 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 321.625 M\n1009.745 321.625 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 307.454 M\n1009.745 307.454 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 295.179 M\n1009.745 295.179 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 284.352 M\n1009.745 284.352 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 274.667 M\n1009.745 274.667 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 210.949 M\n1009.745 210.949 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 173.676 M\n1009.745 173.676 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 147.231 M\n1009.745 147.231 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 126.718 M\n1009.745 126.718 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 109.958 M\n1009.745 109.958 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 95.788 M\n1009.745 95.788 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 83.513 M\n1009.745 83.513 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 72.685 M\n1009.745 72.685 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 63 M\n1009.745 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 27 271.5] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(10) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 47.25 262.5] CT\r\n0.149 GC\r\n/Helvetica 38.4 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 27 192] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(10) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 47.25 183] CT\r\n0.149 GC\r\n/Helvetica 38.4 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 27 112.875] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(10) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 47.25 103.875] CT\r\n0.149 GC\r\n/Helvetica 38.4 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(2) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 27 33.375] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(10) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 47.25 24.375] CT\r\n0.149 GC\r\n/Helvetica 38.4 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(3) t \r\nGR\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24.025 142.68739] CT\r\n0.149 GC\r\nN\r\n-62.536 -11.669 M\n-62.536 -12.966 -61.638 -13.911 QT\n-60.74 -14.856 -59.458 -14.856 QT\n-58.599 -14.856 -58.013 -14.325 QT\n-57.427 -13.794 -57.427 -12.935 QT\n-57.427 -11.935 -58.068 -11.114 QT\n-58.708 -10.294 -59.661 -10.044 QT\n-58.724 -9.7 -57.802 -9.7 QT\n-55.552 -9.7 -53.896 -11.786 QT\n-52.24 -13.872 -51.552 -16.45 QT\n-46.568 -36.388 L\n-46.208 -37.903 -46.208 -38.966 QT\n-46.208 -41.247 -47.786 -41.247 QT\n-50.115 -41.247 -51.857 -39.138 QT\n-53.599 -37.028 -54.693 -34.263 QT\n-54.786 -33.919 -55.099 -33.919 QT\n-55.724 -33.919 L\n-56.161 -33.919 -56.161 -34.419 QT\n-56.161 -34.575 L\n-54.974 -37.763 -52.779 -40.192 QT\n-50.583 -42.622 -47.677 -42.622 QT\n-45.474 -42.622 -44.068 -41.247 QT\n-42.661 -39.872 -42.661 -37.763 QT\n-42.661 -37.013 -42.818 -36.247 QT\n-47.833 -16.122 L\n-48.38 -13.966 -49.904 -12.185 QT\n-51.427 -10.403 -53.552 -9.364 QT\n-55.677 -8.325 -57.896 -8.325 QT\n-59.693 -8.325 -61.115 -9.185 QT\n-62.536 -10.044 -62.536 -11.669 QT\ncp\n-45.755 -51.31 M\n-45.755 -52.481 -44.857 -53.364 QT\n-43.958 -54.247 -42.818 -54.247 QT\n-41.911 -54.247 -41.326 -53.685 QT\n-40.74 -53.122 -40.74 -52.278 QT\n-40.74 -51.091 -41.685 -50.192 QT\n-42.63 -49.294 -43.771 -49.294 QT\n-44.63 -49.294 -45.193 -49.888 QT\n-45.755 -50.481 -45.755 -51.31 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24.025 142.68739] CT\r\n0.149 GC\r\nN\r\n-37.573 -14.2 M\n-37.573 -14.747 -37.464 -15.232 QT\n-34.792 -25.857 L\n-38.683 -25.857 L\n-39.058 -25.857 -39.058 -26.341 QT\n-38.917 -27.153 -38.573 -27.153 QT\n-34.464 -27.153 L\n-32.98 -33.185 L\n-32.839 -33.669 -32.409 -34.013 QT\n-31.98 -34.357 -31.433 -34.357 QT\n-30.964 -34.357 -30.644 -34.075 QT\n-30.323 -33.794 -30.323 -33.325 QT\n-30.323 -33.216 -30.339 -33.153 QT\n-30.355 -33.091 -30.37 -33.028 QT\n-31.855 -27.153 L\n-28.042 -27.153 L\n-27.652 -27.153 -27.652 -26.669 QT\n-27.683 -26.575 -27.73 -26.357 QT\n-27.777 -26.138 -27.87 -25.997 QT\n-27.964 -25.857 -28.152 -25.857 QT\n-32.167 -25.857 L\n-34.823 -15.153 L\n-35.105 -14.107 -35.105 -13.357 QT\n-35.105 -11.763 -34.011 -11.763 QT\n-32.386 -11.763 -31.136 -13.286 QT\n-29.886 -14.81 -29.214 -16.638 QT\n-29.073 -16.857 -28.917 -16.857 QT\n-28.464 -16.857 L\n-28.323 -16.857 -28.238 -16.755 QT\n-28.152 -16.653 -28.152 -16.528 QT\n-28.152 -16.45 -28.183 -16.419 QT\n-28.995 -14.185 -30.55 -12.482 QT\n-32.105 -10.778 -34.105 -10.778 QT\n-35.573 -10.778 -36.573 -11.739 QT\n-37.573 -12.7 -37.573 -14.2 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24.025 142.68739] CT\r\n0.149 GC\r\nN\r\n-22.717 -4.528 M\n-22.717 -4.7 -22.576 -4.841 QT\n-21.233 -6.122 -20.498 -7.802 QT\n-19.764 -9.482 -19.764 -11.341 QT\n-19.764 -11.794 L\n-20.358 -11.2 -21.233 -11.2 QT\n-22.092 -11.2 -22.686 -11.794 QT\n-23.279 -12.388 -23.279 -13.247 QT\n-23.279 -14.107 -22.686 -14.685 QT\n-22.092 -15.263 -21.233 -15.263 QT\n-19.92 -15.263 -19.358 -14.044 QT\n-18.795 -12.825 -18.795 -11.341 QT\n-18.795 -9.278 -19.623 -7.427 QT\n-20.451 -5.575 -21.951 -4.107 QT\n-22.092 -4.028 -22.186 -4.028 QT\n-22.358 -4.028 -22.537 -4.192 QT\n-22.717 -4.357 -22.717 -4.528 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24.025 142.68739] CT\r\n0.149 GC\r\nN\r\n-6.8 -10.778 M\n-9.05 -10.778 -10.87 -11.95 QT\n-12.69 -13.122 -13.737 -15.06 QT\n-14.784 -16.997 -14.784 -19.185 QT\n-14.784 -21.372 -13.745 -23.38 QT\n-12.706 -25.388 -10.878 -26.583 QT\n-9.05 -27.778 -6.8 -27.778 QT\n-4.643 -27.778 -2.862 -26.935 QT\n-1.081 -26.091 -1.081 -24.153 QT\n-1.081 -23.435 -1.597 -22.903 QT\n-2.112 -22.372 -2.847 -22.372 QT\n-3.581 -22.372 -4.097 -22.903 QT\n-4.612 -23.435 -4.612 -24.153 QT\n-4.612 -24.81 -4.198 -25.286 QT\n-3.784 -25.763 -3.175 -25.888 QT\n-4.456 -26.7 -6.768 -26.7 QT\n-8.534 -26.7 -9.62 -25.528 QT\n-10.706 -24.357 -11.143 -22.622 QT\n-11.581 -20.888 -11.581 -19.185 QT\n-11.581 -17.403 -11.042 -15.732 QT\n-10.503 -14.06 -9.323 -12.966 QT\n-8.143 -11.872 -6.347 -11.872 QT\n-4.597 -11.872 -3.37 -12.942 QT\n-2.143 -14.013 -1.69 -15.747 QT\n-1.69 -15.966 -1.409 -15.966 QT\n-0.956 -15.966 L\n-0.847 -15.966 -0.753 -15.872 QT\n-0.659 -15.778 -0.659 -15.638 QT\n-0.659 -15.544 L\n-1.222 -13.357 -2.886 -12.067 QT\n-4.55 -10.778 -6.8 -10.778 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24.025 142.68739] CT\r\n0.149 GC\r\nN\r\n9.824 -10.778 M\n7.605 -10.778 5.707 -11.911 QT\n3.809 -13.044 2.707 -14.942 QT\n1.605 -16.841 1.605 -19.075 QT\n1.605 -20.778 2.207 -22.349 QT\n2.809 -23.919 3.941 -25.153 QT\n5.074 -26.388 6.574 -27.083 QT\n8.074 -27.778 9.824 -27.778 QT\n12.105 -27.778 13.973 -26.583 QT\n15.84 -25.388 16.926 -23.372 QT\n18.012 -21.357 18.012 -19.075 QT\n18.012 -16.857 16.91 -14.95 QT\n15.809 -13.044 13.918 -11.911 QT\n12.027 -10.778 9.824 -10.778 QT\ncp\n9.824 -11.872 M\n12.793 -11.872 13.785 -14.021 QT\n14.777 -16.169 14.777 -19.497 QT\n14.777 -21.357 14.574 -22.575 QT\n14.371 -23.794 13.715 -24.794 QT\n13.293 -25.403 12.652 -25.864 QT\n12.012 -26.325 11.301 -26.567 QT\n10.59 -26.81 9.824 -26.81 QT\n8.668 -26.81 7.629 -26.286 QT\n6.59 -25.763 5.902 -24.794 QT\n5.215 -23.732 5.027 -22.482 QT\n4.84 -21.232 4.84 -19.497 QT\n4.84 -17.419 5.199 -15.763 QT\n5.559 -14.107 6.652 -12.989 QT\n7.746 -11.872 9.824 -11.872 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24.025 142.68739] CT\r\n0.149 GC\r\nN\r\n20.35 -11.2 M\n20.35 -12.497 L\n21.6 -12.497 22.42 -12.7 QT\n23.241 -12.903 23.241 -13.669 QT\n23.241 -23.778 L\n23.241 -24.763 22.936 -25.208 QT\n22.631 -25.653 22.077 -25.755 QT\n21.522 -25.857 20.35 -25.857 QT\n20.35 -27.153 L\n25.71 -27.544 L\n25.71 -23.935 L\n26.444 -25.528 27.905 -26.536 QT\n29.366 -27.544 31.069 -27.544 QT\n33.647 -27.544 34.936 -26.317 QT\n36.225 -25.091 36.225 -22.56 QT\n36.225 -13.669 L\n36.225 -12.903 37.038 -12.7 QT\n37.85 -12.497 39.116 -12.497 QT\n39.116 -11.2 L\n30.647 -11.2 L\n30.647 -12.497 L\n31.913 -12.497 32.725 -12.7 QT\n33.538 -12.903 33.538 -13.669 QT\n33.538 -22.45 L\n33.538 -24.263 33.014 -25.427 QT\n32.491 -26.591 30.85 -26.591 QT\n28.71 -26.591 27.327 -24.872 QT\n25.944 -23.153 25.944 -20.982 QT\n25.944 -13.669 L\n25.944 -12.903 26.756 -12.7 QT\n27.569 -12.497 28.819 -12.497 QT\n28.819 -11.2 L\n20.35 -11.2 L\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24.025 142.68739] CT\r\n0.149 GC\r\nN\r\n47.976 -11.2 M\n42.569 -24.794 L\n42.226 -25.466 41.515 -25.661 QT\n40.804 -25.857 39.648 -25.857 QT\n39.648 -27.153 L\n47.413 -27.153 L\n47.413 -25.857 L\n45.335 -25.857 45.335 -24.966 QT\n45.335 -24.825 45.382 -24.747 QT\n49.538 -14.31 L\n53.273 -23.732 L\n53.382 -24.028 53.382 -24.341 QT\n53.382 -25.044 52.851 -25.45 QT\n52.319 -25.857 51.585 -25.857 QT\n51.585 -27.153 L\n57.741 -27.153 L\n57.741 -25.857 L\n56.601 -25.857 55.741 -25.333 QT\n54.882 -24.81 54.413 -23.778 QT\n49.429 -11.2 L\n49.273 -10.778 48.819 -10.778 QT\n48.554 -10.778 L\n48.101 -10.778 47.976 -11.2 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n2.667 LW\r\nN\r\n163 334.779 M\n171.596 331.31 L\n180.192 443.128 L\n188.788 402.103 L\n197.384 427.33 L\n205.98 413.854 L\n214.576 379.41 L\n223.172 462.215 L\n231.768 427.33 L\n240.364 443.128 L\n248.96 443.128 L\n257.556 413.854 L\n266.152 422.615 L\n274.747 368.583 L\n283.343 382.328 L\n291.939 506.846 L\n300.535 496.019 L\n309.131 533.291 L\n317.727 533.291 L\n326.323 550.051 L\n334.919 550.051 L\n343.515 570.564 L\n352.111 570.564 L\n360.707 570.564 L\n369.303 597.009 L\n377.899 597.009 L\n386.495 597.009 L\n395.091 597.009 L\n403.687 597.009 L\n412.283 597.009 L\n420.879 597.009 L\n429.475 597.009 L\n438.071 597.009 L\n446.667 597.009 L\n455.263 597.009 L\n463.859 597.009 L\n472.455 597.009 L\n481.051 597.009 L\n489.646 597.009 L\n498.242 597.009 L\n506.838 597.009 L\n515.434 597.009 L\n524.03 634.282 L\n532.626 634.282 L\n541.222 634.282 L\n549.818 634.282 L\n558.414 634.282 L\n567.01 634.282 L\n575.606 634.282 L\n584.202 634.282 L\n592.798 634.282 L\n601.394 634.282 L\n609.99 634.282 L\n618.586 634.282 L\n627.182 634.282 L\n635.778 634.282 L\n644.374 634.282 L\n652.97 634.282 L\n661.566 634.282 L\n670.162 634.282 L\n678.758 634.282 L\n687.354 634.282 L\n695.949 634.282 L\n704.545 634.282 L\n713.141 634.282 L\n721.737 634.282 L\n730.333 634.282 L\n738.929 634.282 L\n747.525 634.282 L\n756.121 634.282 L\n764.717 634.282 L\n773.313 634.282 L\n781.909 634.282 L\n790.505 634.282 L\n799.101 634.282 L\n807.697 634.282 L\n816.293 634.282 L\n824.889 698 L\n833.485 634.282 L\n842.081 698 L\n850.677 634.282 L\n859.273 698 L\n867.869 634.282 L\n876.465 698 L\n885.061 698 L\n893.657 634.282 L\n902.253 698 L\n910.849 698 L\n919.444 698 L\n928.04 634.282 L\n936.636 698 L\n945.232 698 L\n953.828 698 L\n962.424 698 L\n971.02 698 L\n979.616 698 L\n988.212 698 L\n996.808 698 L\n1005.404 634.282 L\n1014 698 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 61.125 125.54224] CT\r\nN\r\n0 -4 M\n2.209 -4 4 -2.209 4 0 C\n4 0 L\n4 2.209 2.209 4 0 4 C\n-2.209 4 -4 2.209 -4 0 C\n-4 -2.209 -2.209 -4 0 -4 C\ncp\n0 -6.667 M\n-3.682 -6.667 -6.667 -3.682 -6.667 0 C\n-6.667 3.682 -3.682 6.667 0 6.667 C\n3.682 6.667 6.667 3.682 6.667 0 C\n6.667 0 L\n6.667 -3.682 3.682 -6.667 0 -6.667 C\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 64.34849 124.24125] CT\r\nN\r\n/f-1792389198{0 -4 M\n2.209 -4 4 -2.209 4 0 C\n4 0 L\n4 2.209 2.209 4 0 4 C\n-2.209 4 -4 2.209 -4 0 C\n-4 -2.209 -2.209 -4 0 -4 C\ncp\n0 -6.667 M\n-3.682 -6.667 -6.667 -3.682 -6.667 0 C\n-6.667 3.682 -3.682 6.667 0 6.667 C\n3.682 6.667 6.667 3.682 6.667 0 C\n6.667 0 L\n6.667 -3.682 3.682 -6.667 0 -6.667 C\ncp}def\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 67.57197 166.17297] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 70.79545 150.78851] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 74.01894 160.24893] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 77.24242 155.19519] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 80.46591 142.27872] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 83.68939 173.33075] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 86.91288 160.24893] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 90.13636 166.17297] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 93.35985 166.17297] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 96.58333 155.19519] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 99.80682 158.48075] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 103.0303 138.21849] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 106.25378 143.37316] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 109.47727 190.06723] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 112.70075 186.007] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 115.92424 199.98425] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 119.14772 199.98425] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 122.37122 206.26925] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 125.5947 206.26925] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 128.81819 213.96149] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 132.04167 213.96149] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 135.26515 213.96149] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 138.48864 223.8785] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 141.71212 223.8785] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 144.9356 223.8785] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 148.15909 223.8785] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 151.38257 223.8785] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 154.60606 223.8785] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 157.82954 223.8785] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 161.05302 223.8785] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 164.27652 223.8785] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 167.50001 223.8785] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 170.72348 223.8785] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 173.94697 223.8785] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.17046 223.8785] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 180.39394 223.8785] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 183.61742 223.8785] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 186.84091 223.8785] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 190.06439 223.8785] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 193.28787 223.8785] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 196.51138 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 199.73486 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 202.95834 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 206.18182 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 209.4053 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 212.6288 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 215.85228 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 219.07576 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.29924 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 225.52272 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 228.7462 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 231.9697 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 235.19318 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 238.41666 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 241.64014 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 244.86362 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 248.08713 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 251.31061 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 254.53409 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 257.75759 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 260.98105 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 264.20455 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 267.42803 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 270.65151 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 273.87502 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 277.09847 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 280.32195 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 283.54546 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.76894 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 289.99244 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 293.21592 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 296.43938 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 299.66288 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 302.88636 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 306.10984 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 309.33334 261.75] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 312.55682 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 315.7803 261.75] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 319.00378 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 322.22726 261.75] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 325.45077 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 328.67425 261.75] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 331.89773 261.75] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 335.12121 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 338.34469 261.75] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 341.56819 261.75] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 344.79167 261.75] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 348.01515 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 351.23866 261.75] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 354.46211 261.75] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 357.68559 261.75] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 360.9091 261.75] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 364.13258 261.75] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 367.35606 261.75] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 370.57956 261.75] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 373.80302 261.75] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 377.02652 237.85574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 380.25 261.75] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\n%%Trailer\r\n%%Pages: 1\r\n%%EOF\r\n"
  },
  {
    "path": "matlab/acc2023/closedloop_performance/figures/J-converge-2.eps",
    "content": "%!PS-Adobe-3.0 EPSF-3.0\r\n%%Creator: (MATLAB, The Mathworks, Inc. Version 9.10.0.1649659 \\(R2021a\\) Update 1. Operating System: Windows 10)\r\n%%Title: figures/J-converge-2.eps\r\n%%CreationDate: 2023-01-31T03:11:54\r\n%%Pages: (atend)\r\n%%BoundingBox:     3     6   383   301\r\n%%LanguageLevel: 3\r\n%%EndComments\r\n%%BeginProlog\r\n%%BeginResource: procset (Apache XML Graphics Std ProcSet) 1.2 0\r\n%%Version: 1.2 0\r\n%%Copyright: (Copyright 2001-2003,2010 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/bd{bind def}bind def\r\n/ld{load def}bd\r\n/GR/grestore ld\r\n/GS/gsave ld\r\n/RM/rmoveto ld\r\n/C/curveto ld\r\n/t/show ld\r\n/L/lineto ld\r\n/ML/setmiterlimit ld\r\n/CT/concat ld\r\n/f/fill ld\r\n/N/newpath ld\r\n/S/stroke ld\r\n/CC/setcmykcolor ld\r\n/A/ashow ld\r\n/cp/closepath ld\r\n/RC/setrgbcolor ld\r\n/LJ/setlinejoin ld\r\n/GC/setgray ld\r\n/LW/setlinewidth ld\r\n/M/moveto ld\r\n/re {4 2 roll M\r\n1 index 0 rlineto\r\n0 exch rlineto\r\nneg 0 rlineto\r\ncp } bd\r\n/_ctm matrix def\r\n/_tm matrix def\r\n/BT { _ctm currentmatrix pop matrix _tm copy pop 0 0 moveto } bd\r\n/ET { _ctm setmatrix } bd\r\n/iTm { _ctm setmatrix _tm concat } bd\r\n/Tm { _tm astore pop iTm 0 0 moveto } bd\r\n/ux 0.0 def\r\n/uy 0.0 def\r\n/F {\r\n  /Tp exch def\r\n  /Tf exch def\r\n  Tf findfont Tp scalefont setfont\r\n  /cf Tf def  /cs Tp def\r\n} bd\r\n/ULS {currentpoint /uy exch def /ux exch def} bd\r\n/ULE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add moveto  Tcx uy To add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/OLE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs add moveto Tcx uy To add cs add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/SOE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs 10 mul 26 idiv add moveto Tcx uy To add cs 10 mul 26 idiv add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/QT {\r\n/Y22 exch store\r\n/X22 exch store\r\n/Y21 exch store\r\n/X21 exch store\r\ncurrentpoint\r\n/Y21 load 2 mul add 3 div exch\r\n/X21 load 2 mul add 3 div exch\r\n/X21 load 2 mul /X22 load add 3 div\r\n/Y21 load 2 mul /Y22 load add 3 div\r\n/X22 load /Y22 load curveto\r\n} bd\r\n/SSPD {\r\ndup length /d exch dict def\r\n{\r\n/v exch def\r\n/k exch def\r\ncurrentpagedevice k known {\r\n/cpdv currentpagedevice k get def\r\nv cpdv ne {\r\n/upd false def\r\n/nullv v type /nulltype eq def\r\n/nullcpdv cpdv type /nulltype eq def\r\nnullv nullcpdv or\r\n{\r\n/upd true def\r\n} {\r\n/sametype v type cpdv type eq def\r\nsametype {\r\nv type /arraytype eq {\r\n/vlen v length def\r\n/cpdvlen cpdv length def\r\nvlen cpdvlen eq {\r\n0 1 vlen 1 sub {\r\n/i exch def\r\n/obj v i get def\r\n/cpdobj cpdv i get def\r\nobj cpdobj ne {\r\n/upd true def\r\nexit\r\n} if\r\n} for\r\n} {\r\n/upd true def\r\n} ifelse\r\n} {\r\nv type /dicttype eq {\r\nv {\r\n/dv exch def\r\n/dk exch def\r\n/cpddv cpdv dk get def\r\ndv cpddv ne {\r\n/upd true def\r\nexit\r\n} if\r\n} forall\r\n} {\r\n/upd true def\r\n} ifelse\r\n} ifelse\r\n} if\r\n} ifelse\r\nupd true eq {\r\nd k v put\r\n} if\r\n} if\r\n} if\r\n} forall\r\nd length 0 gt {\r\nd setpagedevice\r\n} if\r\n} bd\r\n/RE { % /NewFontName [NewEncodingArray] /FontName RE -\r\n  findfont dup length dict begin\r\n  {\r\n    1 index /FID ne\r\n    {def} {pop pop} ifelse\r\n  } forall\r\n  /Encoding exch def\r\n  /FontName 1 index def\r\n  currentdict definefont pop\r\n  end\r\n} bind def\r\n%%EndResource\r\n%%BeginResource: procset (Apache XML Graphics EPS ProcSet) 1.0 0\r\n%%Version: 1.0 0\r\n%%Copyright: (Copyright 2002-2003 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/BeginEPSF { %def\r\n/b4_Inc_state save def         % Save state for cleanup\r\n/dict_count countdictstack def % Count objects on dict stack\r\n/op_count count 1 sub def      % Count objects on operand stack\r\nuserdict begin                 % Push userdict on dict stack\r\n/showpage { } def              % Redefine showpage, { } = null proc\r\n0 setgray 0 setlinecap         % Prepare graphics state\r\n1 setlinewidth 0 setlinejoin\r\n10 setmiterlimit [ ] 0 setdash newpath\r\n/languagelevel where           % If level not equal to 1 then\r\n{pop languagelevel             % set strokeadjust and\r\n1 ne                           % overprint to their defaults.\r\n{false setstrokeadjust false setoverprint\r\n} if\r\n} if\r\n} bd\r\n/EndEPSF { %def\r\ncount op_count sub {pop} repeat            % Clean up stacks\r\ncountdictstack dict_count sub {end} repeat\r\nb4_Inc_state restore\r\n} bd\r\n%%EndResource\r\n%FOPBeginFontDict\r\n%%IncludeResource: font Courier-Oblique\r\n%%IncludeResource: font Courier-BoldOblique\r\n%%IncludeResource: font Courier-Bold\r\n%%IncludeResource: font ZapfDingbats\r\n%%IncludeResource: font Symbol\r\n%%IncludeResource: font Helvetica\r\n%%IncludeResource: font Helvetica-Oblique\r\n%%IncludeResource: font Helvetica-Bold\r\n%%IncludeResource: font Helvetica-BoldOblique\r\n%%IncludeResource: font Times-Roman\r\n%%IncludeResource: font Times-Italic\r\n%%IncludeResource: font Times-Bold\r\n%%IncludeResource: font Times-BoldItalic\r\n%%IncludeResource: font Courier\r\n%FOPEndFontDict\r\n%%BeginResource: encoding WinAnsiEncoding\r\n/WinAnsiEncoding [\r\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /space /exclam /quotedbl\n/numbersign /dollar /percent /ampersand /quotesingle\n/parenleft /parenright /asterisk /plus /comma\n/hyphen /period /slash /zero /one\n/two /three /four /five /six\n/seven /eight /nine /colon /semicolon\n/less /equal /greater /question /at\n/A /B /C /D /E\n/F /G /H /I /J\n/K /L /M /N /O\n/P /Q /R /S /T\n/U /V /W /X /Y\n/Z /bracketleft /backslash /bracketright /asciicircum\n/underscore /quoteleft /a /b /c\n/d /e /f /g /h\n/i /j /k /l /m\n/n /o /p /q /r\n/s /t /u /v /w\n/x /y /z /braceleft /bar\n/braceright /asciitilde /bullet /Euro /bullet\n/quotesinglbase /florin /quotedblbase /ellipsis /dagger\n/daggerdbl /circumflex /perthousand /Scaron /guilsinglleft\n/OE /bullet /Zcaron /bullet /bullet\n/quoteleft /quoteright /quotedblleft /quotedblright /bullet\n/endash /emdash /asciitilde /trademark /scaron\n/guilsinglright /oe /bullet /zcaron /Ydieresis\n/space /exclamdown /cent /sterling /currency\n/yen /brokenbar /section /dieresis /copyright\n/ordfeminine /guillemotleft /logicalnot /sfthyphen /registered\n/macron /degree /plusminus /twosuperior /threesuperior\n/acute /mu /paragraph /middot /cedilla\n/onesuperior /ordmasculine /guillemotright /onequarter /onehalf\n/threequarters /questiondown /Agrave /Aacute /Acircumflex\n/Atilde /Adieresis /Aring /AE /Ccedilla\n/Egrave /Eacute /Ecircumflex /Edieresis /Igrave\n/Iacute /Icircumflex /Idieresis /Eth /Ntilde\n/Ograve /Oacute /Ocircumflex /Otilde /Odieresis\n/multiply /Oslash /Ugrave /Uacute /Ucircumflex\n/Udieresis /Yacute /Thorn /germandbls /agrave\n/aacute /acircumflex /atilde /adieresis /aring\n/ae /ccedilla /egrave /eacute /ecircumflex\n/edieresis /igrave /iacute /icircumflex /idieresis\n/eth /ntilde /ograve /oacute /ocircumflex\n/otilde /odieresis /divide /oslash /ugrave\n/uacute /ucircumflex /udieresis /yacute /thorn\n/ydieresis\n] def\r\n%%EndResource\r\n%FOPBeginFontReencode\r\n/Courier-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Oblique exch definefont pop\r\n/Courier-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-BoldOblique exch definefont pop\r\n/Courier-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Bold exch definefont pop\r\n/Helvetica findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica exch definefont pop\r\n/Helvetica-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Oblique exch definefont pop\r\n/Helvetica-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Bold exch definefont pop\r\n/Helvetica-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-BoldOblique exch definefont pop\r\n/Times-Roman findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Roman exch definefont pop\r\n/Times-Italic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Italic exch definefont pop\r\n/Times-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Bold exch definefont pop\r\n/Times-BoldItalic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-BoldItalic exch definefont pop\r\n/Courier findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier exch definefont pop\r\n%FOPEndFontReencode\r\n%%EndProlog\r\n%%Page: 1 1\r\n%%PageBoundingBox: 0 0 420 315\r\n%%BeginPageSetup\r\n[1 0 0 -1 0 315] CT\r\n%%EndPageSetup\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n162 699 M\n1014 699 L\n1014 63 L\n162 63 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 699 M\n1014 699 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 63 M\n1014 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 699 M\n162 690.48 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n334.121 699 M\n334.121 690.48 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n506.242 699 M\n506.242 690.48 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n678.364 699 M\n678.364 690.48 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n850.485 699 M\n850.485 690.48 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 63 M\n162 71.52 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n334.121 63 M\n334.121 71.52 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n506.242 63 M\n506.242 71.52 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n678.364 63 M\n678.364 71.52 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n850.485 63 M\n850.485 71.52 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 60.75 267.72501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-13.5 49 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 125.29546 267.72501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(20) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 189.84091 267.72501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(40) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 254.38637 267.72501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(60) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 318.93182 267.72501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(80) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.50016 291.22499] CT\r\n0.149 GC\r\nN\r\n-6.252 40.055 M\n-6.252 39.274 -6.096 38.586 QT\n-2.268 23.367 L\n-7.83 23.367 L\n-8.361 23.367 -8.361 22.664 QT\n-8.158 21.508 -7.674 21.508 QT\n-1.799 21.508 L\n0.326 12.852 L\n0.529 12.164 1.154 11.672 QT\n1.779 11.18 2.545 11.18 QT\n3.232 11.18 3.685 11.578 QT\n4.139 11.977 4.139 12.649 QT\n4.139 12.805 4.123 12.899 QT\n4.107 12.992 4.076 13.086 QT\n1.951 21.508 L\n7.42 21.508 L\n7.967 21.508 7.967 22.196 QT\n7.935 22.336 7.857 22.641 QT\n7.779 22.946 7.646 23.156 QT\n7.514 23.367 7.264 23.367 QT\n1.498 23.367 L\n-2.315 38.68 L\n-2.705 40.18 -2.705 41.274 QT\n-2.705 43.555 -1.143 43.555 QT\n1.185 43.555 2.982 41.367 QT\n4.779 39.18 5.732 36.555 QT\n5.935 36.258 6.154 36.258 QT\n6.795 36.258 L\n6.998 36.258 7.131 36.399 QT\n7.264 36.539 7.264 36.711 QT\n7.264 36.821 7.217 36.867 QT\n6.045 40.086 3.818 42.516 QT\n1.592 44.946 -1.283 44.946 QT\n-3.377 44.946 -4.815 43.578 QT\n-6.252 42.211 -6.252 40.055 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 699 M\n162 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 699 M\n1014 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 699 M\n170.52 699 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 487 M\n170.52 487 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 275 M\n170.52 275 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 63 M\n170.52 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 699 M\n1005.48 699 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 487 M\n1005.48 487 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 275 M\n1005.48 275 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 63 M\n1005.48 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 699 M\n166.26 699 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 635.182 M\n166.26 635.182 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 597.85 M\n166.26 597.85 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 571.363 M\n166.26 571.363 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 550.818 M\n166.26 550.818 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 534.032 M\n166.26 534.032 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 519.839 M\n166.26 519.839 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 507.545 M\n166.26 507.545 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 496.701 M\n166.26 496.701 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 487 M\n166.26 487 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 423.182 M\n166.26 423.182 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 385.85 M\n166.26 385.85 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 359.363 M\n166.26 359.363 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 338.818 M\n166.26 338.818 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 322.032 M\n166.26 322.032 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 307.839 M\n166.26 307.839 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 295.545 M\n166.26 295.545 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 284.701 M\n166.26 284.701 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 275 M\n166.26 275 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 211.182 M\n166.26 211.182 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 173.85 M\n166.26 173.85 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 147.363 M\n166.26 147.363 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 126.818 M\n166.26 126.818 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 110.032 M\n166.26 110.032 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 95.839 M\n166.26 95.839 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 83.545 M\n166.26 83.545 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 72.701 M\n166.26 72.701 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 63 M\n166.26 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 699 M\n1009.74 699 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 635.182 M\n1009.74 635.182 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 597.85 M\n1009.74 597.85 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 571.363 M\n1009.74 571.363 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 550.818 M\n1009.74 550.818 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 534.032 M\n1009.74 534.032 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 519.839 M\n1009.74 519.839 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 507.545 M\n1009.74 507.545 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 496.701 M\n1009.74 496.701 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 487 M\n1009.74 487 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 423.182 M\n1009.74 423.182 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 385.85 M\n1009.74 385.85 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 359.363 M\n1009.74 359.363 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 338.818 M\n1009.74 338.818 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 322.032 M\n1009.74 322.032 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 307.839 M\n1009.74 307.839 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 295.545 M\n1009.74 295.545 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 284.701 M\n1009.74 284.701 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 275 M\n1009.74 275 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 211.182 M\n1009.74 211.182 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 173.85 M\n1009.74 173.85 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 147.363 M\n1009.74 147.363 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 126.818 M\n1009.74 126.818 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 110.032 M\n1009.74 110.032 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 95.839 M\n1009.74 95.839 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 83.545 M\n1009.74 83.545 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 72.701 M\n1009.74 72.701 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 63 M\n1009.74 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 26.625 271.875] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(10) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 46.875 262.875] CT\r\n0.149 GC\r\n/Helvetica 38.4 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 26.625 192.375] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(10) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 46.875 183.375] CT\r\n0.149 GC\r\n/Helvetica 38.4 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 26.625 112.875] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(10) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 46.875 103.875] CT\r\n0.149 GC\r\n/Helvetica 38.4 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(2) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 26.625 33.375] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(10) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 46.875 24.375] CT\r\n0.149 GC\r\n/Helvetica 38.4 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(3) t \r\nGR\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n-61.918 -11.477 M\n-61.918 -12.774 -61.02 -13.719 QT\n-60.121 -14.664 -58.84 -14.664 QT\n-57.981 -14.664 -57.395 -14.133 QT\n-56.809 -13.602 -56.809 -12.743 QT\n-56.809 -11.743 -57.449 -10.922 QT\n-58.09 -10.102 -59.043 -9.852 QT\n-58.106 -9.508 -57.184 -9.508 QT\n-54.934 -9.508 -53.277 -11.594 QT\n-51.621 -13.68 -50.934 -16.258 QT\n-45.949 -36.196 L\n-45.59 -37.711 -45.59 -38.774 QT\n-45.59 -41.055 -47.168 -41.055 QT\n-49.496 -41.055 -51.238 -38.946 QT\n-52.981 -36.836 -54.074 -34.071 QT\n-54.168 -33.727 -54.481 -33.727 QT\n-55.106 -33.727 L\n-55.543 -33.727 -55.543 -34.227 QT\n-55.543 -34.383 L\n-54.356 -37.571 -52.16 -40 QT\n-49.965 -42.43 -47.059 -42.43 QT\n-44.856 -42.43 -43.449 -41.055 QT\n-42.043 -39.68 -42.043 -37.571 QT\n-42.043 -36.821 -42.199 -36.055 QT\n-47.215 -15.93 L\n-47.762 -13.774 -49.285 -11.993 QT\n-50.809 -10.211 -52.934 -9.172 QT\n-55.059 -8.133 -57.277 -8.133 QT\n-59.074 -8.133 -60.496 -8.993 QT\n-61.918 -9.852 -61.918 -11.477 QT\ncp\n-45.137 -51.118 M\n-45.137 -52.289 -44.238 -53.172 QT\n-43.34 -54.055 -42.199 -54.055 QT\n-41.293 -54.055 -40.707 -53.493 QT\n-40.121 -52.93 -40.121 -52.086 QT\n-40.121 -50.899 -41.067 -50 QT\n-42.012 -49.102 -43.152 -49.102 QT\n-44.012 -49.102 -44.574 -49.696 QT\n-45.137 -50.289 -45.137 -51.118 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n-37.175 -14.088 M\n-37.175 -14.635 -37.065 -15.12 QT\n-34.394 -25.745 L\n-38.284 -25.745 L\n-38.659 -25.745 -38.659 -26.229 QT\n-38.519 -27.041 -38.175 -27.041 QT\n-34.065 -27.041 L\n-32.581 -33.073 L\n-32.44 -33.557 -32.011 -33.901 QT\n-31.581 -34.245 -31.034 -34.245 QT\n-30.565 -34.245 -30.245 -33.963 QT\n-29.925 -33.682 -29.925 -33.213 QT\n-29.925 -33.104 -29.94 -33.041 QT\n-29.956 -32.979 -29.972 -32.916 QT\n-31.456 -27.041 L\n-27.644 -27.041 L\n-27.253 -27.041 -27.253 -26.557 QT\n-27.284 -26.463 -27.331 -26.245 QT\n-27.378 -26.026 -27.472 -25.885 QT\n-27.565 -25.745 -27.753 -25.745 QT\n-31.769 -25.745 L\n-34.425 -15.041 L\n-34.706 -13.995 -34.706 -13.245 QT\n-34.706 -11.651 -33.612 -11.651 QT\n-31.987 -11.651 -30.737 -13.174 QT\n-29.487 -14.698 -28.815 -16.526 QT\n-28.675 -16.745 -28.519 -16.745 QT\n-28.065 -16.745 L\n-27.925 -16.745 -27.839 -16.643 QT\n-27.753 -16.541 -27.753 -16.416 QT\n-27.753 -16.338 -27.784 -16.307 QT\n-28.597 -14.073 -30.151 -12.37 QT\n-31.706 -10.666 -33.706 -10.666 QT\n-35.175 -10.666 -36.175 -11.627 QT\n-37.175 -12.588 -37.175 -14.088 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n-22.453 -4.416 M\n-22.453 -4.588 -22.312 -4.729 QT\n-20.969 -6.01 -20.234 -7.69 QT\n-19.5 -9.37 -19.5 -11.229 QT\n-19.5 -11.682 L\n-20.094 -11.088 -20.969 -11.088 QT\n-21.828 -11.088 -22.422 -11.682 QT\n-23.016 -12.276 -23.016 -13.135 QT\n-23.016 -13.995 -22.422 -14.573 QT\n-21.828 -15.151 -20.969 -15.151 QT\n-19.656 -15.151 -19.094 -13.932 QT\n-18.531 -12.713 -18.531 -11.229 QT\n-18.531 -9.166 -19.359 -7.315 QT\n-20.187 -5.463 -21.687 -3.995 QT\n-21.828 -3.916 -21.922 -3.916 QT\n-22.094 -3.916 -22.273 -4.08 QT\n-22.453 -4.245 -22.453 -4.416 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n-6.64 -10.666 M\n-8.89 -10.666 -10.71 -11.838 QT\n-12.53 -13.01 -13.577 -14.948 QT\n-14.624 -16.885 -14.624 -19.073 QT\n-14.624 -21.26 -13.585 -23.268 QT\n-12.546 -25.276 -10.718 -26.471 QT\n-8.89 -27.666 -6.64 -27.666 QT\n-4.483 -27.666 -2.702 -26.823 QT\n-0.921 -25.979 -0.921 -24.041 QT\n-0.921 -23.323 -1.436 -22.791 QT\n-1.952 -22.26 -2.686 -22.26 QT\n-3.421 -22.26 -3.936 -22.791 QT\n-4.452 -23.323 -4.452 -24.041 QT\n-4.452 -24.698 -4.038 -25.174 QT\n-3.624 -25.651 -3.015 -25.776 QT\n-4.296 -26.588 -6.608 -26.588 QT\n-8.374 -26.588 -9.46 -25.416 QT\n-10.546 -24.245 -10.983 -22.51 QT\n-11.421 -20.776 -11.421 -19.073 QT\n-11.421 -17.291 -10.882 -15.62 QT\n-10.343 -13.948 -9.163 -12.854 QT\n-7.983 -11.76 -6.186 -11.76 QT\n-4.436 -11.76 -3.21 -12.83 QT\n-1.983 -13.901 -1.53 -15.635 QT\n-1.53 -15.854 -1.249 -15.854 QT\n-0.796 -15.854 L\n-0.686 -15.854 -0.593 -15.76 QT\n-0.499 -15.666 -0.499 -15.526 QT\n-0.499 -15.432 L\n-1.061 -13.245 -2.725 -11.955 QT\n-4.39 -10.666 -6.64 -10.666 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n9.818 -10.666 M\n7.6 -10.666 5.701 -11.799 QT\n3.803 -12.932 2.701 -14.83 QT\n1.6 -16.729 1.6 -18.963 QT\n1.6 -20.666 2.201 -22.237 QT\n2.803 -23.807 3.936 -25.041 QT\n5.068 -26.276 6.568 -26.971 QT\n8.068 -27.666 9.818 -27.666 QT\n12.1 -27.666 13.967 -26.471 QT\n15.834 -25.276 16.92 -23.26 QT\n18.006 -21.245 18.006 -18.963 QT\n18.006 -16.745 16.904 -14.838 QT\n15.803 -12.932 13.912 -11.799 QT\n12.022 -10.666 9.818 -10.666 QT\ncp\n9.818 -11.76 M\n12.787 -11.76 13.779 -13.909 QT\n14.772 -16.057 14.772 -19.385 QT\n14.772 -21.245 14.568 -22.463 QT\n14.365 -23.682 13.709 -24.682 QT\n13.287 -25.291 12.647 -25.752 QT\n12.006 -26.213 11.295 -26.455 QT\n10.584 -26.698 9.818 -26.698 QT\n8.662 -26.698 7.623 -26.174 QT\n6.584 -25.651 5.897 -24.682 QT\n5.209 -23.62 5.022 -22.37 QT\n4.834 -21.12 4.834 -19.385 QT\n4.834 -17.307 5.193 -15.651 QT\n5.553 -13.995 6.647 -12.877 QT\n7.74 -11.76 9.818 -11.76 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n20.158 -11.088 M\n20.158 -12.385 L\n21.408 -12.385 22.228 -12.588 QT\n23.048 -12.791 23.048 -13.557 QT\n23.048 -23.666 L\n23.048 -24.651 22.744 -25.096 QT\n22.439 -25.541 21.884 -25.643 QT\n21.33 -25.745 20.158 -25.745 QT\n20.158 -27.041 L\n25.517 -27.432 L\n25.517 -23.823 L\n26.252 -25.416 27.712 -26.424 QT\n29.173 -27.432 30.877 -27.432 QT\n33.455 -27.432 34.744 -26.205 QT\n36.033 -24.979 36.033 -22.448 QT\n36.033 -13.557 L\n36.033 -12.791 36.845 -12.588 QT\n37.658 -12.385 38.923 -12.385 QT\n38.923 -11.088 L\n30.455 -11.088 L\n30.455 -12.385 L\n31.72 -12.385 32.533 -12.588 QT\n33.345 -12.791 33.345 -13.557 QT\n33.345 -22.338 L\n33.345 -24.151 32.822 -25.315 QT\n32.298 -26.479 30.658 -26.479 QT\n28.517 -26.479 27.134 -24.76 QT\n25.752 -23.041 25.752 -20.87 QT\n25.752 -13.557 L\n25.752 -12.791 26.564 -12.588 QT\n27.377 -12.385 28.627 -12.385 QT\n28.627 -11.088 L\n20.158 -11.088 L\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n47.586 -11.088 M\n42.18 -24.682 L\n41.836 -25.354 41.125 -25.549 QT\n40.414 -25.745 39.258 -25.745 QT\n39.258 -27.041 L\n47.024 -27.041 L\n47.024 -25.745 L\n44.946 -25.745 44.946 -24.854 QT\n44.946 -24.713 44.993 -24.635 QT\n49.149 -14.198 L\n52.883 -23.62 L\n52.993 -23.916 52.993 -24.229 QT\n52.993 -24.932 52.461 -25.338 QT\n51.93 -25.745 51.196 -25.745 QT\n51.196 -27.041 L\n57.352 -27.041 L\n57.352 -25.745 L\n56.211 -25.745 55.352 -25.221 QT\n54.493 -24.698 54.024 -23.666 QT\n49.039 -11.088 L\n48.883 -10.666 48.43 -10.666 QT\n48.164 -10.666 L\n47.711 -10.666 47.586 -11.088 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n2.667 LW\r\nN\r\n162 369.064 M\n170.606 350.588 L\n179.212 449.669 L\n187.818 350.588 L\n196.424 449.669 L\n205.03 385.85 L\n213.636 374.326 L\n222.242 303.976 L\n230.848 432.882 L\n239.455 410.314 L\n248.061 423.182 L\n256.667 402.637 L\n265.273 402.637 L\n273.879 487 L\n282.485 348.519 L\n291.091 456.021 L\n299.697 496.701 L\n308.303 534.032 L\n316.909 534.032 L\n325.515 550.818 L\n334.121 550.818 L\n342.727 571.363 L\n351.333 571.363 L\n359.939 571.363 L\n368.545 597.85 L\n377.152 597.85 L\n385.758 597.85 L\n394.364 597.85 L\n402.97 597.85 L\n411.576 597.85 L\n420.182 597.85 L\n428.788 597.85 L\n437.394 597.85 L\n446 597.85 L\n454.606 597.85 L\n463.212 597.85 L\n471.818 597.85 L\n480.424 597.85 L\n489.03 597.85 L\n497.636 597.85 L\n506.242 597.85 L\n514.849 597.85 L\n523.455 635.182 L\n532.061 635.182 L\n540.667 635.182 L\n549.273 635.182 L\n557.879 635.182 L\n566.485 635.182 L\n575.091 635.182 L\n583.697 635.182 L\n592.303 635.182 L\n600.909 635.182 L\n609.515 635.182 L\n618.121 635.182 L\n626.727 635.182 L\n635.333 635.182 L\n643.939 635.182 L\n652.545 635.182 L\n661.151 635.182 L\n669.758 635.182 L\n678.364 635.182 L\n686.97 635.182 L\n695.576 635.182 L\n704.182 635.182 L\n712.788 635.182 L\n721.394 635.182 L\n730 635.182 L\n738.606 635.182 L\n747.212 635.182 L\n755.818 635.182 L\n764.424 635.182 L\n773.03 635.182 L\n781.636 635.182 L\n790.242 635.182 L\n798.848 635.182 L\n807.455 635.182 L\n816.061 635.182 L\n824.667 699 L\n833.273 635.182 L\n841.879 699 L\n850.485 635.182 L\n859.091 699 L\n867.697 635.182 L\n876.303 699 L\n884.909 699 L\n893.515 635.182 L\n902.121 699 L\n910.727 699 L\n919.333 699 L\n927.939 635.182 L\n936.545 699 L\n945.151 699 L\n953.758 699 L\n962.364 699 L\n970.97 699 L\n979.576 699 L\n988.182 699 L\n996.788 635.182 L\n1005.394 699 L\n1014 699 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 60.75 138.39895] CT\r\nN\r\n0 -4 M\n2.209 -4 4 -2.209 4 0 C\n4 0 L\n4 2.209 2.209 4 0 4 C\n-2.209 4 -4 2.209 -4 0 C\n-4 -2.209 -2.209 -4 0 -4 C\ncp\n0 -6.667 M\n-3.682 -6.667 -6.667 -3.682 -6.667 0 C\n-6.667 3.682 -3.682 6.667 0 6.667 C\n3.682 6.667 6.667 3.682 6.667 0 C\n6.667 0 L\n6.667 -3.682 3.682 -6.667 0 -6.667 C\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 63.97727 131.4705] CT\r\nN\r\n/f-1792389198{0 -4 M\n2.209 -4 4 -2.209 4 0 C\n4 0 L\n4 2.209 2.209 4 0 4 C\n-2.209 4 -4 2.209 -4 0 C\n-4 -2.209 -2.209 -4 0 -4 C\ncp\n0 -6.667 M\n-3.682 -6.667 -6.667 -3.682 -6.667 0 C\n-6.667 3.682 -3.682 6.667 0 6.667 C\n3.682 6.667 6.667 3.682 6.667 0 C\n6.667 0 L\n6.667 -3.682 3.682 -6.667 0 -6.667 C\ncp}def\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 67.20455 168.62574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 70.43182 131.4705] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 73.65909 168.62574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 76.88636 144.69386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 80.11364 140.37243] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 83.34091 113.99083] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 86.56818 162.33084] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 89.79545 153.86763] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 93.02273 158.69312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 96.25 150.98877] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 99.47728 150.98877] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 102.70454 182.625] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 105.93181 130.69461] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 109.15909 171.00782] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 112.38636 186.26272] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 115.61364 200.26197] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 118.84091 200.26197] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 122.06819 206.55688] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 125.29546 206.55688] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 128.52272 214.26123] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 131.75 214.26123] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 134.97727 214.26123] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 138.20455 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 141.43182 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 144.65909 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 147.88637 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 151.11364 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 154.3409 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 157.56818 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 160.79545 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 164.02273 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 167.25 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 170.47727 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 173.70455 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 176.93182 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 180.15908 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 183.38636 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 186.61364 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 189.84091 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 193.06819 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 196.29545 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 199.52273 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 202.75001 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 205.97729 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 209.20454 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 212.43182 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 215.6591 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 218.88636 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.11364 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 225.3409 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 228.56818 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 231.79546 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 235.02274 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 238.25002 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 241.47727 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 244.70455 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 247.93181 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 251.15909 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 254.38637 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 257.61365 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 260.8409 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 264.06818 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 267.29546 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 270.52272 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 273.75 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 276.97726 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 280.20454 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 283.43182 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.6591 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 289.88638 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 293.11363 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 296.34089 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 299.56817 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 302.79545 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 306.02273 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 309.25001 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 312.47729 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 315.70454 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 318.93182 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 322.15908 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 325.38636 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 328.61364 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 331.84092 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 335.06818 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 338.29546 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 341.52274 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 344.74999 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 347.97727 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 351.20455 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 354.43181 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 357.65909 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 360.88637 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 364.11365 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 367.3409 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 370.56818 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 373.79544 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 377.02272 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 380.25 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\n%%Trailer\r\n%%Pages: 1\r\n%%EOF\r\n"
  },
  {
    "path": "matlab/acc2023/closedloop_performance/figures/J-converge-3.eps",
    "content": "%!PS-Adobe-3.0 EPSF-3.0\r\n%%Creator: (MATLAB, The Mathworks, Inc. Version 9.10.0.1649659 \\(R2021a\\) Update 1. Operating System: Windows 10)\r\n%%Title: figures/J-converge-3.eps\r\n%%CreationDate: 2023-01-31T03:11:56\r\n%%Pages: (atend)\r\n%%BoundingBox:     3     6   383   301\r\n%%LanguageLevel: 3\r\n%%EndComments\r\n%%BeginProlog\r\n%%BeginResource: procset (Apache XML Graphics Std ProcSet) 1.2 0\r\n%%Version: 1.2 0\r\n%%Copyright: (Copyright 2001-2003,2010 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/bd{bind def}bind def\r\n/ld{load def}bd\r\n/GR/grestore ld\r\n/GS/gsave ld\r\n/RM/rmoveto ld\r\n/C/curveto ld\r\n/t/show ld\r\n/L/lineto ld\r\n/ML/setmiterlimit ld\r\n/CT/concat ld\r\n/f/fill ld\r\n/N/newpath ld\r\n/S/stroke ld\r\n/CC/setcmykcolor ld\r\n/A/ashow ld\r\n/cp/closepath ld\r\n/RC/setrgbcolor ld\r\n/LJ/setlinejoin ld\r\n/GC/setgray ld\r\n/LW/setlinewidth ld\r\n/M/moveto ld\r\n/re {4 2 roll M\r\n1 index 0 rlineto\r\n0 exch rlineto\r\nneg 0 rlineto\r\ncp } bd\r\n/_ctm matrix def\r\n/_tm matrix def\r\n/BT { _ctm currentmatrix pop matrix _tm copy pop 0 0 moveto } bd\r\n/ET { _ctm setmatrix } bd\r\n/iTm { _ctm setmatrix _tm concat } bd\r\n/Tm { _tm astore pop iTm 0 0 moveto } bd\r\n/ux 0.0 def\r\n/uy 0.0 def\r\n/F {\r\n  /Tp exch def\r\n  /Tf exch def\r\n  Tf findfont Tp scalefont setfont\r\n  /cf Tf def  /cs Tp def\r\n} bd\r\n/ULS {currentpoint /uy exch def /ux exch def} bd\r\n/ULE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add moveto  Tcx uy To add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/OLE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs add moveto Tcx uy To add cs add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/SOE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs 10 mul 26 idiv add moveto Tcx uy To add cs 10 mul 26 idiv add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/QT {\r\n/Y22 exch store\r\n/X22 exch store\r\n/Y21 exch store\r\n/X21 exch store\r\ncurrentpoint\r\n/Y21 load 2 mul add 3 div exch\r\n/X21 load 2 mul add 3 div exch\r\n/X21 load 2 mul /X22 load add 3 div\r\n/Y21 load 2 mul /Y22 load add 3 div\r\n/X22 load /Y22 load curveto\r\n} bd\r\n/SSPD {\r\ndup length /d exch dict def\r\n{\r\n/v exch def\r\n/k exch def\r\ncurrentpagedevice k known {\r\n/cpdv currentpagedevice k get def\r\nv cpdv ne {\r\n/upd false def\r\n/nullv v type /nulltype eq def\r\n/nullcpdv cpdv type /nulltype eq def\r\nnullv nullcpdv or\r\n{\r\n/upd true def\r\n} {\r\n/sametype v type cpdv type eq def\r\nsametype {\r\nv type /arraytype eq {\r\n/vlen v length def\r\n/cpdvlen cpdv length def\r\nvlen cpdvlen eq {\r\n0 1 vlen 1 sub {\r\n/i exch def\r\n/obj v i get def\r\n/cpdobj cpdv i get def\r\nobj cpdobj ne {\r\n/upd true def\r\nexit\r\n} if\r\n} for\r\n} {\r\n/upd true def\r\n} ifelse\r\n} {\r\nv type /dicttype eq {\r\nv {\r\n/dv exch def\r\n/dk exch def\r\n/cpddv cpdv dk get def\r\ndv cpddv ne {\r\n/upd true def\r\nexit\r\n} if\r\n} forall\r\n} {\r\n/upd true def\r\n} ifelse\r\n} ifelse\r\n} if\r\n} ifelse\r\nupd true eq {\r\nd k v put\r\n} if\r\n} if\r\n} if\r\n} forall\r\nd length 0 gt {\r\nd setpagedevice\r\n} if\r\n} bd\r\n/RE { % /NewFontName [NewEncodingArray] /FontName RE -\r\n  findfont dup length dict begin\r\n  {\r\n    1 index /FID ne\r\n    {def} {pop pop} ifelse\r\n  } forall\r\n  /Encoding exch def\r\n  /FontName 1 index def\r\n  currentdict definefont pop\r\n  end\r\n} bind def\r\n%%EndResource\r\n%%BeginResource: procset (Apache XML Graphics EPS ProcSet) 1.0 0\r\n%%Version: 1.0 0\r\n%%Copyright: (Copyright 2002-2003 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/BeginEPSF { %def\r\n/b4_Inc_state save def         % Save state for cleanup\r\n/dict_count countdictstack def % Count objects on dict stack\r\n/op_count count 1 sub def      % Count objects on operand stack\r\nuserdict begin                 % Push userdict on dict stack\r\n/showpage { } def              % Redefine showpage, { } = null proc\r\n0 setgray 0 setlinecap         % Prepare graphics state\r\n1 setlinewidth 0 setlinejoin\r\n10 setmiterlimit [ ] 0 setdash newpath\r\n/languagelevel where           % If level not equal to 1 then\r\n{pop languagelevel             % set strokeadjust and\r\n1 ne                           % overprint to their defaults.\r\n{false setstrokeadjust false setoverprint\r\n} if\r\n} if\r\n} bd\r\n/EndEPSF { %def\r\ncount op_count sub {pop} repeat            % Clean up stacks\r\ncountdictstack dict_count sub {end} repeat\r\nb4_Inc_state restore\r\n} bd\r\n%%EndResource\r\n%FOPBeginFontDict\r\n%%IncludeResource: font Courier-Oblique\r\n%%IncludeResource: font Courier-BoldOblique\r\n%%IncludeResource: font Courier-Bold\r\n%%IncludeResource: font ZapfDingbats\r\n%%IncludeResource: font Symbol\r\n%%IncludeResource: font Helvetica\r\n%%IncludeResource: font Helvetica-Oblique\r\n%%IncludeResource: font Helvetica-Bold\r\n%%IncludeResource: font Helvetica-BoldOblique\r\n%%IncludeResource: font Times-Roman\r\n%%IncludeResource: font Times-Italic\r\n%%IncludeResource: font Times-Bold\r\n%%IncludeResource: font Times-BoldItalic\r\n%%IncludeResource: font Courier\r\n%FOPEndFontDict\r\n%%BeginResource: encoding WinAnsiEncoding\r\n/WinAnsiEncoding [\r\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /space /exclam /quotedbl\n/numbersign /dollar /percent /ampersand /quotesingle\n/parenleft /parenright /asterisk /plus /comma\n/hyphen /period /slash /zero /one\n/two /three /four /five /six\n/seven /eight /nine /colon /semicolon\n/less /equal /greater /question /at\n/A /B /C /D /E\n/F /G /H /I /J\n/K /L /M /N /O\n/P /Q /R /S /T\n/U /V /W /X /Y\n/Z /bracketleft /backslash /bracketright /asciicircum\n/underscore /quoteleft /a /b /c\n/d /e /f /g /h\n/i /j /k /l /m\n/n /o /p /q /r\n/s /t /u /v /w\n/x /y /z /braceleft /bar\n/braceright /asciitilde /bullet /Euro /bullet\n/quotesinglbase /florin /quotedblbase /ellipsis /dagger\n/daggerdbl /circumflex /perthousand /Scaron /guilsinglleft\n/OE /bullet /Zcaron /bullet /bullet\n/quoteleft /quoteright /quotedblleft /quotedblright /bullet\n/endash /emdash /asciitilde /trademark /scaron\n/guilsinglright /oe /bullet /zcaron /Ydieresis\n/space /exclamdown /cent /sterling /currency\n/yen /brokenbar /section /dieresis /copyright\n/ordfeminine /guillemotleft /logicalnot /sfthyphen /registered\n/macron /degree /plusminus /twosuperior /threesuperior\n/acute /mu /paragraph /middot /cedilla\n/onesuperior /ordmasculine /guillemotright /onequarter /onehalf\n/threequarters /questiondown /Agrave /Aacute /Acircumflex\n/Atilde /Adieresis /Aring /AE /Ccedilla\n/Egrave /Eacute /Ecircumflex /Edieresis /Igrave\n/Iacute /Icircumflex /Idieresis /Eth /Ntilde\n/Ograve /Oacute /Ocircumflex /Otilde /Odieresis\n/multiply /Oslash /Ugrave /Uacute /Ucircumflex\n/Udieresis /Yacute /Thorn /germandbls /agrave\n/aacute /acircumflex /atilde /adieresis /aring\n/ae /ccedilla /egrave /eacute /ecircumflex\n/edieresis /igrave /iacute /icircumflex /idieresis\n/eth /ntilde /ograve /oacute /ocircumflex\n/otilde /odieresis /divide /oslash /ugrave\n/uacute /ucircumflex /udieresis /yacute /thorn\n/ydieresis\n] def\r\n%%EndResource\r\n%FOPBeginFontReencode\r\n/Courier-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Oblique exch definefont pop\r\n/Courier-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-BoldOblique exch definefont pop\r\n/Courier-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Bold exch definefont pop\r\n/Helvetica findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica exch definefont pop\r\n/Helvetica-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Oblique exch definefont pop\r\n/Helvetica-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Bold exch definefont pop\r\n/Helvetica-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-BoldOblique exch definefont pop\r\n/Times-Roman findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Roman exch definefont pop\r\n/Times-Italic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Italic exch definefont pop\r\n/Times-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Bold exch definefont pop\r\n/Times-BoldItalic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-BoldItalic exch definefont pop\r\n/Courier findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier exch definefont pop\r\n%FOPEndFontReencode\r\n%%EndProlog\r\n%%Page: 1 1\r\n%%PageBoundingBox: 0 0 420 315\r\n%%BeginPageSetup\r\n[1 0 0 -1 0 315] CT\r\n%%EndPageSetup\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n162 699 M\n1014 699 L\n1014 63 L\n162 63 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 699 M\n1014 699 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 63 M\n1014 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 699 M\n162 690.48 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n334.121 699 M\n334.121 690.48 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n506.242 699 M\n506.242 690.48 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n678.364 699 M\n678.364 690.48 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n850.485 699 M\n850.485 690.48 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 63 M\n162 71.52 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n334.121 63 M\n334.121 71.52 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n506.242 63 M\n506.242 71.52 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n678.364 63 M\n678.364 71.52 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n850.485 63 M\n850.485 71.52 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 60.75 267.72501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-13.5 49 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 125.29546 267.72501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(20) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 189.84091 267.72501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(40) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 254.38637 267.72501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(60) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 318.93182 267.72501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(80) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.50016 291.22499] CT\r\n0.149 GC\r\nN\r\n-6.252 40.055 M\n-6.252 39.274 -6.096 38.586 QT\n-2.268 23.367 L\n-7.83 23.367 L\n-8.361 23.367 -8.361 22.664 QT\n-8.158 21.508 -7.674 21.508 QT\n-1.799 21.508 L\n0.326 12.852 L\n0.529 12.164 1.154 11.672 QT\n1.779 11.18 2.545 11.18 QT\n3.232 11.18 3.685 11.578 QT\n4.139 11.977 4.139 12.649 QT\n4.139 12.805 4.123 12.899 QT\n4.107 12.992 4.076 13.086 QT\n1.951 21.508 L\n7.42 21.508 L\n7.967 21.508 7.967 22.196 QT\n7.935 22.336 7.857 22.641 QT\n7.779 22.946 7.646 23.156 QT\n7.514 23.367 7.264 23.367 QT\n1.498 23.367 L\n-2.315 38.68 L\n-2.705 40.18 -2.705 41.274 QT\n-2.705 43.555 -1.143 43.555 QT\n1.185 43.555 2.982 41.367 QT\n4.779 39.18 5.732 36.555 QT\n5.935 36.258 6.154 36.258 QT\n6.795 36.258 L\n6.998 36.258 7.131 36.399 QT\n7.264 36.539 7.264 36.711 QT\n7.264 36.821 7.217 36.867 QT\n6.045 40.086 3.818 42.516 QT\n1.592 44.946 -1.283 44.946 QT\n-3.377 44.946 -4.815 43.578 QT\n-6.252 42.211 -6.252 40.055 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 699 M\n162 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 699 M\n1014 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 699 M\n170.52 699 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 487 M\n170.52 487 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 275 M\n170.52 275 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 63 M\n170.52 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 699 M\n1005.48 699 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 487 M\n1005.48 487 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 275 M\n1005.48 275 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 63 M\n1005.48 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 699 M\n166.26 699 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 635.182 M\n166.26 635.182 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 597.85 M\n166.26 597.85 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 571.363 M\n166.26 571.363 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 550.818 M\n166.26 550.818 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 534.032 M\n166.26 534.032 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 519.839 M\n166.26 519.839 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 507.545 M\n166.26 507.545 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 496.701 M\n166.26 496.701 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 487 M\n166.26 487 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 423.182 M\n166.26 423.182 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 385.85 M\n166.26 385.85 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 359.363 M\n166.26 359.363 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 338.818 M\n166.26 338.818 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 322.032 M\n166.26 322.032 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 307.839 M\n166.26 307.839 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 295.545 M\n166.26 295.545 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 284.701 M\n166.26 284.701 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 275 M\n166.26 275 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 211.182 M\n166.26 211.182 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 173.85 M\n166.26 173.85 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 147.363 M\n166.26 147.363 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 126.818 M\n166.26 126.818 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 110.032 M\n166.26 110.032 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 95.839 M\n166.26 95.839 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 83.545 M\n166.26 83.545 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 72.701 M\n166.26 72.701 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 63 M\n166.26 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 699 M\n1009.74 699 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 635.182 M\n1009.74 635.182 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 597.85 M\n1009.74 597.85 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 571.363 M\n1009.74 571.363 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 550.818 M\n1009.74 550.818 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 534.032 M\n1009.74 534.032 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 519.839 M\n1009.74 519.839 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 507.545 M\n1009.74 507.545 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 496.701 M\n1009.74 496.701 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 487 M\n1009.74 487 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 423.182 M\n1009.74 423.182 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 385.85 M\n1009.74 385.85 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 359.363 M\n1009.74 359.363 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 338.818 M\n1009.74 338.818 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 322.032 M\n1009.74 322.032 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 307.839 M\n1009.74 307.839 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 295.545 M\n1009.74 295.545 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 284.701 M\n1009.74 284.701 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 275 M\n1009.74 275 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 211.182 M\n1009.74 211.182 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 173.85 M\n1009.74 173.85 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 147.363 M\n1009.74 147.363 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 126.818 M\n1009.74 126.818 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 110.032 M\n1009.74 110.032 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 95.839 M\n1009.74 95.839 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 83.545 M\n1009.74 83.545 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 72.701 M\n1009.74 72.701 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 63 M\n1009.74 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 26.625 271.875] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(10) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 46.875 262.875] CT\r\n0.149 GC\r\n/Helvetica 38.4 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 26.625 192.375] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(10) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 46.875 183.375] CT\r\n0.149 GC\r\n/Helvetica 38.4 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 26.625 112.875] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(10) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 46.875 103.875] CT\r\n0.149 GC\r\n/Helvetica 38.4 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(2) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 26.625 33.375] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(10) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 46.875 24.375] CT\r\n0.149 GC\r\n/Helvetica 38.4 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(3) t \r\nGR\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n-61.918 -11.477 M\n-61.918 -12.774 -61.02 -13.719 QT\n-60.121 -14.664 -58.84 -14.664 QT\n-57.981 -14.664 -57.395 -14.133 QT\n-56.809 -13.602 -56.809 -12.743 QT\n-56.809 -11.743 -57.449 -10.922 QT\n-58.09 -10.102 -59.043 -9.852 QT\n-58.106 -9.508 -57.184 -9.508 QT\n-54.934 -9.508 -53.277 -11.594 QT\n-51.621 -13.68 -50.934 -16.258 QT\n-45.949 -36.196 L\n-45.59 -37.711 -45.59 -38.774 QT\n-45.59 -41.055 -47.168 -41.055 QT\n-49.496 -41.055 -51.238 -38.946 QT\n-52.981 -36.836 -54.074 -34.071 QT\n-54.168 -33.727 -54.481 -33.727 QT\n-55.106 -33.727 L\n-55.543 -33.727 -55.543 -34.227 QT\n-55.543 -34.383 L\n-54.356 -37.571 -52.16 -40 QT\n-49.965 -42.43 -47.059 -42.43 QT\n-44.856 -42.43 -43.449 -41.055 QT\n-42.043 -39.68 -42.043 -37.571 QT\n-42.043 -36.821 -42.199 -36.055 QT\n-47.215 -15.93 L\n-47.762 -13.774 -49.285 -11.993 QT\n-50.809 -10.211 -52.934 -9.172 QT\n-55.059 -8.133 -57.277 -8.133 QT\n-59.074 -8.133 -60.496 -8.993 QT\n-61.918 -9.852 -61.918 -11.477 QT\ncp\n-45.137 -51.118 M\n-45.137 -52.289 -44.238 -53.172 QT\n-43.34 -54.055 -42.199 -54.055 QT\n-41.293 -54.055 -40.707 -53.493 QT\n-40.121 -52.93 -40.121 -52.086 QT\n-40.121 -50.899 -41.067 -50 QT\n-42.012 -49.102 -43.152 -49.102 QT\n-44.012 -49.102 -44.574 -49.696 QT\n-45.137 -50.289 -45.137 -51.118 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n-37.175 -14.088 M\n-37.175 -14.635 -37.065 -15.12 QT\n-34.394 -25.745 L\n-38.284 -25.745 L\n-38.659 -25.745 -38.659 -26.229 QT\n-38.519 -27.041 -38.175 -27.041 QT\n-34.065 -27.041 L\n-32.581 -33.073 L\n-32.44 -33.557 -32.011 -33.901 QT\n-31.581 -34.245 -31.034 -34.245 QT\n-30.565 -34.245 -30.245 -33.963 QT\n-29.925 -33.682 -29.925 -33.213 QT\n-29.925 -33.104 -29.94 -33.041 QT\n-29.956 -32.979 -29.972 -32.916 QT\n-31.456 -27.041 L\n-27.644 -27.041 L\n-27.253 -27.041 -27.253 -26.557 QT\n-27.284 -26.463 -27.331 -26.245 QT\n-27.378 -26.026 -27.472 -25.885 QT\n-27.565 -25.745 -27.753 -25.745 QT\n-31.769 -25.745 L\n-34.425 -15.041 L\n-34.706 -13.995 -34.706 -13.245 QT\n-34.706 -11.651 -33.612 -11.651 QT\n-31.987 -11.651 -30.737 -13.174 QT\n-29.487 -14.698 -28.815 -16.526 QT\n-28.675 -16.745 -28.519 -16.745 QT\n-28.065 -16.745 L\n-27.925 -16.745 -27.839 -16.643 QT\n-27.753 -16.541 -27.753 -16.416 QT\n-27.753 -16.338 -27.784 -16.307 QT\n-28.597 -14.073 -30.151 -12.37 QT\n-31.706 -10.666 -33.706 -10.666 QT\n-35.175 -10.666 -36.175 -11.627 QT\n-37.175 -12.588 -37.175 -14.088 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n-22.453 -4.416 M\n-22.453 -4.588 -22.312 -4.729 QT\n-20.969 -6.01 -20.234 -7.69 QT\n-19.5 -9.37 -19.5 -11.229 QT\n-19.5 -11.682 L\n-20.094 -11.088 -20.969 -11.088 QT\n-21.828 -11.088 -22.422 -11.682 QT\n-23.016 -12.276 -23.016 -13.135 QT\n-23.016 -13.995 -22.422 -14.573 QT\n-21.828 -15.151 -20.969 -15.151 QT\n-19.656 -15.151 -19.094 -13.932 QT\n-18.531 -12.713 -18.531 -11.229 QT\n-18.531 -9.166 -19.359 -7.315 QT\n-20.187 -5.463 -21.687 -3.995 QT\n-21.828 -3.916 -21.922 -3.916 QT\n-22.094 -3.916 -22.273 -4.08 QT\n-22.453 -4.245 -22.453 -4.416 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n-6.64 -10.666 M\n-8.89 -10.666 -10.71 -11.838 QT\n-12.53 -13.01 -13.577 -14.948 QT\n-14.624 -16.885 -14.624 -19.073 QT\n-14.624 -21.26 -13.585 -23.268 QT\n-12.546 -25.276 -10.718 -26.471 QT\n-8.89 -27.666 -6.64 -27.666 QT\n-4.483 -27.666 -2.702 -26.823 QT\n-0.921 -25.979 -0.921 -24.041 QT\n-0.921 -23.323 -1.436 -22.791 QT\n-1.952 -22.26 -2.686 -22.26 QT\n-3.421 -22.26 -3.936 -22.791 QT\n-4.452 -23.323 -4.452 -24.041 QT\n-4.452 -24.698 -4.038 -25.174 QT\n-3.624 -25.651 -3.015 -25.776 QT\n-4.296 -26.588 -6.608 -26.588 QT\n-8.374 -26.588 -9.46 -25.416 QT\n-10.546 -24.245 -10.983 -22.51 QT\n-11.421 -20.776 -11.421 -19.073 QT\n-11.421 -17.291 -10.882 -15.62 QT\n-10.343 -13.948 -9.163 -12.854 QT\n-7.983 -11.76 -6.186 -11.76 QT\n-4.436 -11.76 -3.21 -12.83 QT\n-1.983 -13.901 -1.53 -15.635 QT\n-1.53 -15.854 -1.249 -15.854 QT\n-0.796 -15.854 L\n-0.686 -15.854 -0.593 -15.76 QT\n-0.499 -15.666 -0.499 -15.526 QT\n-0.499 -15.432 L\n-1.061 -13.245 -2.725 -11.955 QT\n-4.39 -10.666 -6.64 -10.666 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n9.818 -10.666 M\n7.6 -10.666 5.701 -11.799 QT\n3.803 -12.932 2.701 -14.83 QT\n1.6 -16.729 1.6 -18.963 QT\n1.6 -20.666 2.201 -22.237 QT\n2.803 -23.807 3.936 -25.041 QT\n5.068 -26.276 6.568 -26.971 QT\n8.068 -27.666 9.818 -27.666 QT\n12.1 -27.666 13.967 -26.471 QT\n15.834 -25.276 16.92 -23.26 QT\n18.006 -21.245 18.006 -18.963 QT\n18.006 -16.745 16.904 -14.838 QT\n15.803 -12.932 13.912 -11.799 QT\n12.022 -10.666 9.818 -10.666 QT\ncp\n9.818 -11.76 M\n12.787 -11.76 13.779 -13.909 QT\n14.772 -16.057 14.772 -19.385 QT\n14.772 -21.245 14.568 -22.463 QT\n14.365 -23.682 13.709 -24.682 QT\n13.287 -25.291 12.647 -25.752 QT\n12.006 -26.213 11.295 -26.455 QT\n10.584 -26.698 9.818 -26.698 QT\n8.662 -26.698 7.623 -26.174 QT\n6.584 -25.651 5.897 -24.682 QT\n5.209 -23.62 5.022 -22.37 QT\n4.834 -21.12 4.834 -19.385 QT\n4.834 -17.307 5.193 -15.651 QT\n5.553 -13.995 6.647 -12.877 QT\n7.74 -11.76 9.818 -11.76 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n20.158 -11.088 M\n20.158 -12.385 L\n21.408 -12.385 22.228 -12.588 QT\n23.048 -12.791 23.048 -13.557 QT\n23.048 -23.666 L\n23.048 -24.651 22.744 -25.096 QT\n22.439 -25.541 21.884 -25.643 QT\n21.33 -25.745 20.158 -25.745 QT\n20.158 -27.041 L\n25.517 -27.432 L\n25.517 -23.823 L\n26.252 -25.416 27.712 -26.424 QT\n29.173 -27.432 30.877 -27.432 QT\n33.455 -27.432 34.744 -26.205 QT\n36.033 -24.979 36.033 -22.448 QT\n36.033 -13.557 L\n36.033 -12.791 36.845 -12.588 QT\n37.658 -12.385 38.923 -12.385 QT\n38.923 -11.088 L\n30.455 -11.088 L\n30.455 -12.385 L\n31.72 -12.385 32.533 -12.588 QT\n33.345 -12.791 33.345 -13.557 QT\n33.345 -22.338 L\n33.345 -24.151 32.822 -25.315 QT\n32.298 -26.479 30.658 -26.479 QT\n28.517 -26.479 27.134 -24.76 QT\n25.752 -23.041 25.752 -20.87 QT\n25.752 -13.557 L\n25.752 -12.791 26.564 -12.588 QT\n27.377 -12.385 28.627 -12.385 QT\n28.627 -11.088 L\n20.158 -11.088 L\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n47.586 -11.088 M\n42.18 -24.682 L\n41.836 -25.354 41.125 -25.549 QT\n40.414 -25.745 39.258 -25.745 QT\n39.258 -27.041 L\n47.024 -27.041 L\n47.024 -25.745 L\n44.946 -25.745 44.946 -24.854 QT\n44.946 -24.713 44.993 -24.635 QT\n49.149 -14.198 L\n52.883 -23.62 L\n52.993 -23.916 52.993 -24.229 QT\n52.993 -24.932 52.461 -25.338 QT\n51.93 -25.745 51.196 -25.745 QT\n51.196 -27.041 L\n57.352 -27.041 L\n57.352 -25.745 L\n56.211 -25.745 55.352 -25.221 QT\n54.493 -24.698 54.024 -23.666 QT\n49.039 -11.088 L\n48.883 -10.666 48.43 -10.666 QT\n48.164 -10.666 L\n47.711 -10.666 47.586 -11.088 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n2.667 LW\r\nN\r\n162 392.202 M\n170.606 352.705 L\n179.212 402.637 L\n187.818 392.202 L\n196.424 438.145 L\n205.03 385.85 L\n213.636 418.69 L\n222.242 176.972 L\n230.848 399.026 L\n239.455 402.637 L\n248.061 449.669 L\n256.667 427.904 L\n265.273 418.69 L\n273.879 496.701 L\n282.485 478.225 L\n291.091 449.669 L\n299.697 550.818 L\n308.303 519.839 L\n316.909 534.032 L\n325.515 550.818 L\n334.121 550.818 L\n342.727 550.818 L\n351.333 571.363 L\n359.939 571.363 L\n368.545 571.363 L\n377.152 597.85 L\n385.758 597.85 L\n394.364 597.85 L\n402.97 597.85 L\n411.576 597.85 L\n420.182 597.85 L\n428.788 597.85 L\n437.394 597.85 L\n446 597.85 L\n454.606 597.85 L\n463.212 597.85 L\n471.818 597.85 L\n480.424 597.85 L\n489.03 597.85 L\n497.636 597.85 L\n506.242 597.85 L\n514.849 597.85 L\n523.455 597.85 L\n532.061 635.182 L\n540.667 635.182 L\n549.273 635.182 L\n557.879 635.182 L\n566.485 635.182 L\n575.091 635.182 L\n583.697 635.182 L\n592.303 635.182 L\n600.909 635.182 L\n609.515 635.182 L\n618.121 635.182 L\n626.727 635.182 L\n635.333 635.182 L\n643.939 635.182 L\n652.545 635.182 L\n661.151 635.182 L\n669.758 635.182 L\n678.364 635.182 L\n686.97 635.182 L\n695.576 635.182 L\n704.182 635.182 L\n712.788 635.182 L\n721.394 635.182 L\n730 635.182 L\n738.606 635.182 L\n747.212 635.182 L\n755.818 635.182 L\n764.424 635.182 L\n773.03 635.182 L\n781.636 635.182 L\n790.242 635.182 L\n798.848 635.182 L\n807.455 635.182 L\n816.061 635.182 L\n824.667 635.182 L\n833.273 699 L\n841.879 635.182 L\n850.485 699 L\n859.091 635.182 L\n867.697 699 L\n876.303 635.182 L\n884.909 699 L\n893.515 699 L\n902.121 635.182 L\n910.727 699 L\n919.333 699 L\n927.939 699 L\n936.545 699 L\n945.151 635.182 L\n953.758 699 L\n962.364 699 L\n970.97 699 L\n979.576 699 L\n988.182 699 L\n996.788 699 L\n1005.394 699 L\n1014 699 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 60.75 147.07593] CT\r\nN\r\n0 -4 M\n2.209 -4 4 -2.209 4 0 C\n4 0 L\n4 2.209 2.209 4 0 4 C\n-2.209 4 -4 2.209 -4 0 C\n-4 -2.209 -2.209 -4 0 -4 C\ncp\n0 -6.667 M\n-3.682 -6.667 -6.667 -3.682 -6.667 0 C\n-6.667 3.682 -3.682 6.667 0 6.667 C\n3.682 6.667 6.667 3.682 6.667 0 C\n6.667 0 L\n6.667 -3.682 3.682 -6.667 0 -6.667 C\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 63.97727 132.26426] CT\r\nN\r\n/f-1792389198{0 -4 M\n2.209 -4 4 -2.209 4 0 C\n4 0 L\n4 2.209 2.209 4 0 4 C\n-2.209 4 -4 2.209 -4 0 C\n-4 -2.209 -2.209 -4 0 -4 C\ncp\n0 -6.667 M\n-3.682 -6.667 -6.667 -3.682 -6.667 0 C\n-6.667 3.682 -3.682 6.667 0 6.667 C\n3.682 6.667 6.667 3.682 6.667 0 C\n6.667 0 L\n6.667 -3.682 3.682 -6.667 0 -6.667 C\ncp}def\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 67.20455 150.98877] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 70.43182 147.07593] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 73.65909 164.30431] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 76.88636 144.69386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 80.11364 157.00857] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 83.34091 66.36436] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 86.56818 149.63462] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 89.79545 150.98877] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 93.02273 168.62574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 96.25 160.46409] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 99.47728 157.00857] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 102.70454 186.26272] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 105.93181 179.33429] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 109.15909 168.62574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 112.38636 206.55688] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 115.61364 194.93971] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 118.84091 200.26197] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 122.06819 206.55688] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 125.29546 206.55688] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 128.52272 206.55688] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 131.75 214.26123] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 134.97727 214.26123] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 138.20455 214.26123] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 141.43182 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 144.65909 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 147.88637 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 151.11364 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 154.3409 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 157.56818 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 160.79545 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 164.02273 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 167.25 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 170.47727 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 173.70455 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 176.93182 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 180.15908 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 183.38636 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 186.61364 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 189.84091 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 193.06819 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 196.29545 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 199.52273 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 202.75001 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 205.97729 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 209.20454 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 212.43182 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 215.6591 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 218.88636 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.11364 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 225.3409 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 228.56818 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 231.79546 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 235.02274 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 238.25002 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 241.47727 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 244.70455 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 247.93181 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 251.15909 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 254.38637 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 257.61365 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 260.8409 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 264.06818 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 267.29546 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 270.52272 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 273.75 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 276.97726 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 280.20454 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 283.43182 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.6591 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 289.88638 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 293.11363 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 296.34089 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 299.56817 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 302.79545 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 306.02273 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 309.25001 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 312.47729 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 315.70454 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 318.93182 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 322.15908 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 325.38636 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 328.61364 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 331.84092 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 335.06818 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 338.29546 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 341.52274 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 344.74999 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 347.97727 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 351.20455 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 354.43181 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 357.65909 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 360.88637 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 364.11365 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 367.3409 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 370.56818 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 373.79544 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 377.02272 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 380.25 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\n%%Trailer\r\n%%Pages: 1\r\n%%EOF\r\n"
  },
  {
    "path": "matlab/acc2023/closedloop_performance/figures/J-converge-4.eps",
    "content": "%!PS-Adobe-3.0 EPSF-3.0\r\n%%Creator: (MATLAB, The Mathworks, Inc. Version 9.10.0.1649659 \\(R2021a\\) Update 1. Operating System: Windows 10)\r\n%%Title: figures/J-converge-4.eps\r\n%%CreationDate: 2023-01-31T03:11:58\r\n%%Pages: (atend)\r\n%%BoundingBox:     3     6   383   301\r\n%%LanguageLevel: 3\r\n%%EndComments\r\n%%BeginProlog\r\n%%BeginResource: procset (Apache XML Graphics Std ProcSet) 1.2 0\r\n%%Version: 1.2 0\r\n%%Copyright: (Copyright 2001-2003,2010 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/bd{bind def}bind def\r\n/ld{load def}bd\r\n/GR/grestore ld\r\n/GS/gsave ld\r\n/RM/rmoveto ld\r\n/C/curveto ld\r\n/t/show ld\r\n/L/lineto ld\r\n/ML/setmiterlimit ld\r\n/CT/concat ld\r\n/f/fill ld\r\n/N/newpath ld\r\n/S/stroke ld\r\n/CC/setcmykcolor ld\r\n/A/ashow ld\r\n/cp/closepath ld\r\n/RC/setrgbcolor ld\r\n/LJ/setlinejoin ld\r\n/GC/setgray ld\r\n/LW/setlinewidth ld\r\n/M/moveto ld\r\n/re {4 2 roll M\r\n1 index 0 rlineto\r\n0 exch rlineto\r\nneg 0 rlineto\r\ncp } bd\r\n/_ctm matrix def\r\n/_tm matrix def\r\n/BT { _ctm currentmatrix pop matrix _tm copy pop 0 0 moveto } bd\r\n/ET { _ctm setmatrix } bd\r\n/iTm { _ctm setmatrix _tm concat } bd\r\n/Tm { _tm astore pop iTm 0 0 moveto } bd\r\n/ux 0.0 def\r\n/uy 0.0 def\r\n/F {\r\n  /Tp exch def\r\n  /Tf exch def\r\n  Tf findfont Tp scalefont setfont\r\n  /cf Tf def  /cs Tp def\r\n} bd\r\n/ULS {currentpoint /uy exch def /ux exch def} bd\r\n/ULE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add moveto  Tcx uy To add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/OLE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs add moveto Tcx uy To add cs add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/SOE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs 10 mul 26 idiv add moveto Tcx uy To add cs 10 mul 26 idiv add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/QT {\r\n/Y22 exch store\r\n/X22 exch store\r\n/Y21 exch store\r\n/X21 exch store\r\ncurrentpoint\r\n/Y21 load 2 mul add 3 div exch\r\n/X21 load 2 mul add 3 div exch\r\n/X21 load 2 mul /X22 load add 3 div\r\n/Y21 load 2 mul /Y22 load add 3 div\r\n/X22 load /Y22 load curveto\r\n} bd\r\n/SSPD {\r\ndup length /d exch dict def\r\n{\r\n/v exch def\r\n/k exch def\r\ncurrentpagedevice k known {\r\n/cpdv currentpagedevice k get def\r\nv cpdv ne {\r\n/upd false def\r\n/nullv v type /nulltype eq def\r\n/nullcpdv cpdv type /nulltype eq def\r\nnullv nullcpdv or\r\n{\r\n/upd true def\r\n} {\r\n/sametype v type cpdv type eq def\r\nsametype {\r\nv type /arraytype eq {\r\n/vlen v length def\r\n/cpdvlen cpdv length def\r\nvlen cpdvlen eq {\r\n0 1 vlen 1 sub {\r\n/i exch def\r\n/obj v i get def\r\n/cpdobj cpdv i get def\r\nobj cpdobj ne {\r\n/upd true def\r\nexit\r\n} if\r\n} for\r\n} {\r\n/upd true def\r\n} ifelse\r\n} {\r\nv type /dicttype eq {\r\nv {\r\n/dv exch def\r\n/dk exch def\r\n/cpddv cpdv dk get def\r\ndv cpddv ne {\r\n/upd true def\r\nexit\r\n} if\r\n} forall\r\n} {\r\n/upd true def\r\n} ifelse\r\n} ifelse\r\n} if\r\n} ifelse\r\nupd true eq {\r\nd k v put\r\n} if\r\n} if\r\n} if\r\n} forall\r\nd length 0 gt {\r\nd setpagedevice\r\n} if\r\n} bd\r\n/RE { % /NewFontName [NewEncodingArray] /FontName RE -\r\n  findfont dup length dict begin\r\n  {\r\n    1 index /FID ne\r\n    {def} {pop pop} ifelse\r\n  } forall\r\n  /Encoding exch def\r\n  /FontName 1 index def\r\n  currentdict definefont pop\r\n  end\r\n} bind def\r\n%%EndResource\r\n%%BeginResource: procset (Apache XML Graphics EPS ProcSet) 1.0 0\r\n%%Version: 1.0 0\r\n%%Copyright: (Copyright 2002-2003 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/BeginEPSF { %def\r\n/b4_Inc_state save def         % Save state for cleanup\r\n/dict_count countdictstack def % Count objects on dict stack\r\n/op_count count 1 sub def      % Count objects on operand stack\r\nuserdict begin                 % Push userdict on dict stack\r\n/showpage { } def              % Redefine showpage, { } = null proc\r\n0 setgray 0 setlinecap         % Prepare graphics state\r\n1 setlinewidth 0 setlinejoin\r\n10 setmiterlimit [ ] 0 setdash newpath\r\n/languagelevel where           % If level not equal to 1 then\r\n{pop languagelevel             % set strokeadjust and\r\n1 ne                           % overprint to their defaults.\r\n{false setstrokeadjust false setoverprint\r\n} if\r\n} if\r\n} bd\r\n/EndEPSF { %def\r\ncount op_count sub {pop} repeat            % Clean up stacks\r\ncountdictstack dict_count sub {end} repeat\r\nb4_Inc_state restore\r\n} bd\r\n%%EndResource\r\n%FOPBeginFontDict\r\n%%IncludeResource: font Courier-Oblique\r\n%%IncludeResource: font Courier-BoldOblique\r\n%%IncludeResource: font Courier-Bold\r\n%%IncludeResource: font ZapfDingbats\r\n%%IncludeResource: font Symbol\r\n%%IncludeResource: font Helvetica\r\n%%IncludeResource: font Helvetica-Oblique\r\n%%IncludeResource: font Helvetica-Bold\r\n%%IncludeResource: font Helvetica-BoldOblique\r\n%%IncludeResource: font Times-Roman\r\n%%IncludeResource: font Times-Italic\r\n%%IncludeResource: font Times-Bold\r\n%%IncludeResource: font Times-BoldItalic\r\n%%IncludeResource: font Courier\r\n%FOPEndFontDict\r\n%%BeginResource: encoding WinAnsiEncoding\r\n/WinAnsiEncoding [\r\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /space /exclam /quotedbl\n/numbersign /dollar /percent /ampersand /quotesingle\n/parenleft /parenright /asterisk /plus /comma\n/hyphen /period /slash /zero /one\n/two /three /four /five /six\n/seven /eight /nine /colon /semicolon\n/less /equal /greater /question /at\n/A /B /C /D /E\n/F /G /H /I /J\n/K /L /M /N /O\n/P /Q /R /S /T\n/U /V /W /X /Y\n/Z /bracketleft /backslash /bracketright /asciicircum\n/underscore /quoteleft /a /b /c\n/d /e /f /g /h\n/i /j /k /l /m\n/n /o /p /q /r\n/s /t /u /v /w\n/x /y /z /braceleft /bar\n/braceright /asciitilde /bullet /Euro /bullet\n/quotesinglbase /florin /quotedblbase /ellipsis /dagger\n/daggerdbl /circumflex /perthousand /Scaron /guilsinglleft\n/OE /bullet /Zcaron /bullet /bullet\n/quoteleft /quoteright /quotedblleft /quotedblright /bullet\n/endash /emdash /asciitilde /trademark /scaron\n/guilsinglright /oe /bullet /zcaron /Ydieresis\n/space /exclamdown /cent /sterling /currency\n/yen /brokenbar /section /dieresis /copyright\n/ordfeminine /guillemotleft /logicalnot /sfthyphen /registered\n/macron /degree /plusminus /twosuperior /threesuperior\n/acute /mu /paragraph /middot /cedilla\n/onesuperior /ordmasculine /guillemotright /onequarter /onehalf\n/threequarters /questiondown /Agrave /Aacute /Acircumflex\n/Atilde /Adieresis /Aring /AE /Ccedilla\n/Egrave /Eacute /Ecircumflex /Edieresis /Igrave\n/Iacute /Icircumflex /Idieresis /Eth /Ntilde\n/Ograve /Oacute /Ocircumflex /Otilde /Odieresis\n/multiply /Oslash /Ugrave /Uacute /Ucircumflex\n/Udieresis /Yacute /Thorn /germandbls /agrave\n/aacute /acircumflex /atilde /adieresis /aring\n/ae /ccedilla /egrave /eacute /ecircumflex\n/edieresis /igrave /iacute /icircumflex /idieresis\n/eth /ntilde /ograve /oacute /ocircumflex\n/otilde /odieresis /divide /oslash /ugrave\n/uacute /ucircumflex /udieresis /yacute /thorn\n/ydieresis\n] def\r\n%%EndResource\r\n%FOPBeginFontReencode\r\n/Courier-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Oblique exch definefont pop\r\n/Courier-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-BoldOblique exch definefont pop\r\n/Courier-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Bold exch definefont pop\r\n/Helvetica findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica exch definefont pop\r\n/Helvetica-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Oblique exch definefont pop\r\n/Helvetica-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Bold exch definefont pop\r\n/Helvetica-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-BoldOblique exch definefont pop\r\n/Times-Roman findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Roman exch definefont pop\r\n/Times-Italic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Italic exch definefont pop\r\n/Times-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Bold exch definefont pop\r\n/Times-BoldItalic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-BoldItalic exch definefont pop\r\n/Courier findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier exch definefont pop\r\n%FOPEndFontReencode\r\n%%EndProlog\r\n%%Page: 1 1\r\n%%PageBoundingBox: 0 0 420 315\r\n%%BeginPageSetup\r\n[1 0 0 -1 0 315] CT\r\n%%EndPageSetup\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n162 699 M\n1014 699 L\n1014 63 L\n162 63 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 699 M\n1014 699 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 63 M\n1014 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 699 M\n162 690.48 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n334.121 699 M\n334.121 690.48 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n506.242 699 M\n506.242 690.48 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n678.364 699 M\n678.364 690.48 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n850.485 699 M\n850.485 690.48 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 63 M\n162 71.52 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n334.121 63 M\n334.121 71.52 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n506.242 63 M\n506.242 71.52 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n678.364 63 M\n678.364 71.52 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n850.485 63 M\n850.485 71.52 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 60.75 267.72501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-13.5 49 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 125.29546 267.72501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(20) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 189.84091 267.72501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(40) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 254.38637 267.72501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(60) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 318.93182 267.72501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(80) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.50016 291.22499] CT\r\n0.149 GC\r\nN\r\n-6.252 40.055 M\n-6.252 39.274 -6.096 38.586 QT\n-2.268 23.367 L\n-7.83 23.367 L\n-8.361 23.367 -8.361 22.664 QT\n-8.158 21.508 -7.674 21.508 QT\n-1.799 21.508 L\n0.326 12.852 L\n0.529 12.164 1.154 11.672 QT\n1.779 11.18 2.545 11.18 QT\n3.232 11.18 3.685 11.578 QT\n4.139 11.977 4.139 12.649 QT\n4.139 12.805 4.123 12.899 QT\n4.107 12.992 4.076 13.086 QT\n1.951 21.508 L\n7.42 21.508 L\n7.967 21.508 7.967 22.196 QT\n7.935 22.336 7.857 22.641 QT\n7.779 22.946 7.646 23.156 QT\n7.514 23.367 7.264 23.367 QT\n1.498 23.367 L\n-2.315 38.68 L\n-2.705 40.18 -2.705 41.274 QT\n-2.705 43.555 -1.143 43.555 QT\n1.185 43.555 2.982 41.367 QT\n4.779 39.18 5.732 36.555 QT\n5.935 36.258 6.154 36.258 QT\n6.795 36.258 L\n6.998 36.258 7.131 36.399 QT\n7.264 36.539 7.264 36.711 QT\n7.264 36.821 7.217 36.867 QT\n6.045 40.086 3.818 42.516 QT\n1.592 44.946 -1.283 44.946 QT\n-3.377 44.946 -4.815 43.578 QT\n-6.252 42.211 -6.252 40.055 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 699 M\n162 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 699 M\n1014 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 699 M\n170.52 699 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 487 M\n170.52 487 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 275 M\n170.52 275 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 63 M\n170.52 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 699 M\n1005.48 699 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 487 M\n1005.48 487 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 275 M\n1005.48 275 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 63 M\n1005.48 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 699 M\n166.26 699 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 635.182 M\n166.26 635.182 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 597.85 M\n166.26 597.85 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 571.363 M\n166.26 571.363 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 550.818 M\n166.26 550.818 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 534.032 M\n166.26 534.032 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 519.839 M\n166.26 519.839 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 507.545 M\n166.26 507.545 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 496.701 M\n166.26 496.701 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 487 M\n166.26 487 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 423.182 M\n166.26 423.182 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 385.85 M\n166.26 385.85 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 359.363 M\n166.26 359.363 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 338.818 M\n166.26 338.818 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 322.032 M\n166.26 322.032 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 307.839 M\n166.26 307.839 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 295.545 M\n166.26 295.545 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 284.701 M\n166.26 284.701 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 275 M\n166.26 275 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 211.182 M\n166.26 211.182 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 173.85 M\n166.26 173.85 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 147.363 M\n166.26 147.363 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 126.818 M\n166.26 126.818 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 110.032 M\n166.26 110.032 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 95.839 M\n166.26 95.839 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 83.545 M\n166.26 83.545 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 72.701 M\n166.26 72.701 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n162 63 M\n166.26 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 699 M\n1009.74 699 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 635.182 M\n1009.74 635.182 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 597.85 M\n1009.74 597.85 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 571.363 M\n1009.74 571.363 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 550.818 M\n1009.74 550.818 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 534.032 M\n1009.74 534.032 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 519.839 M\n1009.74 519.839 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 507.545 M\n1009.74 507.545 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 496.701 M\n1009.74 496.701 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 487 M\n1009.74 487 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 423.182 M\n1009.74 423.182 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 385.85 M\n1009.74 385.85 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 359.363 M\n1009.74 359.363 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 338.818 M\n1009.74 338.818 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 322.032 M\n1009.74 322.032 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 307.839 M\n1009.74 307.839 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 295.545 M\n1009.74 295.545 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 284.701 M\n1009.74 284.701 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 275 M\n1009.74 275 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 211.182 M\n1009.74 211.182 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 173.85 M\n1009.74 173.85 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 147.363 M\n1009.74 147.363 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 126.818 M\n1009.74 126.818 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 110.032 M\n1009.74 110.032 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 95.839 M\n1009.74 95.839 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 83.545 M\n1009.74 83.545 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 72.701 M\n1009.74 72.701 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 63 M\n1009.74 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 26.625 271.875] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(10) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 46.875 262.875] CT\r\n0.149 GC\r\n/Helvetica 38.4 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 26.625 192.375] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(10) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 46.875 183.375] CT\r\n0.149 GC\r\n/Helvetica 38.4 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 26.625 112.875] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(10) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 46.875 103.875] CT\r\n0.149 GC\r\n/Helvetica 38.4 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(2) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 26.625 33.375] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(10) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 46.875 24.375] CT\r\n0.149 GC\r\n/Helvetica 38.4 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n0 0 moveto \r\n1 -1 scale\r\n(3) t \r\nGR\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n-61.918 -11.477 M\n-61.918 -12.774 -61.02 -13.719 QT\n-60.121 -14.664 -58.84 -14.664 QT\n-57.981 -14.664 -57.395 -14.133 QT\n-56.809 -13.602 -56.809 -12.743 QT\n-56.809 -11.743 -57.449 -10.922 QT\n-58.09 -10.102 -59.043 -9.852 QT\n-58.106 -9.508 -57.184 -9.508 QT\n-54.934 -9.508 -53.277 -11.594 QT\n-51.621 -13.68 -50.934 -16.258 QT\n-45.949 -36.196 L\n-45.59 -37.711 -45.59 -38.774 QT\n-45.59 -41.055 -47.168 -41.055 QT\n-49.496 -41.055 -51.238 -38.946 QT\n-52.981 -36.836 -54.074 -34.071 QT\n-54.168 -33.727 -54.481 -33.727 QT\n-55.106 -33.727 L\n-55.543 -33.727 -55.543 -34.227 QT\n-55.543 -34.383 L\n-54.356 -37.571 -52.16 -40 QT\n-49.965 -42.43 -47.059 -42.43 QT\n-44.856 -42.43 -43.449 -41.055 QT\n-42.043 -39.68 -42.043 -37.571 QT\n-42.043 -36.821 -42.199 -36.055 QT\n-47.215 -15.93 L\n-47.762 -13.774 -49.285 -11.993 QT\n-50.809 -10.211 -52.934 -9.172 QT\n-55.059 -8.133 -57.277 -8.133 QT\n-59.074 -8.133 -60.496 -8.993 QT\n-61.918 -9.852 -61.918 -11.477 QT\ncp\n-45.137 -51.118 M\n-45.137 -52.289 -44.238 -53.172 QT\n-43.34 -54.055 -42.199 -54.055 QT\n-41.293 -54.055 -40.707 -53.493 QT\n-40.121 -52.93 -40.121 -52.086 QT\n-40.121 -50.899 -41.067 -50 QT\n-42.012 -49.102 -43.152 -49.102 QT\n-44.012 -49.102 -44.574 -49.696 QT\n-45.137 -50.289 -45.137 -51.118 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n-37.175 -14.088 M\n-37.175 -14.635 -37.065 -15.12 QT\n-34.394 -25.745 L\n-38.284 -25.745 L\n-38.659 -25.745 -38.659 -26.229 QT\n-38.519 -27.041 -38.175 -27.041 QT\n-34.065 -27.041 L\n-32.581 -33.073 L\n-32.44 -33.557 -32.011 -33.901 QT\n-31.581 -34.245 -31.034 -34.245 QT\n-30.565 -34.245 -30.245 -33.963 QT\n-29.925 -33.682 -29.925 -33.213 QT\n-29.925 -33.104 -29.94 -33.041 QT\n-29.956 -32.979 -29.972 -32.916 QT\n-31.456 -27.041 L\n-27.644 -27.041 L\n-27.253 -27.041 -27.253 -26.557 QT\n-27.284 -26.463 -27.331 -26.245 QT\n-27.378 -26.026 -27.472 -25.885 QT\n-27.565 -25.745 -27.753 -25.745 QT\n-31.769 -25.745 L\n-34.425 -15.041 L\n-34.706 -13.995 -34.706 -13.245 QT\n-34.706 -11.651 -33.612 -11.651 QT\n-31.987 -11.651 -30.737 -13.174 QT\n-29.487 -14.698 -28.815 -16.526 QT\n-28.675 -16.745 -28.519 -16.745 QT\n-28.065 -16.745 L\n-27.925 -16.745 -27.839 -16.643 QT\n-27.753 -16.541 -27.753 -16.416 QT\n-27.753 -16.338 -27.784 -16.307 QT\n-28.597 -14.073 -30.151 -12.37 QT\n-31.706 -10.666 -33.706 -10.666 QT\n-35.175 -10.666 -36.175 -11.627 QT\n-37.175 -12.588 -37.175 -14.088 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n-22.453 -4.416 M\n-22.453 -4.588 -22.312 -4.729 QT\n-20.969 -6.01 -20.234 -7.69 QT\n-19.5 -9.37 -19.5 -11.229 QT\n-19.5 -11.682 L\n-20.094 -11.088 -20.969 -11.088 QT\n-21.828 -11.088 -22.422 -11.682 QT\n-23.016 -12.276 -23.016 -13.135 QT\n-23.016 -13.995 -22.422 -14.573 QT\n-21.828 -15.151 -20.969 -15.151 QT\n-19.656 -15.151 -19.094 -13.932 QT\n-18.531 -12.713 -18.531 -11.229 QT\n-18.531 -9.166 -19.359 -7.315 QT\n-20.187 -5.463 -21.687 -3.995 QT\n-21.828 -3.916 -21.922 -3.916 QT\n-22.094 -3.916 -22.273 -4.08 QT\n-22.453 -4.245 -22.453 -4.416 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n-6.64 -10.666 M\n-8.89 -10.666 -10.71 -11.838 QT\n-12.53 -13.01 -13.577 -14.948 QT\n-14.624 -16.885 -14.624 -19.073 QT\n-14.624 -21.26 -13.585 -23.268 QT\n-12.546 -25.276 -10.718 -26.471 QT\n-8.89 -27.666 -6.64 -27.666 QT\n-4.483 -27.666 -2.702 -26.823 QT\n-0.921 -25.979 -0.921 -24.041 QT\n-0.921 -23.323 -1.436 -22.791 QT\n-1.952 -22.26 -2.686 -22.26 QT\n-3.421 -22.26 -3.936 -22.791 QT\n-4.452 -23.323 -4.452 -24.041 QT\n-4.452 -24.698 -4.038 -25.174 QT\n-3.624 -25.651 -3.015 -25.776 QT\n-4.296 -26.588 -6.608 -26.588 QT\n-8.374 -26.588 -9.46 -25.416 QT\n-10.546 -24.245 -10.983 -22.51 QT\n-11.421 -20.776 -11.421 -19.073 QT\n-11.421 -17.291 -10.882 -15.62 QT\n-10.343 -13.948 -9.163 -12.854 QT\n-7.983 -11.76 -6.186 -11.76 QT\n-4.436 -11.76 -3.21 -12.83 QT\n-1.983 -13.901 -1.53 -15.635 QT\n-1.53 -15.854 -1.249 -15.854 QT\n-0.796 -15.854 L\n-0.686 -15.854 -0.593 -15.76 QT\n-0.499 -15.666 -0.499 -15.526 QT\n-0.499 -15.432 L\n-1.061 -13.245 -2.725 -11.955 QT\n-4.39 -10.666 -6.64 -10.666 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n9.818 -10.666 M\n7.6 -10.666 5.701 -11.799 QT\n3.803 -12.932 2.701 -14.83 QT\n1.6 -16.729 1.6 -18.963 QT\n1.6 -20.666 2.201 -22.237 QT\n2.803 -23.807 3.936 -25.041 QT\n5.068 -26.276 6.568 -26.971 QT\n8.068 -27.666 9.818 -27.666 QT\n12.1 -27.666 13.967 -26.471 QT\n15.834 -25.276 16.92 -23.26 QT\n18.006 -21.245 18.006 -18.963 QT\n18.006 -16.745 16.904 -14.838 QT\n15.803 -12.932 13.912 -11.799 QT\n12.022 -10.666 9.818 -10.666 QT\ncp\n9.818 -11.76 M\n12.787 -11.76 13.779 -13.909 QT\n14.772 -16.057 14.772 -19.385 QT\n14.772 -21.245 14.568 -22.463 QT\n14.365 -23.682 13.709 -24.682 QT\n13.287 -25.291 12.647 -25.752 QT\n12.006 -26.213 11.295 -26.455 QT\n10.584 -26.698 9.818 -26.698 QT\n8.662 -26.698 7.623 -26.174 QT\n6.584 -25.651 5.897 -24.682 QT\n5.209 -23.62 5.022 -22.37 QT\n4.834 -21.12 4.834 -19.385 QT\n4.834 -17.307 5.193 -15.651 QT\n5.553 -13.995 6.647 -12.877 QT\n7.74 -11.76 9.818 -11.76 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n20.158 -11.088 M\n20.158 -12.385 L\n21.408 -12.385 22.228 -12.588 QT\n23.048 -12.791 23.048 -13.557 QT\n23.048 -23.666 L\n23.048 -24.651 22.744 -25.096 QT\n22.439 -25.541 21.884 -25.643 QT\n21.33 -25.745 20.158 -25.745 QT\n20.158 -27.041 L\n25.517 -27.432 L\n25.517 -23.823 L\n26.252 -25.416 27.712 -26.424 QT\n29.173 -27.432 30.877 -27.432 QT\n33.455 -27.432 34.744 -26.205 QT\n36.033 -24.979 36.033 -22.448 QT\n36.033 -13.557 L\n36.033 -12.791 36.845 -12.588 QT\n37.658 -12.385 38.923 -12.385 QT\n38.923 -11.088 L\n30.455 -11.088 L\n30.455 -12.385 L\n31.72 -12.385 32.533 -12.588 QT\n33.345 -12.791 33.345 -13.557 QT\n33.345 -22.338 L\n33.345 -24.151 32.822 -25.315 QT\n32.298 -26.479 30.658 -26.479 QT\n28.517 -26.479 27.134 -24.76 QT\n25.752 -23.041 25.752 -20.87 QT\n25.752 -13.557 L\n25.752 -12.791 26.564 -12.588 QT\n27.377 -12.385 28.627 -12.385 QT\n28.627 -11.088 L\n20.158 -11.088 L\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.65 142.87489] CT\r\n0.149 GC\r\nN\r\n47.586 -11.088 M\n42.18 -24.682 L\n41.836 -25.354 41.125 -25.549 QT\n40.414 -25.745 39.258 -25.745 QT\n39.258 -27.041 L\n47.024 -27.041 L\n47.024 -25.745 L\n44.946 -25.745 44.946 -24.854 QT\n44.946 -24.713 44.993 -24.635 QT\n49.149 -14.198 L\n52.883 -23.62 L\n52.993 -23.916 52.993 -24.229 QT\n52.993 -24.932 52.461 -25.338 QT\n51.93 -25.745 51.196 -25.745 QT\n51.196 -27.041 L\n57.352 -27.041 L\n57.352 -25.745 L\n56.211 -25.745 55.352 -25.221 QT\n54.493 -24.698 54.024 -23.666 QT\n49.039 -11.088 L\n48.883 -10.666 48.43 -10.666 QT\n48.164 -10.666 L\n47.711 -10.666 47.586 -11.088 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n2.667 LW\r\nN\r\n162 402.637 M\n170.606 248.054 L\n179.212 63 L\n187.818 342.577 L\n196.424 418.69 L\n205.03 369.064 L\n213.636 406.395 L\n222.242 406.395 L\n230.848 395.551 L\n239.455 379.908 L\n248.061 449.669 L\n256.667 449.669 L\n265.273 456.021 L\n273.879 443.727 L\n282.485 438.145 L\n291.091 438.145 L\n299.697 507.545 L\n308.303 507.545 L\n316.909 519.839 L\n325.515 534.032 L\n334.121 550.818 L\n342.727 550.818 L\n351.333 571.363 L\n359.939 571.363 L\n368.545 571.363 L\n377.152 571.363 L\n385.758 597.85 L\n394.364 597.85 L\n402.97 597.85 L\n411.576 597.85 L\n420.182 597.85 L\n428.788 597.85 L\n437.394 597.85 L\n446 597.85 L\n454.606 597.85 L\n463.212 597.85 L\n471.818 597.85 L\n480.424 597.85 L\n489.03 597.85 L\n497.636 597.85 L\n506.242 597.85 L\n514.849 597.85 L\n523.455 597.85 L\n532.061 597.85 L\n540.667 635.182 L\n549.273 635.182 L\n557.879 635.182 L\n566.485 635.182 L\n575.091 635.182 L\n583.697 635.182 L\n592.303 635.182 L\n600.909 635.182 L\n609.515 635.182 L\n618.121 635.182 L\n626.727 635.182 L\n635.333 635.182 L\n643.939 635.182 L\n652.545 635.182 L\n661.151 635.182 L\n669.758 635.182 L\n678.364 635.182 L\n686.97 635.182 L\n695.576 635.182 L\n704.182 635.182 L\n712.788 635.182 L\n721.394 635.182 L\n730 635.182 L\n738.606 635.182 L\n747.212 635.182 L\n755.818 635.182 L\n764.424 635.182 L\n773.03 635.182 L\n781.636 635.182 L\n790.242 635.182 L\n798.848 635.182 L\n807.455 635.182 L\n816.061 635.182 L\n824.667 635.182 L\n833.273 635.182 L\n841.879 699 L\n850.485 635.182 L\n859.091 699 L\n867.697 635.182 L\n876.303 699 L\n884.909 635.182 L\n893.515 699 L\n902.121 699 L\n910.727 635.182 L\n919.333 699 L\n927.939 699 L\n936.545 699 L\n945.151 635.182 L\n953.758 699 L\n962.364 699 L\n970.97 699 L\n979.576 699 L\n988.182 699 L\n996.788 699 L\n1005.394 699 L\n1014 699 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 60.75 150.98877] CT\r\nN\r\n0 -4 M\n2.209 -4 4 -2.209 4 0 C\n4 0 L\n4 2.209 2.209 4 0 4 C\n-2.209 4 -4 2.209 -4 0 C\n-4 -2.209 -2.209 -4 0 -4 C\ncp\n0 -6.667 M\n-3.682 -6.667 -6.667 -3.682 -6.667 0 C\n-6.667 3.682 -3.682 6.667 0 6.667 C\n3.682 6.667 6.667 3.682 6.667 0 C\n6.667 0 L\n6.667 -3.682 3.682 -6.667 0 -6.667 C\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 63.97727 93.02017] CT\r\nN\r\n/f-1792389198{0 -4 M\n2.209 -4 4 -2.209 4 0 C\n4 0 L\n4 2.209 2.209 4 0 4 C\n-2.209 4 -4 2.209 -4 0 C\n-4 -2.209 -2.209 -4 0 -4 C\ncp\n0 -6.667 M\n-3.682 -6.667 -6.667 -3.682 -6.667 0 C\n-6.667 3.682 -3.682 6.667 0 6.667 C\n3.682 6.667 6.667 3.682 6.667 0 C\n6.667 0 L\n6.667 -3.682 3.682 -6.667 0 -6.667 C\ncp}def\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 67.20455 23.625] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 70.43182 128.46633] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 73.65909 157.00857] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 76.88636 138.39895] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 80.11364 152.39821] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 83.34091 152.39821] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 86.56818 148.33158] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 89.79545 142.46558] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 93.02273 168.62574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 96.25 168.62574] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 99.47728 171.00782] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 102.70454 166.39746] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 105.93181 164.30431] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 109.15909 164.30431] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 112.38636 190.32935] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 115.61364 190.32935] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 118.84091 194.93971] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 122.06819 200.26197] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 125.29546 206.55688] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 128.52272 206.55688] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 131.75 214.26123] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 134.97727 214.26123] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 138.20455 214.26123] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 141.43182 214.26123] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 144.65909 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 147.88637 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 151.11364 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 154.3409 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 157.56818 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 160.79545 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 164.02273 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 167.25 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 170.47727 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 173.70455 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 176.93182 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 180.15908 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 183.38636 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 186.61364 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 189.84091 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 193.06819 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 196.29545 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 199.52273 224.19386] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 202.75001 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 205.97729 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 209.20454 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 212.43182 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 215.6591 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 218.88636 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.11364 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 225.3409 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 228.56818 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 231.79546 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 235.02274 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 238.25002 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 241.47727 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 244.70455 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 247.93181 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 251.15909 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 254.38637 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 257.61365 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 260.8409 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 264.06818 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 267.29546 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 270.52272 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 273.75 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 276.97726 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 280.20454 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 283.43182 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.6591 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 289.88638 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 293.11363 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 296.34089 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 299.56817 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 302.79545 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 306.02273 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 309.25001 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 312.47729 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 315.70454 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 318.93182 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 322.15908 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 325.38636 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 328.61364 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 331.84092 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 335.06818 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 338.29546 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 341.52274 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 344.74999 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 347.97727 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 351.20455 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 354.43181 238.19312] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 357.65909 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 360.88637 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 364.11365 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 367.3409 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 370.56818 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 373.79544 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 377.02272 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 380.25 262.125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\n%%Trailer\r\n%%Pages: 1\r\n%%EOF\r\n"
  },
  {
    "path": "matlab/acc2023/closedloop_performance/figures/closedloop-snapshots1.eps",
    "content": "%!PS-Adobe-3.0 EPSF-3.0\r\n%%Creator: (MATLAB, The Mathworks, Inc. Version 9.10.0.1649659 \\(R2021a\\) Update 1. Operating System: Windows 10)\r\n%%Title: figures/closedloop-snapshots1.eps\r\n%%CreationDate: 2023-01-31T03:11:33\r\n%%Pages: (atend)\r\n%%BoundingBox:     1     1   418   301\r\n%%LanguageLevel: 3\r\n%%EndComments\r\n%%BeginProlog\r\n%%BeginResource: procset (Apache XML Graphics Std ProcSet) 1.2 0\r\n%%Version: 1.2 0\r\n%%Copyright: (Copyright 2001-2003,2010 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/bd{bind def}bind def\r\n/ld{load def}bd\r\n/GR/grestore ld\r\n/GS/gsave ld\r\n/RM/rmoveto ld\r\n/C/curveto ld\r\n/t/show ld\r\n/L/lineto ld\r\n/ML/setmiterlimit ld\r\n/CT/concat ld\r\n/f/fill ld\r\n/N/newpath ld\r\n/S/stroke ld\r\n/CC/setcmykcolor ld\r\n/A/ashow ld\r\n/cp/closepath ld\r\n/RC/setrgbcolor ld\r\n/LJ/setlinejoin ld\r\n/GC/setgray ld\r\n/LW/setlinewidth ld\r\n/M/moveto ld\r\n/re {4 2 roll M\r\n1 index 0 rlineto\r\n0 exch rlineto\r\nneg 0 rlineto\r\ncp } bd\r\n/_ctm matrix def\r\n/_tm matrix def\r\n/BT { _ctm currentmatrix pop matrix _tm copy pop 0 0 moveto } bd\r\n/ET { _ctm setmatrix } bd\r\n/iTm { _ctm setmatrix _tm concat } bd\r\n/Tm { _tm astore pop iTm 0 0 moveto } bd\r\n/ux 0.0 def\r\n/uy 0.0 def\r\n/F {\r\n  /Tp exch def\r\n  /Tf exch def\r\n  Tf findfont Tp scalefont setfont\r\n  /cf Tf def  /cs Tp def\r\n} bd\r\n/ULS {currentpoint /uy exch def /ux exch def} bd\r\n/ULE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add moveto  Tcx uy To add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/OLE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs add moveto Tcx uy To add cs add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/SOE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs 10 mul 26 idiv add moveto Tcx uy To add cs 10 mul 26 idiv add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/QT {\r\n/Y22 exch store\r\n/X22 exch store\r\n/Y21 exch store\r\n/X21 exch store\r\ncurrentpoint\r\n/Y21 load 2 mul add 3 div exch\r\n/X21 load 2 mul add 3 div exch\r\n/X21 load 2 mul /X22 load add 3 div\r\n/Y21 load 2 mul /Y22 load add 3 div\r\n/X22 load /Y22 load curveto\r\n} bd\r\n/SSPD {\r\ndup length /d exch dict def\r\n{\r\n/v exch def\r\n/k exch def\r\ncurrentpagedevice k known {\r\n/cpdv currentpagedevice k get def\r\nv cpdv ne {\r\n/upd false def\r\n/nullv v type /nulltype eq def\r\n/nullcpdv cpdv type /nulltype eq def\r\nnullv nullcpdv or\r\n{\r\n/upd true def\r\n} {\r\n/sametype v type cpdv type eq def\r\nsametype {\r\nv type /arraytype eq {\r\n/vlen v length def\r\n/cpdvlen cpdv length def\r\nvlen cpdvlen eq {\r\n0 1 vlen 1 sub {\r\n/i exch def\r\n/obj v i get def\r\n/cpdobj cpdv i get def\r\nobj cpdobj ne {\r\n/upd true def\r\nexit\r\n} if\r\n} for\r\n} {\r\n/upd true def\r\n} ifelse\r\n} {\r\nv type /dicttype eq {\r\nv {\r\n/dv exch def\r\n/dk exch def\r\n/cpddv cpdv dk get def\r\ndv cpddv ne {\r\n/upd true def\r\nexit\r\n} if\r\n} forall\r\n} {\r\n/upd true def\r\n} ifelse\r\n} ifelse\r\n} if\r\n} ifelse\r\nupd true eq {\r\nd k v put\r\n} if\r\n} if\r\n} if\r\n} forall\r\nd length 0 gt {\r\nd setpagedevice\r\n} if\r\n} bd\r\n/RE { % /NewFontName [NewEncodingArray] /FontName RE -\r\n  findfont dup length dict begin\r\n  {\r\n    1 index /FID ne\r\n    {def} {pop pop} ifelse\r\n  } forall\r\n  /Encoding exch def\r\n  /FontName 1 index def\r\n  currentdict definefont pop\r\n  end\r\n} bind def\r\n%%EndResource\r\n%%BeginResource: procset (Apache XML Graphics EPS ProcSet) 1.0 0\r\n%%Version: 1.0 0\r\n%%Copyright: (Copyright 2002-2003 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/BeginEPSF { %def\r\n/b4_Inc_state save def         % Save state for cleanup\r\n/dict_count countdictstack def % Count objects on dict stack\r\n/op_count count 1 sub def      % Count objects on operand stack\r\nuserdict begin                 % Push userdict on dict stack\r\n/showpage { } def              % Redefine showpage, { } = null proc\r\n0 setgray 0 setlinecap         % Prepare graphics state\r\n1 setlinewidth 0 setlinejoin\r\n10 setmiterlimit [ ] 0 setdash newpath\r\n/languagelevel where           % If level not equal to 1 then\r\n{pop languagelevel             % set strokeadjust and\r\n1 ne                           % overprint to their defaults.\r\n{false setstrokeadjust false setoverprint\r\n} if\r\n} if\r\n} bd\r\n/EndEPSF { %def\r\ncount op_count sub {pop} repeat            % Clean up stacks\r\ncountdictstack dict_count sub {end} repeat\r\nb4_Inc_state restore\r\n} bd\r\n%%EndResource\r\n%FOPBeginFontDict\r\n%%IncludeResource: font Courier-Oblique\r\n%%IncludeResource: font Courier-BoldOblique\r\n%%IncludeResource: font Courier-Bold\r\n%%IncludeResource: font ZapfDingbats\r\n%%IncludeResource: font Symbol\r\n%%IncludeResource: font Helvetica\r\n%%IncludeResource: font Helvetica-Oblique\r\n%%IncludeResource: font Helvetica-Bold\r\n%%IncludeResource: font Helvetica-BoldOblique\r\n%%IncludeResource: font Times-Roman\r\n%%IncludeResource: font Times-Italic\r\n%%IncludeResource: font Times-Bold\r\n%%IncludeResource: font Times-BoldItalic\r\n%%IncludeResource: font Courier\r\n%FOPEndFontDict\r\n%%BeginResource: encoding WinAnsiEncoding\r\n/WinAnsiEncoding [\r\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /space /exclam /quotedbl\n/numbersign /dollar /percent /ampersand /quotesingle\n/parenleft /parenright /asterisk /plus /comma\n/hyphen /period /slash /zero /one\n/two /three /four /five /six\n/seven /eight /nine /colon /semicolon\n/less /equal /greater /question /at\n/A /B /C /D /E\n/F /G /H /I /J\n/K /L /M /N /O\n/P /Q /R /S /T\n/U /V /W /X /Y\n/Z /bracketleft /backslash /bracketright /asciicircum\n/underscore /quoteleft /a /b /c\n/d /e /f /g /h\n/i /j /k /l /m\n/n /o /p /q /r\n/s /t /u /v /w\n/x /y /z /braceleft /bar\n/braceright /asciitilde /bullet /Euro /bullet\n/quotesinglbase /florin /quotedblbase /ellipsis /dagger\n/daggerdbl /circumflex /perthousand /Scaron /guilsinglleft\n/OE /bullet /Zcaron /bullet /bullet\n/quoteleft /quoteright /quotedblleft /quotedblright /bullet\n/endash /emdash /asciitilde /trademark /scaron\n/guilsinglright /oe /bullet /zcaron /Ydieresis\n/space /exclamdown /cent /sterling /currency\n/yen /brokenbar /section /dieresis /copyright\n/ordfeminine /guillemotleft /logicalnot /sfthyphen /registered\n/macron /degree /plusminus /twosuperior /threesuperior\n/acute /mu /paragraph /middot /cedilla\n/onesuperior /ordmasculine /guillemotright /onequarter /onehalf\n/threequarters /questiondown /Agrave /Aacute /Acircumflex\n/Atilde /Adieresis /Aring /AE /Ccedilla\n/Egrave /Eacute /Ecircumflex /Edieresis /Igrave\n/Iacute /Icircumflex /Idieresis /Eth /Ntilde\n/Ograve /Oacute /Ocircumflex /Otilde /Odieresis\n/multiply /Oslash /Ugrave /Uacute /Ucircumflex\n/Udieresis /Yacute /Thorn /germandbls /agrave\n/aacute /acircumflex /atilde /adieresis /aring\n/ae /ccedilla /egrave /eacute /ecircumflex\n/edieresis /igrave /iacute /icircumflex /idieresis\n/eth /ntilde /ograve /oacute /ocircumflex\n/otilde /odieresis /divide /oslash /ugrave\n/uacute /ucircumflex /udieresis /yacute /thorn\n/ydieresis\n] def\r\n%%EndResource\r\n%FOPBeginFontReencode\r\n/Courier-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Oblique exch definefont pop\r\n/Courier-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-BoldOblique exch definefont pop\r\n/Courier-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Bold exch definefont pop\r\n/Helvetica findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica exch definefont pop\r\n/Helvetica-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Oblique exch definefont pop\r\n/Helvetica-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Bold exch definefont pop\r\n/Helvetica-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-BoldOblique exch definefont pop\r\n/Times-Roman findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Roman exch definefont pop\r\n/Times-Italic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Italic exch definefont pop\r\n/Times-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Bold exch definefont pop\r\n/Times-BoldItalic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-BoldItalic exch definefont pop\r\n/Courier findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier exch definefont pop\r\n%FOPEndFontReencode\r\n%%EndProlog\r\n%%Page: 1 1\r\n%%PageBoundingBox: 0 0 420 315\r\n%%BeginPageSetup\r\n[1 0 0 -1 0 315] CT\r\n%%EndPageSetup\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n130 700.667 M\n1101 700.667 L\n1101 53.333 L\n130 53.333 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n130 700.667 M\n130 53.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n291.833 700.667 M\n291.833 53.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n453.667 700.667 M\n453.667 53.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n615.5 700.667 M\n615.5 53.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n777.333 700.667 M\n777.333 53.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n939.167 700.667 M\n939.167 53.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 700.667 M\n1101 53.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 700.667 M\n130 700.667 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 538.833 M\n130 538.833 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 377 M\n130 377 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 215.167 M\n130 215.167 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 53.333 M\n130 53.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n130 700.667 M\n1101 700.667 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n130 700.667 M\n130 690.957 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n291.833 700.667 M\n291.833 690.957 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n453.667 700.667 M\n453.667 690.957 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n615.5 700.667 M\n615.5 690.957 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n777.333 700.667 M\n777.333 690.957 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n939.167 700.667 M\n939.167 690.957 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 700.667 M\n1101 690.957 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 48.75 268.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-21.5 49 moveto \r\n1 -1 scale\r\n(-3) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 109.4375 268.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-21.5 49 moveto \r\n1 -1 scale\r\n(-2) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 170.125 268.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-21.5 49 moveto \r\n1 -1 scale\r\n(-1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 230.8125 268.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-13.5 49 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 291.49999 268.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-13.5 49 moveto \r\n1 -1 scale\r\n(1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 352.18751 268.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-13.5 49 moveto \r\n1 -1 scale\r\n(2) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.875 268.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-13.5 49 moveto \r\n1 -1 scale\r\n(3) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 230.81268 291.85] CT\r\n0.149 GC\r\nN\r\n-55.255 43.269 M\n-54.317 44.003 -52.614 44.003 QT\n-50.958 44.003 -49.692 42.409 QT\n-48.426 40.815 -47.958 38.925 QT\n-45.551 29.534 L\n-44.973 26.972 -44.973 26.034 QT\n-44.973 24.722 -45.715 23.737 QT\n-46.458 22.753 -47.77 22.753 QT\n-49.458 22.753 -50.934 23.8 QT\n-52.411 24.847 -53.419 26.464 QT\n-54.426 28.081 -54.833 29.737 QT\n-54.942 30.081 -55.255 30.081 QT\n-55.895 30.081 L\n-56.317 30.081 -56.317 29.581 QT\n-56.317 29.425 L\n-55.801 27.456 -54.559 25.581 QT\n-53.317 23.706 -51.52 22.542 QT\n-49.723 21.378 -47.676 21.378 QT\n-45.723 21.378 -44.161 22.417 QT\n-42.598 23.456 -41.958 25.237 QT\n-41.051 23.612 -39.637 22.495 QT\n-38.223 21.378 -36.551 21.378 QT\n-35.411 21.378 -34.215 21.776 QT\n-33.02 22.175 -32.27 23.003 QT\n-31.52 23.831 -31.52 25.081 QT\n-31.52 26.425 -32.387 27.394 QT\n-33.255 28.362 -34.598 28.362 QT\n-35.458 28.362 -36.028 27.823 QT\n-36.598 27.284 -36.598 26.456 QT\n-36.598 25.331 -35.833 24.495 QT\n-35.067 23.659 -34.005 23.503 QT\n-34.958 22.753 -36.645 22.753 QT\n-38.348 22.753 -39.606 24.331 QT\n-40.864 25.909 -41.38 27.847 QT\n-43.708 37.222 L\n-44.286 39.347 -44.286 40.706 QT\n-44.286 42.05 -43.52 43.026 QT\n-42.755 44.003 -41.489 44.003 QT\n-39.005 44.003 -37.051 41.815 QT\n-35.098 39.628 -34.473 37.003 QT\n-34.364 36.706 -34.067 36.706 QT\n-33.411 36.706 L\n-33.208 36.706 -33.075 36.847 QT\n-32.942 36.987 -32.942 37.159 QT\n-32.942 37.222 -33.005 37.315 QT\n-33.755 40.472 -36.161 42.933 QT\n-38.567 45.394 -41.583 45.394 QT\n-43.536 45.394 -45.098 44.347 QT\n-46.661 43.3 -47.317 41.519 QT\n-48.145 43.065 -49.606 44.229 QT\n-51.067 45.394 -52.723 45.394 QT\n-53.864 45.394 -55.067 44.995 QT\n-56.27 44.597 -57.02 43.769 QT\n-57.77 42.94 -57.77 41.675 QT\n-57.77 40.425 -56.903 39.401 QT\n-56.036 38.378 -54.739 38.378 QT\n-53.864 38.378 -53.262 38.909 QT\n-52.661 39.44 -52.661 40.3 QT\n-52.661 41.409 -53.403 42.237 QT\n-54.145 43.065 -55.255 43.269 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 230.81268 291.85] CT\r\n0.149 GC\r\nN\r\n-12.476 57.94 M\n-15.429 55.612 -17.562 52.597 QT\n-19.695 49.581 -21.054 46.167 QT\n-22.414 42.753 -23.086 39.026 QT\n-23.757 35.3 -23.757 31.55 QT\n-23.757 27.753 -23.086 24.026 QT\n-22.414 20.3 -21.031 16.854 QT\n-19.648 13.409 -17.5 10.409 QT\n-15.351 7.409 -12.476 5.159 QT\n-12.476 5.05 -12.226 5.05 QT\n-11.726 5.05 L\n-11.57 5.05 -11.445 5.19 QT\n-11.32 5.331 -11.32 5.519 QT\n-11.32 5.753 -11.414 5.847 QT\n-14.007 8.394 -15.726 11.292 QT\n-17.445 14.19 -18.492 17.464 QT\n-19.539 20.737 -20.007 24.245 QT\n-20.476 27.753 -20.476 31.55 QT\n-20.476 48.394 -11.476 57.144 QT\n-11.32 57.3 -11.32 57.581 QT\n-11.32 57.706 -11.461 57.878 QT\n-11.601 58.05 -11.726 58.05 QT\n-12.226 58.05 L\n-12.476 58.05 -12.476 57.94 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 230.81268 291.85] CT\r\n0.149 GC\r\nN\r\n-4.079 43.894 M\n-4.079 43.581 -4.032 43.425 QT\n-0.079 27.612 L\n0.311 26.144 0.311 25.034 QT\n0.311 22.753 -1.235 22.753 QT\n-2.892 22.753 -3.696 24.729 QT\n-4.501 26.706 -5.251 29.737 QT\n-5.251 29.894 -5.407 29.987 QT\n-5.564 30.081 -5.689 30.081 QT\n-6.314 30.081 L\n-6.485 30.081 -6.618 29.886 QT\n-6.751 29.69 -6.751 29.534 QT\n-6.173 27.222 -5.649 25.62 QT\n-5.126 24.019 -3.993 22.698 QT\n-2.86 21.378 -1.189 21.378 QT\n0.811 21.378 2.335 22.636 QT\n3.858 23.894 3.858 25.831 QT\n5.436 23.753 7.561 22.565 QT\n9.686 21.378 12.061 21.378 QT\n14.577 21.378 16.397 22.659 QT\n18.218 23.94 18.218 26.3 QT\n19.858 23.987 22.046 22.683 QT\n24.233 21.378 26.811 21.378 QT\n29.561 21.378 31.226 22.87 QT\n32.89 24.362 32.89 27.097 QT\n32.89 29.269 31.921 32.347 QT\n30.952 35.425 29.515 39.237 QT\n28.749 41.065 28.749 42.425 QT\n28.749 44.003 29.999 44.003 QT\n32.061 44.003 33.436 41.776 QT\n34.811 39.55 35.374 37.003 QT\n35.53 36.706 35.827 36.706 QT\n36.436 36.706 L\n36.655 36.706 36.796 36.847 QT\n36.936 36.987 36.936 37.159 QT\n36.936 37.222 36.89 37.315 QT\n36.155 40.315 34.358 42.854 QT\n32.561 45.394 29.874 45.394 QT\n27.999 45.394 26.686 44.112 QT\n25.374 42.831 25.374 41.003 QT\n25.374 40.065 25.811 38.925 QT\n27.311 34.94 28.304 31.808 QT\n29.296 28.675 29.296 26.3 QT\n29.296 24.815 28.702 23.784 QT\n28.108 22.753 26.718 22.753 QT\n23.811 22.753 21.694 24.526 QT\n19.577 26.3 18.015 29.222 QT\n17.921 29.737 17.858 30.019 QT\n14.452 43.628 L\n14.265 44.362 13.632 44.878 QT\n12.999 45.394 12.218 45.394 QT\n11.593 45.394 11.116 44.979 QT\n10.64 44.565 10.64 43.894 QT\n10.64 43.581 10.686 43.425 QT\n14.077 29.925 L\n14.624 27.753 14.624 26.3 QT\n14.624 24.815 14.015 23.784 QT\n13.405 22.753 11.968 22.753 QT\n10.015 22.753 8.39 23.604 QT\n6.765 24.456 5.546 25.87 QT\n4.327 27.284 3.311 29.222 QT\n-0.282 43.628 L\n-0.454 44.362 -1.095 44.878 QT\n-1.735 45.394 -2.501 45.394 QT\n-3.157 45.394 -3.618 44.979 QT\n-4.079 44.565 -4.079 43.894 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 230.81268 291.85] CT\r\n0.149 GC\r\nN\r\n42.092 58.05 M\n41.623 58.05 41.623 57.581 QT\n41.623 57.347 41.733 57.253 QT\n50.795 48.394 50.795 31.55 QT\n50.795 14.706 41.842 5.956 QT\n41.623 5.831 41.623 5.519 QT\n41.623 5.331 41.772 5.19 QT\n41.92 5.05 42.092 5.05 QT\n42.592 5.05 L\n42.748 5.05 42.842 5.159 QT\n46.654 8.159 49.186 12.456 QT\n51.717 16.753 52.897 21.612 QT\n54.076 26.472 54.076 31.55 QT\n54.076 35.3 53.444 38.94 QT\n52.811 42.581 51.428 46.112 QT\n50.045 49.644 47.92 52.628 QT\n45.795 55.612 42.842 57.94 QT\n42.748 58.05 42.592 58.05 QT\n42.092 58.05 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n130 700.667 M\n130 53.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n130 700.667 M\n139.71 700.667 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n130 538.833 M\n139.71 538.833 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n130 377 M\n139.71 377 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n130 215.167 M\n139.71 215.167 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n130 53.333 M\n139.71 53.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 43.14999 262.75001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-43 19 moveto \r\n1 -1 scale\r\n(-2) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 43.14999 202.06249] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-43 19 moveto \r\n1 -1 scale\r\n(-1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 43.14999 141.375] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 19 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 43.14999 80.6875] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 19 moveto \r\n1 -1 scale\r\n(1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 43.14999 20] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 19 moveto \r\n1 -1 scale\r\n(2) t \r\nGR\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24.02501 141.37489] CT\r\n0.149 GC\r\nN\r\n-53.732 -11.622 M\n-52.623 -9.7 -49.857 -9.7 QT\n-47.342 -9.7 -45.506 -11.458 QT\n-43.67 -13.216 -42.545 -15.716 QT\n-41.42 -18.216 -40.795 -20.825 QT\n-43.154 -18.606 -45.889 -18.606 QT\n-47.982 -18.606 -49.459 -19.333 QT\n-50.935 -20.06 -51.756 -21.497 QT\n-52.576 -22.935 -52.576 -24.966 QT\n-52.576 -26.7 -52.107 -28.528 QT\n-51.639 -30.356 -50.795 -32.591 QT\n-49.951 -34.825 -49.342 -36.481 QT\n-48.639 -38.435 -48.639 -39.669 QT\n-48.639 -41.247 -49.795 -41.247 QT\n-51.904 -41.247 -53.256 -39.091 QT\n-54.607 -36.935 -55.264 -34.263 QT\n-55.357 -33.919 -55.701 -33.919 QT\n-56.326 -33.919 L\n-56.764 -33.919 -56.764 -34.419 QT\n-56.764 -34.575 L\n-55.904 -37.731 -54.146 -40.177 QT\n-52.389 -42.622 -49.701 -42.622 QT\n-47.81 -42.622 -46.506 -41.38 QT\n-45.201 -40.138 -45.201 -38.216 QT\n-45.201 -37.231 -45.639 -36.153 QT\n-45.873 -35.497 -46.701 -33.325 QT\n-47.529 -31.153 -47.967 -29.731 QT\n-48.404 -28.31 -48.685 -26.935 QT\n-48.967 -25.56 -48.967 -24.2 QT\n-48.967 -22.435 -48.217 -21.216 QT\n-47.467 -19.997 -45.842 -19.997 QT\n-42.56 -19.997 -39.935 -24.013 QT\n-35.935 -40.341 L\n-35.748 -41.044 -35.099 -41.544 QT\n-34.451 -42.044 -33.701 -42.044 QT\n-33.06 -42.044 -32.576 -41.63 QT\n-32.092 -41.216 -32.092 -40.544 QT\n-32.092 -40.247 -32.154 -40.138 QT\n-37.404 -19.044 L\n-38.107 -16.325 -39.967 -13.841 QT\n-41.826 -11.356 -44.451 -9.841 QT\n-47.076 -8.325 -49.935 -8.325 QT\n-51.295 -8.325 -52.646 -8.856 QT\n-53.998 -9.388 -54.826 -10.45 QT\n-55.654 -11.513 -55.654 -12.935 QT\n-55.654 -14.388 -54.795 -15.45 QT\n-53.935 -16.513 -52.514 -16.513 QT\n-51.67 -16.513 -51.084 -15.981 QT\n-50.498 -15.45 -50.498 -14.591 QT\n-50.498 -13.372 -51.404 -12.466 QT\n-52.31 -11.56 -53.529 -11.56 QT\n-53.576 -11.591 -53.631 -11.606 QT\n-53.685 -11.622 -53.732 -11.622 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24.02501 141.37489] CT\r\n0.149 GC\r\nN\r\n-13.686 -6.06 M\n-16.639 -8.388 -18.772 -11.403 QT\n-20.905 -14.419 -22.264 -17.833 QT\n-23.624 -21.247 -24.295 -24.974 QT\n-24.967 -28.7 -24.967 -32.45 QT\n-24.967 -36.247 -24.295 -39.974 QT\n-23.624 -43.7 -22.241 -47.146 QT\n-20.858 -50.591 -18.709 -53.591 QT\n-16.561 -56.591 -13.686 -58.841 QT\n-13.686 -58.95 -13.436 -58.95 QT\n-12.936 -58.95 L\n-12.78 -58.95 -12.655 -58.81 QT\n-12.53 -58.669 -12.53 -58.481 QT\n-12.53 -58.247 -12.624 -58.153 QT\n-15.217 -55.606 -16.936 -52.708 QT\n-18.655 -49.81 -19.702 -46.536 QT\n-20.749 -43.263 -21.217 -39.755 QT\n-21.686 -36.247 -21.686 -32.45 QT\n-21.686 -15.606 -12.686 -6.856 QT\n-12.53 -6.7 -12.53 -6.419 QT\n-12.53 -6.294 -12.67 -6.122 QT\n-12.811 -5.95 -12.936 -5.95 QT\n-13.436 -5.95 L\n-13.686 -5.95 -13.686 -6.06 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24.02501 141.37489] CT\r\n0.149 GC\r\nN\r\n-5.289 -20.106 M\n-5.289 -20.419 -5.242 -20.575 QT\n-1.289 -36.388 L\n-0.898 -37.856 -0.898 -38.966 QT\n-0.898 -41.247 -2.445 -41.247 QT\n-4.101 -41.247 -4.906 -39.271 QT\n-5.711 -37.294 -6.461 -34.263 QT\n-6.461 -34.106 -6.617 -34.013 QT\n-6.773 -33.919 -6.898 -33.919 QT\n-7.523 -33.919 L\n-7.695 -33.919 -7.828 -34.114 QT\n-7.961 -34.31 -7.961 -34.466 QT\n-7.383 -36.778 -6.859 -38.38 QT\n-6.336 -39.981 -5.203 -41.302 QT\n-4.07 -42.622 -2.398 -42.622 QT\n-0.398 -42.622 1.125 -41.364 QT\n2.649 -40.106 2.649 -38.169 QT\n4.227 -40.247 6.352 -41.435 QT\n8.477 -42.622 10.852 -42.622 QT\n13.367 -42.622 15.188 -41.341 QT\n17.008 -40.06 17.008 -37.7 QT\n18.649 -40.013 20.836 -41.317 QT\n23.024 -42.622 25.602 -42.622 QT\n28.352 -42.622 30.016 -41.13 QT\n31.68 -39.638 31.68 -36.903 QT\n31.68 -34.731 30.711 -31.653 QT\n29.742 -28.575 28.305 -24.763 QT\n27.539 -22.935 27.539 -21.575 QT\n27.539 -19.997 28.789 -19.997 QT\n30.852 -19.997 32.227 -22.224 QT\n33.602 -24.45 34.164 -26.997 QT\n34.32 -27.294 34.617 -27.294 QT\n35.227 -27.294 L\n35.445 -27.294 35.586 -27.153 QT\n35.727 -27.013 35.727 -26.841 QT\n35.727 -26.778 35.68 -26.685 QT\n34.945 -23.685 33.149 -21.146 QT\n31.352 -18.606 28.664 -18.606 QT\n26.789 -18.606 25.477 -19.888 QT\n24.164 -21.169 24.164 -22.997 QT\n24.164 -23.935 24.602 -25.075 QT\n26.102 -29.06 27.094 -32.192 QT\n28.086 -35.325 28.086 -37.7 QT\n28.086 -39.185 27.492 -40.216 QT\n26.899 -41.247 25.508 -41.247 QT\n22.602 -41.247 20.484 -39.474 QT\n18.367 -37.7 16.805 -34.778 QT\n16.711 -34.263 16.649 -33.981 QT\n13.242 -20.372 L\n13.055 -19.638 12.422 -19.122 QT\n11.789 -18.606 11.008 -18.606 QT\n10.383 -18.606 9.906 -19.021 QT\n9.43 -19.435 9.43 -20.106 QT\n9.43 -20.419 9.477 -20.575 QT\n12.867 -34.075 L\n13.414 -36.247 13.414 -37.7 QT\n13.414 -39.185 12.805 -40.216 QT\n12.195 -41.247 10.758 -41.247 QT\n8.805 -41.247 7.18 -40.396 QT\n5.555 -39.544 4.336 -38.13 QT\n3.117 -36.716 2.102 -34.778 QT\n-1.492 -20.372 L\n-1.664 -19.638 -2.305 -19.122 QT\n-2.945 -18.606 -3.711 -18.606 QT\n-4.367 -18.606 -4.828 -19.021 QT\n-5.289 -19.435 -5.289 -20.106 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24.02501 141.37489] CT\r\n0.149 GC\r\nN\r\n40.882 -5.95 M\n40.413 -5.95 40.413 -6.419 QT\n40.413 -6.653 40.523 -6.747 QT\n49.585 -15.606 49.585 -32.45 QT\n49.585 -49.294 40.632 -58.044 QT\n40.413 -58.169 40.413 -58.481 QT\n40.413 -58.669 40.562 -58.81 QT\n40.71 -58.95 40.882 -58.95 QT\n41.382 -58.95 L\n41.538 -58.95 41.632 -58.841 QT\n45.445 -55.841 47.976 -51.544 QT\n50.507 -47.247 51.687 -42.388 QT\n52.867 -37.528 52.867 -32.45 QT\n52.867 -28.7 52.234 -25.06 QT\n51.601 -21.419 50.218 -17.888 QT\n48.835 -14.356 46.71 -11.372 QT\n44.585 -8.388 41.632 -6.06 QT\n41.538 -5.95 41.382 -5.95 QT\n40.882 -5.95 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n5.333 LW\r\nN\r\n777.333 377 M\n777.008 366.736 L\n776.031 356.513 L\n774.409 346.373 L\n772.146 336.356 L\n769.253 326.503 L\n765.741 316.853 L\n761.624 307.445 L\n756.918 298.317 L\n751.643 289.506 L\n745.82 281.048 L\n739.471 272.976 L\n732.624 265.322 L\n725.305 258.119 L\n717.544 251.394 L\n709.373 245.174 L\n700.823 239.486 L\n691.929 234.351 L\n682.728 229.791 L\n673.256 225.824 L\n663.552 222.465 L\n653.654 219.728 L\n643.602 217.625 L\n633.437 216.164 L\n623.2 215.35 L\n612.932 215.187 L\n602.675 215.676 L\n592.469 216.814 L\n582.355 218.597 L\n572.376 221.018 L\n562.57 224.067 L\n552.977 227.732 L\n543.635 231.998 L\n534.583 236.848 L\n525.857 242.262 L\n517.492 248.219 L\n509.522 254.695 L\n501.978 261.662 L\n494.891 269.095 L\n488.29 276.961 L\n482.202 285.231 L\n476.65 293.87 L\n471.657 302.844 L\n467.243 312.116 L\n463.426 321.65 L\n460.222 331.406 L\n457.643 341.346 L\n455.699 351.43 L\n454.399 361.617 L\n453.748 371.865 L\n453.748 382.135 L\n454.399 392.383 L\n455.699 402.57 L\n457.643 412.654 L\n460.222 422.594 L\n463.426 432.35 L\n467.243 441.884 L\n471.657 451.156 L\n476.65 460.13 L\n482.202 468.769 L\n488.29 477.039 L\n494.891 484.905 L\n501.978 492.338 L\n509.522 499.305 L\n517.492 505.781 L\n525.857 511.738 L\n534.583 517.152 L\n543.635 522.002 L\n552.977 526.268 L\n562.57 529.933 L\n572.376 532.982 L\n582.355 535.403 L\n592.469 537.186 L\n602.675 538.324 L\n612.932 538.813 L\n623.2 538.65 L\n633.437 537.836 L\n643.602 536.375 L\n653.654 534.271 L\n663.552 531.535 L\n673.256 528.176 L\n682.728 524.209 L\n691.929 519.649 L\n700.823 514.514 L\n709.373 508.826 L\n717.544 502.606 L\n725.305 495.881 L\n732.624 488.678 L\n739.471 481.024 L\n745.82 472.952 L\n751.643 464.494 L\n756.918 455.683 L\n761.624 446.555 L\n765.741 437.147 L\n769.253 427.497 L\n772.146 417.644 L\n774.409 407.627 L\n776.031 397.487 L\n777.008 387.264 L\n777.333 377 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0.502 0 RC\r\nN\r\n488.29 477.039 M\n494.891 484.905 L\n501.978 492.338 L\n509.522 499.305 L\n517.492 505.781 L\n525.857 511.738 L\n534.583 517.152 L\n543.635 522.002 L\n552.977 526.268 L\n562.57 529.933 L\n572.376 532.982 L\n582.355 535.403 L\n592.469 537.186 L\n602.675 538.324 L\n612.932 538.813 L\n623.2 538.65 L\n633.437 537.836 L\n643.602 536.375 L\n653.654 534.271 L\n663.552 531.535 L\n673.256 528.176 L\n682.728 524.209 L\n691.929 519.649 L\n700.823 514.514 L\n709.373 508.826 L\n717.544 502.606 L\n725.305 495.881 L\n732.624 488.678 L\n739.471 481.024 L\n745.82 472.952 L\n751.643 464.494 L\n756.918 455.683 L\n761.624 446.555 L\n765.741 437.147 L\n769.253 427.497 L\n772.146 417.644 L\n774.409 407.627 L\n776.031 397.487 L\n777.008 387.264 L\n777.333 377 L\n777.008 366.736 L\n776.031 356.513 L\n774.409 346.373 L\n772.146 336.356 L\n769.253 326.503 L\n765.741 316.853 L\n761.624 307.445 L\n756.918 298.317 L\n751.643 289.506 L\n745.82 281.048 L\n739.471 272.976 L\n732.624 265.322 L\n725.305 258.119 L\n717.544 251.394 L\n709.373 245.174 L\n700.823 239.486 L\n691.929 234.351 L\n682.728 229.791 L\n673.256 225.824 L\n663.552 222.465 L\n653.654 219.728 L\n643.602 217.625 L\n633.437 216.164 L\n623.2 215.35 L\n612.932 215.187 L\n602.675 215.676 L\n592.469 216.814 L\n582.355 218.597 L\n572.376 221.018 L\n562.57 224.067 L\n552.977 227.732 L\n543.635 231.998 L\n534.583 236.848 L\n525.857 242.262 L\n517.492 248.219 L\n509.522 254.695 L\n501.978 261.662 L\n494.891 269.095 L\n488.29 276.961 L\n482.202 285.231 L\n476.65 293.87 L\n471.657 302.844 L\n467.243 312.116 L\n463.426 321.65 L\n460.222 331.406 L\n457.643 341.346 L\n455.699 351.43 L\n454.399 361.617 L\n453.748 371.865 L\n453.748 382.135 L\n454.399 392.383 L\n455.699 402.57 L\n457.643 412.654 L\n460.222 422.594 L\n463.426 432.35 L\n467.243 441.884 L\n471.657 451.156 L\n476.65 460.13 L\n482.202 468.769 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n2 setlinecap\r\n10.0 ML\r\n1.333 LW\r\nN\r\n777.333 377 M\n777.008 366.736 L\n776.031 356.513 L\n774.409 346.373 L\n772.146 336.356 L\n769.253 326.503 L\n765.741 316.853 L\n761.624 307.445 L\n756.918 298.317 L\n751.643 289.506 L\n745.82 281.048 L\n739.471 272.976 L\n732.624 265.322 L\n725.305 258.119 L\n717.544 251.394 L\n709.373 245.174 L\n700.823 239.486 L\n691.929 234.351 L\n682.728 229.791 L\n673.256 225.824 L\n663.552 222.465 L\n653.654 219.728 L\n643.602 217.625 L\n633.437 216.164 L\n623.2 215.35 L\n612.932 215.187 L\n602.675 215.676 L\n592.469 216.814 L\n582.355 218.597 L\n572.376 221.018 L\n562.57 224.067 L\n552.977 227.732 L\n543.635 231.998 L\n534.583 236.848 L\n525.857 242.262 L\n517.492 248.219 L\n509.522 254.695 L\n501.978 261.662 L\n494.891 269.095 L\n488.29 276.961 L\n482.202 285.231 L\n476.65 293.87 L\n471.657 302.844 L\n467.243 312.116 L\n463.426 321.65 L\n460.222 331.406 L\n457.643 341.346 L\n455.699 351.43 L\n454.399 361.617 L\n453.748 371.865 L\n453.748 382.135 L\n454.399 392.383 L\n455.699 402.57 L\n457.643 412.654 L\n460.222 422.594 L\n463.426 432.35 L\n467.243 441.884 L\n471.657 451.156 L\n476.65 460.13 L\n482.202 468.769 L\n488.29 477.039 L\n494.891 484.905 L\n501.978 492.338 L\n509.522 499.305 L\n517.492 505.781 L\n525.857 511.738 L\n534.583 517.152 L\n543.635 522.002 L\n552.977 526.268 L\n562.57 529.933 L\n572.376 532.982 L\n582.355 535.403 L\n592.469 537.186 L\n602.675 538.324 L\n612.932 538.813 L\n623.2 538.65 L\n633.437 537.836 L\n643.602 536.375 L\n653.654 534.271 L\n663.552 531.535 L\n673.256 528.176 L\n682.728 524.209 L\n691.929 519.649 L\n700.823 514.514 L\n709.373 508.826 L\n717.544 502.606 L\n725.305 495.881 L\n732.624 488.678 L\n739.471 481.024 L\n745.82 472.952 L\n751.643 464.494 L\n756.918 455.683 L\n761.624 446.555 L\n765.741 437.147 L\n769.253 427.497 L\n772.146 417.644 L\n774.409 407.627 L\n776.031 397.487 L\n777.008 387.264 L\n777.333 377 L\n777.333 377 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 48.75 141.375] CT\r\n0 0 1 RC\r\n10.0 ML\r\n2.667 LW\r\nN\r\n-8 0 M\n0 10.64 L\n8 0 L\n0 -10.64 L\ncp\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.875 140.76812] CT\r\n1 0 0 RC\r\n10.0 ML\r\n2.667 LW\r\nN\r\n-8 0 M\n0 10.64 L\n8 0 L\n0 -10.64 L\ncp\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n5.333 LW\r\nN\r\n130 377 M\n130 377 L\n137.878 375.148 L\n153.148 369.792 L\n174.253 360.73 L\n202.212 349.273 L\n233.459 336.589 L\n269.102 323.471 L\n310.83 308.125 L\n355.474 289.905 L\n400.295 268.45 L\n444.964 246.002 L\n490.223 225.817 L\n536.496 211.234 L\n583.017 204.561 L\n628.028 207.138 L\n669.481 217.329 L\n707.573 229.695 L\n742.88 242.147 L\n775.547 254.015 L\n805.683 265.035 L\n833.403 275.112 L\n858.836 284.228 L\n882.119 292.401 L\n903.394 299.673 L\n922.804 306.096 L\n940.487 311.732 L\n956.576 316.641 L\n971.195 320.891 L\n984.463 324.544 L\n996.49 327.665 L\n1007.376 330.315 L\n1017.217 332.551 L\n1026.102 334.427 L\n1034.111 335.992 L\n1041.322 337.291 L\n1047.805 338.364 L\n1053.626 339.245 L\n1058.845 339.966 L\n1063.519 340.553 L\n1067.7 341.03 L\n1071.435 341.415 L\n1074.768 341.725 L\n1077.74 341.975 L\n1080.387 342.174 L\n1082.743 342.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n130 377 M\n130 377 L\n138.065 376.101 L\n154.027 378.51 L\n177.891 374.095 L\n210.039 377.812 L\n234.428 376.492 L\n265.509 366.944 L\n296.455 354.455 L\n328.411 341.437 L\n361.609 326.969 L\n398.868 308.554 L\n438.215 285.948 L\n477.215 259.825 L\n518.116 236.03 L\n561.812 219.581 L\n606.659 213.43 L\n649.714 218.161 L\n689.486 228.334 L\n726.217 239.993 L\n760.171 251.64 L\n791.512 262.686 L\n820.367 272.905 L\n846.867 282.216 L\n871.149 290.608 L\n893.353 298.107 L\n913.624 304.757 L\n932.102 310.611 L\n948.923 315.728 L\n964.216 320.172 L\n978.102 324.004 L\n990.695 327.289 L\n1002.101 330.086 L\n1012.419 332.453 L\n1021.739 334.446 L\n1030.149 336.113 L\n1037.725 337.5 L\n1044.542 338.649 L\n1050.668 339.595 L\n1056.166 340.372 L\n1061.095 341.006 L\n1065.507 341.522 L\n1069.453 341.94 L\n1072.978 342.278 L\n1076.124 342.55 L\n1078.93 342.768 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n130 377 M\n130 377 L\n138.091 376.924 L\n153.947 373.686 L\n177.179 366.646 L\n206.631 356.87 L\n241.756 345.523 L\n281.452 332.505 L\n323.644 317.47 L\n365.631 299.287 L\n406.13 278.131 L\n445.652 256.089 L\n485.316 235.728 L\n525.911 219.641 L\n567.219 209.885 L\n608.265 208.904 L\n646.783 213.683 L\n682.712 222.471 L\n716.211 232.457 L\n747.466 242.446 L\n776.582 251.967 L\n803.645 260.829 L\n828.74 268.96 L\n851.963 276.347 L\n873.415 283.005 L\n893.2 288.966 L\n911.422 294.271 L\n928.185 298.965 L\n943.587 303.097 L\n957.725 306.715 L\n970.69 309.867 L\n982.567 312.6 L\n993.436 314.957 L\n1003.374 316.983 L\n1012.451 318.715 L\n1020.735 320.191 L\n1028.287 321.442 L\n1035.166 322.5 L\n1041.427 323.391 L\n1047.119 324.138 L\n1052.29 324.764 L\n1056.985 325.286 L\n1061.243 325.72 L\n1065.104 326.08 L\n1068.6 326.378 L\n1071.766 326.625 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n130 377 M\n130 377 L\n138.083 376.795 L\n154.099 379.095 L\n176.473 384.836 L\n204.294 394.103 L\n237.234 406.051 L\n276.694 400.199 L\n312.148 385.834 L\n345.322 368.539 L\n376.091 349.449 L\n408.142 327.27 L\n443.765 301.354 L\n480.264 272.516 L\n517.332 243.227 L\n559.815 223.586 L\n604.621 215.437 L\n648.047 218.959 L\n688.716 228.376 L\n726 239.916 L\n760.857 251.891 L\n793.331 263.567 L\n823.501 274.581 L\n851.446 284.771 L\n877.239 294.073 L\n900.977 302.464 L\n922.773 309.952 L\n942.746 316.568 L\n961.014 322.36 L\n977.695 327.383 L\n992.9 331.702 L\n1006.701 335.386 L\n1019.232 338.499 L\n1030.591 341.108 L\n1040.872 343.278 L\n1050.162 345.069 L\n1058.545 346.539 L\n1066.06 347.73 L\n1072.755 348.685 L\n1078.684 349.441 L\n1083.905 350.033 L\n1088.48 350.493 L\n1092.472 350.847 L\n1095.938 351.118 L\n1098.935 351.322 L\n1101.039 351.444 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n1080 679 M\n1080 461 L\n494 461 L\n494 679 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 184.0765] CT\r\nN\r\n2.016 10.368 M\n1.594 10.368 1.594 9.805 QT\n1.609 9.696 1.68 9.43 QT\n1.75 9.165 1.859 9.008 QT\n1.969 8.852 2.141 8.852 QT\n6.25 8.852 6.922 6.227 QT\n12.766 -17.288 L\n11.563 -17.492 8.984 -17.492 QT\n8.563 -17.492 8.563 -18.054 QT\n8.594 -18.163 8.656 -18.429 QT\n8.719 -18.695 8.828 -18.851 QT\n8.938 -19.007 9.109 -19.007 QT\n16.547 -19.007 L\n16.859 -19.007 16.938 -18.726 QT\n26.5 4.008 L\n31.266 -15.038 L\n31.344 -15.507 31.344 -15.695 QT\n31.344 -17.492 28.031 -17.492 QT\n27.609 -17.492 27.609 -18.054 QT\n27.75 -18.601 27.836 -18.804 QT\n27.922 -19.007 28.344 -19.007 QT\n37.547 -19.007 L\n37.969 -19.007 37.969 -18.445 QT\n37.938 -18.335 37.875 -18.07 QT\n37.813 -17.804 37.695 -17.648 QT\n37.578 -17.492 37.422 -17.492 QT\n33.297 -17.492 32.625 -14.867 QT\n26.453 9.993 L\n26.313 10.368 26.016 10.368 QT\n25.484 10.368 L\n25.203 10.368 25.109 10.071 QT\n14.156 -15.945 L\n14.063 -16.21 L\n13.984 -16.304 13.984 -16.335 QT\n8.297 6.415 L\n8.25 6.524 8.227 6.68 QT\n8.203 6.837 8.172 7.055 QT\n8.172 8.165 9.133 8.508 QT\n10.094 8.852 11.531 8.852 QT\n11.953 8.852 11.953 9.43 QT\n11.797 10.008 11.695 10.188 QT\n11.594 10.368 11.234 10.368 QT\n2.016 10.368 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 184.0765] CT\r\nN\r\n54.654 4.649 M\n54.295 4.649 54.068 4.383 QT\n53.841 4.118 53.841 3.79 QT\n53.841 3.446 54.068 3.188 QT\n54.295 2.93 54.654 2.93 QT\n81.654 2.93 L\n81.966 2.93 82.201 3.188 QT\n82.435 3.446 82.435 3.79 QT\n82.435 4.118 82.201 4.383 QT\n81.966 4.649 81.654 4.649 QT\n54.654 4.649 L\ncp\n54.654 -3.695 M\n54.295 -3.695 54.068 -3.952 QT\n53.841 -4.21 53.841 -4.554 QT\n53.841 -4.882 54.068 -5.156 QT\n54.295 -5.429 54.654 -5.429 QT\n81.654 -5.429 L\n81.966 -5.429 82.201 -5.156 QT\n82.435 -4.882 82.435 -4.554 QT\n82.435 -4.21 82.201 -3.952 QT\n81.966 -3.695 81.654 -3.695 QT\n54.654 -3.695 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 184.0765] CT\r\nN\r\n99.16 10.368 M\n99.16 9.212 L\n99.16 9.102 99.238 8.977 QT\n105.926 1.587 L\n107.441 -0.054 108.379 -1.163 QT\n109.316 -2.273 110.246 -3.718 QT\n111.176 -5.163 111.707 -6.671 QT\n112.238 -8.179 112.238 -9.851 QT\n112.238 -11.617 111.59 -13.226 QT\n110.941 -14.835 109.652 -15.796 QT\n108.363 -16.757 106.535 -16.757 QT\n104.66 -16.757 103.168 -15.632 QT\n101.676 -14.507 101.066 -12.726 QT\n101.238 -12.773 101.535 -12.773 QT\n102.504 -12.773 103.183 -12.124 QT\n103.863 -11.476 103.863 -10.445 QT\n103.863 -9.46 103.183 -8.773 QT\n102.504 -8.085 101.535 -8.085 QT\n100.519 -8.085 99.84 -8.788 QT\n99.16 -9.492 99.16 -10.445 QT\n99.16 -12.054 99.769 -13.476 QT\n100.379 -14.898 101.519 -15.999 QT\n102.66 -17.101 104.105 -17.687 QT\n105.551 -18.273 107.16 -18.273 QT\n109.613 -18.273 111.738 -17.234 QT\n113.863 -16.195 115.098 -14.296 QT\n116.332 -12.398 116.332 -9.851 QT\n116.332 -7.976 115.512 -6.296 QT\n114.691 -4.617 113.418 -3.242 QT\n112.144 -1.867 110.144 -0.124 QT\n108.144 1.618 107.519 2.196 QT\n102.644 6.883 L\n106.785 6.883 L\n109.832 6.883 111.879 6.829 QT\n113.926 6.774 114.051 6.665 QT\n114.551 6.133 115.082 2.712 QT\n116.332 2.712 L\n115.113 10.368 L\n99.16 10.368 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 184.0765] CT\r\nN\r\n119.823 3.274 M\n119.823 1.758 L\n133.104 -18.054 L\n133.26 -18.273 133.541 -18.273 QT\n134.182 -18.273 L\n134.666 -18.273 134.666 -17.788 QT\n134.666 1.758 L\n138.885 1.758 L\n138.885 3.274 L\n134.666 3.274 L\n134.666 7.493 L\n134.666 8.368 135.924 8.61 QT\n137.182 8.852 138.838 8.852 QT\n138.838 10.368 L\n126.994 10.368 L\n126.994 8.852 L\n128.651 8.852 129.916 8.61 QT\n131.182 8.368 131.182 7.493 QT\n131.182 3.274 L\n119.823 3.274 L\ncp\n121.244 1.758 M\n131.432 1.758 L\n131.432 -13.46 L\n121.244 1.758 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 184.0765] CT\r\nN\r\n144.485 18.118 M\n144.485 17.93 144.657 17.758 QT\n146.204 16.274 147.063 14.321 QT\n147.923 12.368 147.923 10.196 QT\n147.923 9.68 L\n147.235 10.368 146.204 10.368 QT\n145.22 10.368 144.524 9.673 QT\n143.829 8.977 143.829 7.993 QT\n143.829 6.993 144.524 6.321 QT\n145.22 5.649 146.204 5.649 QT\n147.735 5.649 148.384 7.063 QT\n149.032 8.477 149.032 10.196 QT\n149.032 12.587 148.079 14.743 QT\n147.126 16.899 145.391 18.618 QT\n145.22 18.696 145.11 18.696 QT\n144.907 18.696 144.696 18.508 QT\n144.485 18.321 144.485 18.118 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 184.0765] CT\r\nN\r\n172.107 18.79 M\n172.107 17.821 172.537 15.977 QT\n172.966 14.133 173.583 12.04 QT\n174.201 9.946 174.638 8.602 QT\n174.81 6.462 174.81 5.368 QT\n174.81 2.602 174.263 0.219 QT\n173.716 -2.163 172.208 -3.773 QT\n170.701 -5.382 167.982 -5.382 QT\n166.56 -5.382 165.138 -4.773 QT\n163.716 -4.163 162.701 -3.07 QT\n161.685 -1.976 161.31 -0.585 QT\n161.232 -0.335 160.966 -0.335 QT\n160.451 -0.335 L\n160.107 -0.335 160.107 -0.726 QT\n160.107 -0.867 L\n160.591 -2.804 161.818 -4.593 QT\n163.044 -6.382 164.826 -7.507 QT\n166.607 -8.632 168.576 -8.632 QT\n170.591 -8.632 172.06 -7.265 QT\n173.529 -5.898 174.412 -3.804 QT\n175.294 -1.71 175.685 0.43 QT\n176.076 2.571 176.076 4.462 QT\n178.232 -1.413 180.919 -6.663 QT\n181.576 -8.038 L\n181.701 -8.179 181.857 -8.179 QT\n182.388 -8.179 L\n182.732 -8.179 182.732 -7.773 QT\n182.732 -7.695 182.638 -7.523 QT\n181.998 -6.179 L\n180.123 -2.46 178.56 1.36 QT\n176.998 5.18 175.888 8.727 QT\n175.716 10.18 175.24 12.696 QT\n174.763 15.212 174.091 17.391 QT\n173.419 19.571 172.748 19.649 QT\n172.107 19.649 172.107 18.79 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 184.0765] CT\r\nN\r\n184.567 16.848 M\n184.567 15.785 L\n188.317 15.785 188.317 14.848 QT\n188.317 -0.902 L\n186.77 -0.152 184.395 -0.152 QT\n184.395 -1.215 L\n188.067 -1.215 189.942 -3.137 QT\n190.363 -3.137 L\n190.473 -3.137 190.567 -3.051 QT\n190.66 -2.965 190.66 -2.871 QT\n190.66 14.848 L\n190.66 15.785 194.41 15.785 QT\n194.41 16.848 L\n184.567 16.848 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 184.0765] CT\r\nN\r\n214.299 4.649 M\n213.94 4.649 213.714 4.383 QT\n213.487 4.118 213.487 3.79 QT\n213.487 3.446 213.714 3.188 QT\n213.94 2.93 214.299 2.93 QT\n241.299 2.93 L\n241.612 2.93 241.846 3.188 QT\n242.081 3.446 242.081 3.79 QT\n242.081 4.118 241.846 4.383 QT\n241.612 4.649 241.299 4.649 QT\n214.299 4.649 L\ncp\n214.299 -3.695 M\n213.94 -3.695 213.714 -3.952 QT\n213.487 -4.21 213.487 -4.554 QT\n213.487 -4.882 213.714 -5.156 QT\n213.94 -5.429 214.299 -5.429 QT\n241.299 -5.429 L\n241.612 -5.429 241.846 -5.156 QT\n242.081 -4.882 242.081 -4.554 QT\n242.081 -4.21 241.846 -3.952 QT\n241.612 -3.695 241.299 -3.695 QT\n214.299 -3.695 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 184.0765] CT\r\nN\r\n267.415 11.305 M\n262.149 11.305 260.251 6.969 QT\n258.352 2.633 258.352 -3.335 QT\n258.352 -7.085 259.032 -10.382 QT\n259.712 -13.679 261.735 -15.976 QT\n263.759 -18.273 267.415 -18.273 QT\n270.243 -18.273 272.056 -16.89 QT\n273.868 -15.507 274.806 -13.312 QT\n275.743 -11.117 276.095 -8.609 QT\n276.446 -6.101 276.446 -3.335 QT\n276.446 0.352 275.759 3.579 QT\n275.071 6.805 273.079 9.055 QT\n271.087 11.305 267.415 11.305 QT\ncp\n267.415 10.196 M\n269.806 10.196 270.985 7.743 QT\n272.165 5.29 272.438 2.305 QT\n272.712 -0.679 272.712 -4.038 QT\n272.712 -7.273 272.438 -9.999 QT\n272.165 -12.726 271.001 -14.945 QT\n269.837 -17.163 267.415 -17.163 QT\n264.977 -17.163 263.806 -14.937 QT\n262.634 -12.71 262.36 -9.992 QT\n262.087 -7.273 262.087 -4.038 QT\n262.087 -1.648 262.196 0.477 QT\n262.306 2.602 262.813 4.86 QT\n263.321 7.118 264.446 8.657 QT\n265.571 10.196 267.415 10.196 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 184.0765] CT\r\nN\r\n281.874 7.993 M\n281.874 7.024 282.593 6.337 QT\n283.312 5.649 284.249 5.649 QT\n284.843 5.649 285.406 5.962 QT\n285.968 6.274 286.281 6.844 QT\n286.593 7.415 286.593 7.993 QT\n286.593 8.946 285.906 9.657 QT\n285.218 10.368 284.249 10.368 QT\n283.312 10.368 282.593 9.657 QT\n281.874 8.946 281.874 7.993 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 184.0765] CT\r\nN\r\n291.468 3.274 M\n291.468 1.758 L\n304.749 -18.054 L\n304.906 -18.273 305.187 -18.273 QT\n305.828 -18.273 L\n306.312 -18.273 306.312 -17.788 QT\n306.312 1.758 L\n310.531 1.758 L\n310.531 3.274 L\n306.312 3.274 L\n306.312 7.493 L\n306.312 8.368 307.57 8.61 QT\n308.828 8.852 310.484 8.852 QT\n310.484 10.368 L\n298.64 10.368 L\n298.64 8.852 L\n300.296 8.852 301.562 8.61 QT\n302.828 8.368 302.828 7.493 QT\n302.828 3.274 L\n291.468 3.274 L\ncp\n292.89 1.758 M\n303.078 1.758 L\n303.078 -13.46 L\n292.89 1.758 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 184.0765] CT\r\nN\r\n316.131 18.118 M\n316.131 17.93 316.303 17.758 QT\n317.849 16.274 318.709 14.321 QT\n319.568 12.368 319.568 10.196 QT\n319.568 9.68 L\n318.881 10.368 317.849 10.368 QT\n316.865 10.368 316.17 9.673 QT\n315.474 8.977 315.474 7.993 QT\n315.474 6.993 316.17 6.321 QT\n316.865 5.649 317.849 5.649 QT\n319.381 5.649 320.029 7.063 QT\n320.678 8.477 320.678 10.196 QT\n320.678 12.587 319.724 14.743 QT\n318.771 16.899 317.037 18.618 QT\n316.865 18.696 316.756 18.696 QT\n316.553 18.696 316.342 18.508 QT\n316.131 18.321 316.131 18.118 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 184.0765] CT\r\nN\r\n343.752 18.79 M\n343.752 17.821 344.182 15.977 QT\n344.612 14.133 345.229 12.04 QT\n345.846 9.946 346.284 8.602 QT\n346.456 6.462 346.456 5.368 QT\n346.456 2.602 345.909 0.219 QT\n345.362 -2.163 343.854 -3.773 QT\n342.346 -5.382 339.627 -5.382 QT\n338.206 -5.382 336.784 -4.773 QT\n335.362 -4.163 334.346 -3.07 QT\n333.331 -1.976 332.956 -0.585 QT\n332.877 -0.335 332.612 -0.335 QT\n332.096 -0.335 L\n331.752 -0.335 331.752 -0.726 QT\n331.752 -0.867 L\n332.237 -2.804 333.463 -4.593 QT\n334.69 -6.382 336.471 -7.507 QT\n338.252 -8.632 340.221 -8.632 QT\n342.237 -8.632 343.706 -7.265 QT\n345.174 -5.898 346.057 -3.804 QT\n346.94 -1.71 347.331 0.43 QT\n347.721 2.571 347.721 4.462 QT\n349.877 -1.413 352.565 -6.663 QT\n353.221 -8.038 L\n353.346 -8.179 353.502 -8.179 QT\n354.034 -8.179 L\n354.377 -8.179 354.377 -7.773 QT\n354.377 -7.695 354.284 -7.523 QT\n353.643 -6.179 L\n351.768 -2.46 350.206 1.36 QT\n348.643 5.18 347.534 8.727 QT\n347.362 10.18 346.885 12.696 QT\n346.409 15.212 345.737 17.391 QT\n345.065 19.571 344.393 19.649 QT\n343.752 19.649 343.752 18.79 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 184.0765] CT\r\nN\r\n354.931 16.848 M\n354.931 16.035 L\n354.931 15.973 354.978 15.879 QT\n359.65 10.723 L\n360.697 9.582 361.353 8.809 QT\n362.009 8.035 362.657 7.02 QT\n363.306 6.004 363.681 4.957 QT\n364.056 3.91 364.056 2.738 QT\n364.056 1.504 363.603 0.387 QT\n363.15 -0.73 362.243 -1.402 QT\n361.337 -2.074 360.072 -2.074 QT\n358.759 -2.074 357.72 -1.293 QT\n356.681 -0.512 356.259 0.738 QT\n356.368 0.707 356.587 0.707 QT\n357.259 0.707 357.736 1.16 QT\n358.212 1.613 358.212 2.332 QT\n358.212 3.02 357.736 3.496 QT\n357.259 3.973 356.587 3.973 QT\n355.884 3.973 355.407 3.481 QT\n354.931 2.988 354.931 2.332 QT\n354.931 1.207 355.353 0.215 QT\n355.775 -0.777 356.572 -1.543 QT\n357.368 -2.308 358.376 -2.723 QT\n359.384 -3.137 360.509 -3.137 QT\n362.228 -3.137 363.704 -2.41 QT\n365.181 -1.683 366.048 -0.355 QT\n366.915 0.973 366.915 2.738 QT\n366.915 4.051 366.337 5.223 QT\n365.759 6.395 364.868 7.348 QT\n363.978 8.301 362.587 9.52 QT\n361.197 10.738 360.759 11.145 QT\n357.353 14.41 L\n360.243 14.41 L\n362.368 14.41 363.798 14.379 QT\n365.228 14.348 365.306 14.27 QT\n365.665 13.895 366.025 11.504 QT\n366.915 11.504 L\n366.056 16.848 L\n354.931 16.848 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 184.0765] CT\r\nN\r\n385.945 4.649 M\n385.586 4.649 385.359 4.383 QT\n385.133 4.118 385.133 3.79 QT\n385.133 3.446 385.359 3.188 QT\n385.586 2.93 385.945 2.93 QT\n412.945 2.93 L\n413.258 2.93 413.492 3.188 QT\n413.726 3.446 413.726 3.79 QT\n413.726 4.118 413.492 4.383 QT\n413.258 4.649 412.945 4.649 QT\n385.945 4.649 L\ncp\n385.945 -3.695 M\n385.586 -3.695 385.359 -3.952 QT\n385.133 -4.21 385.133 -4.554 QT\n385.133 -4.882 385.359 -5.156 QT\n385.586 -5.429 385.945 -5.429 QT\n412.945 -5.429 L\n413.258 -5.429 413.492 -5.156 QT\n413.726 -4.882 413.726 -4.554 QT\n413.726 -4.21 413.492 -3.952 QT\n413.258 -3.695 412.945 -3.695 QT\n385.945 -3.695 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 184.0765] CT\r\nN\r\n439.06 11.305 M\n433.795 11.305 431.896 6.969 QT\n429.998 2.633 429.998 -3.335 QT\n429.998 -7.085 430.678 -10.382 QT\n431.357 -13.679 433.381 -15.976 QT\n435.404 -18.273 439.06 -18.273 QT\n441.889 -18.273 443.701 -16.89 QT\n445.514 -15.507 446.451 -13.312 QT\n447.389 -11.117 447.74 -8.609 QT\n448.092 -6.101 448.092 -3.335 QT\n448.092 0.352 447.404 3.579 QT\n446.717 6.805 444.724 9.055 QT\n442.732 11.305 439.06 11.305 QT\ncp\n439.06 10.196 M\n441.451 10.196 442.631 7.743 QT\n443.81 5.29 444.084 2.305 QT\n444.357 -0.679 444.357 -4.038 QT\n444.357 -7.273 444.084 -9.999 QT\n443.81 -12.726 442.646 -14.945 QT\n441.482 -17.163 439.06 -17.163 QT\n436.623 -17.163 435.451 -14.937 QT\n434.279 -12.71 434.006 -9.992 QT\n433.732 -7.273 433.732 -4.038 QT\n433.732 -1.648 433.842 0.477 QT\n433.951 2.602 434.459 4.86 QT\n434.967 7.118 436.092 8.657 QT\n437.217 10.196 439.06 10.196 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 184.0765] CT\r\nN\r\n453.52 7.993 M\n453.52 7.024 454.239 6.337 QT\n454.957 5.649 455.895 5.649 QT\n456.489 5.649 457.051 5.962 QT\n457.614 6.274 457.926 6.844 QT\n458.239 7.415 458.239 7.993 QT\n458.239 8.946 457.551 9.657 QT\n456.864 10.368 455.895 10.368 QT\n454.957 10.368 454.239 9.657 QT\n453.52 8.946 453.52 7.993 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 184.0765] CT\r\nN\r\n463.114 3.274 M\n463.114 1.758 L\n476.395 -18.054 L\n476.551 -18.273 476.832 -18.273 QT\n477.473 -18.273 L\n477.957 -18.273 477.957 -17.788 QT\n477.957 1.758 L\n482.176 1.758 L\n482.176 3.274 L\n477.957 3.274 L\n477.957 7.493 L\n477.957 8.368 479.215 8.61 QT\n480.473 8.852 482.129 8.852 QT\n482.129 10.368 L\n470.286 10.368 L\n470.286 8.852 L\n471.942 8.852 473.207 8.61 QT\n474.473 8.368 474.473 7.493 QT\n474.473 3.274 L\n463.114 3.274 L\ncp\n464.536 1.758 M\n474.723 1.758 L\n474.723 -13.46 L\n464.536 1.758 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n5.333 LW\r\nN\r\n502.007 490.871 M\n582.074 490.871 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 203.85883] CT\r\nN\r\n/f-1698885829{2.016 10.368 M\n1.594 10.368 1.594 9.805 QT\n1.609 9.696 1.68 9.43 QT\n1.75 9.165 1.859 9.008 QT\n1.969 8.852 2.141 8.852 QT\n6.25 8.852 6.922 6.227 QT\n12.766 -17.288 L\n11.563 -17.492 8.984 -17.492 QT\n8.563 -17.492 8.563 -18.054 QT\n8.594 -18.163 8.656 -18.429 QT\n8.719 -18.695 8.828 -18.851 QT\n8.938 -19.007 9.109 -19.007 QT\n16.547 -19.007 L\n16.859 -19.007 16.938 -18.726 QT\n26.5 4.008 L\n31.266 -15.038 L\n31.344 -15.507 31.344 -15.695 QT\n31.344 -17.492 28.031 -17.492 QT\n27.609 -17.492 27.609 -18.054 QT\n27.75 -18.601 27.836 -18.804 QT\n27.922 -19.007 28.344 -19.007 QT\n37.547 -19.007 L\n37.969 -19.007 37.969 -18.445 QT\n37.938 -18.335 37.875 -18.07 QT\n37.813 -17.804 37.695 -17.648 QT\n37.578 -17.492 37.422 -17.492 QT\n33.297 -17.492 32.625 -14.867 QT\n26.453 9.993 L\n26.313 10.368 26.016 10.368 QT\n25.484 10.368 L\n25.203 10.368 25.109 10.071 QT\n14.156 -15.945 L\n14.063 -16.21 L\n13.984 -16.304 13.984 -16.335 QT\n8.297 6.415 L\n8.25 6.524 8.227 6.68 QT\n8.203 6.837 8.172 7.055 QT\n8.172 8.165 9.133 8.508 QT\n10.094 8.852 11.531 8.852 QT\n11.953 8.852 11.953 9.43 QT\n11.797 10.008 11.695 10.188 QT\n11.594 10.368 11.234 10.368 QT\n2.016 10.368 L\ncp}def\r\nf-1698885829\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 203.85883] CT\r\nN\r\n/f-1758447675{54.654 4.649 M\n54.295 4.649 54.068 4.383 QT\n53.841 4.118 53.841 3.79 QT\n53.841 3.446 54.068 3.188 QT\n54.295 2.93 54.654 2.93 QT\n81.654 2.93 L\n81.966 2.93 82.201 3.188 QT\n82.435 3.446 82.435 3.79 QT\n82.435 4.118 82.201 4.383 QT\n81.966 4.649 81.654 4.649 QT\n54.654 4.649 L\ncp\n54.654 -3.695 M\n54.295 -3.695 54.068 -3.952 QT\n53.841 -4.21 53.841 -4.554 QT\n53.841 -4.882 54.068 -5.156 QT\n54.295 -5.429 54.654 -5.429 QT\n81.654 -5.429 L\n81.966 -5.429 82.201 -5.156 QT\n82.435 -4.882 82.435 -4.554 QT\n82.435 -4.21 82.201 -3.952 QT\n81.966 -3.695 81.654 -3.695 QT\n54.654 -3.695 L\ncp}def\r\nf-1758447675\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 203.85883] CT\r\nN\r\n/f-2127470435{99.16 10.368 M\n99.16 9.212 L\n99.16 9.102 99.238 8.977 QT\n105.926 1.587 L\n107.441 -0.054 108.379 -1.163 QT\n109.316 -2.273 110.246 -3.718 QT\n111.176 -5.163 111.707 -6.671 QT\n112.238 -8.179 112.238 -9.851 QT\n112.238 -11.617 111.59 -13.226 QT\n110.941 -14.835 109.652 -15.796 QT\n108.363 -16.757 106.535 -16.757 QT\n104.66 -16.757 103.168 -15.632 QT\n101.676 -14.507 101.066 -12.726 QT\n101.238 -12.773 101.535 -12.773 QT\n102.504 -12.773 103.183 -12.124 QT\n103.863 -11.476 103.863 -10.445 QT\n103.863 -9.46 103.183 -8.773 QT\n102.504 -8.085 101.535 -8.085 QT\n100.519 -8.085 99.84 -8.788 QT\n99.16 -9.492 99.16 -10.445 QT\n99.16 -12.054 99.769 -13.476 QT\n100.379 -14.898 101.519 -15.999 QT\n102.66 -17.101 104.105 -17.687 QT\n105.551 -18.273 107.16 -18.273 QT\n109.613 -18.273 111.738 -17.234 QT\n113.863 -16.195 115.098 -14.296 QT\n116.332 -12.398 116.332 -9.851 QT\n116.332 -7.976 115.512 -6.296 QT\n114.691 -4.617 113.418 -3.242 QT\n112.144 -1.867 110.144 -0.124 QT\n108.144 1.618 107.519 2.196 QT\n102.644 6.883 L\n106.785 6.883 L\n109.832 6.883 111.879 6.829 QT\n113.926 6.774 114.051 6.665 QT\n114.551 6.133 115.082 2.712 QT\n116.332 2.712 L\n115.113 10.368 L\n99.16 10.368 L\ncp}def\r\nf-2127470435\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 203.85883] CT\r\nN\r\n/f-2019066066{119.823 3.274 M\n119.823 1.758 L\n133.104 -18.054 L\n133.26 -18.273 133.541 -18.273 QT\n134.182 -18.273 L\n134.666 -18.273 134.666 -17.788 QT\n134.666 1.758 L\n138.885 1.758 L\n138.885 3.274 L\n134.666 3.274 L\n134.666 7.493 L\n134.666 8.368 135.924 8.61 QT\n137.182 8.852 138.838 8.852 QT\n138.838 10.368 L\n126.994 10.368 L\n126.994 8.852 L\n128.651 8.852 129.916 8.61 QT\n131.182 8.368 131.182 7.493 QT\n131.182 3.274 L\n119.823 3.274 L\ncp\n121.244 1.758 M\n131.432 1.758 L\n131.432 -13.46 L\n121.244 1.758 L\ncp}def\r\nf-2019066066\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 203.85883] CT\r\nN\r\n/f-1779188984{144.485 18.118 M\n144.485 17.93 144.657 17.758 QT\n146.204 16.274 147.063 14.321 QT\n147.923 12.368 147.923 10.196 QT\n147.923 9.68 L\n147.235 10.368 146.204 10.368 QT\n145.22 10.368 144.524 9.673 QT\n143.829 8.977 143.829 7.993 QT\n143.829 6.993 144.524 6.321 QT\n145.22 5.649 146.204 5.649 QT\n147.735 5.649 148.384 7.063 QT\n149.032 8.477 149.032 10.196 QT\n149.032 12.587 148.079 14.743 QT\n147.126 16.899 145.391 18.618 QT\n145.22 18.696 145.11 18.696 QT\n144.907 18.696 144.696 18.508 QT\n144.485 18.321 144.485 18.118 QT\ncp}def\r\nf-1779188984\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 203.85883] CT\r\nN\r\n/f2034987691{172.107 18.79 M\n172.107 17.821 172.537 15.977 QT\n172.966 14.133 173.583 12.04 QT\n174.201 9.946 174.638 8.602 QT\n174.81 6.462 174.81 5.368 QT\n174.81 2.602 174.263 0.219 QT\n173.716 -2.163 172.208 -3.773 QT\n170.701 -5.382 167.982 -5.382 QT\n166.56 -5.382 165.138 -4.773 QT\n163.716 -4.163 162.701 -3.07 QT\n161.685 -1.976 161.31 -0.585 QT\n161.232 -0.335 160.966 -0.335 QT\n160.451 -0.335 L\n160.107 -0.335 160.107 -0.726 QT\n160.107 -0.867 L\n160.591 -2.804 161.818 -4.593 QT\n163.044 -6.382 164.826 -7.507 QT\n166.607 -8.632 168.576 -8.632 QT\n170.591 -8.632 172.06 -7.265 QT\n173.529 -5.898 174.412 -3.804 QT\n175.294 -1.71 175.685 0.43 QT\n176.076 2.571 176.076 4.462 QT\n178.232 -1.413 180.919 -6.663 QT\n181.576 -8.038 L\n181.701 -8.179 181.857 -8.179 QT\n182.388 -8.179 L\n182.732 -8.179 182.732 -7.773 QT\n182.732 -7.695 182.638 -7.523 QT\n181.998 -6.179 L\n180.123 -2.46 178.56 1.36 QT\n176.998 5.18 175.888 8.727 QT\n175.716 10.18 175.24 12.696 QT\n174.763 15.212 174.091 17.391 QT\n173.419 19.571 172.748 19.649 QT\n172.107 19.649 172.107 18.79 QT\ncp}def\r\nf2034987691\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 203.85883] CT\r\nN\r\n/f-173962665{184.567 16.848 M\n184.567 15.785 L\n188.317 15.785 188.317 14.848 QT\n188.317 -0.902 L\n186.77 -0.152 184.395 -0.152 QT\n184.395 -1.215 L\n188.067 -1.215 189.942 -3.137 QT\n190.363 -3.137 L\n190.473 -3.137 190.567 -3.051 QT\n190.66 -2.965 190.66 -2.871 QT\n190.66 14.848 L\n190.66 15.785 194.41 15.785 QT\n194.41 16.848 L\n184.567 16.848 L\ncp}def\r\nf-173962665\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 203.85883] CT\r\nN\r\n/f-988291271{214.299 4.649 M\n213.94 4.649 213.714 4.383 QT\n213.487 4.118 213.487 3.79 QT\n213.487 3.446 213.714 3.188 QT\n213.94 2.93 214.299 2.93 QT\n241.299 2.93 L\n241.612 2.93 241.846 3.188 QT\n242.081 3.446 242.081 3.79 QT\n242.081 4.118 241.846 4.383 QT\n241.612 4.649 241.299 4.649 QT\n214.299 4.649 L\ncp\n214.299 -3.695 M\n213.94 -3.695 213.714 -3.952 QT\n213.487 -4.21 213.487 -4.554 QT\n213.487 -4.882 213.714 -5.156 QT\n213.94 -5.429 214.299 -5.429 QT\n241.299 -5.429 L\n241.612 -5.429 241.846 -5.156 QT\n242.081 -4.882 242.081 -4.554 QT\n242.081 -4.21 241.846 -3.952 QT\n241.612 -3.695 241.299 -3.695 QT\n214.299 -3.695 L\ncp}def\r\nf-988291271\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 203.85883] CT\r\nN\r\n/f2141106481{267.415 11.305 M\n262.149 11.305 260.251 6.969 QT\n258.352 2.633 258.352 -3.335 QT\n258.352 -7.085 259.032 -10.382 QT\n259.712 -13.679 261.735 -15.976 QT\n263.759 -18.273 267.415 -18.273 QT\n270.243 -18.273 272.056 -16.89 QT\n273.868 -15.507 274.806 -13.312 QT\n275.743 -11.117 276.095 -8.609 QT\n276.446 -6.101 276.446 -3.335 QT\n276.446 0.352 275.759 3.579 QT\n275.071 6.805 273.079 9.055 QT\n271.087 11.305 267.415 11.305 QT\ncp\n267.415 10.196 M\n269.806 10.196 270.985 7.743 QT\n272.165 5.29 272.438 2.305 QT\n272.712 -0.679 272.712 -4.038 QT\n272.712 -7.273 272.438 -9.999 QT\n272.165 -12.726 271.001 -14.945 QT\n269.837 -17.163 267.415 -17.163 QT\n264.977 -17.163 263.806 -14.937 QT\n262.634 -12.71 262.36 -9.992 QT\n262.087 -7.273 262.087 -4.038 QT\n262.087 -1.648 262.196 0.477 QT\n262.306 2.602 262.813 4.86 QT\n263.321 7.118 264.446 8.657 QT\n265.571 10.196 267.415 10.196 QT\ncp}def\r\nf2141106481\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 203.85883] CT\r\nN\r\n/f-689209901{281.874 7.993 M\n281.874 7.024 282.593 6.337 QT\n283.312 5.649 284.249 5.649 QT\n284.843 5.649 285.406 5.962 QT\n285.968 6.274 286.281 6.844 QT\n286.593 7.415 286.593 7.993 QT\n286.593 8.946 285.906 9.657 QT\n285.218 10.368 284.249 10.368 QT\n283.312 10.368 282.593 9.657 QT\n281.874 8.946 281.874 7.993 QT\ncp}def\r\nf-689209901\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 203.85883] CT\r\nN\r\n/f-830940872{301.015 11.305 M\n298.343 11.305 296.562 9.891 QT\n294.781 8.477 293.804 6.219 QT\n292.828 3.962 292.453 1.485 QT\n292.078 -0.992 292.078 -3.538 QT\n292.078 -6.929 293.398 -10.351 QT\n294.718 -13.773 297.288 -16.023 QT\n299.859 -18.273 303.39 -18.273 QT\n304.859 -18.273 306.132 -17.718 QT\n307.406 -17.163 308.124 -16.077 QT\n308.843 -14.992 308.843 -13.46 QT\n308.843 -12.585 308.249 -11.984 QT\n307.656 -11.382 306.765 -11.382 QT\n305.921 -11.382 305.32 -11.992 QT\n304.718 -12.601 304.718 -13.46 QT\n304.718 -14.304 305.32 -14.913 QT\n305.921 -15.523 306.765 -15.523 QT\n306.999 -15.523 L\n306.453 -16.304 305.453 -16.671 QT\n304.453 -17.038 303.39 -17.038 QT\n302.093 -17.038 300.984 -16.468 QT\n299.874 -15.898 298.999 -14.929 QT\n298.124 -13.96 297.531 -12.796 QT\n296.937 -11.632 296.617 -10.14 QT\n296.296 -8.648 296.21 -7.351 QT\n296.124 -6.054 296.124 -4.085 QT\n296.874 -5.835 298.265 -6.96 QT\n299.656 -8.085 301.39 -8.085 QT\n303.296 -8.085 304.874 -7.312 QT\n306.453 -6.538 307.585 -5.163 QT\n308.718 -3.788 309.32 -2.023 QT\n309.921 -0.257 309.921 1.555 QT\n309.921 4.071 308.796 6.344 QT\n307.671 8.618 305.632 9.962 QT\n303.593 11.305 301.015 11.305 QT\ncp\n301.015 9.946 M\n302.671 9.946 303.679 9.188 QT\n304.687 8.43 305.163 7.18 QT\n305.64 5.93 305.749 4.665 QT\n305.859 3.399 305.859 1.555 QT\n305.859 -0.882 305.632 -2.609 QT\n305.406 -4.335 304.374 -5.648 QT\n303.343 -6.96 301.218 -6.96 QT\n299.484 -6.96 298.359 -5.781 QT\n297.234 -4.601 296.718 -2.804 QT\n296.203 -1.007 296.203 0.649 QT\n296.203 1.212 296.249 1.508 QT\n296.249 1.571 296.242 1.61 QT\n296.234 1.649 296.203 1.712 QT\n296.203 3.571 296.585 5.454 QT\n296.968 7.337 298.038 8.641 QT\n299.109 9.946 301.015 9.946 QT\ncp}def\r\nf-830940872\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 203.85883] CT\r\nN\r\n/f1312883481{316.131 18.118 M\n316.131 17.93 316.303 17.758 QT\n317.849 16.274 318.709 14.321 QT\n319.568 12.368 319.568 10.196 QT\n319.568 9.68 L\n318.881 10.368 317.849 10.368 QT\n316.865 10.368 316.17 9.673 QT\n315.474 8.977 315.474 7.993 QT\n315.474 6.993 316.17 6.321 QT\n316.865 5.649 317.849 5.649 QT\n319.381 5.649 320.029 7.063 QT\n320.678 8.477 320.678 10.196 QT\n320.678 12.587 319.724 14.743 QT\n318.771 16.899 317.037 18.618 QT\n316.865 18.696 316.756 18.696 QT\n316.553 18.696 316.342 18.508 QT\n316.131 18.321 316.131 18.118 QT\ncp}def\r\nf1312883481\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 203.85883] CT\r\nN\r\n/f1797501460{343.752 18.79 M\n343.752 17.821 344.182 15.977 QT\n344.612 14.133 345.229 12.04 QT\n345.846 9.946 346.284 8.602 QT\n346.456 6.462 346.456 5.368 QT\n346.456 2.602 345.909 0.219 QT\n345.362 -2.163 343.854 -3.773 QT\n342.346 -5.382 339.627 -5.382 QT\n338.206 -5.382 336.784 -4.773 QT\n335.362 -4.163 334.346 -3.07 QT\n333.331 -1.976 332.956 -0.585 QT\n332.877 -0.335 332.612 -0.335 QT\n332.096 -0.335 L\n331.752 -0.335 331.752 -0.726 QT\n331.752 -0.867 L\n332.237 -2.804 333.463 -4.593 QT\n334.69 -6.382 336.471 -7.507 QT\n338.252 -8.632 340.221 -8.632 QT\n342.237 -8.632 343.706 -7.265 QT\n345.174 -5.898 346.057 -3.804 QT\n346.94 -1.71 347.331 0.43 QT\n347.721 2.571 347.721 4.462 QT\n349.877 -1.413 352.565 -6.663 QT\n353.221 -8.038 L\n353.346 -8.179 353.502 -8.179 QT\n354.034 -8.179 L\n354.377 -8.179 354.377 -7.773 QT\n354.377 -7.695 354.284 -7.523 QT\n353.643 -6.179 L\n351.768 -2.46 350.206 1.36 QT\n348.643 5.18 347.534 8.727 QT\n347.362 10.18 346.885 12.696 QT\n346.409 15.212 345.737 17.391 QT\n345.065 19.571 344.393 19.649 QT\n343.752 19.649 343.752 18.79 QT\ncp}def\r\nf1797501460\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 203.85883] CT\r\nN\r\n/f1851169393{354.931 16.848 M\n354.931 16.035 L\n354.931 15.973 354.978 15.879 QT\n359.65 10.723 L\n360.697 9.582 361.353 8.809 QT\n362.009 8.035 362.657 7.02 QT\n363.306 6.004 363.681 4.957 QT\n364.056 3.91 364.056 2.738 QT\n364.056 1.504 363.603 0.387 QT\n363.15 -0.73 362.243 -1.402 QT\n361.337 -2.074 360.072 -2.074 QT\n358.759 -2.074 357.72 -1.293 QT\n356.681 -0.512 356.259 0.738 QT\n356.368 0.707 356.587 0.707 QT\n357.259 0.707 357.736 1.16 QT\n358.212 1.613 358.212 2.332 QT\n358.212 3.02 357.736 3.496 QT\n357.259 3.973 356.587 3.973 QT\n355.884 3.973 355.407 3.481 QT\n354.931 2.988 354.931 2.332 QT\n354.931 1.207 355.353 0.215 QT\n355.775 -0.777 356.572 -1.543 QT\n357.368 -2.308 358.376 -2.723 QT\n359.384 -3.137 360.509 -3.137 QT\n362.228 -3.137 363.704 -2.41 QT\n365.181 -1.683 366.048 -0.355 QT\n366.915 0.973 366.915 2.738 QT\n366.915 4.051 366.337 5.223 QT\n365.759 6.395 364.868 7.348 QT\n363.978 8.301 362.587 9.52 QT\n361.197 10.738 360.759 11.145 QT\n357.353 14.41 L\n360.243 14.41 L\n362.368 14.41 363.798 14.379 QT\n365.228 14.348 365.306 14.27 QT\n365.665 13.895 366.025 11.504 QT\n366.915 11.504 L\n366.056 16.848 L\n354.931 16.848 L\ncp}def\r\nf1851169393\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 203.85883] CT\r\nN\r\n/f464326539{385.945 4.649 M\n385.586 4.649 385.359 4.383 QT\n385.133 4.118 385.133 3.79 QT\n385.133 3.446 385.359 3.188 QT\n385.586 2.93 385.945 2.93 QT\n412.945 2.93 L\n413.258 2.93 413.492 3.188 QT\n413.726 3.446 413.726 3.79 QT\n413.726 4.118 413.492 4.383 QT\n413.258 4.649 412.945 4.649 QT\n385.945 4.649 L\ncp\n385.945 -3.695 M\n385.586 -3.695 385.359 -3.952 QT\n385.133 -4.21 385.133 -4.554 QT\n385.133 -4.882 385.359 -5.156 QT\n385.586 -5.429 385.945 -5.429 QT\n412.945 -5.429 L\n413.258 -5.429 413.492 -5.156 QT\n413.726 -4.882 413.726 -4.554 QT\n413.726 -4.21 413.492 -3.952 QT\n413.258 -3.695 412.945 -3.695 QT\n385.945 -3.695 L\ncp}def\r\nf464326539\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 203.85883] CT\r\nN\r\n/f769333717{439.06 11.305 M\n433.795 11.305 431.896 6.969 QT\n429.998 2.633 429.998 -3.335 QT\n429.998 -7.085 430.678 -10.382 QT\n431.357 -13.679 433.381 -15.976 QT\n435.404 -18.273 439.06 -18.273 QT\n441.889 -18.273 443.701 -16.89 QT\n445.514 -15.507 446.451 -13.312 QT\n447.389 -11.117 447.74 -8.609 QT\n448.092 -6.101 448.092 -3.335 QT\n448.092 0.352 447.404 3.579 QT\n446.717 6.805 444.724 9.055 QT\n442.732 11.305 439.06 11.305 QT\ncp\n439.06 10.196 M\n441.451 10.196 442.631 7.743 QT\n443.81 5.29 444.084 2.305 QT\n444.357 -0.679 444.357 -4.038 QT\n444.357 -7.273 444.084 -9.999 QT\n443.81 -12.726 442.646 -14.945 QT\n441.482 -17.163 439.06 -17.163 QT\n436.623 -17.163 435.451 -14.937 QT\n434.279 -12.71 434.006 -9.992 QT\n433.732 -7.273 433.732 -4.038 QT\n433.732 -1.648 433.842 0.477 QT\n433.951 2.602 434.459 4.86 QT\n434.967 7.118 436.092 8.657 QT\n437.217 10.196 439.06 10.196 QT\ncp}def\r\nf769333717\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 203.85883] CT\r\nN\r\n/f187970572{453.52 7.993 M\n453.52 7.024 454.239 6.337 QT\n454.957 5.649 455.895 5.649 QT\n456.489 5.649 457.051 5.962 QT\n457.614 6.274 457.926 6.844 QT\n458.239 7.415 458.239 7.993 QT\n458.239 8.946 457.551 9.657 QT\n456.864 10.368 455.895 10.368 QT\n454.957 10.368 454.239 9.657 QT\n453.52 8.946 453.52 7.993 QT\ncp}def\r\nf187970572\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 203.85883] CT\r\nN\r\n/f-1662342170{472.661 11.305 M\n469.989 11.305 468.207 9.891 QT\n466.426 8.477 465.45 6.219 QT\n464.473 3.962 464.098 1.485 QT\n463.723 -0.992 463.723 -3.538 QT\n463.723 -6.929 465.043 -10.351 QT\n466.364 -13.773 468.934 -16.023 QT\n471.504 -18.273 475.036 -18.273 QT\n476.504 -18.273 477.778 -17.718 QT\n479.051 -17.163 479.77 -16.077 QT\n480.489 -14.992 480.489 -13.46 QT\n480.489 -12.585 479.895 -11.984 QT\n479.301 -11.382 478.411 -11.382 QT\n477.567 -11.382 476.965 -11.992 QT\n476.364 -12.601 476.364 -13.46 QT\n476.364 -14.304 476.965 -14.913 QT\n477.567 -15.523 478.411 -15.523 QT\n478.645 -15.523 L\n478.098 -16.304 477.098 -16.671 QT\n476.098 -17.038 475.036 -17.038 QT\n473.739 -17.038 472.629 -16.468 QT\n471.52 -15.898 470.645 -14.929 QT\n469.77 -13.96 469.176 -12.796 QT\n468.582 -11.632 468.262 -10.14 QT\n467.942 -8.648 467.856 -7.351 QT\n467.77 -6.054 467.77 -4.085 QT\n468.52 -5.835 469.911 -6.96 QT\n471.301 -8.085 473.036 -8.085 QT\n474.942 -8.085 476.52 -7.312 QT\n478.098 -6.538 479.231 -5.163 QT\n480.364 -3.788 480.965 -2.023 QT\n481.567 -0.257 481.567 1.555 QT\n481.567 4.071 480.442 6.344 QT\n479.317 8.618 477.278 9.962 QT\n475.239 11.305 472.661 11.305 QT\ncp\n472.661 9.946 M\n474.317 9.946 475.325 9.188 QT\n476.332 8.43 476.809 7.18 QT\n477.286 5.93 477.395 4.665 QT\n477.504 3.399 477.504 1.555 QT\n477.504 -0.882 477.278 -2.609 QT\n477.051 -4.335 476.02 -5.648 QT\n474.989 -6.96 472.864 -6.96 QT\n471.129 -6.96 470.004 -5.781 QT\n468.879 -4.601 468.364 -2.804 QT\n467.848 -1.007 467.848 0.649 QT\n467.848 1.212 467.895 1.508 QT\n467.895 1.571 467.887 1.61 QT\n467.879 1.649 467.848 1.712 QT\n467.848 3.571 468.231 5.454 QT\n468.614 7.337 469.684 8.641 QT\n470.754 9.946 472.661 9.946 QT\ncp}def\r\nf-1662342170\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n502.007 543.624 M\n582.074 543.624 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 223.64117] CT\r\nN\r\nf-1698885829\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 223.64117] CT\r\nN\r\nf-1758447675\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 223.64117] CT\r\nN\r\n/f1717920742{101.004 10.368 M\n101.004 8.852 L\n106.379 8.852 106.379 7.493 QT\n106.379 -15.085 L\n104.16 -14.007 100.754 -14.007 QT\n100.754 -15.523 L\n106.019 -15.523 108.707 -18.273 QT\n109.316 -18.273 L\n109.473 -18.273 109.605 -18.156 QT\n109.738 -18.038 109.738 -17.898 QT\n109.738 7.493 L\n109.738 8.852 115.113 8.852 QT\n115.113 10.368 L\n101.004 10.368 L\ncp}def\r\nf1717920742\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 223.64117] CT\r\nN\r\n/f-1038411071{129.369 11.305 M\n126.698 11.305 124.916 9.891 QT\n123.135 8.477 122.159 6.219 QT\n121.182 3.962 120.807 1.485 QT\n120.432 -0.992 120.432 -3.538 QT\n120.432 -6.929 121.752 -10.351 QT\n123.073 -13.773 125.643 -16.023 QT\n128.213 -18.273 131.744 -18.273 QT\n133.213 -18.273 134.487 -17.718 QT\n135.76 -17.163 136.479 -16.077 QT\n137.198 -14.992 137.198 -13.46 QT\n137.198 -12.585 136.604 -11.984 QT\n136.01 -11.382 135.119 -11.382 QT\n134.276 -11.382 133.674 -11.992 QT\n133.073 -12.601 133.073 -13.46 QT\n133.073 -14.304 133.674 -14.913 QT\n134.276 -15.523 135.119 -15.523 QT\n135.354 -15.523 L\n134.807 -16.304 133.807 -16.671 QT\n132.807 -17.038 131.744 -17.038 QT\n130.448 -17.038 129.338 -16.468 QT\n128.229 -15.898 127.354 -14.929 QT\n126.479 -13.96 125.885 -12.796 QT\n125.291 -11.632 124.971 -10.14 QT\n124.651 -8.648 124.565 -7.351 QT\n124.479 -6.054 124.479 -4.085 QT\n125.229 -5.835 126.619 -6.96 QT\n128.01 -8.085 129.744 -8.085 QT\n131.651 -8.085 133.229 -7.312 QT\n134.807 -6.538 135.94 -5.163 QT\n137.073 -3.788 137.674 -2.023 QT\n138.276 -0.257 138.276 1.555 QT\n138.276 4.071 137.151 6.344 QT\n136.026 8.618 133.987 9.962 QT\n131.948 11.305 129.369 11.305 QT\ncp\n129.369 9.946 M\n131.026 9.946 132.034 9.188 QT\n133.041 8.43 133.518 7.18 QT\n133.994 5.93 134.104 4.665 QT\n134.213 3.399 134.213 1.555 QT\n134.213 -0.882 133.987 -2.609 QT\n133.76 -4.335 132.729 -5.648 QT\n131.698 -6.96 129.573 -6.96 QT\n127.838 -6.96 126.713 -5.781 QT\n125.588 -4.601 125.073 -2.804 QT\n124.557 -1.007 124.557 0.649 QT\n124.557 1.212 124.604 1.508 QT\n124.604 1.571 124.596 1.61 QT\n124.588 1.649 124.557 1.712 QT\n124.557 3.571 124.94 5.454 QT\n125.323 7.337 126.393 8.641 QT\n127.463 9.946 129.369 9.946 QT\ncp}def\r\nf-1038411071\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 223.64117] CT\r\nN\r\nf-1779188984\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 223.64117] CT\r\nN\r\nf2034987691\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 223.64117] CT\r\nN\r\nf-173962665\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 223.64117] CT\r\nN\r\nf-988291271\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 223.64117] CT\r\nN\r\nf2141106481\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 223.64117] CT\r\nN\r\nf-689209901\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 223.64117] CT\r\nN\r\n/f2096529930{291.468 3.274 M\n291.468 1.758 L\n304.749 -18.054 L\n304.906 -18.273 305.187 -18.273 QT\n305.828 -18.273 L\n306.312 -18.273 306.312 -17.788 QT\n306.312 1.758 L\n310.531 1.758 L\n310.531 3.274 L\n306.312 3.274 L\n306.312 7.493 L\n306.312 8.368 307.57 8.61 QT\n308.828 8.852 310.484 8.852 QT\n310.484 10.368 L\n298.64 10.368 L\n298.64 8.852 L\n300.296 8.852 301.562 8.61 QT\n302.828 8.368 302.828 7.493 QT\n302.828 3.274 L\n291.468 3.274 L\ncp\n292.89 1.758 M\n303.078 1.758 L\n303.078 -13.46 L\n292.89 1.758 L\ncp}def\r\nf2096529930\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 223.64117] CT\r\nN\r\nf1312883481\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 223.64117] CT\r\nN\r\nf1797501460\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 223.64117] CT\r\nN\r\nf1851169393\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 223.64117] CT\r\nN\r\nf464326539\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 223.64117] CT\r\nN\r\nf769333717\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 223.64117] CT\r\nN\r\nf187970572\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 223.64117] CT\r\nN\r\n/f306768704{463.114 3.274 M\n463.114 1.758 L\n476.395 -18.054 L\n476.551 -18.273 476.832 -18.273 QT\n477.473 -18.273 L\n477.957 -18.273 477.957 -17.788 QT\n477.957 1.758 L\n482.176 1.758 L\n482.176 3.274 L\n477.957 3.274 L\n477.957 7.493 L\n477.957 8.368 479.215 8.61 QT\n480.473 8.852 482.129 8.852 QT\n482.129 10.368 L\n470.286 10.368 L\n470.286 8.852 L\n471.942 8.852 473.207 8.61 QT\n474.473 8.368 474.473 7.493 QT\n474.473 3.274 L\n463.114 3.274 L\ncp\n464.536 1.758 M\n474.723 1.758 L\n474.723 -13.46 L\n464.536 1.758 L\ncp}def\r\nf306768704\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n502.007 596.376 M\n582.074 596.376 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 243.4235] CT\r\nN\r\nf-1698885829\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 243.4235] CT\r\nN\r\nf-1758447675\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 243.4235] CT\r\nN\r\nf1717920742\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 243.4235] CT\r\nN\r\nf-1038411071\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 243.4235] CT\r\nN\r\nf-1779188984\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 243.4235] CT\r\nN\r\nf2034987691\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 243.4235] CT\r\nN\r\nf-173962665\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 243.4235] CT\r\nN\r\nf-988291271\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 243.4235] CT\r\nN\r\nf2141106481\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 243.4235] CT\r\nN\r\nf-689209901\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 243.4235] CT\r\nN\r\nf-830940872\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 243.4235] CT\r\nN\r\nf1312883481\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 243.4235] CT\r\nN\r\nf1797501460\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 243.4235] CT\r\nN\r\nf1851169393\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 243.4235] CT\r\nN\r\nf464326539\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 243.4235] CT\r\nN\r\nf769333717\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 243.4235] CT\r\nN\r\nf187970572\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 220.52946 243.4235] CT\r\nN\r\nf-1662342170\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n502.007 649.129 M\n582.074 649.129 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n10.0 ML\r\n0.533 LW\r\nN\r\n494 679 M\n494 461 L\n1080 461 L\n1080 679 L\ncp\r\nS\r\nGR\r\n%%Trailer\r\n%%Pages: 1\r\n%%EOF\r\n"
  },
  {
    "path": "matlab/acc2023/closedloop_performance/figures/closedloop-snapshots2.eps",
    "content": "%!PS-Adobe-3.0 EPSF-3.0\r\n%%Creator: (MATLAB, The Mathworks, Inc. Version 9.10.0.1649659 \\(R2021a\\) Update 1. Operating System: Windows 10)\r\n%%Title: figures/closedloop-snapshots2.eps\r\n%%CreationDate: 2023-01-31T03:11:39\r\n%%Pages: (atend)\r\n%%BoundingBox:     1     2   417   300\r\n%%LanguageLevel: 3\r\n%%EndComments\r\n%%BeginProlog\r\n%%BeginResource: procset (Apache XML Graphics Std ProcSet) 1.2 0\r\n%%Version: 1.2 0\r\n%%Copyright: (Copyright 2001-2003,2010 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/bd{bind def}bind def\r\n/ld{load def}bd\r\n/GR/grestore ld\r\n/GS/gsave ld\r\n/RM/rmoveto ld\r\n/C/curveto ld\r\n/t/show ld\r\n/L/lineto ld\r\n/ML/setmiterlimit ld\r\n/CT/concat ld\r\n/f/fill ld\r\n/N/newpath ld\r\n/S/stroke ld\r\n/CC/setcmykcolor ld\r\n/A/ashow ld\r\n/cp/closepath ld\r\n/RC/setrgbcolor ld\r\n/LJ/setlinejoin ld\r\n/GC/setgray ld\r\n/LW/setlinewidth ld\r\n/M/moveto ld\r\n/re {4 2 roll M\r\n1 index 0 rlineto\r\n0 exch rlineto\r\nneg 0 rlineto\r\ncp } bd\r\n/_ctm matrix def\r\n/_tm matrix def\r\n/BT { _ctm currentmatrix pop matrix _tm copy pop 0 0 moveto } bd\r\n/ET { _ctm setmatrix } bd\r\n/iTm { _ctm setmatrix _tm concat } bd\r\n/Tm { _tm astore pop iTm 0 0 moveto } bd\r\n/ux 0.0 def\r\n/uy 0.0 def\r\n/F {\r\n  /Tp exch def\r\n  /Tf exch def\r\n  Tf findfont Tp scalefont setfont\r\n  /cf Tf def  /cs Tp def\r\n} bd\r\n/ULS {currentpoint /uy exch def /ux exch def} bd\r\n/ULE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add moveto  Tcx uy To add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/OLE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs add moveto Tcx uy To add cs add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/SOE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs 10 mul 26 idiv add moveto Tcx uy To add cs 10 mul 26 idiv add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/QT {\r\n/Y22 exch store\r\n/X22 exch store\r\n/Y21 exch store\r\n/X21 exch store\r\ncurrentpoint\r\n/Y21 load 2 mul add 3 div exch\r\n/X21 load 2 mul add 3 div exch\r\n/X21 load 2 mul /X22 load add 3 div\r\n/Y21 load 2 mul /Y22 load add 3 div\r\n/X22 load /Y22 load curveto\r\n} bd\r\n/SSPD {\r\ndup length /d exch dict def\r\n{\r\n/v exch def\r\n/k exch def\r\ncurrentpagedevice k known {\r\n/cpdv currentpagedevice k get def\r\nv cpdv ne {\r\n/upd false def\r\n/nullv v type /nulltype eq def\r\n/nullcpdv cpdv type /nulltype eq def\r\nnullv nullcpdv or\r\n{\r\n/upd true def\r\n} {\r\n/sametype v type cpdv type eq def\r\nsametype {\r\nv type /arraytype eq {\r\n/vlen v length def\r\n/cpdvlen cpdv length def\r\nvlen cpdvlen eq {\r\n0 1 vlen 1 sub {\r\n/i exch def\r\n/obj v i get def\r\n/cpdobj cpdv i get def\r\nobj cpdobj ne {\r\n/upd true def\r\nexit\r\n} if\r\n} for\r\n} {\r\n/upd true def\r\n} ifelse\r\n} {\r\nv type /dicttype eq {\r\nv {\r\n/dv exch def\r\n/dk exch def\r\n/cpddv cpdv dk get def\r\ndv cpddv ne {\r\n/upd true def\r\nexit\r\n} if\r\n} forall\r\n} {\r\n/upd true def\r\n} ifelse\r\n} ifelse\r\n} if\r\n} ifelse\r\nupd true eq {\r\nd k v put\r\n} if\r\n} if\r\n} if\r\n} forall\r\nd length 0 gt {\r\nd setpagedevice\r\n} if\r\n} bd\r\n/RE { % /NewFontName [NewEncodingArray] /FontName RE -\r\n  findfont dup length dict begin\r\n  {\r\n    1 index /FID ne\r\n    {def} {pop pop} ifelse\r\n  } forall\r\n  /Encoding exch def\r\n  /FontName 1 index def\r\n  currentdict definefont pop\r\n  end\r\n} bind def\r\n%%EndResource\r\n%%BeginResource: procset (Apache XML Graphics EPS ProcSet) 1.0 0\r\n%%Version: 1.0 0\r\n%%Copyright: (Copyright 2002-2003 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/BeginEPSF { %def\r\n/b4_Inc_state save def         % Save state for cleanup\r\n/dict_count countdictstack def % Count objects on dict stack\r\n/op_count count 1 sub def      % Count objects on operand stack\r\nuserdict begin                 % Push userdict on dict stack\r\n/showpage { } def              % Redefine showpage, { } = null proc\r\n0 setgray 0 setlinecap         % Prepare graphics state\r\n1 setlinewidth 0 setlinejoin\r\n10 setmiterlimit [ ] 0 setdash newpath\r\n/languagelevel where           % If level not equal to 1 then\r\n{pop languagelevel             % set strokeadjust and\r\n1 ne                           % overprint to their defaults.\r\n{false setstrokeadjust false setoverprint\r\n} if\r\n} if\r\n} bd\r\n/EndEPSF { %def\r\ncount op_count sub {pop} repeat            % Clean up stacks\r\ncountdictstack dict_count sub {end} repeat\r\nb4_Inc_state restore\r\n} bd\r\n%%EndResource\r\n%FOPBeginFontDict\r\n%%IncludeResource: font Courier-Oblique\r\n%%IncludeResource: font Courier-BoldOblique\r\n%%IncludeResource: font Courier-Bold\r\n%%IncludeResource: font ZapfDingbats\r\n%%IncludeResource: font Symbol\r\n%%IncludeResource: font Helvetica\r\n%%IncludeResource: font Helvetica-Oblique\r\n%%IncludeResource: font Helvetica-Bold\r\n%%IncludeResource: font Helvetica-BoldOblique\r\n%%IncludeResource: font Times-Roman\r\n%%IncludeResource: font Times-Italic\r\n%%IncludeResource: font Times-Bold\r\n%%IncludeResource: font Times-BoldItalic\r\n%%IncludeResource: font Courier\r\n%FOPEndFontDict\r\n%%BeginResource: encoding WinAnsiEncoding\r\n/WinAnsiEncoding [\r\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /space /exclam /quotedbl\n/numbersign /dollar /percent /ampersand /quotesingle\n/parenleft /parenright /asterisk /plus /comma\n/hyphen /period /slash /zero /one\n/two /three /four /five /six\n/seven /eight /nine /colon /semicolon\n/less /equal /greater /question /at\n/A /B /C /D /E\n/F /G /H /I /J\n/K /L /M /N /O\n/P /Q /R /S /T\n/U /V /W /X /Y\n/Z /bracketleft /backslash /bracketright /asciicircum\n/underscore /quoteleft /a /b /c\n/d /e /f /g /h\n/i /j /k /l /m\n/n /o /p /q /r\n/s /t /u /v /w\n/x /y /z /braceleft /bar\n/braceright /asciitilde /bullet /Euro /bullet\n/quotesinglbase /florin /quotedblbase /ellipsis /dagger\n/daggerdbl /circumflex /perthousand /Scaron /guilsinglleft\n/OE /bullet /Zcaron /bullet /bullet\n/quoteleft /quoteright /quotedblleft /quotedblright /bullet\n/endash /emdash /asciitilde /trademark /scaron\n/guilsinglright /oe /bullet /zcaron /Ydieresis\n/space /exclamdown /cent /sterling /currency\n/yen /brokenbar /section /dieresis /copyright\n/ordfeminine /guillemotleft /logicalnot /sfthyphen /registered\n/macron /degree /plusminus /twosuperior /threesuperior\n/acute /mu /paragraph /middot /cedilla\n/onesuperior /ordmasculine /guillemotright /onequarter /onehalf\n/threequarters /questiondown /Agrave /Aacute /Acircumflex\n/Atilde /Adieresis /Aring /AE /Ccedilla\n/Egrave /Eacute /Ecircumflex /Edieresis /Igrave\n/Iacute /Icircumflex /Idieresis /Eth /Ntilde\n/Ograve /Oacute /Ocircumflex /Otilde /Odieresis\n/multiply /Oslash /Ugrave /Uacute /Ucircumflex\n/Udieresis /Yacute /Thorn /germandbls /agrave\n/aacute /acircumflex /atilde /adieresis /aring\n/ae /ccedilla /egrave /eacute /ecircumflex\n/edieresis /igrave /iacute /icircumflex /idieresis\n/eth /ntilde /ograve /oacute /ocircumflex\n/otilde /odieresis /divide /oslash /ugrave\n/uacute /ucircumflex /udieresis /yacute /thorn\n/ydieresis\n] def\r\n%%EndResource\r\n%FOPBeginFontReencode\r\n/Courier-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Oblique exch definefont pop\r\n/Courier-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-BoldOblique exch definefont pop\r\n/Courier-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Bold exch definefont pop\r\n/Helvetica findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica exch definefont pop\r\n/Helvetica-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Oblique exch definefont pop\r\n/Helvetica-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Bold exch definefont pop\r\n/Helvetica-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-BoldOblique exch definefont pop\r\n/Times-Roman findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Roman exch definefont pop\r\n/Times-Italic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Italic exch definefont pop\r\n/Times-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Bold exch definefont pop\r\n/Times-BoldItalic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-BoldItalic exch definefont pop\r\n/Courier findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier exch definefont pop\r\n%FOPEndFontReencode\r\n%%EndProlog\r\n%%Page: 1 1\r\n%%PageBoundingBox: 0 0 420 315\r\n%%BeginPageSetup\r\n[1 0 0 -1 0 315] CT\r\n%%EndPageSetup\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n124 706.667 M\n1101 706.667 L\n1101 55.333 L\n124 55.333 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n124 706.667 M\n124 55.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n286.833 706.667 M\n286.833 55.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n449.667 706.667 M\n449.667 55.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n612.5 706.667 M\n612.5 55.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n775.333 706.667 M\n775.333 55.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n938.167 706.667 M\n938.167 55.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 706.667 M\n1101 55.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 706.667 M\n124 706.667 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 543.833 M\n124 543.833 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 381 M\n124 381 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 218.167 M\n124 218.167 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 55.333 M\n124 55.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n124 706.667 M\n1101 706.667 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n124 706.667 M\n124 696.897 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n286.833 706.667 M\n286.833 696.897 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n449.667 706.667 M\n449.667 696.897 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n612.5 706.667 M\n612.5 696.897 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n775.333 706.667 M\n775.333 696.897 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n938.167 706.667 M\n938.167 696.897 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 706.667 M\n1101 696.897 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 46.5 270.2] CT\r\n0.149 GC\r\n/Helvetica 42.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-19 43 moveto \r\n1 -1 scale\r\n(-3) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 107.5625 270.2] CT\r\n0.149 GC\r\n/Helvetica 42.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-19 43 moveto \r\n1 -1 scale\r\n(-2) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 168.625 270.2] CT\r\n0.149 GC\r\n/Helvetica 42.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-19 43 moveto \r\n1 -1 scale\r\n(-1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 229.6875 270.2] CT\r\n0.149 GC\r\n/Helvetica 42.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-12 43 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 290.74999 270.2] CT\r\n0.149 GC\r\n/Helvetica 42.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-12 43 moveto \r\n1 -1 scale\r\n(1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 351.81251 270.2] CT\r\n0.149 GC\r\n/Helvetica 42.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-12 43 moveto \r\n1 -1 scale\r\n(2) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.875 270.2] CT\r\n0.149 GC\r\n/Helvetica 42.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-12 43 moveto \r\n1 -1 scale\r\n(3) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 229.68768 291.075] CT\r\n0.149 GC\r\nN\r\n-55.255 43.269 M\n-54.317 44.003 -52.614 44.003 QT\n-50.958 44.003 -49.692 42.409 QT\n-48.426 40.815 -47.958 38.925 QT\n-45.551 29.534 L\n-44.973 26.972 -44.973 26.034 QT\n-44.973 24.722 -45.715 23.737 QT\n-46.458 22.753 -47.77 22.753 QT\n-49.458 22.753 -50.934 23.8 QT\n-52.411 24.847 -53.419 26.464 QT\n-54.426 28.081 -54.833 29.737 QT\n-54.942 30.081 -55.255 30.081 QT\n-55.895 30.081 L\n-56.317 30.081 -56.317 29.581 QT\n-56.317 29.425 L\n-55.801 27.456 -54.559 25.581 QT\n-53.317 23.706 -51.52 22.542 QT\n-49.723 21.378 -47.676 21.378 QT\n-45.723 21.378 -44.161 22.417 QT\n-42.598 23.456 -41.958 25.237 QT\n-41.051 23.612 -39.637 22.495 QT\n-38.223 21.378 -36.551 21.378 QT\n-35.411 21.378 -34.215 21.776 QT\n-33.02 22.175 -32.27 23.003 QT\n-31.52 23.831 -31.52 25.081 QT\n-31.52 26.425 -32.387 27.394 QT\n-33.255 28.362 -34.598 28.362 QT\n-35.458 28.362 -36.028 27.823 QT\n-36.598 27.284 -36.598 26.456 QT\n-36.598 25.331 -35.833 24.495 QT\n-35.067 23.659 -34.005 23.503 QT\n-34.958 22.753 -36.645 22.753 QT\n-38.348 22.753 -39.606 24.331 QT\n-40.864 25.909 -41.38 27.847 QT\n-43.708 37.222 L\n-44.286 39.347 -44.286 40.706 QT\n-44.286 42.05 -43.52 43.026 QT\n-42.755 44.003 -41.489 44.003 QT\n-39.005 44.003 -37.051 41.815 QT\n-35.098 39.628 -34.473 37.003 QT\n-34.364 36.706 -34.067 36.706 QT\n-33.411 36.706 L\n-33.208 36.706 -33.075 36.847 QT\n-32.942 36.987 -32.942 37.159 QT\n-32.942 37.222 -33.005 37.315 QT\n-33.755 40.472 -36.161 42.933 QT\n-38.567 45.394 -41.583 45.394 QT\n-43.536 45.394 -45.098 44.347 QT\n-46.661 43.3 -47.317 41.519 QT\n-48.145 43.065 -49.606 44.229 QT\n-51.067 45.394 -52.723 45.394 QT\n-53.864 45.394 -55.067 44.995 QT\n-56.27 44.597 -57.02 43.769 QT\n-57.77 42.94 -57.77 41.675 QT\n-57.77 40.425 -56.903 39.401 QT\n-56.036 38.378 -54.739 38.378 QT\n-53.864 38.378 -53.262 38.909 QT\n-52.661 39.44 -52.661 40.3 QT\n-52.661 41.409 -53.403 42.237 QT\n-54.145 43.065 -55.255 43.269 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 229.68768 291.075] CT\r\n0.149 GC\r\nN\r\n-12.476 57.94 M\n-15.429 55.612 -17.562 52.597 QT\n-19.695 49.581 -21.054 46.167 QT\n-22.414 42.753 -23.086 39.026 QT\n-23.757 35.3 -23.757 31.55 QT\n-23.757 27.753 -23.086 24.026 QT\n-22.414 20.3 -21.031 16.854 QT\n-19.648 13.409 -17.5 10.409 QT\n-15.351 7.409 -12.476 5.159 QT\n-12.476 5.05 -12.226 5.05 QT\n-11.726 5.05 L\n-11.57 5.05 -11.445 5.19 QT\n-11.32 5.331 -11.32 5.519 QT\n-11.32 5.753 -11.414 5.847 QT\n-14.007 8.394 -15.726 11.292 QT\n-17.445 14.19 -18.492 17.464 QT\n-19.539 20.737 -20.007 24.245 QT\n-20.476 27.753 -20.476 31.55 QT\n-20.476 48.394 -11.476 57.144 QT\n-11.32 57.3 -11.32 57.581 QT\n-11.32 57.706 -11.461 57.878 QT\n-11.601 58.05 -11.726 58.05 QT\n-12.226 58.05 L\n-12.476 58.05 -12.476 57.94 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 229.68768 291.075] CT\r\n0.149 GC\r\nN\r\n-4.079 43.894 M\n-4.079 43.581 -4.032 43.425 QT\n-0.079 27.612 L\n0.311 26.144 0.311 25.034 QT\n0.311 22.753 -1.235 22.753 QT\n-2.892 22.753 -3.696 24.729 QT\n-4.501 26.706 -5.251 29.737 QT\n-5.251 29.894 -5.407 29.987 QT\n-5.564 30.081 -5.689 30.081 QT\n-6.314 30.081 L\n-6.485 30.081 -6.618 29.886 QT\n-6.751 29.69 -6.751 29.534 QT\n-6.173 27.222 -5.649 25.62 QT\n-5.126 24.019 -3.993 22.698 QT\n-2.86 21.378 -1.189 21.378 QT\n0.811 21.378 2.335 22.636 QT\n3.858 23.894 3.858 25.831 QT\n5.436 23.753 7.561 22.565 QT\n9.686 21.378 12.061 21.378 QT\n14.577 21.378 16.397 22.659 QT\n18.218 23.94 18.218 26.3 QT\n19.858 23.987 22.046 22.683 QT\n24.233 21.378 26.811 21.378 QT\n29.561 21.378 31.226 22.87 QT\n32.89 24.362 32.89 27.097 QT\n32.89 29.269 31.921 32.347 QT\n30.952 35.425 29.515 39.237 QT\n28.749 41.065 28.749 42.425 QT\n28.749 44.003 29.999 44.003 QT\n32.061 44.003 33.436 41.776 QT\n34.811 39.55 35.374 37.003 QT\n35.53 36.706 35.827 36.706 QT\n36.436 36.706 L\n36.655 36.706 36.796 36.847 QT\n36.936 36.987 36.936 37.159 QT\n36.936 37.222 36.89 37.315 QT\n36.155 40.315 34.358 42.854 QT\n32.561 45.394 29.874 45.394 QT\n27.999 45.394 26.686 44.112 QT\n25.374 42.831 25.374 41.003 QT\n25.374 40.065 25.811 38.925 QT\n27.311 34.94 28.304 31.808 QT\n29.296 28.675 29.296 26.3 QT\n29.296 24.815 28.702 23.784 QT\n28.108 22.753 26.718 22.753 QT\n23.811 22.753 21.694 24.526 QT\n19.577 26.3 18.015 29.222 QT\n17.921 29.737 17.858 30.019 QT\n14.452 43.628 L\n14.265 44.362 13.632 44.878 QT\n12.999 45.394 12.218 45.394 QT\n11.593 45.394 11.116 44.979 QT\n10.64 44.565 10.64 43.894 QT\n10.64 43.581 10.686 43.425 QT\n14.077 29.925 L\n14.624 27.753 14.624 26.3 QT\n14.624 24.815 14.015 23.784 QT\n13.405 22.753 11.968 22.753 QT\n10.015 22.753 8.39 23.604 QT\n6.765 24.456 5.546 25.87 QT\n4.327 27.284 3.311 29.222 QT\n-0.282 43.628 L\n-0.454 44.362 -1.095 44.878 QT\n-1.735 45.394 -2.501 45.394 QT\n-3.157 45.394 -3.618 44.979 QT\n-4.079 44.565 -4.079 43.894 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 229.68768 291.075] CT\r\n0.149 GC\r\nN\r\n42.092 58.05 M\n41.623 58.05 41.623 57.581 QT\n41.623 57.347 41.733 57.253 QT\n50.795 48.394 50.795 31.55 QT\n50.795 14.706 41.842 5.956 QT\n41.623 5.831 41.623 5.519 QT\n41.623 5.331 41.772 5.19 QT\n41.92 5.05 42.092 5.05 QT\n42.592 5.05 L\n42.748 5.05 42.842 5.159 QT\n46.654 8.159 49.186 12.456 QT\n51.717 16.753 52.897 21.612 QT\n54.076 26.472 54.076 31.55 QT\n54.076 35.3 53.444 38.94 QT\n52.811 42.581 51.428 46.112 QT\n50.045 49.644 47.92 52.628 QT\n45.795 55.612 42.842 57.94 QT\n42.748 58.05 42.592 58.05 QT\n42.092 58.05 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n124 706.667 M\n124 55.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n124 706.667 M\n133.77 706.667 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n124 543.833 M\n133.77 543.833 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n124 381 M\n133.77 381 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n124 218.167 M\n133.77 218.167 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n124 55.333 M\n133.77 55.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 41.3 265.00001] CT\r\n0.149 GC\r\n/Helvetica 42.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-38 16.5 moveto \r\n1 -1 scale\r\n(-2) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 41.3 203.93749] CT\r\n0.149 GC\r\n/Helvetica 42.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-38 16.5 moveto \r\n1 -1 scale\r\n(-1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 41.3 142.875] CT\r\n0.149 GC\r\n/Helvetica 42.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-24 16.5 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 41.3 81.8125] CT\r\n0.149 GC\r\n/Helvetica 42.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-24 16.5 moveto \r\n1 -1 scale\r\n(1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 41.3 20.75] CT\r\n0.149 GC\r\n/Helvetica 42.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-24 16.5 moveto \r\n1 -1 scale\r\n(2) t \r\nGR\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24.05 142.87489] CT\r\n0.149 GC\r\nN\r\n-53.732 -11.622 M\n-52.623 -9.7 -49.857 -9.7 QT\n-47.342 -9.7 -45.506 -11.458 QT\n-43.67 -13.216 -42.545 -15.716 QT\n-41.42 -18.216 -40.795 -20.825 QT\n-43.154 -18.606 -45.889 -18.606 QT\n-47.982 -18.606 -49.459 -19.333 QT\n-50.935 -20.06 -51.756 -21.497 QT\n-52.576 -22.935 -52.576 -24.966 QT\n-52.576 -26.7 -52.107 -28.528 QT\n-51.639 -30.356 -50.795 -32.591 QT\n-49.951 -34.825 -49.342 -36.481 QT\n-48.639 -38.435 -48.639 -39.669 QT\n-48.639 -41.247 -49.795 -41.247 QT\n-51.904 -41.247 -53.256 -39.091 QT\n-54.607 -36.935 -55.264 -34.263 QT\n-55.357 -33.919 -55.701 -33.919 QT\n-56.326 -33.919 L\n-56.764 -33.919 -56.764 -34.419 QT\n-56.764 -34.575 L\n-55.904 -37.731 -54.146 -40.177 QT\n-52.389 -42.622 -49.701 -42.622 QT\n-47.81 -42.622 -46.506 -41.38 QT\n-45.201 -40.138 -45.201 -38.216 QT\n-45.201 -37.231 -45.639 -36.153 QT\n-45.873 -35.497 -46.701 -33.325 QT\n-47.529 -31.153 -47.967 -29.731 QT\n-48.404 -28.31 -48.685 -26.935 QT\n-48.967 -25.56 -48.967 -24.2 QT\n-48.967 -22.435 -48.217 -21.216 QT\n-47.467 -19.997 -45.842 -19.997 QT\n-42.56 -19.997 -39.935 -24.013 QT\n-35.935 -40.341 L\n-35.748 -41.044 -35.099 -41.544 QT\n-34.451 -42.044 -33.701 -42.044 QT\n-33.06 -42.044 -32.576 -41.63 QT\n-32.092 -41.216 -32.092 -40.544 QT\n-32.092 -40.247 -32.154 -40.138 QT\n-37.404 -19.044 L\n-38.107 -16.325 -39.967 -13.841 QT\n-41.826 -11.356 -44.451 -9.841 QT\n-47.076 -8.325 -49.935 -8.325 QT\n-51.295 -8.325 -52.646 -8.856 QT\n-53.998 -9.388 -54.826 -10.45 QT\n-55.654 -11.513 -55.654 -12.935 QT\n-55.654 -14.388 -54.795 -15.45 QT\n-53.935 -16.513 -52.514 -16.513 QT\n-51.67 -16.513 -51.084 -15.981 QT\n-50.498 -15.45 -50.498 -14.591 QT\n-50.498 -13.372 -51.404 -12.466 QT\n-52.31 -11.56 -53.529 -11.56 QT\n-53.576 -11.591 -53.631 -11.606 QT\n-53.685 -11.622 -53.732 -11.622 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24.05 142.87489] CT\r\n0.149 GC\r\nN\r\n-13.686 -6.06 M\n-16.639 -8.388 -18.772 -11.403 QT\n-20.905 -14.419 -22.264 -17.833 QT\n-23.624 -21.247 -24.295 -24.974 QT\n-24.967 -28.7 -24.967 -32.45 QT\n-24.967 -36.247 -24.295 -39.974 QT\n-23.624 -43.7 -22.241 -47.146 QT\n-20.858 -50.591 -18.709 -53.591 QT\n-16.561 -56.591 -13.686 -58.841 QT\n-13.686 -58.95 -13.436 -58.95 QT\n-12.936 -58.95 L\n-12.78 -58.95 -12.655 -58.81 QT\n-12.53 -58.669 -12.53 -58.481 QT\n-12.53 -58.247 -12.624 -58.153 QT\n-15.217 -55.606 -16.936 -52.708 QT\n-18.655 -49.81 -19.702 -46.536 QT\n-20.749 -43.263 -21.217 -39.755 QT\n-21.686 -36.247 -21.686 -32.45 QT\n-21.686 -15.606 -12.686 -6.856 QT\n-12.53 -6.7 -12.53 -6.419 QT\n-12.53 -6.294 -12.67 -6.122 QT\n-12.811 -5.95 -12.936 -5.95 QT\n-13.436 -5.95 L\n-13.686 -5.95 -13.686 -6.06 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24.05 142.87489] CT\r\n0.149 GC\r\nN\r\n-5.289 -20.106 M\n-5.289 -20.419 -5.242 -20.575 QT\n-1.289 -36.388 L\n-0.898 -37.856 -0.898 -38.966 QT\n-0.898 -41.247 -2.445 -41.247 QT\n-4.101 -41.247 -4.906 -39.271 QT\n-5.711 -37.294 -6.461 -34.263 QT\n-6.461 -34.106 -6.617 -34.013 QT\n-6.773 -33.919 -6.898 -33.919 QT\n-7.523 -33.919 L\n-7.695 -33.919 -7.828 -34.114 QT\n-7.961 -34.31 -7.961 -34.466 QT\n-7.383 -36.778 -6.859 -38.38 QT\n-6.336 -39.981 -5.203 -41.302 QT\n-4.07 -42.622 -2.398 -42.622 QT\n-0.398 -42.622 1.125 -41.364 QT\n2.649 -40.106 2.649 -38.169 QT\n4.227 -40.247 6.352 -41.435 QT\n8.477 -42.622 10.852 -42.622 QT\n13.367 -42.622 15.188 -41.341 QT\n17.008 -40.06 17.008 -37.7 QT\n18.649 -40.013 20.836 -41.317 QT\n23.024 -42.622 25.602 -42.622 QT\n28.352 -42.622 30.016 -41.13 QT\n31.68 -39.638 31.68 -36.903 QT\n31.68 -34.731 30.711 -31.653 QT\n29.742 -28.575 28.305 -24.763 QT\n27.539 -22.935 27.539 -21.575 QT\n27.539 -19.997 28.789 -19.997 QT\n30.852 -19.997 32.227 -22.224 QT\n33.602 -24.45 34.164 -26.997 QT\n34.32 -27.294 34.617 -27.294 QT\n35.227 -27.294 L\n35.445 -27.294 35.586 -27.153 QT\n35.727 -27.013 35.727 -26.841 QT\n35.727 -26.778 35.68 -26.685 QT\n34.945 -23.685 33.149 -21.146 QT\n31.352 -18.606 28.664 -18.606 QT\n26.789 -18.606 25.477 -19.888 QT\n24.164 -21.169 24.164 -22.997 QT\n24.164 -23.935 24.602 -25.075 QT\n26.102 -29.06 27.094 -32.192 QT\n28.086 -35.325 28.086 -37.7 QT\n28.086 -39.185 27.492 -40.216 QT\n26.899 -41.247 25.508 -41.247 QT\n22.602 -41.247 20.484 -39.474 QT\n18.367 -37.7 16.805 -34.778 QT\n16.711 -34.263 16.649 -33.981 QT\n13.242 -20.372 L\n13.055 -19.638 12.422 -19.122 QT\n11.789 -18.606 11.008 -18.606 QT\n10.383 -18.606 9.906 -19.021 QT\n9.43 -19.435 9.43 -20.106 QT\n9.43 -20.419 9.477 -20.575 QT\n12.867 -34.075 L\n13.414 -36.247 13.414 -37.7 QT\n13.414 -39.185 12.805 -40.216 QT\n12.195 -41.247 10.758 -41.247 QT\n8.805 -41.247 7.18 -40.396 QT\n5.555 -39.544 4.336 -38.13 QT\n3.117 -36.716 2.102 -34.778 QT\n-1.492 -20.372 L\n-1.664 -19.638 -2.305 -19.122 QT\n-2.945 -18.606 -3.711 -18.606 QT\n-4.367 -18.606 -4.828 -19.021 QT\n-5.289 -19.435 -5.289 -20.106 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24.05 142.87489] CT\r\n0.149 GC\r\nN\r\n40.882 -5.95 M\n40.413 -5.95 40.413 -6.419 QT\n40.413 -6.653 40.523 -6.747 QT\n49.585 -15.606 49.585 -32.45 QT\n49.585 -49.294 40.632 -58.044 QT\n40.413 -58.169 40.413 -58.481 QT\n40.413 -58.669 40.562 -58.81 QT\n40.71 -58.95 40.882 -58.95 QT\n41.382 -58.95 L\n41.538 -58.95 41.632 -58.841 QT\n45.445 -55.841 47.976 -51.544 QT\n50.507 -47.247 51.687 -42.388 QT\n52.867 -37.528 52.867 -32.45 QT\n52.867 -28.7 52.234 -25.06 QT\n51.601 -21.419 50.218 -17.888 QT\n48.835 -14.356 46.71 -11.372 QT\n44.585 -8.388 41.632 -6.06 QT\n41.538 -5.95 41.382 -5.95 QT\n40.882 -5.95 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n5.333 LW\r\nN\r\n775.333 381 M\n775.005 370.672 L\n774.023 360.387 L\n772.391 350.184 L\n770.114 340.105 L\n767.203 330.191 L\n763.669 320.481 L\n759.527 311.015 L\n754.792 301.831 L\n749.484 292.966 L\n743.625 284.455 L\n737.238 276.333 L\n730.348 268.632 L\n722.984 261.384 L\n715.175 254.617 L\n706.953 248.36 L\n698.35 242.636 L\n689.401 237.47 L\n680.143 232.882 L\n670.613 228.89 L\n660.849 225.51 L\n650.889 222.757 L\n640.776 220.64 L\n630.548 219.17 L\n620.248 218.351 L\n609.917 218.187 L\n599.595 218.679 L\n589.326 219.824 L\n579.151 221.618 L\n569.109 224.054 L\n559.242 227.122 L\n549.59 230.81 L\n540.191 235.102 L\n531.083 239.982 L\n522.303 245.43 L\n513.887 251.423 L\n505.867 257.939 L\n498.276 264.95 L\n491.146 272.428 L\n484.504 280.343 L\n478.378 288.664 L\n472.792 297.356 L\n467.768 306.385 L\n463.327 315.715 L\n459.487 325.308 L\n456.263 335.125 L\n453.668 345.126 L\n451.712 355.272 L\n450.404 365.522 L\n449.749 375.834 L\n449.749 386.166 L\n450.404 396.478 L\n451.712 406.728 L\n453.668 416.874 L\n456.263 426.875 L\n459.487 436.692 L\n463.327 446.285 L\n467.768 455.615 L\n472.792 464.644 L\n478.378 473.336 L\n484.504 481.657 L\n491.146 489.572 L\n498.276 497.05 L\n505.867 504.061 L\n513.887 510.577 L\n522.303 516.57 L\n531.083 522.018 L\n540.191 526.898 L\n549.59 531.19 L\n559.242 534.878 L\n569.109 537.946 L\n579.151 540.382 L\n589.326 542.176 L\n599.595 543.321 L\n609.917 543.813 L\n620.248 543.649 L\n630.548 542.83 L\n640.776 541.359 L\n650.889 539.243 L\n660.849 536.49 L\n670.613 533.11 L\n680.143 529.118 L\n689.401 524.53 L\n698.35 519.364 L\n706.953 513.64 L\n715.175 507.383 L\n722.984 500.616 L\n730.348 493.368 L\n737.238 485.667 L\n743.625 477.545 L\n749.484 469.034 L\n754.792 460.169 L\n759.527 450.985 L\n763.669 441.519 L\n767.203 431.809 L\n770.114 421.895 L\n772.391 411.816 L\n774.023 401.613 L\n775.005 391.328 L\n775.333 381 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0.502 0 RC\r\nN\r\n484.504 481.657 M\n491.146 489.572 L\n498.276 497.05 L\n505.867 504.061 L\n513.887 510.577 L\n522.303 516.57 L\n531.083 522.018 L\n540.191 526.898 L\n549.59 531.19 L\n559.242 534.878 L\n569.109 537.946 L\n579.151 540.382 L\n589.326 542.176 L\n599.595 543.321 L\n609.917 543.813 L\n620.248 543.649 L\n630.548 542.83 L\n640.776 541.359 L\n650.889 539.243 L\n660.849 536.49 L\n670.613 533.11 L\n680.143 529.118 L\n689.401 524.53 L\n698.35 519.364 L\n706.953 513.64 L\n715.175 507.383 L\n722.984 500.616 L\n730.348 493.368 L\n737.238 485.667 L\n743.625 477.545 L\n749.484 469.034 L\n754.792 460.169 L\n759.527 450.985 L\n763.669 441.519 L\n767.203 431.809 L\n770.114 421.895 L\n772.391 411.816 L\n774.023 401.613 L\n775.005 391.328 L\n775.333 381 L\n775.005 370.672 L\n774.023 360.387 L\n772.391 350.184 L\n770.114 340.105 L\n767.203 330.191 L\n763.669 320.481 L\n759.527 311.015 L\n754.792 301.831 L\n749.484 292.966 L\n743.625 284.455 L\n737.238 276.333 L\n730.348 268.632 L\n722.984 261.384 L\n715.175 254.617 L\n706.953 248.36 L\n698.35 242.636 L\n689.401 237.47 L\n680.143 232.882 L\n670.613 228.89 L\n660.849 225.51 L\n650.889 222.757 L\n640.776 220.64 L\n630.548 219.17 L\n620.248 218.351 L\n609.917 218.187 L\n599.595 218.679 L\n589.326 219.824 L\n579.151 221.618 L\n569.109 224.054 L\n559.242 227.122 L\n549.59 230.81 L\n540.191 235.102 L\n531.083 239.982 L\n522.303 245.43 L\n513.887 251.423 L\n505.867 257.939 L\n498.276 264.95 L\n491.146 272.428 L\n484.504 280.343 L\n478.378 288.664 L\n472.792 297.356 L\n467.768 306.385 L\n463.327 315.715 L\n459.487 325.308 L\n456.263 335.125 L\n453.668 345.126 L\n451.712 355.272 L\n450.404 365.522 L\n449.749 375.834 L\n449.749 386.166 L\n450.404 396.478 L\n451.712 406.728 L\n453.668 416.874 L\n456.263 426.875 L\n459.487 436.692 L\n463.327 446.285 L\n467.768 455.615 L\n472.792 464.644 L\n478.378 473.336 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n2 setlinecap\r\n10.0 ML\r\n1.333 LW\r\nN\r\n775.333 381 M\n775.005 370.672 L\n774.023 360.387 L\n772.391 350.184 L\n770.114 340.105 L\n767.203 330.191 L\n763.669 320.481 L\n759.527 311.015 L\n754.792 301.831 L\n749.484 292.966 L\n743.625 284.455 L\n737.238 276.333 L\n730.348 268.632 L\n722.984 261.384 L\n715.175 254.617 L\n706.953 248.36 L\n698.35 242.636 L\n689.401 237.47 L\n680.143 232.882 L\n670.613 228.89 L\n660.849 225.51 L\n650.889 222.757 L\n640.776 220.64 L\n630.548 219.17 L\n620.248 218.351 L\n609.917 218.187 L\n599.595 218.679 L\n589.326 219.824 L\n579.151 221.618 L\n569.109 224.054 L\n559.242 227.122 L\n549.59 230.81 L\n540.191 235.102 L\n531.083 239.982 L\n522.303 245.43 L\n513.887 251.423 L\n505.867 257.939 L\n498.276 264.95 L\n491.146 272.428 L\n484.504 280.343 L\n478.378 288.664 L\n472.792 297.356 L\n467.768 306.385 L\n463.327 315.715 L\n459.487 325.308 L\n456.263 335.125 L\n453.668 345.126 L\n451.712 355.272 L\n450.404 365.522 L\n449.749 375.834 L\n449.749 386.166 L\n450.404 396.478 L\n451.712 406.728 L\n453.668 416.874 L\n456.263 426.875 L\n459.487 436.692 L\n463.327 446.285 L\n467.768 455.615 L\n472.792 464.644 L\n478.378 473.336 L\n484.504 481.657 L\n491.146 489.572 L\n498.276 497.05 L\n505.867 504.061 L\n513.887 510.577 L\n522.303 516.57 L\n531.083 522.018 L\n540.191 526.898 L\n549.59 531.19 L\n559.242 534.878 L\n569.109 537.946 L\n579.151 540.382 L\n589.326 542.176 L\n599.595 543.321 L\n609.917 543.813 L\n620.248 543.649 L\n630.548 542.83 L\n640.776 541.359 L\n650.889 539.243 L\n660.849 536.49 L\n670.613 533.11 L\n680.143 529.118 L\n689.401 524.53 L\n698.35 519.364 L\n706.953 513.64 L\n715.175 507.383 L\n722.984 500.616 L\n730.348 493.368 L\n737.238 485.667 L\n743.625 477.545 L\n749.484 469.034 L\n754.792 460.169 L\n759.527 450.985 L\n763.669 441.519 L\n767.203 431.809 L\n770.114 421.895 L\n772.391 411.816 L\n774.023 401.613 L\n775.005 391.328 L\n775.333 381 L\n775.333 381 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 46.5 142.875] CT\r\n0 0 1 RC\r\n10.0 ML\r\n2.667 LW\r\nN\r\n-8 0 M\n0 10.64 L\n8 0 L\n0 -10.64 L\ncp\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.875 142.26438] CT\r\n1 0 0 RC\r\n10.0 ML\r\n2.667 LW\r\nN\r\n-8 0 M\n0 10.64 L\n8 0 L\n0 -10.64 L\ncp\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n[20 20] 0 setdash\r\n2 LJ\r\n5.333 LW\r\nN\r\n124 381 M\n132.098 380.159 L\n148.129 377.304 L\n171.942 371.871 L\n203.421 363.525 L\n242.484 352.067 L\n286.105 335.032 L\n329.774 312.184 L\n372.627 285.936 L\n415.539 259.347 L\n459.642 235.398 L\n505.422 216.82 L\n552.31 205.846 L\n598.75 203.846 L\n642.637 211.081 L\n683.073 222.833 L\n720.426 235.637 L\n754.959 248.204 L\n786.829 260.034 L\n816.167 270.937 L\n843.105 280.854 L\n867.784 289.786 L\n890.352 297.767 L\n910.954 304.843 L\n929.735 311.074 L\n946.834 316.523 L\n962.381 321.255 L\n976.501 325.339 L\n989.309 328.84 L\n1000.91 331.822 L\n1011.406 334.346 L\n1020.887 336.471 L\n1029.441 338.249 L\n1037.147 339.728 L\n1044.08 340.952 L\n1050.307 341.961 L\n1055.894 342.788 L\n1060.9 343.462 L\n1065.379 344.01 L\n1069.381 344.454 L\n1072.955 344.812 L\n1076.141 345.1 L\n1078.979 345.331 L\n1081.504 345.515 L\n1083.749 345.661 L\n1085.743 345.778 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n[20 20] 0 setdash\r\n2 LJ\r\n5.333 LW\r\nN\r\n124 381 M\n132.104 380.22 L\n148.172 377.579 L\n172.074 372.553 L\n203.701 364.784 L\n242.913 353.849 L\n289.513 339.194 L\n339.683 321.427 L\n390.688 301.076 L\n438.333 275.295 L\n484.193 249.14 L\n530.797 228.333 L\n578.32 216.845 L\n624.747 216.409 L\n667.576 225.376 L\n706.78 237.113 L\n742.802 249.245 L\n775.926 260.889 L\n806.349 271.709 L\n834.24 281.591 L\n859.763 290.512 L\n883.079 298.494 L\n904.348 305.581 L\n923.726 311.829 L\n941.359 317.299 L\n957.386 322.056 L\n971.938 326.166 L\n985.135 329.695 L\n997.089 332.706 L\n1007.904 335.259 L\n1017.677 337.411 L\n1026.496 339.216 L\n1034.445 340.72 L\n1041.6 341.968 L\n1048.031 342.997 L\n1053.806 343.843 L\n1058.983 344.535 L\n1063.621 345.099 L\n1067.77 345.556 L\n1071.477 345.926 L\n1074.787 346.224 L\n1077.739 346.463 L\n1080.37 346.655 L\n1082.712 346.809 L\n1084.795 346.931 L\n1086.648 347.028 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n[20 20] 0 setdash\r\n2 LJ\r\n5.333 LW\r\nN\r\n124 381 M\n132.142 380.991 L\n148.425 380.956 L\n172.85 380.871 L\n205.033 375.885 L\n244.007 366.209 L\n285.883 352.278 L\n326.594 332.993 L\n362.282 342.395 L\n387.192 370.414 L\n408.329 403.849 L\n430.242 438.921 L\n455.98 472.842 L\n486.969 502.811 L\n522.973 526.211 L\n562.403 541.124 L\n602.913 546.69 L\n642.049 543.141 L\n678.516 534.73 L\n712.454 524.815 L\n744.071 514.748 L\n773.5 505.09 L\n800.84 496.074 L\n826.188 487.788 L\n849.641 480.255 L\n871.304 473.461 L\n891.282 467.376 L\n909.683 461.958 L\n926.61 457.163 L\n942.164 452.942 L\n956.442 449.245 L\n969.535 446.024 L\n981.529 443.231 L\n992.506 440.82 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 1 RC\r\n[20 20] 0 setdash\r\n2 LJ\r\n5.333 LW\r\nN\r\n124 381 M\n132.142 380.992 L\n148.425 380.959 L\n172.85 380.881 L\n205.094 380.718 L\n244.688 372.757 L\n288.314 359.466 L\n333.553 342.299 L\n377.143 357.586 L\n408.85 391.011 L\n434.95 429.185 L\n462.053 466.642 L\n493.91 499.495 L\n531.019 524.509 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 107.5625 210.04376] CT\r\nN\r\n2.984 7.629 M\n2.984 6.926 3.125 6.285 QT\n6.594 -7.496 L\n1.547 -7.496 L\n1.063 -7.496 1.063 -8.121 QT\n1.25 -9.183 1.688 -9.183 QT\n7.016 -9.183 L\n8.938 -17.011 L\n9.125 -17.636 9.688 -18.082 QT\n10.25 -18.527 10.953 -18.527 QT\n11.563 -18.527 11.969 -18.168 QT\n12.375 -17.808 12.375 -17.199 QT\n12.375 -17.058 12.367 -16.972 QT\n12.359 -16.886 12.328 -16.793 QT\n10.406 -9.183 L\n15.359 -9.183 L\n15.844 -9.183 15.844 -8.543 QT\n15.828 -8.433 15.758 -8.152 QT\n15.688 -7.871 15.57 -7.683 QT\n15.453 -7.496 15.219 -7.496 QT\n9.984 -7.496 L\n6.547 6.379 L\n6.188 7.739 6.188 8.723 QT\n6.188 10.785 7.594 10.785 QT\n9.703 10.785 11.336 8.809 QT\n12.969 6.832 13.828 4.457 QT\n14.016 4.176 14.203 4.176 QT\n14.797 4.176 L\n14.984 4.176 15.102 4.309 QT\n15.219 4.442 15.219 4.598 QT\n15.219 4.692 15.172 4.739 QT\n14.109 7.645 12.094 9.856 QT\n10.078 12.067 7.484 12.067 QT\n5.578 12.067 4.281 10.817 QT\n2.984 9.567 2.984 7.629 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 107.5625 210.04376] CT\r\nN\r\n34.276 5.145 M\n33.885 5.145 33.627 4.84 QT\n33.369 4.535 33.369 4.176 QT\n33.369 3.785 33.627 3.504 QT\n33.885 3.223 34.276 3.223 QT\n64.416 3.223 L\n64.776 3.223 65.034 3.504 QT\n65.291 3.785 65.291 4.176 QT\n65.291 4.535 65.034 4.84 QT\n64.776 5.145 64.416 5.145 QT\n34.276 5.145 L\ncp\n34.276 -4.183 M\n33.885 -4.183 33.627 -4.465 QT\n33.369 -4.746 33.369 -5.152 QT\n33.369 -5.496 33.627 -5.8 QT\n33.885 -6.105 34.276 -6.105 QT\n64.416 -6.105 L\n64.776 -6.105 65.034 -5.8 QT\n65.291 -5.496 65.291 -5.152 QT\n65.291 -4.746 65.034 -4.465 QT\n64.776 -4.183 64.416 -4.183 QT\n34.276 -4.183 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 107.5625 210.04376] CT\r\nN\r\n85.786 11.52 M\n85.786 9.832 L\n91.786 9.832 91.786 8.301 QT\n91.786 -16.886 L\n89.302 -15.699 85.505 -15.699 QT\n85.505 -17.386 L\n91.395 -17.386 94.395 -20.449 QT\n95.067 -20.449 L\n95.239 -20.449 95.388 -20.324 QT\n95.536 -20.199 95.536 -20.027 QT\n95.536 8.301 L\n95.536 9.832 101.536 9.832 QT\n101.536 11.52 L\n85.786 11.52 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 107.5625 210.04376] CT\r\nN\r\n109.911 7.817 M\n111.036 9.457 112.934 10.254 QT\n114.833 11.051 117.005 11.051 QT\n119.802 11.051 120.974 8.668 QT\n122.145 6.285 122.145 3.27 QT\n122.145 1.91 121.895 0.551 QT\n121.645 -0.808 121.059 -1.98 QT\n120.474 -3.152 119.458 -3.855 QT\n118.442 -4.558 116.958 -4.558 QT\n113.77 -4.558 L\n113.349 -4.558 113.349 -5.011 QT\n113.349 -5.433 L\n113.349 -5.808 113.77 -5.808 QT\n116.427 -6.011 L\n118.114 -6.011 119.224 -7.277 QT\n120.333 -8.543 120.849 -10.363 QT\n121.364 -12.183 121.364 -13.824 QT\n121.364 -16.121 120.286 -17.597 QT\n119.208 -19.074 117.005 -19.074 QT\n115.177 -19.074 113.513 -18.379 QT\n111.849 -17.683 110.864 -16.277 QT\n110.958 -16.308 111.028 -16.316 QT\n111.099 -16.324 111.192 -16.324 QT\n112.27 -16.324 112.997 -15.574 QT\n113.724 -14.824 113.724 -13.777 QT\n113.724 -12.746 112.997 -11.996 QT\n112.27 -11.246 111.192 -11.246 QT\n110.145 -11.246 109.395 -11.996 QT\n108.645 -12.746 108.645 -13.777 QT\n108.645 -15.84 109.888 -17.363 QT\n111.13 -18.886 113.083 -19.668 QT\n115.036 -20.449 117.005 -20.449 QT\n118.458 -20.449 120.075 -20.019 QT\n121.692 -19.59 123.005 -18.777 QT\n124.317 -17.965 125.153 -16.699 QT\n125.989 -15.433 125.989 -13.824 QT\n125.989 -11.808 125.083 -10.097 QT\n124.177 -8.386 122.606 -7.144 QT\n121.036 -5.902 119.161 -5.293 QT\n121.255 -4.886 123.13 -3.715 QT\n125.005 -2.543 126.138 -0.715 QT\n127.27 1.114 127.27 3.223 QT\n127.27 5.864 125.817 8.012 QT\n124.364 10.16 121.997 11.371 QT\n119.63 12.582 117.005 12.582 QT\n114.755 12.582 112.497 11.723 QT\n110.239 10.864 108.794 9.153 QT\n107.349 7.442 107.349 5.051 QT\n107.349 3.848 108.145 3.051 QT\n108.942 2.254 110.145 2.254 QT\n110.911 2.254 111.559 2.621 QT\n112.208 2.989 112.567 3.645 QT\n112.927 4.301 112.927 5.051 QT\n112.927 6.223 112.106 7.02 QT\n111.286 7.817 110.145 7.817 QT\n109.911 7.817 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 290.74999 136.76875] CT\r\nN\r\n/f1843140893{2.984 7.629 M\n2.984 6.926 3.125 6.285 QT\n6.594 -7.496 L\n1.547 -7.496 L\n1.063 -7.496 1.063 -8.121 QT\n1.25 -9.183 1.688 -9.183 QT\n7.016 -9.183 L\n8.938 -17.011 L\n9.125 -17.636 9.688 -18.082 QT\n10.25 -18.527 10.953 -18.527 QT\n11.563 -18.527 11.969 -18.168 QT\n12.375 -17.808 12.375 -17.199 QT\n12.375 -17.058 12.367 -16.972 QT\n12.359 -16.886 12.328 -16.793 QT\n10.406 -9.183 L\n15.359 -9.183 L\n15.844 -9.183 15.844 -8.543 QT\n15.828 -8.433 15.758 -8.152 QT\n15.688 -7.871 15.57 -7.683 QT\n15.453 -7.496 15.219 -7.496 QT\n9.984 -7.496 L\n6.547 6.379 L\n6.188 7.739 6.188 8.723 QT\n6.188 10.785 7.594 10.785 QT\n9.703 10.785 11.336 8.809 QT\n12.969 6.832 13.828 4.457 QT\n14.016 4.176 14.203 4.176 QT\n14.797 4.176 L\n14.984 4.176 15.102 4.309 QT\n15.219 4.442 15.219 4.598 QT\n15.219 4.692 15.172 4.739 QT\n14.109 7.645 12.094 9.856 QT\n10.078 12.067 7.484 12.067 QT\n5.578 12.067 4.281 10.817 QT\n2.984 9.567 2.984 7.629 QT\ncp}def\r\nf1843140893\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 290.74999 136.76875] CT\r\nN\r\n/f819103698{34.276 5.145 M\n33.885 5.145 33.627 4.84 QT\n33.369 4.535 33.369 4.176 QT\n33.369 3.785 33.627 3.504 QT\n33.885 3.223 34.276 3.223 QT\n64.416 3.223 L\n64.776 3.223 65.034 3.504 QT\n65.291 3.785 65.291 4.176 QT\n65.291 4.535 65.034 4.84 QT\n64.776 5.145 64.416 5.145 QT\n34.276 5.145 L\ncp\n34.276 -4.183 M\n33.885 -4.183 33.627 -4.465 QT\n33.369 -4.746 33.369 -5.152 QT\n33.369 -5.496 33.627 -5.8 QT\n33.885 -6.105 34.276 -6.105 QT\n64.416 -6.105 L\n64.776 -6.105 65.034 -5.8 QT\n65.291 -5.496 65.291 -5.152 QT\n65.291 -4.746 65.034 -4.465 QT\n64.776 -4.183 64.416 -4.183 QT\n34.276 -4.183 L\ncp}def\r\nf819103698\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 290.74999 136.76875] CT\r\nN\r\n/f852245701{85.911 7.817 M\n87.036 9.457 88.934 10.254 QT\n90.833 11.051 93.005 11.051 QT\n95.802 11.051 96.973 8.668 QT\n98.145 6.285 98.145 3.27 QT\n98.145 1.91 97.895 0.551 QT\n97.645 -0.808 97.059 -1.98 QT\n96.473 -3.152 95.458 -3.855 QT\n94.442 -4.558 92.958 -4.558 QT\n89.77 -4.558 L\n89.348 -4.558 89.348 -5.011 QT\n89.348 -5.433 L\n89.348 -5.808 89.77 -5.808 QT\n92.427 -6.011 L\n94.114 -6.011 95.223 -7.277 QT\n96.333 -8.543 96.848 -10.363 QT\n97.364 -12.183 97.364 -13.824 QT\n97.364 -16.121 96.286 -17.597 QT\n95.208 -19.074 93.005 -19.074 QT\n91.177 -19.074 89.513 -18.379 QT\n87.848 -17.683 86.864 -16.277 QT\n86.958 -16.308 87.028 -16.316 QT\n87.098 -16.324 87.192 -16.324 QT\n88.27 -16.324 88.997 -15.574 QT\n89.723 -14.824 89.723 -13.777 QT\n89.723 -12.746 88.997 -11.996 QT\n88.27 -11.246 87.192 -11.246 QT\n86.145 -11.246 85.395 -11.996 QT\n84.645 -12.746 84.645 -13.777 QT\n84.645 -15.84 85.888 -17.363 QT\n87.13 -18.886 89.083 -19.668 QT\n91.036 -20.449 93.005 -20.449 QT\n94.458 -20.449 96.075 -20.019 QT\n97.692 -19.59 99.005 -18.777 QT\n100.317 -17.965 101.153 -16.699 QT\n101.989 -15.433 101.989 -13.824 QT\n101.989 -11.808 101.083 -10.097 QT\n100.177 -8.386 98.606 -7.144 QT\n97.036 -5.902 95.161 -5.293 QT\n97.255 -4.886 99.13 -3.715 QT\n101.005 -2.543 102.138 -0.715 QT\n103.27 1.114 103.27 3.223 QT\n103.27 5.864 101.817 8.012 QT\n100.364 10.16 97.997 11.371 QT\n95.63 12.582 93.005 12.582 QT\n90.755 12.582 88.497 11.723 QT\n86.239 10.864 84.794 9.153 QT\n83.348 7.442 83.348 5.051 QT\n83.348 3.848 84.145 3.051 QT\n84.942 2.254 86.145 2.254 QT\n86.911 2.254 87.559 2.621 QT\n88.208 2.989 88.567 3.645 QT\n88.927 4.301 88.927 5.051 QT\n88.927 6.223 88.106 7.02 QT\n87.286 7.817 86.145 7.817 QT\n85.911 7.817 L\ncp}def\r\nf852245701\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 290.74999 136.76875] CT\r\nN\r\n/f1068786795{109.911 7.817 M\n111.036 9.457 112.934 10.254 QT\n114.833 11.051 117.005 11.051 QT\n119.802 11.051 120.974 8.668 QT\n122.145 6.285 122.145 3.27 QT\n122.145 1.91 121.895 0.551 QT\n121.645 -0.808 121.059 -1.98 QT\n120.474 -3.152 119.458 -3.855 QT\n118.442 -4.558 116.958 -4.558 QT\n113.77 -4.558 L\n113.349 -4.558 113.349 -5.011 QT\n113.349 -5.433 L\n113.349 -5.808 113.77 -5.808 QT\n116.427 -6.011 L\n118.114 -6.011 119.224 -7.277 QT\n120.333 -8.543 120.849 -10.363 QT\n121.364 -12.183 121.364 -13.824 QT\n121.364 -16.121 120.286 -17.597 QT\n119.208 -19.074 117.005 -19.074 QT\n115.177 -19.074 113.513 -18.379 QT\n111.849 -17.683 110.864 -16.277 QT\n110.958 -16.308 111.028 -16.316 QT\n111.099 -16.324 111.192 -16.324 QT\n112.27 -16.324 112.997 -15.574 QT\n113.724 -14.824 113.724 -13.777 QT\n113.724 -12.746 112.997 -11.996 QT\n112.27 -11.246 111.192 -11.246 QT\n110.145 -11.246 109.395 -11.996 QT\n108.645 -12.746 108.645 -13.777 QT\n108.645 -15.84 109.888 -17.363 QT\n111.13 -18.886 113.083 -19.668 QT\n115.036 -20.449 117.005 -20.449 QT\n118.458 -20.449 120.075 -20.019 QT\n121.692 -19.59 123.005 -18.777 QT\n124.317 -17.965 125.153 -16.699 QT\n125.989 -15.433 125.989 -13.824 QT\n125.989 -11.808 125.083 -10.097 QT\n124.177 -8.386 122.606 -7.144 QT\n121.036 -5.902 119.161 -5.293 QT\n121.255 -4.886 123.13 -3.715 QT\n125.005 -2.543 126.138 -0.715 QT\n127.27 1.114 127.27 3.223 QT\n127.27 5.864 125.817 8.012 QT\n124.364 10.16 121.997 11.371 QT\n119.63 12.582 117.005 12.582 QT\n114.755 12.582 112.497 11.723 QT\n110.239 10.864 108.794 9.153 QT\n107.349 7.442 107.349 5.051 QT\n107.349 3.848 108.145 3.051 QT\n108.942 2.254 110.145 2.254 QT\n110.911 2.254 111.559 2.621 QT\n112.208 2.989 112.567 3.645 QT\n112.927 4.301 112.927 5.051 QT\n112.927 6.223 112.106 7.02 QT\n111.286 7.817 110.145 7.817 QT\n109.911 7.817 L\ncp}def\r\nf1068786795\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n1080 685 M\n1080 490 L\n548 490 L\n548 685 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 193.8734] CT\r\nN\r\n/f574533680{1.781 9.216 M\n1.406 9.216 1.406 8.716 QT\n1.422 8.622 1.484 8.388 QT\n1.547 8.153 1.648 8.013 QT\n1.75 7.872 1.891 7.872 QT\n5.531 7.872 6.125 5.56 QT\n11.281 -15.222 L\n10.219 -15.409 7.938 -15.409 QT\n7.578 -15.409 7.578 -15.909 QT\n7.594 -16.003 7.648 -16.237 QT\n7.703 -16.472 7.805 -16.604 QT\n7.906 -16.737 8.047 -16.737 QT\n14.625 -16.737 L\n14.906 -16.737 14.969 -16.503 QT\n23.422 3.591 L\n27.625 -13.237 L\n27.703 -13.644 27.703 -13.815 QT\n27.703 -15.409 24.766 -15.409 QT\n24.406 -15.409 24.406 -15.909 QT\n24.531 -16.394 24.602 -16.565 QT\n24.672 -16.737 25.047 -16.737 QT\n33.172 -16.737 L\n33.547 -16.737 33.547 -16.237 QT\n33.531 -16.144 33.477 -15.917 QT\n33.422 -15.69 33.32 -15.55 QT\n33.219 -15.409 33.063 -15.409 QT\n29.422 -15.409 28.828 -13.081 QT\n23.375 8.888 L\n23.25 9.216 22.984 9.216 QT\n22.531 9.216 L\n22.266 9.216 22.188 8.95 QT\n12.5 -14.034 L\n12.438 -14.269 L\n12.359 -14.347 12.359 -14.394 QT\n7.328 5.731 L\n7.297 5.825 7.273 5.958 QT\n7.25 6.091 7.219 6.278 QT\n7.219 7.263 8.07 7.567 QT\n8.922 7.872 10.188 7.872 QT\n10.563 7.872 10.563 8.388 QT\n10.422 8.903 10.336 9.06 QT\n10.25 9.216 9.922 9.216 QT\n1.781 9.216 L\ncp}def\r\nf574533680\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 193.8734] CT\r\nN\r\n/f735976676{48.566 4.169 M\n48.253 4.169 48.05 3.927 QT\n47.847 3.685 47.847 3.403 QT\n47.847 3.091 48.05 2.872 QT\n48.253 2.653 48.566 2.653 QT\n72.425 2.653 L\n72.706 2.653 72.909 2.872 QT\n73.113 3.091 73.113 3.403 QT\n73.113 3.685 72.909 3.927 QT\n72.706 4.169 72.425 4.169 QT\n48.566 4.169 L\ncp\n48.566 -3.222 M\n48.253 -3.222 48.05 -3.44 QT\n47.847 -3.659 47.847 -3.972 QT\n47.847 -4.253 48.05 -4.495 QT\n48.253 -4.737 48.566 -4.737 QT\n72.425 -4.737 L\n72.706 -4.737 72.909 -4.495 QT\n73.113 -4.253 73.113 -3.972 QT\n73.113 -3.659 72.909 -3.44 QT\n72.706 -3.222 72.425 -3.222 QT\n48.566 -3.222 L\ncp}def\r\nf735976676\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 193.8734] CT\r\nN\r\n/f1533900297{88.13 9.216 M\n88.13 8.2 L\n88.13 8.106 88.208 7.997 QT\n94.114 1.466 L\n95.443 0.013 96.279 -0.972 QT\n97.114 -1.956 97.927 -3.237 QT\n98.739 -4.519 99.216 -5.847 QT\n99.693 -7.175 99.693 -8.659 QT\n99.693 -10.206 99.114 -11.628 QT\n98.536 -13.05 97.396 -13.901 QT\n96.255 -14.753 94.646 -14.753 QT\n92.989 -14.753 91.677 -13.761 QT\n90.364 -12.769 89.818 -11.19 QT\n89.974 -11.237 90.224 -11.237 QT\n91.083 -11.237 91.685 -10.659 QT\n92.286 -10.081 92.286 -9.175 QT\n92.286 -8.3 91.685 -7.698 QT\n91.083 -7.097 90.224 -7.097 QT\n89.333 -7.097 88.732 -7.714 QT\n88.13 -8.331 88.13 -9.175 QT\n88.13 -10.597 88.669 -11.854 QT\n89.208 -13.112 90.216 -14.081 QT\n91.224 -15.05 92.497 -15.573 QT\n93.771 -16.097 95.208 -16.097 QT\n97.38 -16.097 99.247 -15.175 QT\n101.114 -14.253 102.216 -12.573 QT\n103.318 -10.894 103.318 -8.659 QT\n103.318 -7.003 102.591 -5.519 QT\n101.864 -4.034 100.732 -2.815 QT\n99.599 -1.597 97.833 -0.058 QT\n96.068 1.481 95.521 1.997 QT\n91.208 6.138 L\n94.864 6.138 L\n97.552 6.138 99.364 6.091 QT\n101.177 6.044 101.286 5.95 QT\n101.739 5.466 102.193 2.45 QT\n103.318 2.45 L\n102.239 9.216 L\n88.13 9.216 L\ncp}def\r\nf1533900297\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 193.8734] CT\r\nN\r\n/f-819923682{106.502 2.95 M\n106.502 1.606 L\n118.236 -15.909 L\n118.377 -16.097 118.627 -16.097 QT\n119.19 -16.097 L\n119.611 -16.097 119.611 -15.659 QT\n119.611 1.606 L\n123.346 1.606 L\n123.346 2.95 L\n119.611 2.95 L\n119.611 6.669 L\n119.611 7.45 120.729 7.661 QT\n121.846 7.872 123.315 7.872 QT\n123.315 9.216 L\n112.846 9.216 L\n112.846 7.872 L\n114.315 7.872 115.424 7.661 QT\n116.533 7.45 116.533 6.669 QT\n116.533 2.95 L\n106.502 2.95 L\ncp\n107.752 1.606 M\n116.752 1.606 L\n116.752 -11.847 L\n107.752 1.606 L\ncp}def\r\nf-819923682\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 193.8734] CT\r\nN\r\n/f-1106082528{128.405 16.06 M\n128.405 15.903 128.561 15.747 QT\n129.921 14.435 130.686 12.708 QT\n131.452 10.981 131.452 9.06 QT\n131.452 8.606 L\n130.843 9.216 129.921 9.216 QT\n129.061 9.216 128.444 8.606 QT\n127.827 7.997 127.827 7.122 QT\n127.827 6.231 128.444 5.638 QT\n129.061 5.044 129.921 5.044 QT\n131.28 5.044 131.858 6.294 QT\n132.436 7.544 132.436 9.06 QT\n132.436 11.185 131.593 13.083 QT\n130.749 14.981 129.202 16.513 QT\n129.061 16.575 128.968 16.575 QT\n128.78 16.575 128.593 16.411 QT\n128.405 16.247 128.405 16.06 QT\ncp}def\r\nf-1106082528\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 193.8734] CT\r\nN\r\n/f-2022938735{152.909 16.653 M\n152.909 15.81 153.292 14.177 QT\n153.675 12.544 154.222 10.692 QT\n154.769 8.841 155.159 7.653 QT\n155.3 5.763 155.3 4.794 QT\n155.3 2.356 154.823 0.247 QT\n154.347 -1.862 153.011 -3.284 QT\n151.675 -4.706 149.284 -4.706 QT\n148.019 -4.706 146.761 -4.167 QT\n145.503 -3.628 144.605 -2.659 QT\n143.706 -1.69 143.378 -0.472 QT\n143.3 -0.253 143.081 -0.253 QT\n142.612 -0.253 L\n142.315 -0.253 142.315 -0.581 QT\n142.315 -0.706 L\n142.753 -2.425 143.831 -4.011 QT\n144.909 -5.597 146.48 -6.589 QT\n148.05 -7.581 149.8 -7.581 QT\n151.581 -7.581 152.878 -6.37 QT\n154.175 -5.159 154.956 -3.308 QT\n155.737 -1.456 156.081 0.435 QT\n156.425 2.325 156.425 3.997 QT\n158.331 -1.19 160.706 -5.831 QT\n161.284 -7.05 L\n161.394 -7.175 161.534 -7.175 QT\n162.003 -7.175 L\n162.3 -7.175 162.3 -6.815 QT\n162.3 -6.737 162.222 -6.597 QT\n161.659 -5.409 L\n160.003 -2.128 158.62 1.255 QT\n157.237 4.638 156.253 7.763 QT\n156.112 9.044 155.69 11.271 QT\n155.269 13.497 154.675 15.419 QT\n154.081 17.341 153.487 17.419 QT\n152.909 17.419 152.909 16.653 QT\ncp}def\r\nf-2022938735\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 193.8734] CT\r\nN\r\n/f-1608834715{164.087 14.976 M\n164.087 14.023 L\n167.462 14.023 167.462 13.163 QT\n167.462 -1.009 L\n166.071 -0.337 163.931 -0.337 QT\n163.931 -1.274 L\n167.243 -1.274 168.931 -3.009 QT\n169.306 -3.009 L\n169.399 -3.009 169.485 -2.938 QT\n169.571 -2.868 169.571 -2.774 QT\n169.571 13.163 L\n169.571 14.023 172.946 14.023 QT\n172.946 14.976 L\n164.087 14.976 L\ncp}def\r\nf-1608834715\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 193.8734] CT\r\nN\r\n/f-1300927600{190.473 4.169 M\n190.16 4.169 189.957 3.927 QT\n189.754 3.685 189.754 3.403 QT\n189.754 3.091 189.957 2.872 QT\n190.16 2.653 190.473 2.653 QT\n214.332 2.653 L\n214.613 2.653 214.816 2.872 QT\n215.02 3.091 215.02 3.403 QT\n215.02 3.685 214.816 3.927 QT\n214.613 4.169 214.332 4.169 QT\n190.473 4.169 L\ncp\n190.473 -3.222 M\n190.16 -3.222 189.957 -3.44 QT\n189.754 -3.659 189.754 -3.972 QT\n189.754 -4.253 189.957 -4.495 QT\n190.16 -4.737 190.473 -4.737 QT\n214.332 -4.737 L\n214.613 -4.737 214.816 -4.495 QT\n215.02 -4.253 215.02 -3.972 QT\n215.02 -3.659 214.816 -3.44 QT\n214.613 -3.222 214.332 -3.222 QT\n190.473 -3.222 L\ncp}def\r\nf-1300927600\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 193.8734] CT\r\nN\r\n/f-1997795938{237.647 10.044 M\n232.99 10.044 231.311 6.216 QT\n229.631 2.388 229.631 -2.894 QT\n229.631 -6.206 230.232 -9.12 QT\n230.834 -12.034 232.623 -14.065 QT\n234.412 -16.097 237.647 -16.097 QT\n240.147 -16.097 241.748 -14.87 QT\n243.35 -13.644 244.178 -11.706 QT\n245.006 -9.769 245.318 -7.55 QT\n245.631 -5.331 245.631 -2.894 QT\n245.631 0.372 245.022 3.216 QT\n244.412 6.06 242.654 8.052 QT\n240.897 10.044 237.647 10.044 QT\ncp\n237.647 9.06 M\n239.756 9.06 240.795 6.896 QT\n241.834 4.731 242.076 2.091 QT\n242.318 -0.55 242.318 -3.519 QT\n242.318 -6.378 242.076 -8.784 QT\n241.834 -11.19 240.811 -13.151 QT\n239.787 -15.112 237.647 -15.112 QT\n235.49 -15.112 234.451 -13.144 QT\n233.412 -11.175 233.17 -8.776 QT\n232.928 -6.378 232.928 -3.519 QT\n232.928 -1.394 233.029 0.481 QT\n233.131 2.356 233.576 4.349 QT\n234.022 6.341 235.022 7.7 QT\n236.022 9.06 237.647 9.06 QT\ncp}def\r\nf-1997795938\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 193.8734] CT\r\nN\r\n/f1065174994{250.534 7.122 M\n250.534 6.263 251.167 5.653 QT\n251.8 5.044 252.628 5.044 QT\n253.159 5.044 253.659 5.317 QT\n254.159 5.591 254.433 6.099 QT\n254.706 6.606 254.706 7.122 QT\n254.706 7.95 254.097 8.583 QT\n253.487 9.216 252.628 9.216 QT\n251.8 9.216 251.167 8.583 QT\n250.534 7.95 250.534 7.122 QT\ncp}def\r\nf1065174994\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 193.8734] CT\r\nN\r\n/f1247873414{259.076 2.95 M\n259.076 1.606 L\n270.81 -15.909 L\n270.951 -16.097 271.201 -16.097 QT\n271.763 -16.097 L\n272.185 -16.097 272.185 -15.659 QT\n272.185 1.606 L\n275.92 1.606 L\n275.92 2.95 L\n272.185 2.95 L\n272.185 6.669 L\n272.185 7.45 273.302 7.661 QT\n274.42 7.872 275.888 7.872 QT\n275.888 9.216 L\n265.42 9.216 L\n265.42 7.872 L\n266.888 7.872 267.998 7.661 QT\n269.107 7.45 269.107 6.669 QT\n269.107 2.95 L\n259.076 2.95 L\ncp\n260.326 1.606 M\n269.326 1.606 L\n269.326 -11.847 L\n260.326 1.606 L\ncp}def\r\nf1247873414\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 193.8734] CT\r\nN\r\n/f-1867049319{280.979 16.06 M\n280.979 15.903 281.135 15.747 QT\n282.495 14.435 283.26 12.708 QT\n284.026 10.981 284.026 9.06 QT\n284.026 8.606 L\n283.416 9.216 282.495 9.216 QT\n281.635 9.216 281.018 8.606 QT\n280.401 7.997 280.401 7.122 QT\n280.401 6.231 281.018 5.638 QT\n281.635 5.044 282.495 5.044 QT\n283.854 5.044 284.432 6.294 QT\n285.01 7.544 285.01 9.06 QT\n285.01 11.185 284.166 13.083 QT\n283.323 14.981 281.776 16.513 QT\n281.635 16.575 281.541 16.575 QT\n281.354 16.575 281.166 16.411 QT\n280.979 16.247 280.979 16.06 QT\ncp}def\r\nf-1867049319\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 193.8734] CT\r\nN\r\n/f-1823982240{305.483 16.653 M\n305.483 15.81 305.866 14.177 QT\n306.249 12.544 306.796 10.692 QT\n307.342 8.841 307.733 7.653 QT\n307.874 5.763 307.874 4.794 QT\n307.874 2.356 307.397 0.247 QT\n306.921 -1.862 305.585 -3.284 QT\n304.249 -4.706 301.858 -4.706 QT\n300.592 -4.706 299.335 -4.167 QT\n298.077 -3.628 297.178 -2.659 QT\n296.28 -1.69 295.952 -0.472 QT\n295.874 -0.253 295.655 -0.253 QT\n295.186 -0.253 L\n294.889 -0.253 294.889 -0.581 QT\n294.889 -0.706 L\n295.327 -2.425 296.405 -4.011 QT\n297.483 -5.597 299.053 -6.589 QT\n300.624 -7.581 302.374 -7.581 QT\n304.155 -7.581 305.452 -6.37 QT\n306.749 -5.159 307.53 -3.308 QT\n308.311 -1.456 308.655 0.435 QT\n308.999 2.325 308.999 3.997 QT\n310.905 -1.19 313.28 -5.831 QT\n313.858 -7.05 L\n313.967 -7.175 314.108 -7.175 QT\n314.577 -7.175 L\n314.874 -7.175 314.874 -6.815 QT\n314.874 -6.737 314.796 -6.597 QT\n314.233 -5.409 L\n312.577 -2.128 311.194 1.255 QT\n309.811 4.638 308.827 7.763 QT\n308.686 9.044 308.264 11.271 QT\n307.842 13.497 307.249 15.419 QT\n306.655 17.341 306.061 17.419 QT\n305.483 17.419 305.483 16.653 QT\ncp}def\r\nf-1823982240\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 193.8734] CT\r\nN\r\n/f-1287452466{315.505 14.976 M\n315.505 14.257 L\n315.505 14.179 315.551 14.101 QT\n319.755 9.46 L\n320.708 8.429 321.294 7.734 QT\n321.88 7.038 322.465 6.132 QT\n323.051 5.226 323.387 4.28 QT\n323.723 3.335 323.723 2.273 QT\n323.723 1.179 323.309 0.163 QT\n322.895 -0.852 322.09 -1.454 QT\n321.286 -2.055 320.13 -2.055 QT\n318.958 -2.055 318.02 -1.352 QT\n317.083 -0.649 316.708 0.476 QT\n316.817 0.445 316.989 0.445 QT\n317.598 0.445 318.028 0.851 QT\n318.458 1.257 318.458 1.913 QT\n318.458 2.523 318.028 2.952 QT\n317.598 3.382 316.989 3.382 QT\n316.364 3.382 315.934 2.945 QT\n315.505 2.507 315.505 1.913 QT\n315.505 0.898 315.887 0.007 QT\n316.27 -0.884 316.989 -1.579 QT\n317.708 -2.274 318.614 -2.641 QT\n319.52 -3.009 320.536 -3.009 QT\n322.067 -3.009 323.403 -2.352 QT\n324.739 -1.696 325.512 -0.509 QT\n326.286 0.679 326.286 2.273 QT\n326.286 3.46 325.77 4.515 QT\n325.255 5.57 324.458 6.429 QT\n323.661 7.288 322.403 8.382 QT\n321.145 9.476 320.755 9.851 QT\n317.692 12.788 L\n320.286 12.788 L\n322.208 12.788 323.489 12.757 QT\n324.77 12.726 324.848 12.648 QT\n325.176 12.32 325.505 10.163 QT\n326.286 10.163 L\n325.52 14.976 L\n315.505 14.976 L\ncp}def\r\nf-1287452466\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 193.8734] CT\r\nN\r\n/f-172155240{343.047 4.169 M\n342.734 4.169 342.531 3.927 QT\n342.328 3.685 342.328 3.403 QT\n342.328 3.091 342.531 2.872 QT\n342.734 2.653 343.047 2.653 QT\n366.906 2.653 L\n367.187 2.653 367.39 2.872 QT\n367.593 3.091 367.593 3.403 QT\n367.593 3.685 367.39 3.927 QT\n367.187 4.169 366.906 4.169 QT\n343.047 4.169 L\ncp\n343.047 -3.222 M\n342.734 -3.222 342.531 -3.44 QT\n342.328 -3.659 342.328 -3.972 QT\n342.328 -4.253 342.531 -4.495 QT\n342.734 -4.737 343.047 -4.737 QT\n366.906 -4.737 L\n367.187 -4.737 367.39 -4.495 QT\n367.593 -4.253 367.593 -3.972 QT\n367.593 -3.659 367.39 -3.44 QT\n367.187 -3.222 366.906 -3.222 QT\n343.047 -3.222 L\ncp}def\r\nf-172155240\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 193.8734] CT\r\nN\r\n/f-1794144311{390.22 10.044 M\n385.564 10.044 383.884 6.216 QT\n382.205 2.388 382.205 -2.894 QT\n382.205 -6.206 382.806 -9.12 QT\n383.408 -12.034 385.197 -14.065 QT\n386.986 -16.097 390.22 -16.097 QT\n392.72 -16.097 394.322 -14.87 QT\n395.923 -13.644 396.752 -11.706 QT\n397.58 -9.769 397.892 -7.55 QT\n398.205 -5.331 398.205 -2.894 QT\n398.205 0.372 397.595 3.216 QT\n396.986 6.06 395.228 8.052 QT\n393.47 10.044 390.22 10.044 QT\ncp\n390.22 9.06 M\n392.33 9.06 393.369 6.896 QT\n394.408 4.731 394.65 2.091 QT\n394.892 -0.55 394.892 -3.519 QT\n394.892 -6.378 394.65 -8.784 QT\n394.408 -11.19 393.384 -13.151 QT\n392.361 -15.112 390.22 -15.112 QT\n388.064 -15.112 387.025 -13.144 QT\n385.986 -11.175 385.744 -8.776 QT\n385.502 -6.378 385.502 -3.519 QT\n385.502 -1.394 385.603 0.481 QT\n385.705 2.356 386.15 4.349 QT\n386.595 6.341 387.595 7.7 QT\n388.595 9.06 390.22 9.06 QT\ncp}def\r\nf-1794144311\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 193.8734] CT\r\nN\r\n/f-1192358335{403.108 7.122 M\n403.108 6.263 403.741 5.653 QT\n404.374 5.044 405.202 5.044 QT\n405.733 5.044 406.233 5.317 QT\n406.733 5.591 407.006 6.099 QT\n407.28 6.606 407.28 7.122 QT\n407.28 7.95 406.67 8.583 QT\n406.061 9.216 405.202 9.216 QT\n404.374 9.216 403.741 8.583 QT\n403.108 7.95 403.108 7.122 QT\ncp}def\r\nf-1192358335\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 193.8734] CT\r\nN\r\n/f947843481{411.65 2.95 M\n411.65 1.606 L\n423.384 -15.909 L\n423.525 -16.097 423.775 -16.097 QT\n424.337 -16.097 L\n424.759 -16.097 424.759 -15.659 QT\n424.759 1.606 L\n428.493 1.606 L\n428.493 2.95 L\n424.759 2.95 L\n424.759 6.669 L\n424.759 7.45 425.876 7.661 QT\n426.993 7.872 428.462 7.872 QT\n428.462 9.216 L\n417.993 9.216 L\n417.993 7.872 L\n419.462 7.872 420.571 7.661 QT\n421.681 7.45 421.681 6.669 QT\n421.681 2.95 L\n411.65 2.95 L\ncp\n412.9 1.606 M\n421.9 1.606 L\n421.9 -11.847 L\n412.9 1.606 L\ncp}def\r\nf947843481\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n[20 20] 0 setdash\r\n2 LJ\r\n5.333 LW\r\nN\r\n556.003 516.996 M\n636.035 516.996 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 211.49947] CT\r\nN\r\nf574533680\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 211.49947] CT\r\nN\r\nf735976676\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 211.49947] CT\r\nN\r\nf1533900297\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 211.49947] CT\r\nN\r\nf-819923682\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 211.49947] CT\r\nN\r\nf-1106082528\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 211.49947] CT\r\nN\r\nf-2022938735\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 211.49947] CT\r\nN\r\nf-1608834715\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 211.49947] CT\r\nN\r\nf-1300927600\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 211.49947] CT\r\nN\r\nf-1997795938\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 211.49947] CT\r\nN\r\nf1065174994\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 211.49947] CT\r\nN\r\n/f-1449850694{267.513 10.044 M\n265.154 10.044 263.576 8.794 QT\n261.998 7.544 261.138 5.552 QT\n260.279 3.56 259.943 1.372 QT\n259.607 -0.815 259.607 -3.065 QT\n259.607 -6.081 260.779 -9.104 QT\n261.951 -12.128 264.224 -14.112 QT\n266.498 -16.097 269.607 -16.097 QT\n270.904 -16.097 272.029 -15.604 QT\n273.154 -15.112 273.795 -14.159 QT\n274.435 -13.206 274.435 -11.847 QT\n274.435 -11.065 273.904 -10.534 QT\n273.373 -10.003 272.591 -10.003 QT\n271.857 -10.003 271.318 -10.542 QT\n270.779 -11.081 270.779 -11.847 QT\n270.779 -12.581 271.318 -13.12 QT\n271.857 -13.659 272.591 -13.659 QT\n272.795 -13.659 L\n272.326 -14.347 271.443 -14.675 QT\n270.56 -15.003 269.607 -15.003 QT\n268.466 -15.003 267.49 -14.503 QT\n266.513 -14.003 265.732 -13.144 QT\n264.951 -12.284 264.435 -11.261 QT\n263.92 -10.237 263.63 -8.917 QT\n263.341 -7.597 263.263 -6.448 QT\n263.185 -5.3 263.185 -3.55 QT\n263.857 -5.112 265.084 -6.104 QT\n266.31 -7.097 267.841 -7.097 QT\n269.529 -7.097 270.927 -6.409 QT\n272.326 -5.722 273.326 -4.503 QT\n274.326 -3.284 274.857 -1.729 QT\n275.388 -0.175 275.388 1.419 QT\n275.388 3.653 274.388 5.661 QT\n273.388 7.669 271.591 8.856 QT\n269.795 10.044 267.513 10.044 QT\ncp\n267.513 8.841 M\n268.982 8.841 269.873 8.177 QT\n270.763 7.513 271.177 6.403 QT\n271.591 5.294 271.693 4.177 QT\n271.795 3.06 271.795 1.419 QT\n271.795 -0.737 271.591 -2.253 QT\n271.388 -3.769 270.482 -4.933 QT\n269.576 -6.097 267.701 -6.097 QT\n266.154 -6.097 265.162 -5.058 QT\n264.17 -4.019 263.716 -2.433 QT\n263.263 -0.847 263.263 0.622 QT\n263.263 1.122 263.295 1.388 QT\n263.295 1.435 263.287 1.474 QT\n263.279 1.513 263.263 1.575 QT\n263.263 3.2 263.599 4.872 QT\n263.935 6.544 264.88 7.692 QT\n265.826 8.841 267.513 8.841 QT\ncp}def\r\nf-1449850694\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 211.49947] CT\r\nN\r\nf-1867049319\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 211.49947] CT\r\nN\r\nf-1823982240\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 211.49947] CT\r\nN\r\nf-1287452466\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 211.49947] CT\r\nN\r\nf-172155240\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 211.49947] CT\r\nN\r\nf-1794144311\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 211.49947] CT\r\nN\r\nf-1192358335\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 211.49947] CT\r\nN\r\n/f1069079805{420.087 10.044 M\n417.728 10.044 416.15 8.794 QT\n414.571 7.544 413.712 5.552 QT\n412.853 3.56 412.517 1.372 QT\n412.181 -0.815 412.181 -3.065 QT\n412.181 -6.081 413.353 -9.104 QT\n414.525 -12.128 416.798 -14.112 QT\n419.071 -16.097 422.181 -16.097 QT\n423.478 -16.097 424.603 -15.604 QT\n425.728 -15.112 426.368 -14.159 QT\n427.009 -13.206 427.009 -11.847 QT\n427.009 -11.065 426.478 -10.534 QT\n425.946 -10.003 425.165 -10.003 QT\n424.431 -10.003 423.892 -10.542 QT\n423.353 -11.081 423.353 -11.847 QT\n423.353 -12.581 423.892 -13.12 QT\n424.431 -13.659 425.165 -13.659 QT\n425.368 -13.659 L\n424.9 -14.347 424.017 -14.675 QT\n423.134 -15.003 422.181 -15.003 QT\n421.04 -15.003 420.064 -14.503 QT\n419.087 -14.003 418.306 -13.144 QT\n417.525 -12.284 417.009 -11.261 QT\n416.493 -10.237 416.204 -8.917 QT\n415.915 -7.597 415.837 -6.448 QT\n415.759 -5.3 415.759 -3.55 QT\n416.431 -5.112 417.657 -6.104 QT\n418.884 -7.097 420.415 -7.097 QT\n422.103 -7.097 423.501 -6.409 QT\n424.9 -5.722 425.9 -4.503 QT\n426.9 -3.284 427.431 -1.729 QT\n427.962 -0.175 427.962 1.419 QT\n427.962 3.653 426.962 5.661 QT\n425.962 7.669 424.165 8.856 QT\n422.368 10.044 420.087 10.044 QT\ncp\n420.087 8.841 M\n421.556 8.841 422.446 8.177 QT\n423.337 7.513 423.751 6.403 QT\n424.165 5.294 424.267 4.177 QT\n424.368 3.06 424.368 1.419 QT\n424.368 -0.737 424.165 -2.253 QT\n423.962 -3.769 423.056 -4.933 QT\n422.15 -6.097 420.275 -6.097 QT\n418.728 -6.097 417.736 -5.058 QT\n416.743 -4.019 416.29 -2.433 QT\n415.837 -0.847 415.837 0.622 QT\n415.837 1.122 415.868 1.388 QT\n415.868 1.435 415.861 1.474 QT\n415.853 1.513 415.837 1.575 QT\n415.837 3.2 416.173 4.872 QT\n416.509 6.544 417.454 7.692 QT\n418.4 8.841 420.087 8.841 QT\ncp}def\r\nf1069079805\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n[20 20] 0 setdash\r\n2 LJ\r\n5.333 LW\r\nN\r\n556.003 563.999 M\n636.035 563.999 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 229.12553] CT\r\nN\r\nf574533680\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 229.12553] CT\r\nN\r\nf735976676\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 229.12553] CT\r\nN\r\n/f887460689{89.771 9.216 M\n89.771 7.872 L\n94.521 7.872 94.521 6.669 QT\n94.521 -13.269 L\n92.552 -12.331 89.536 -12.331 QT\n89.536 -13.659 L\n94.193 -13.659 96.568 -16.097 QT\n97.114 -16.097 L\n97.239 -16.097 97.364 -15.995 QT\n97.489 -15.894 97.489 -15.753 QT\n97.489 6.669 L\n97.489 7.872 102.239 7.872 QT\n102.239 9.216 L\n89.771 9.216 L\ncp}def\r\nf887460689\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 229.12553] CT\r\nN\r\n/f433478275{114.94 10.044 M\n112.58 10.044 111.002 8.794 QT\n109.424 7.544 108.565 5.552 QT\n107.705 3.56 107.369 1.372 QT\n107.033 -0.815 107.033 -3.065 QT\n107.033 -6.081 108.205 -9.104 QT\n109.377 -12.128 111.65 -14.112 QT\n113.924 -16.097 117.033 -16.097 QT\n118.33 -16.097 119.455 -15.604 QT\n120.58 -15.112 121.221 -14.159 QT\n121.861 -13.206 121.861 -11.847 QT\n121.861 -11.065 121.33 -10.534 QT\n120.799 -10.003 120.018 -10.003 QT\n119.283 -10.003 118.744 -10.542 QT\n118.205 -11.081 118.205 -11.847 QT\n118.205 -12.581 118.744 -13.12 QT\n119.283 -13.659 120.018 -13.659 QT\n120.221 -13.659 L\n119.752 -14.347 118.869 -14.675 QT\n117.986 -15.003 117.033 -15.003 QT\n115.893 -15.003 114.916 -14.503 QT\n113.94 -14.003 113.158 -13.144 QT\n112.377 -12.284 111.861 -11.261 QT\n111.346 -10.237 111.057 -8.917 QT\n110.768 -7.597 110.69 -6.448 QT\n110.611 -5.3 110.611 -3.55 QT\n111.283 -5.112 112.51 -6.104 QT\n113.736 -7.097 115.268 -7.097 QT\n116.955 -7.097 118.354 -6.409 QT\n119.752 -5.722 120.752 -4.503 QT\n121.752 -3.284 122.283 -1.729 QT\n122.815 -0.175 122.815 1.419 QT\n122.815 3.653 121.815 5.661 QT\n120.815 7.669 119.018 8.856 QT\n117.221 10.044 114.94 10.044 QT\ncp\n114.94 8.841 M\n116.408 8.841 117.299 8.177 QT\n118.19 7.513 118.604 6.403 QT\n119.018 5.294 119.119 4.177 QT\n119.221 3.06 119.221 1.419 QT\n119.221 -0.737 119.018 -2.253 QT\n118.815 -3.769 117.908 -4.933 QT\n117.002 -6.097 115.127 -6.097 QT\n113.58 -6.097 112.588 -5.058 QT\n111.596 -4.019 111.143 -2.433 QT\n110.69 -0.847 110.69 0.622 QT\n110.69 1.122 110.721 1.388 QT\n110.721 1.435 110.713 1.474 QT\n110.705 1.513 110.69 1.575 QT\n110.69 3.2 111.025 4.872 QT\n111.361 6.544 112.307 7.692 QT\n113.252 8.841 114.94 8.841 QT\ncp}def\r\nf433478275\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 229.12553] CT\r\nN\r\nf-1106082528\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 229.12553] CT\r\nN\r\nf-2022938735\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 229.12553] CT\r\nN\r\nf-1608834715\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 229.12553] CT\r\nN\r\nf-1300927600\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 229.12553] CT\r\nN\r\nf-1997795938\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 229.12553] CT\r\nN\r\nf1065174994\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 229.12553] CT\r\nN\r\nf1247873414\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 229.12553] CT\r\nN\r\nf-1867049319\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 229.12553] CT\r\nN\r\nf-1823982240\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 229.12553] CT\r\nN\r\nf-1287452466\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 229.12553] CT\r\nN\r\nf-172155240\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 229.12553] CT\r\nN\r\nf-1794144311\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 229.12553] CT\r\nN\r\nf-1192358335\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 229.12553] CT\r\nN\r\nf947843481\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n[20 20] 0 setdash\r\n2 LJ\r\n5.333 LW\r\nN\r\n556.003 611.001 M\n636.035 611.001 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 246.7516] CT\r\nN\r\nf574533680\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 246.7516] CT\r\nN\r\nf735976676\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 246.7516] CT\r\nN\r\nf887460689\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 246.7516] CT\r\nN\r\nf433478275\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 246.7516] CT\r\nN\r\nf-1106082528\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 246.7516] CT\r\nN\r\nf-2022938735\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 246.7516] CT\r\nN\r\nf-1608834715\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 246.7516] CT\r\nN\r\nf-1300927600\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 246.7516] CT\r\nN\r\nf-1997795938\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 246.7516] CT\r\nN\r\nf1065174994\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 246.7516] CT\r\nN\r\nf-1449850694\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 246.7516] CT\r\nN\r\nf-1867049319\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 246.7516] CT\r\nN\r\nf-1823982240\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 246.7516] CT\r\nN\r\nf-1287452466\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 246.7516] CT\r\nN\r\nf-172155240\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 246.7516] CT\r\nN\r\nf-1794144311\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 246.7516] CT\r\nN\r\nf-1192358335\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 240.76412 246.7516] CT\r\nN\r\nf1069079805\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 1 RC\r\n[20 20] 0 setdash\r\n2 LJ\r\n5.333 LW\r\nN\r\n556.003 658.004 M\n636.035 658.004 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n10.0 ML\r\n0.533 LW\r\nN\r\n548 685 M\n548 490 L\n1080 490 L\n1080 685 L\ncp\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n414.4 562.8 M\n510.17 526.886 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n497.92 520.8 M\n526.4 520.8 L\n510.17 526.886 L\n497.92 520.8 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n526.4 520.8 M\n504.942 539.527 L\n510.17 526.886 L\n526.4 520.8 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\nN\r\n526.4 520.8 M\n497.92 520.8 L\n510.17 526.886 L\n504.942 539.527 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n873.6 394.8 M\n969.37 430.714 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n964.142 418.073 M\n985.6 436.8 L\n969.37 430.714 L\n964.142 418.073 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n985.6 436.8 M\n957.12 436.8 L\n969.37 430.714 L\n985.6 436.8 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\nN\r\n985.6 436.8 M\n964.142 418.073 L\n969.37 430.714 L\n957.12 436.8 L\ncp\r\nf\r\nGR\r\n%%Trailer\r\n%%Pages: 1\r\n%%EOF\r\n"
  },
  {
    "path": "matlab/acc2023/closedloop_performance/figures/closedloop-snapshots3.eps",
    "content": "%!PS-Adobe-3.0 EPSF-3.0\r\n%%Creator: (MATLAB, The Mathworks, Inc. Version 9.10.0.1649659 \\(R2021a\\) Update 1. Operating System: Windows 10)\r\n%%Title: figures/closedloop-snapshots3.eps\r\n%%CreationDate: 2023-01-31T03:11:45\r\n%%Pages: (atend)\r\n%%BoundingBox:     1     0   419   301\r\n%%LanguageLevel: 3\r\n%%EndComments\r\n%%BeginProlog\r\n%%BeginResource: procset (Apache XML Graphics Std ProcSet) 1.2 0\r\n%%Version: 1.2 0\r\n%%Copyright: (Copyright 2001-2003,2010 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/bd{bind def}bind def\r\n/ld{load def}bd\r\n/GR/grestore ld\r\n/GS/gsave ld\r\n/RM/rmoveto ld\r\n/C/curveto ld\r\n/t/show ld\r\n/L/lineto ld\r\n/ML/setmiterlimit ld\r\n/CT/concat ld\r\n/f/fill ld\r\n/N/newpath ld\r\n/S/stroke ld\r\n/CC/setcmykcolor ld\r\n/A/ashow ld\r\n/cp/closepath ld\r\n/RC/setrgbcolor ld\r\n/LJ/setlinejoin ld\r\n/GC/setgray ld\r\n/LW/setlinewidth ld\r\n/M/moveto ld\r\n/re {4 2 roll M\r\n1 index 0 rlineto\r\n0 exch rlineto\r\nneg 0 rlineto\r\ncp } bd\r\n/_ctm matrix def\r\n/_tm matrix def\r\n/BT { _ctm currentmatrix pop matrix _tm copy pop 0 0 moveto } bd\r\n/ET { _ctm setmatrix } bd\r\n/iTm { _ctm setmatrix _tm concat } bd\r\n/Tm { _tm astore pop iTm 0 0 moveto } bd\r\n/ux 0.0 def\r\n/uy 0.0 def\r\n/F {\r\n  /Tp exch def\r\n  /Tf exch def\r\n  Tf findfont Tp scalefont setfont\r\n  /cf Tf def  /cs Tp def\r\n} bd\r\n/ULS {currentpoint /uy exch def /ux exch def} bd\r\n/ULE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add moveto  Tcx uy To add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/OLE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs add moveto Tcx uy To add cs add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/SOE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs 10 mul 26 idiv add moveto Tcx uy To add cs 10 mul 26 idiv add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/QT {\r\n/Y22 exch store\r\n/X22 exch store\r\n/Y21 exch store\r\n/X21 exch store\r\ncurrentpoint\r\n/Y21 load 2 mul add 3 div exch\r\n/X21 load 2 mul add 3 div exch\r\n/X21 load 2 mul /X22 load add 3 div\r\n/Y21 load 2 mul /Y22 load add 3 div\r\n/X22 load /Y22 load curveto\r\n} bd\r\n/SSPD {\r\ndup length /d exch dict def\r\n{\r\n/v exch def\r\n/k exch def\r\ncurrentpagedevice k known {\r\n/cpdv currentpagedevice k get def\r\nv cpdv ne {\r\n/upd false def\r\n/nullv v type /nulltype eq def\r\n/nullcpdv cpdv type /nulltype eq def\r\nnullv nullcpdv or\r\n{\r\n/upd true def\r\n} {\r\n/sametype v type cpdv type eq def\r\nsametype {\r\nv type /arraytype eq {\r\n/vlen v length def\r\n/cpdvlen cpdv length def\r\nvlen cpdvlen eq {\r\n0 1 vlen 1 sub {\r\n/i exch def\r\n/obj v i get def\r\n/cpdobj cpdv i get def\r\nobj cpdobj ne {\r\n/upd true def\r\nexit\r\n} if\r\n} for\r\n} {\r\n/upd true def\r\n} ifelse\r\n} {\r\nv type /dicttype eq {\r\nv {\r\n/dv exch def\r\n/dk exch def\r\n/cpddv cpdv dk get def\r\ndv cpddv ne {\r\n/upd true def\r\nexit\r\n} if\r\n} forall\r\n} {\r\n/upd true def\r\n} ifelse\r\n} ifelse\r\n} if\r\n} ifelse\r\nupd true eq {\r\nd k v put\r\n} if\r\n} if\r\n} if\r\n} forall\r\nd length 0 gt {\r\nd setpagedevice\r\n} if\r\n} bd\r\n/RE { % /NewFontName [NewEncodingArray] /FontName RE -\r\n  findfont dup length dict begin\r\n  {\r\n    1 index /FID ne\r\n    {def} {pop pop} ifelse\r\n  } forall\r\n  /Encoding exch def\r\n  /FontName 1 index def\r\n  currentdict definefont pop\r\n  end\r\n} bind def\r\n%%EndResource\r\n%%BeginResource: procset (Apache XML Graphics EPS ProcSet) 1.0 0\r\n%%Version: 1.0 0\r\n%%Copyright: (Copyright 2002-2003 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/BeginEPSF { %def\r\n/b4_Inc_state save def         % Save state for cleanup\r\n/dict_count countdictstack def % Count objects on dict stack\r\n/op_count count 1 sub def      % Count objects on operand stack\r\nuserdict begin                 % Push userdict on dict stack\r\n/showpage { } def              % Redefine showpage, { } = null proc\r\n0 setgray 0 setlinecap         % Prepare graphics state\r\n1 setlinewidth 0 setlinejoin\r\n10 setmiterlimit [ ] 0 setdash newpath\r\n/languagelevel where           % If level not equal to 1 then\r\n{pop languagelevel             % set strokeadjust and\r\n1 ne                           % overprint to their defaults.\r\n{false setstrokeadjust false setoverprint\r\n} if\r\n} if\r\n} bd\r\n/EndEPSF { %def\r\ncount op_count sub {pop} repeat            % Clean up stacks\r\ncountdictstack dict_count sub {end} repeat\r\nb4_Inc_state restore\r\n} bd\r\n%%EndResource\r\n%FOPBeginFontDict\r\n%%IncludeResource: font Courier-Oblique\r\n%%IncludeResource: font Courier-BoldOblique\r\n%%IncludeResource: font Courier-Bold\r\n%%IncludeResource: font ZapfDingbats\r\n%%IncludeResource: font Symbol\r\n%%IncludeResource: font Helvetica\r\n%%IncludeResource: font Helvetica-Oblique\r\n%%IncludeResource: font Helvetica-Bold\r\n%%IncludeResource: font Helvetica-BoldOblique\r\n%%IncludeResource: font Times-Roman\r\n%%IncludeResource: font Times-Italic\r\n%%IncludeResource: font Times-Bold\r\n%%IncludeResource: font Times-BoldItalic\r\n%%IncludeResource: font Courier\r\n%FOPEndFontDict\r\n%%BeginResource: encoding WinAnsiEncoding\r\n/WinAnsiEncoding [\r\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /space /exclam /quotedbl\n/numbersign /dollar /percent /ampersand /quotesingle\n/parenleft /parenright /asterisk /plus /comma\n/hyphen /period /slash /zero /one\n/two /three /four /five /six\n/seven /eight /nine /colon /semicolon\n/less /equal /greater /question /at\n/A /B /C /D /E\n/F /G /H /I /J\n/K /L /M /N /O\n/P /Q /R /S /T\n/U /V /W /X /Y\n/Z /bracketleft /backslash /bracketright /asciicircum\n/underscore /quoteleft /a /b /c\n/d /e /f /g /h\n/i /j /k /l /m\n/n /o /p /q /r\n/s /t /u /v /w\n/x /y /z /braceleft /bar\n/braceright /asciitilde /bullet /Euro /bullet\n/quotesinglbase /florin /quotedblbase /ellipsis /dagger\n/daggerdbl /circumflex /perthousand /Scaron /guilsinglleft\n/OE /bullet /Zcaron /bullet /bullet\n/quoteleft /quoteright /quotedblleft /quotedblright /bullet\n/endash /emdash /asciitilde /trademark /scaron\n/guilsinglright /oe /bullet /zcaron /Ydieresis\n/space /exclamdown /cent /sterling /currency\n/yen /brokenbar /section /dieresis /copyright\n/ordfeminine /guillemotleft /logicalnot /sfthyphen /registered\n/macron /degree /plusminus /twosuperior /threesuperior\n/acute /mu /paragraph /middot /cedilla\n/onesuperior /ordmasculine /guillemotright /onequarter /onehalf\n/threequarters /questiondown /Agrave /Aacute /Acircumflex\n/Atilde /Adieresis /Aring /AE /Ccedilla\n/Egrave /Eacute /Ecircumflex /Edieresis /Igrave\n/Iacute /Icircumflex /Idieresis /Eth /Ntilde\n/Ograve /Oacute /Ocircumflex /Otilde /Odieresis\n/multiply /Oslash /Ugrave /Uacute /Ucircumflex\n/Udieresis /Yacute /Thorn /germandbls /agrave\n/aacute /acircumflex /atilde /adieresis /aring\n/ae /ccedilla /egrave /eacute /ecircumflex\n/edieresis /igrave /iacute /icircumflex /idieresis\n/eth /ntilde /ograve /oacute /ocircumflex\n/otilde /odieresis /divide /oslash /ugrave\n/uacute /ucircumflex /udieresis /yacute /thorn\n/ydieresis\n] def\r\n%%EndResource\r\n%FOPBeginFontReencode\r\n/Courier-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Oblique exch definefont pop\r\n/Courier-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-BoldOblique exch definefont pop\r\n/Courier-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Bold exch definefont pop\r\n/Helvetica findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica exch definefont pop\r\n/Helvetica-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Oblique exch definefont pop\r\n/Helvetica-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Bold exch definefont pop\r\n/Helvetica-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-BoldOblique exch definefont pop\r\n/Times-Roman findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Roman exch definefont pop\r\n/Times-Italic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Italic exch definefont pop\r\n/Times-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Bold exch definefont pop\r\n/Times-BoldItalic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-BoldItalic exch definefont pop\r\n/Courier findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier exch definefont pop\r\n%FOPEndFontReencode\r\n%%EndProlog\r\n%%Page: 1 1\r\n%%PageBoundingBox: 0 0 420 315\r\n%%BeginPageSetup\r\n[1 0 0 -1 0 315] CT\r\n%%EndPageSetup\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n130 703 M\n1105 703 L\n1105 53 L\n130 53 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n130 703 M\n130 53 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n292.5 703 M\n292.5 53 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n455 703 M\n455 53 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n617.5 703 M\n617.5 53 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n780 703 M\n780 53 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n942.5 703 M\n942.5 53 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1105 703 M\n1105 53 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1105 703 M\n130 703 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1105 540.5 M\n130 540.5 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1105 378 M\n130 378 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1105 215.5 M\n130 215.5 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1105 53 M\n130 53 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n130 703 M\n1105 703 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n130 703 M\n130 693.25 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n292.5 703 M\n292.5 693.25 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n455 703 M\n455 693.25 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n617.5 703 M\n617.5 693.25 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n780 703 M\n780 693.25 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n942.5 703 M\n942.5 693.25 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n1105 703 M\n1105 693.25 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 48.75 269.22501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-21.5 49 moveto \r\n1 -1 scale\r\n(-3) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 109.6875 269.22501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-21.5 49 moveto \r\n1 -1 scale\r\n(-2) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 170.625 269.22501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-21.5 49 moveto \r\n1 -1 scale\r\n(-1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 231.5625 269.22501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-13.5 49 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 292.5 269.22501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-13.5 49 moveto \r\n1 -1 scale\r\n(1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 353.4375 269.22501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-13.5 49 moveto \r\n1 -1 scale\r\n(2) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 414.375 269.22501] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-13.5 49 moveto \r\n1 -1 scale\r\n(3) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 231.56268 292.72499] CT\r\n0.149 GC\r\nN\r\n-55.255 43.269 M\n-54.317 44.003 -52.614 44.003 QT\n-50.958 44.003 -49.692 42.409 QT\n-48.426 40.815 -47.958 38.925 QT\n-45.551 29.534 L\n-44.973 26.972 -44.973 26.034 QT\n-44.973 24.722 -45.715 23.737 QT\n-46.458 22.753 -47.77 22.753 QT\n-49.458 22.753 -50.934 23.8 QT\n-52.411 24.847 -53.419 26.464 QT\n-54.426 28.081 -54.833 29.737 QT\n-54.942 30.081 -55.255 30.081 QT\n-55.895 30.081 L\n-56.317 30.081 -56.317 29.581 QT\n-56.317 29.425 L\n-55.801 27.456 -54.559 25.581 QT\n-53.317 23.706 -51.52 22.542 QT\n-49.723 21.378 -47.676 21.378 QT\n-45.723 21.378 -44.161 22.417 QT\n-42.598 23.456 -41.958 25.237 QT\n-41.051 23.612 -39.637 22.495 QT\n-38.223 21.378 -36.551 21.378 QT\n-35.411 21.378 -34.215 21.776 QT\n-33.02 22.175 -32.27 23.003 QT\n-31.52 23.831 -31.52 25.081 QT\n-31.52 26.425 -32.387 27.394 QT\n-33.255 28.362 -34.598 28.362 QT\n-35.458 28.362 -36.028 27.823 QT\n-36.598 27.284 -36.598 26.456 QT\n-36.598 25.331 -35.833 24.495 QT\n-35.067 23.659 -34.005 23.503 QT\n-34.958 22.753 -36.645 22.753 QT\n-38.348 22.753 -39.606 24.331 QT\n-40.864 25.909 -41.38 27.847 QT\n-43.708 37.222 L\n-44.286 39.347 -44.286 40.706 QT\n-44.286 42.05 -43.52 43.026 QT\n-42.755 44.003 -41.489 44.003 QT\n-39.005 44.003 -37.051 41.815 QT\n-35.098 39.628 -34.473 37.003 QT\n-34.364 36.706 -34.067 36.706 QT\n-33.411 36.706 L\n-33.208 36.706 -33.075 36.847 QT\n-32.942 36.987 -32.942 37.159 QT\n-32.942 37.222 -33.005 37.315 QT\n-33.755 40.472 -36.161 42.933 QT\n-38.567 45.394 -41.583 45.394 QT\n-43.536 45.394 -45.098 44.347 QT\n-46.661 43.3 -47.317 41.519 QT\n-48.145 43.065 -49.606 44.229 QT\n-51.067 45.394 -52.723 45.394 QT\n-53.864 45.394 -55.067 44.995 QT\n-56.27 44.597 -57.02 43.769 QT\n-57.77 42.94 -57.77 41.675 QT\n-57.77 40.425 -56.903 39.401 QT\n-56.036 38.378 -54.739 38.378 QT\n-53.864 38.378 -53.262 38.909 QT\n-52.661 39.44 -52.661 40.3 QT\n-52.661 41.409 -53.403 42.237 QT\n-54.145 43.065 -55.255 43.269 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 231.56268 292.72499] CT\r\n0.149 GC\r\nN\r\n-12.476 57.94 M\n-15.429 55.612 -17.562 52.597 QT\n-19.695 49.581 -21.054 46.167 QT\n-22.414 42.753 -23.086 39.026 QT\n-23.757 35.3 -23.757 31.55 QT\n-23.757 27.753 -23.086 24.026 QT\n-22.414 20.3 -21.031 16.854 QT\n-19.648 13.409 -17.5 10.409 QT\n-15.351 7.409 -12.476 5.159 QT\n-12.476 5.05 -12.226 5.05 QT\n-11.726 5.05 L\n-11.57 5.05 -11.445 5.19 QT\n-11.32 5.331 -11.32 5.519 QT\n-11.32 5.753 -11.414 5.847 QT\n-14.007 8.394 -15.726 11.292 QT\n-17.445 14.19 -18.492 17.464 QT\n-19.539 20.737 -20.007 24.245 QT\n-20.476 27.753 -20.476 31.55 QT\n-20.476 48.394 -11.476 57.144 QT\n-11.32 57.3 -11.32 57.581 QT\n-11.32 57.706 -11.461 57.878 QT\n-11.601 58.05 -11.726 58.05 QT\n-12.226 58.05 L\n-12.476 58.05 -12.476 57.94 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 231.56268 292.72499] CT\r\n0.149 GC\r\nN\r\n-4.079 43.894 M\n-4.079 43.581 -4.032 43.425 QT\n-0.079 27.612 L\n0.311 26.144 0.311 25.034 QT\n0.311 22.753 -1.235 22.753 QT\n-2.892 22.753 -3.696 24.729 QT\n-4.501 26.706 -5.251 29.737 QT\n-5.251 29.894 -5.407 29.987 QT\n-5.564 30.081 -5.689 30.081 QT\n-6.314 30.081 L\n-6.485 30.081 -6.618 29.886 QT\n-6.751 29.69 -6.751 29.534 QT\n-6.173 27.222 -5.649 25.62 QT\n-5.126 24.019 -3.993 22.698 QT\n-2.86 21.378 -1.189 21.378 QT\n0.811 21.378 2.335 22.636 QT\n3.858 23.894 3.858 25.831 QT\n5.436 23.753 7.561 22.565 QT\n9.686 21.378 12.061 21.378 QT\n14.577 21.378 16.397 22.659 QT\n18.218 23.94 18.218 26.3 QT\n19.858 23.987 22.046 22.683 QT\n24.233 21.378 26.811 21.378 QT\n29.561 21.378 31.226 22.87 QT\n32.89 24.362 32.89 27.097 QT\n32.89 29.269 31.921 32.347 QT\n30.952 35.425 29.515 39.237 QT\n28.749 41.065 28.749 42.425 QT\n28.749 44.003 29.999 44.003 QT\n32.061 44.003 33.436 41.776 QT\n34.811 39.55 35.374 37.003 QT\n35.53 36.706 35.827 36.706 QT\n36.436 36.706 L\n36.655 36.706 36.796 36.847 QT\n36.936 36.987 36.936 37.159 QT\n36.936 37.222 36.89 37.315 QT\n36.155 40.315 34.358 42.854 QT\n32.561 45.394 29.874 45.394 QT\n27.999 45.394 26.686 44.112 QT\n25.374 42.831 25.374 41.003 QT\n25.374 40.065 25.811 38.925 QT\n27.311 34.94 28.304 31.808 QT\n29.296 28.675 29.296 26.3 QT\n29.296 24.815 28.702 23.784 QT\n28.108 22.753 26.718 22.753 QT\n23.811 22.753 21.694 24.526 QT\n19.577 26.3 18.015 29.222 QT\n17.921 29.737 17.858 30.019 QT\n14.452 43.628 L\n14.265 44.362 13.632 44.878 QT\n12.999 45.394 12.218 45.394 QT\n11.593 45.394 11.116 44.979 QT\n10.64 44.565 10.64 43.894 QT\n10.64 43.581 10.686 43.425 QT\n14.077 29.925 L\n14.624 27.753 14.624 26.3 QT\n14.624 24.815 14.015 23.784 QT\n13.405 22.753 11.968 22.753 QT\n10.015 22.753 8.39 23.604 QT\n6.765 24.456 5.546 25.87 QT\n4.327 27.284 3.311 29.222 QT\n-0.282 43.628 L\n-0.454 44.362 -1.095 44.878 QT\n-1.735 45.394 -2.501 45.394 QT\n-3.157 45.394 -3.618 44.979 QT\n-4.079 44.565 -4.079 43.894 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 231.56268 292.72499] CT\r\n0.149 GC\r\nN\r\n42.092 58.05 M\n41.623 58.05 41.623 57.581 QT\n41.623 57.347 41.733 57.253 QT\n50.795 48.394 50.795 31.55 QT\n50.795 14.706 41.842 5.956 QT\n41.623 5.831 41.623 5.519 QT\n41.623 5.331 41.772 5.19 QT\n41.92 5.05 42.092 5.05 QT\n42.592 5.05 L\n42.748 5.05 42.842 5.159 QT\n46.654 8.159 49.186 12.456 QT\n51.717 16.753 52.897 21.612 QT\n54.076 26.472 54.076 31.55 QT\n54.076 35.3 53.444 38.94 QT\n52.811 42.581 51.428 46.112 QT\n50.045 49.644 47.92 52.628 QT\n45.795 55.612 42.842 57.94 QT\n42.748 58.05 42.592 58.05 QT\n42.092 58.05 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n130 703 M\n130 53 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n130 703 M\n139.75 703 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n130 540.5 M\n139.75 540.5 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n130 378 M\n139.75 378 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n130 215.5 M\n139.75 215.5 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n130 53 M\n139.75 53 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 43.15 263.625] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-43 19 moveto \r\n1 -1 scale\r\n(-2) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 43.15 202.6875] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-43 19 moveto \r\n1 -1 scale\r\n(-1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 43.15 141.75] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 19 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 43.15 80.8125] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 19 moveto \r\n1 -1 scale\r\n(1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 43.15 19.875] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 19 moveto \r\n1 -1 scale\r\n(2) t \r\nGR\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24.025 141.74989] CT\r\n0.149 GC\r\nN\r\n-53.732 -11.622 M\n-52.623 -9.7 -49.857 -9.7 QT\n-47.342 -9.7 -45.506 -11.458 QT\n-43.67 -13.216 -42.545 -15.716 QT\n-41.42 -18.216 -40.795 -20.825 QT\n-43.154 -18.606 -45.889 -18.606 QT\n-47.982 -18.606 -49.459 -19.333 QT\n-50.935 -20.06 -51.756 -21.497 QT\n-52.576 -22.935 -52.576 -24.966 QT\n-52.576 -26.7 -52.107 -28.528 QT\n-51.639 -30.356 -50.795 -32.591 QT\n-49.951 -34.825 -49.342 -36.481 QT\n-48.639 -38.435 -48.639 -39.669 QT\n-48.639 -41.247 -49.795 -41.247 QT\n-51.904 -41.247 -53.256 -39.091 QT\n-54.607 -36.935 -55.264 -34.263 QT\n-55.357 -33.919 -55.701 -33.919 QT\n-56.326 -33.919 L\n-56.764 -33.919 -56.764 -34.419 QT\n-56.764 -34.575 L\n-55.904 -37.731 -54.146 -40.177 QT\n-52.389 -42.622 -49.701 -42.622 QT\n-47.81 -42.622 -46.506 -41.38 QT\n-45.201 -40.138 -45.201 -38.216 QT\n-45.201 -37.231 -45.639 -36.153 QT\n-45.873 -35.497 -46.701 -33.325 QT\n-47.529 -31.153 -47.967 -29.731 QT\n-48.404 -28.31 -48.685 -26.935 QT\n-48.967 -25.56 -48.967 -24.2 QT\n-48.967 -22.435 -48.217 -21.216 QT\n-47.467 -19.997 -45.842 -19.997 QT\n-42.56 -19.997 -39.935 -24.013 QT\n-35.935 -40.341 L\n-35.748 -41.044 -35.099 -41.544 QT\n-34.451 -42.044 -33.701 -42.044 QT\n-33.06 -42.044 -32.576 -41.63 QT\n-32.092 -41.216 -32.092 -40.544 QT\n-32.092 -40.247 -32.154 -40.138 QT\n-37.404 -19.044 L\n-38.107 -16.325 -39.967 -13.841 QT\n-41.826 -11.356 -44.451 -9.841 QT\n-47.076 -8.325 -49.935 -8.325 QT\n-51.295 -8.325 -52.646 -8.856 QT\n-53.998 -9.388 -54.826 -10.45 QT\n-55.654 -11.513 -55.654 -12.935 QT\n-55.654 -14.388 -54.795 -15.45 QT\n-53.935 -16.513 -52.514 -16.513 QT\n-51.67 -16.513 -51.084 -15.981 QT\n-50.498 -15.45 -50.498 -14.591 QT\n-50.498 -13.372 -51.404 -12.466 QT\n-52.31 -11.56 -53.529 -11.56 QT\n-53.576 -11.591 -53.631 -11.606 QT\n-53.685 -11.622 -53.732 -11.622 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24.025 141.74989] CT\r\n0.149 GC\r\nN\r\n-13.686 -6.06 M\n-16.639 -8.388 -18.772 -11.403 QT\n-20.905 -14.419 -22.264 -17.833 QT\n-23.624 -21.247 -24.295 -24.974 QT\n-24.967 -28.7 -24.967 -32.45 QT\n-24.967 -36.247 -24.295 -39.974 QT\n-23.624 -43.7 -22.241 -47.146 QT\n-20.858 -50.591 -18.709 -53.591 QT\n-16.561 -56.591 -13.686 -58.841 QT\n-13.686 -58.95 -13.436 -58.95 QT\n-12.936 -58.95 L\n-12.78 -58.95 -12.655 -58.81 QT\n-12.53 -58.669 -12.53 -58.481 QT\n-12.53 -58.247 -12.624 -58.153 QT\n-15.217 -55.606 -16.936 -52.708 QT\n-18.655 -49.81 -19.702 -46.536 QT\n-20.749 -43.263 -21.217 -39.755 QT\n-21.686 -36.247 -21.686 -32.45 QT\n-21.686 -15.606 -12.686 -6.856 QT\n-12.53 -6.7 -12.53 -6.419 QT\n-12.53 -6.294 -12.67 -6.122 QT\n-12.811 -5.95 -12.936 -5.95 QT\n-13.436 -5.95 L\n-13.686 -5.95 -13.686 -6.06 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24.025 141.74989] CT\r\n0.149 GC\r\nN\r\n-5.289 -20.106 M\n-5.289 -20.419 -5.242 -20.575 QT\n-1.289 -36.388 L\n-0.898 -37.856 -0.898 -38.966 QT\n-0.898 -41.247 -2.445 -41.247 QT\n-4.101 -41.247 -4.906 -39.271 QT\n-5.711 -37.294 -6.461 -34.263 QT\n-6.461 -34.106 -6.617 -34.013 QT\n-6.773 -33.919 -6.898 -33.919 QT\n-7.523 -33.919 L\n-7.695 -33.919 -7.828 -34.114 QT\n-7.961 -34.31 -7.961 -34.466 QT\n-7.383 -36.778 -6.859 -38.38 QT\n-6.336 -39.981 -5.203 -41.302 QT\n-4.07 -42.622 -2.398 -42.622 QT\n-0.398 -42.622 1.125 -41.364 QT\n2.649 -40.106 2.649 -38.169 QT\n4.227 -40.247 6.352 -41.435 QT\n8.477 -42.622 10.852 -42.622 QT\n13.367 -42.622 15.188 -41.341 QT\n17.008 -40.06 17.008 -37.7 QT\n18.649 -40.013 20.836 -41.317 QT\n23.024 -42.622 25.602 -42.622 QT\n28.352 -42.622 30.016 -41.13 QT\n31.68 -39.638 31.68 -36.903 QT\n31.68 -34.731 30.711 -31.653 QT\n29.742 -28.575 28.305 -24.763 QT\n27.539 -22.935 27.539 -21.575 QT\n27.539 -19.997 28.789 -19.997 QT\n30.852 -19.997 32.227 -22.224 QT\n33.602 -24.45 34.164 -26.997 QT\n34.32 -27.294 34.617 -27.294 QT\n35.227 -27.294 L\n35.445 -27.294 35.586 -27.153 QT\n35.727 -27.013 35.727 -26.841 QT\n35.727 -26.778 35.68 -26.685 QT\n34.945 -23.685 33.149 -21.146 QT\n31.352 -18.606 28.664 -18.606 QT\n26.789 -18.606 25.477 -19.888 QT\n24.164 -21.169 24.164 -22.997 QT\n24.164 -23.935 24.602 -25.075 QT\n26.102 -29.06 27.094 -32.192 QT\n28.086 -35.325 28.086 -37.7 QT\n28.086 -39.185 27.492 -40.216 QT\n26.899 -41.247 25.508 -41.247 QT\n22.602 -41.247 20.484 -39.474 QT\n18.367 -37.7 16.805 -34.778 QT\n16.711 -34.263 16.649 -33.981 QT\n13.242 -20.372 L\n13.055 -19.638 12.422 -19.122 QT\n11.789 -18.606 11.008 -18.606 QT\n10.383 -18.606 9.906 -19.021 QT\n9.43 -19.435 9.43 -20.106 QT\n9.43 -20.419 9.477 -20.575 QT\n12.867 -34.075 L\n13.414 -36.247 13.414 -37.7 QT\n13.414 -39.185 12.805 -40.216 QT\n12.195 -41.247 10.758 -41.247 QT\n8.805 -41.247 7.18 -40.396 QT\n5.555 -39.544 4.336 -38.13 QT\n3.117 -36.716 2.102 -34.778 QT\n-1.492 -20.372 L\n-1.664 -19.638 -2.305 -19.122 QT\n-2.945 -18.606 -3.711 -18.606 QT\n-4.367 -18.606 -4.828 -19.021 QT\n-5.289 -19.435 -5.289 -20.106 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24.025 141.74989] CT\r\n0.149 GC\r\nN\r\n40.882 -5.95 M\n40.413 -5.95 40.413 -6.419 QT\n40.413 -6.653 40.523 -6.747 QT\n49.585 -15.606 49.585 -32.45 QT\n49.585 -49.294 40.632 -58.044 QT\n40.413 -58.169 40.413 -58.481 QT\n40.413 -58.669 40.562 -58.81 QT\n40.71 -58.95 40.882 -58.95 QT\n41.382 -58.95 L\n41.538 -58.95 41.632 -58.841 QT\n45.445 -55.841 47.976 -51.544 QT\n50.507 -47.247 51.687 -42.388 QT\n52.867 -37.528 52.867 -32.45 QT\n52.867 -28.7 52.234 -25.06 QT\n51.601 -21.419 50.218 -17.888 QT\n48.835 -14.356 46.71 -11.372 QT\n44.585 -8.388 41.632 -6.06 QT\n41.538 -5.95 41.382 -5.95 QT\n40.882 -5.95 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n5.333 LW\r\nN\r\n780 378 M\n779.673 367.694 L\n778.693 357.429 L\n777.063 347.247 L\n774.792 337.188 L\n771.887 327.295 L\n768.36 317.605 L\n764.226 308.158 L\n759.501 298.993 L\n754.204 290.146 L\n748.356 281.652 L\n741.982 273.547 L\n735.107 265.862 L\n727.758 258.629 L\n719.965 251.876 L\n711.759 245.631 L\n703.174 239.92 L\n694.244 234.764 L\n685.005 230.185 L\n675.494 226.201 L\n665.75 222.828 L\n655.811 220.081 L\n645.718 217.969 L\n635.511 216.501 L\n625.232 215.684 L\n614.922 215.52 L\n604.622 216.011 L\n594.374 217.154 L\n584.219 218.945 L\n574.198 221.376 L\n564.351 224.437 L\n554.719 228.117 L\n545.339 232.401 L\n536.25 237.271 L\n527.488 242.707 L\n519.088 248.689 L\n511.085 255.191 L\n503.51 262.187 L\n496.395 269.65 L\n489.766 277.549 L\n483.653 285.853 L\n478.078 294.527 L\n473.064 303.538 L\n468.632 312.849 L\n464.8 322.422 L\n461.582 332.218 L\n458.993 342.2 L\n457.041 352.325 L\n455.736 362.553 L\n455.082 372.844 L\n455.082 383.156 L\n455.736 393.447 L\n457.041 403.675 L\n458.993 413.8 L\n461.582 423.782 L\n464.8 433.578 L\n468.632 443.151 L\n473.064 452.462 L\n478.078 461.473 L\n483.653 470.147 L\n489.766 478.451 L\n496.395 486.35 L\n503.51 493.813 L\n511.085 500.809 L\n519.088 507.311 L\n527.488 513.293 L\n536.25 518.729 L\n545.339 523.599 L\n554.719 527.883 L\n564.351 531.563 L\n574.198 534.624 L\n584.219 537.055 L\n594.374 538.846 L\n604.622 539.989 L\n614.922 540.48 L\n625.232 540.316 L\n635.511 539.499 L\n645.718 538.031 L\n655.811 535.919 L\n665.75 533.172 L\n675.494 529.799 L\n685.005 525.815 L\n694.244 521.236 L\n703.174 516.08 L\n711.759 510.369 L\n719.965 504.124 L\n727.758 497.371 L\n735.107 490.138 L\n741.982 482.453 L\n748.356 474.348 L\n754.204 465.854 L\n759.501 457.007 L\n764.226 447.842 L\n768.36 438.395 L\n771.887 428.705 L\n774.792 418.812 L\n777.063 408.753 L\n778.693 398.571 L\n779.673 388.306 L\n780 378 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0.502 0 RC\r\nN\r\n489.766 478.451 M\n496.395 486.35 L\n503.51 493.813 L\n511.085 500.809 L\n519.088 507.311 L\n527.488 513.293 L\n536.25 518.729 L\n545.339 523.599 L\n554.719 527.883 L\n564.351 531.563 L\n574.198 534.624 L\n584.219 537.055 L\n594.374 538.846 L\n604.622 539.989 L\n614.922 540.48 L\n625.232 540.316 L\n635.511 539.499 L\n645.718 538.031 L\n655.811 535.919 L\n665.75 533.172 L\n675.494 529.799 L\n685.005 525.815 L\n694.244 521.236 L\n703.174 516.08 L\n711.759 510.369 L\n719.965 504.124 L\n727.758 497.371 L\n735.107 490.138 L\n741.982 482.453 L\n748.356 474.348 L\n754.204 465.854 L\n759.501 457.007 L\n764.226 447.842 L\n768.36 438.395 L\n771.887 428.705 L\n774.792 418.812 L\n777.063 408.753 L\n778.693 398.571 L\n779.673 388.306 L\n780 378 L\n779.673 367.694 L\n778.693 357.429 L\n777.063 347.247 L\n774.792 337.188 L\n771.887 327.295 L\n768.36 317.605 L\n764.226 308.158 L\n759.501 298.993 L\n754.204 290.146 L\n748.356 281.652 L\n741.982 273.547 L\n735.107 265.862 L\n727.758 258.629 L\n719.965 251.876 L\n711.759 245.631 L\n703.174 239.92 L\n694.244 234.764 L\n685.005 230.185 L\n675.494 226.201 L\n665.75 222.828 L\n655.811 220.081 L\n645.718 217.969 L\n635.511 216.501 L\n625.232 215.684 L\n614.922 215.52 L\n604.622 216.011 L\n594.374 217.154 L\n584.219 218.945 L\n574.198 221.376 L\n564.351 224.437 L\n554.719 228.117 L\n545.339 232.401 L\n536.25 237.271 L\n527.488 242.707 L\n519.088 248.689 L\n511.085 255.191 L\n503.51 262.187 L\n496.395 269.65 L\n489.766 277.549 L\n483.653 285.853 L\n478.078 294.527 L\n473.064 303.538 L\n468.632 312.849 L\n464.8 322.422 L\n461.582 332.218 L\n458.993 342.2 L\n457.041 352.325 L\n455.736 362.553 L\n455.082 372.844 L\n455.082 383.156 L\n455.736 393.447 L\n457.041 403.675 L\n458.993 413.8 L\n461.582 423.782 L\n464.8 433.578 L\n468.632 443.151 L\n473.064 452.462 L\n478.078 461.473 L\n483.653 470.147 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n2 setlinecap\r\n10.0 ML\r\n1.333 LW\r\nN\r\n780 378 M\n779.673 367.694 L\n778.693 357.429 L\n777.063 347.247 L\n774.792 337.188 L\n771.887 327.295 L\n768.36 317.605 L\n764.226 308.158 L\n759.501 298.993 L\n754.204 290.146 L\n748.356 281.652 L\n741.982 273.547 L\n735.107 265.862 L\n727.758 258.629 L\n719.965 251.876 L\n711.759 245.631 L\n703.174 239.92 L\n694.244 234.764 L\n685.005 230.185 L\n675.494 226.201 L\n665.75 222.828 L\n655.811 220.081 L\n645.718 217.969 L\n635.511 216.501 L\n625.232 215.684 L\n614.922 215.52 L\n604.622 216.011 L\n594.374 217.154 L\n584.219 218.945 L\n574.198 221.376 L\n564.351 224.437 L\n554.719 228.117 L\n545.339 232.401 L\n536.25 237.271 L\n527.488 242.707 L\n519.088 248.689 L\n511.085 255.191 L\n503.51 262.187 L\n496.395 269.65 L\n489.766 277.549 L\n483.653 285.853 L\n478.078 294.527 L\n473.064 303.538 L\n468.632 312.849 L\n464.8 322.422 L\n461.582 332.218 L\n458.993 342.2 L\n457.041 352.325 L\n455.736 362.553 L\n455.082 372.844 L\n455.082 383.156 L\n455.736 393.447 L\n457.041 403.675 L\n458.993 413.8 L\n461.582 423.782 L\n464.8 433.578 L\n468.632 443.151 L\n473.064 452.462 L\n478.078 461.473 L\n483.653 470.147 L\n489.766 478.451 L\n496.395 486.35 L\n503.51 493.813 L\n511.085 500.809 L\n519.088 507.311 L\n527.488 513.293 L\n536.25 518.729 L\n545.339 523.599 L\n554.719 527.883 L\n564.351 531.563 L\n574.198 534.624 L\n584.219 537.055 L\n594.374 538.846 L\n604.622 539.989 L\n614.922 540.48 L\n625.232 540.316 L\n635.511 539.499 L\n645.718 538.031 L\n655.811 535.919 L\n665.75 533.172 L\n675.494 529.799 L\n685.005 525.815 L\n694.244 521.236 L\n703.174 516.08 L\n711.759 510.369 L\n719.965 504.124 L\n727.758 497.371 L\n735.107 490.138 L\n741.982 482.453 L\n748.356 474.348 L\n754.204 465.854 L\n759.501 457.007 L\n764.226 447.842 L\n768.36 438.395 L\n771.887 428.705 L\n774.792 418.812 L\n777.063 408.753 L\n778.693 398.571 L\n779.673 388.306 L\n780 378 L\n780 378 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 48.75 141.75] CT\r\n0 0 1 RC\r\n10.0 ML\r\n2.667 LW\r\nN\r\n-8 0 M\n0 10.64 L\n8 0 L\n0 -10.64 L\ncp\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 414.375 141.14063] CT\r\n1 0 0 RC\r\n10.0 ML\r\n2.667 LW\r\nN\r\n-8 0 M\n0 10.64 L\n8 0 L\n0 -10.64 L\ncp\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n5.333 LW\r\nN\r\n130 378 M\n130 378 L\n138.118 377.512 L\n154.199 380.002 L\n177.031 386.679 L\n206.063 396.743 L\n238.228 408.147 L\n271.882 420.187 L\n305.911 431.631 L\n340.589 444.026 L\n377.263 458.484 L\n418.522 475.762 L\n460.353 496.861 L\n501.749 519.954 L\n545.468 537.374 L\n590.794 546.087 L\n635.044 543.053 L\n676.095 532.99 L\n714.002 520.799 L\n749.653 508.197 L\n783.025 495.889 L\n814.135 484.245 L\n843.009 473.429 L\n869.735 463.526 L\n894.378 454.558 L\n917.039 446.523 L\n937.829 439.395 L\n956.865 433.132 L\n974.263 427.679 L\n990.135 422.974 L\n1004.556 418.946 L\n1017.658 415.531 L\n1029.543 412.66 L\n1040.305 410.265 L\n1050.034 408.282 L\n1058.816 406.651 L\n1066.73 405.32 L\n1073.816 404.245 L\n1080.121 403.387 L\n1085.698 402.711 L\n1090.605 402.182 L\n1094.904 401.772 L\n1098.652 401.458 L\n1101.905 401.219 L\n1104.717 401.039 L\n1105.039 401.021 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n130 378 M\n130 378 L\n138.116 377.794 L\n154.198 380.103 L\n176.665 385.868 L\n204.6 395.173 L\n237.676 407.171 L\n277.298 401.294 L\n312.899 386.87 L\n346.209 369.504 L\n377.105 350.335 L\n409.288 328.065 L\n445.058 302.043 L\n481.707 273.085 L\n518.928 243.676 L\n561.586 223.954 L\n606.576 215.771 L\n650.181 219.308 L\n691.018 228.764 L\n728.456 240.351 L\n763.455 252.376 L\n796.063 264.1 L\n826.358 275.159 L\n854.418 285.391 L\n880.317 294.732 L\n904.153 303.157 L\n926.039 310.676 L\n946.094 317.319 L\n964.437 323.135 L\n981.187 328.179 L\n996.454 332.515 L\n1010.312 336.215 L\n1022.895 339.34 L\n1034.301 341.96 L\n1044.624 344.139 L\n1053.953 345.938 L\n1062.37 347.414 L\n1069.917 348.61 L\n1076.639 349.568 L\n1082.593 350.327 L\n1087.835 350.922 L\n1092.429 351.384 L\n1096.437 351.74 L\n1099.917 352.011 L\n1102.926 352.217 L\n1105.039 352.339 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n[20 20] 0 setdash\r\n2 LJ\r\n5.333 LW\r\nN\r\n130 378 M\n138.086 377.201 L\n154.269 378.675 L\n178.439 375.519 L\n210.533 380.64 L\n249.598 391.788 L\n296.236 379.618 L\n343.115 356.658 L\n387.713 327.195 L\n428.471 293.148 L\n469.021 260.132 L\n512.422 233.248 L\n558.649 215.967 L\n605.51 209.958 L\n650.067 215.121 L\n690.887 225.864 L\n728.369 238.034 L\n762.869 250.109 L\n794.608 261.51 L\n823.756 272.02 L\n850.473 281.571 L\n874.914 290.162 L\n897.237 297.826 L\n917.597 304.612 L\n936.141 310.579 L\n953.012 315.789 L\n968.343 320.308 L\n982.258 324.203 L\n994.873 327.537 L\n1006.296 330.375 L\n1016.626 332.776 L\n1025.955 334.794 L\n1034.37 336.482 L\n1041.949 337.886 L\n1048.767 339.048 L\n1054.892 340.004 L\n1060.387 340.788 L\n1065.312 341.428 L\n1069.719 341.949 L\n1073.658 342.37 L\n1077.177 342.71 L\n1080.315 342.983 L\n1083.112 343.202 L\n1085.603 343.378 L\n1087.818 343.518 L\n1089.788 343.629 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 1 RC\r\n[20 20] 0 setdash\r\n2 LJ\r\n5.333 LW\r\nN\r\n130 378 M\n138.089 377.233 L\n154.129 374.633 L\n177.997 369.683 L\n209.58 362.02 L\n248.741 351.211 L\n295.28 336.697 L\n345.413 319.032 L\n396.394 298.632 L\n446.211 275.761 L\n493.253 250.448 L\n539.654 228.164 L\n587.188 215.744 L\n633.671 215.272 L\n676.416 224.182 L\n715.443 235.836 L\n751.231 247.868 L\n784.088 259.401 L\n814.23 270.105 L\n841.836 279.867 L\n867.079 288.67 L\n890.127 296.538 L\n911.141 303.516 L\n930.278 309.661 L\n947.687 315.035 L\n963.506 319.705 L\n977.864 323.736 L\n990.882 327.193 L\n1002.672 330.14 L\n1013.336 332.638 L\n1022.97 334.741 L\n1031.662 336.503 L\n1039.495 337.971 L\n1046.544 339.188 L\n1052.879 340.191 L\n1058.566 341.015 L\n1063.664 341.689 L\n1068.23 342.237 L\n1072.314 342.682 L\n1075.963 343.041 L\n1079.22 343.331 L\n1082.125 343.564 L\n1084.713 343.75 L\n1087.017 343.899 L\n1089.067 344.017 L\n1090.889 344.112 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n1084 682 M\n1084 463 L\n670 463 L\n670 682 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 184.87788] CT\r\nN\r\n2.016 10.368 M\n1.594 10.368 1.594 9.805 QT\n1.609 9.696 1.68 9.43 QT\n1.75 9.165 1.859 9.008 QT\n1.969 8.852 2.141 8.852 QT\n6.25 8.852 6.922 6.227 QT\n12.766 -17.288 L\n11.563 -17.492 8.984 -17.492 QT\n8.563 -17.492 8.563 -18.054 QT\n8.594 -18.163 8.656 -18.429 QT\n8.719 -18.695 8.828 -18.851 QT\n8.938 -19.007 9.109 -19.007 QT\n16.547 -19.007 L\n16.859 -19.007 16.938 -18.726 QT\n26.5 4.008 L\n31.266 -15.038 L\n31.344 -15.507 31.344 -15.695 QT\n31.344 -17.492 28.031 -17.492 QT\n27.609 -17.492 27.609 -18.054 QT\n27.75 -18.601 27.836 -18.804 QT\n27.922 -19.007 28.344 -19.007 QT\n37.547 -19.007 L\n37.969 -19.007 37.969 -18.445 QT\n37.938 -18.335 37.875 -18.07 QT\n37.813 -17.804 37.695 -17.648 QT\n37.578 -17.492 37.422 -17.492 QT\n33.297 -17.492 32.625 -14.867 QT\n26.453 9.993 L\n26.313 10.368 26.016 10.368 QT\n25.484 10.368 L\n25.203 10.368 25.109 10.071 QT\n14.156 -15.945 L\n14.063 -16.21 L\n13.984 -16.304 13.984 -16.335 QT\n8.297 6.415 L\n8.25 6.524 8.227 6.68 QT\n8.203 6.837 8.172 7.055 QT\n8.172 8.165 9.133 8.508 QT\n10.094 8.852 11.531 8.852 QT\n11.953 8.852 11.953 9.43 QT\n11.797 10.008 11.695 10.188 QT\n11.594 10.368 11.234 10.368 QT\n2.016 10.368 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 184.87788] CT\r\nN\r\n54.654 4.649 M\n54.295 4.649 54.068 4.383 QT\n53.841 4.118 53.841 3.79 QT\n53.841 3.446 54.068 3.188 QT\n54.295 2.93 54.654 2.93 QT\n81.654 2.93 L\n81.966 2.93 82.201 3.188 QT\n82.435 3.446 82.435 3.79 QT\n82.435 4.118 82.201 4.383 QT\n81.966 4.649 81.654 4.649 QT\n54.654 4.649 L\ncp\n54.654 -3.695 M\n54.295 -3.695 54.068 -3.952 QT\n53.841 -4.21 53.841 -4.554 QT\n53.841 -4.882 54.068 -5.156 QT\n54.295 -5.429 54.654 -5.429 QT\n81.654 -5.429 L\n81.966 -5.429 82.201 -5.156 QT\n82.435 -4.882 82.435 -4.554 QT\n82.435 -4.21 82.201 -3.952 QT\n81.966 -3.695 81.654 -3.695 QT\n54.654 -3.695 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 184.87788] CT\r\nN\r\n99.16 10.368 M\n99.16 9.212 L\n99.16 9.102 99.238 8.977 QT\n105.926 1.587 L\n107.441 -0.054 108.379 -1.163 QT\n109.316 -2.273 110.246 -3.718 QT\n111.176 -5.163 111.707 -6.671 QT\n112.238 -8.179 112.238 -9.851 QT\n112.238 -11.617 111.59 -13.226 QT\n110.941 -14.835 109.652 -15.796 QT\n108.363 -16.757 106.535 -16.757 QT\n104.66 -16.757 103.168 -15.632 QT\n101.676 -14.507 101.066 -12.726 QT\n101.238 -12.773 101.535 -12.773 QT\n102.504 -12.773 103.183 -12.124 QT\n103.863 -11.476 103.863 -10.445 QT\n103.863 -9.46 103.183 -8.773 QT\n102.504 -8.085 101.535 -8.085 QT\n100.519 -8.085 99.84 -8.788 QT\n99.16 -9.492 99.16 -10.445 QT\n99.16 -12.054 99.769 -13.476 QT\n100.379 -14.898 101.519 -15.999 QT\n102.66 -17.101 104.105 -17.687 QT\n105.551 -18.273 107.16 -18.273 QT\n109.613 -18.273 111.738 -17.234 QT\n113.863 -16.195 115.098 -14.296 QT\n116.332 -12.398 116.332 -9.851 QT\n116.332 -7.976 115.512 -6.296 QT\n114.691 -4.617 113.418 -3.242 QT\n112.144 -1.867 110.144 -0.124 QT\n108.144 1.618 107.519 2.196 QT\n102.644 6.883 L\n106.785 6.883 L\n109.832 6.883 111.879 6.829 QT\n113.926 6.774 114.051 6.665 QT\n114.551 6.133 115.082 2.712 QT\n116.332 2.712 L\n115.113 10.368 L\n99.16 10.368 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 184.87788] CT\r\nN\r\n119.823 3.274 M\n119.823 1.758 L\n133.104 -18.054 L\n133.26 -18.273 133.541 -18.273 QT\n134.182 -18.273 L\n134.666 -18.273 134.666 -17.788 QT\n134.666 1.758 L\n138.885 1.758 L\n138.885 3.274 L\n134.666 3.274 L\n134.666 7.493 L\n134.666 8.368 135.924 8.61 QT\n137.182 8.852 138.838 8.852 QT\n138.838 10.368 L\n126.994 10.368 L\n126.994 8.852 L\n128.651 8.852 129.916 8.61 QT\n131.182 8.368 131.182 7.493 QT\n131.182 3.274 L\n119.823 3.274 L\ncp\n121.244 1.758 M\n131.432 1.758 L\n131.432 -13.46 L\n121.244 1.758 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 184.87788] CT\r\nN\r\n144.485 18.118 M\n144.485 17.93 144.657 17.758 QT\n146.204 16.274 147.063 14.321 QT\n147.923 12.368 147.923 10.196 QT\n147.923 9.68 L\n147.235 10.368 146.204 10.368 QT\n145.22 10.368 144.524 9.673 QT\n143.829 8.977 143.829 7.993 QT\n143.829 6.993 144.524 6.321 QT\n145.22 5.649 146.204 5.649 QT\n147.735 5.649 148.384 7.063 QT\n149.032 8.477 149.032 10.196 QT\n149.032 12.587 148.079 14.743 QT\n147.126 16.899 145.391 18.618 QT\n145.22 18.696 145.11 18.696 QT\n144.907 18.696 144.696 18.508 QT\n144.485 18.321 144.485 18.118 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 184.87788] CT\r\nN\r\n172.107 18.79 M\n172.107 17.821 172.537 15.977 QT\n172.966 14.133 173.583 12.04 QT\n174.201 9.946 174.638 8.602 QT\n174.81 6.462 174.81 5.368 QT\n174.81 2.602 174.263 0.219 QT\n173.716 -2.163 172.208 -3.773 QT\n170.701 -5.382 167.982 -5.382 QT\n166.56 -5.382 165.138 -4.773 QT\n163.716 -4.163 162.701 -3.07 QT\n161.685 -1.976 161.31 -0.585 QT\n161.232 -0.335 160.966 -0.335 QT\n160.451 -0.335 L\n160.107 -0.335 160.107 -0.726 QT\n160.107 -0.867 L\n160.591 -2.804 161.818 -4.593 QT\n163.044 -6.382 164.826 -7.507 QT\n166.607 -8.632 168.576 -8.632 QT\n170.591 -8.632 172.06 -7.265 QT\n173.529 -5.898 174.412 -3.804 QT\n175.294 -1.71 175.685 0.43 QT\n176.076 2.571 176.076 4.462 QT\n178.232 -1.413 180.919 -6.663 QT\n181.576 -8.038 L\n181.701 -8.179 181.857 -8.179 QT\n182.388 -8.179 L\n182.732 -8.179 182.732 -7.773 QT\n182.732 -7.695 182.638 -7.523 QT\n181.998 -6.179 L\n180.123 -2.46 178.56 1.36 QT\n176.998 5.18 175.888 8.727 QT\n175.716 10.18 175.24 12.696 QT\n174.763 15.212 174.091 17.391 QT\n173.419 19.571 172.748 19.649 QT\n172.107 19.649 172.107 18.79 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 184.87788] CT\r\nN\r\n184.567 16.848 M\n184.567 15.785 L\n188.317 15.785 188.317 14.848 QT\n188.317 -0.902 L\n186.77 -0.152 184.395 -0.152 QT\n184.395 -1.215 L\n188.067 -1.215 189.942 -3.137 QT\n190.363 -3.137 L\n190.473 -3.137 190.567 -3.051 QT\n190.66 -2.965 190.66 -2.871 QT\n190.66 14.848 L\n190.66 15.785 194.41 15.785 QT\n194.41 16.848 L\n184.567 16.848 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 184.87788] CT\r\nN\r\n214.299 4.649 M\n213.94 4.649 213.714 4.383 QT\n213.487 4.118 213.487 3.79 QT\n213.487 3.446 213.714 3.188 QT\n213.94 2.93 214.299 2.93 QT\n241.299 2.93 L\n241.612 2.93 241.846 3.188 QT\n242.081 3.446 242.081 3.79 QT\n242.081 4.118 241.846 4.383 QT\n241.612 4.649 241.299 4.649 QT\n214.299 4.649 L\ncp\n214.299 -3.695 M\n213.94 -3.695 213.714 -3.952 QT\n213.487 -4.21 213.487 -4.554 QT\n213.487 -4.882 213.714 -5.156 QT\n213.94 -5.429 214.299 -5.429 QT\n241.299 -5.429 L\n241.612 -5.429 241.846 -5.156 QT\n242.081 -4.882 242.081 -4.554 QT\n242.081 -4.21 241.846 -3.952 QT\n241.612 -3.695 241.299 -3.695 QT\n214.299 -3.695 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 184.87788] CT\r\nN\r\n267.415 11.305 M\n262.149 11.305 260.251 6.969 QT\n258.352 2.633 258.352 -3.335 QT\n258.352 -7.085 259.032 -10.382 QT\n259.712 -13.679 261.735 -15.976 QT\n263.759 -18.273 267.415 -18.273 QT\n270.243 -18.273 272.056 -16.89 QT\n273.868 -15.507 274.806 -13.312 QT\n275.743 -11.117 276.095 -8.609 QT\n276.446 -6.101 276.446 -3.335 QT\n276.446 0.352 275.759 3.579 QT\n275.071 6.805 273.079 9.055 QT\n271.087 11.305 267.415 11.305 QT\ncp\n267.415 10.196 M\n269.806 10.196 270.985 7.743 QT\n272.165 5.29 272.438 2.305 QT\n272.712 -0.679 272.712 -4.038 QT\n272.712 -7.273 272.438 -9.999 QT\n272.165 -12.726 271.001 -14.945 QT\n269.837 -17.163 267.415 -17.163 QT\n264.977 -17.163 263.806 -14.937 QT\n262.634 -12.71 262.36 -9.992 QT\n262.087 -7.273 262.087 -4.038 QT\n262.087 -1.648 262.196 0.477 QT\n262.306 2.602 262.813 4.86 QT\n263.321 7.118 264.446 8.657 QT\n265.571 10.196 267.415 10.196 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 184.87788] CT\r\nN\r\n281.874 7.993 M\n281.874 7.024 282.593 6.337 QT\n283.312 5.649 284.249 5.649 QT\n284.843 5.649 285.406 5.962 QT\n285.968 6.274 286.281 6.844 QT\n286.593 7.415 286.593 7.993 QT\n286.593 8.946 285.906 9.657 QT\n285.218 10.368 284.249 10.368 QT\n283.312 10.368 282.593 9.657 QT\n281.874 8.946 281.874 7.993 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 184.87788] CT\r\nN\r\n291.468 3.274 M\n291.468 1.758 L\n304.749 -18.054 L\n304.906 -18.273 305.187 -18.273 QT\n305.828 -18.273 L\n306.312 -18.273 306.312 -17.788 QT\n306.312 1.758 L\n310.531 1.758 L\n310.531 3.274 L\n306.312 3.274 L\n306.312 7.493 L\n306.312 8.368 307.57 8.61 QT\n308.828 8.852 310.484 8.852 QT\n310.484 10.368 L\n298.64 10.368 L\n298.64 8.852 L\n300.296 8.852 301.562 8.61 QT\n302.828 8.368 302.828 7.493 QT\n302.828 3.274 L\n291.468 3.274 L\ncp\n292.89 1.758 M\n303.078 1.758 L\n303.078 -13.46 L\n292.89 1.758 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n5.333 LW\r\nN\r\n678.003 493.008 M\n758.029 493.008 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 204.75096] CT\r\nN\r\n/f-1698885829{2.016 10.368 M\n1.594 10.368 1.594 9.805 QT\n1.609 9.696 1.68 9.43 QT\n1.75 9.165 1.859 9.008 QT\n1.969 8.852 2.141 8.852 QT\n6.25 8.852 6.922 6.227 QT\n12.766 -17.288 L\n11.563 -17.492 8.984 -17.492 QT\n8.563 -17.492 8.563 -18.054 QT\n8.594 -18.163 8.656 -18.429 QT\n8.719 -18.695 8.828 -18.851 QT\n8.938 -19.007 9.109 -19.007 QT\n16.547 -19.007 L\n16.859 -19.007 16.938 -18.726 QT\n26.5 4.008 L\n31.266 -15.038 L\n31.344 -15.507 31.344 -15.695 QT\n31.344 -17.492 28.031 -17.492 QT\n27.609 -17.492 27.609 -18.054 QT\n27.75 -18.601 27.836 -18.804 QT\n27.922 -19.007 28.344 -19.007 QT\n37.547 -19.007 L\n37.969 -19.007 37.969 -18.445 QT\n37.938 -18.335 37.875 -18.07 QT\n37.813 -17.804 37.695 -17.648 QT\n37.578 -17.492 37.422 -17.492 QT\n33.297 -17.492 32.625 -14.867 QT\n26.453 9.993 L\n26.313 10.368 26.016 10.368 QT\n25.484 10.368 L\n25.203 10.368 25.109 10.071 QT\n14.156 -15.945 L\n14.063 -16.21 L\n13.984 -16.304 13.984 -16.335 QT\n8.297 6.415 L\n8.25 6.524 8.227 6.68 QT\n8.203 6.837 8.172 7.055 QT\n8.172 8.165 9.133 8.508 QT\n10.094 8.852 11.531 8.852 QT\n11.953 8.852 11.953 9.43 QT\n11.797 10.008 11.695 10.188 QT\n11.594 10.368 11.234 10.368 QT\n2.016 10.368 L\ncp}def\r\nf-1698885829\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 204.75096] CT\r\nN\r\n/f-1758447675{54.654 4.649 M\n54.295 4.649 54.068 4.383 QT\n53.841 4.118 53.841 3.79 QT\n53.841 3.446 54.068 3.188 QT\n54.295 2.93 54.654 2.93 QT\n81.654 2.93 L\n81.966 2.93 82.201 3.188 QT\n82.435 3.446 82.435 3.79 QT\n82.435 4.118 82.201 4.383 QT\n81.966 4.649 81.654 4.649 QT\n54.654 4.649 L\ncp\n54.654 -3.695 M\n54.295 -3.695 54.068 -3.952 QT\n53.841 -4.21 53.841 -4.554 QT\n53.841 -4.882 54.068 -5.156 QT\n54.295 -5.429 54.654 -5.429 QT\n81.654 -5.429 L\n81.966 -5.429 82.201 -5.156 QT\n82.435 -4.882 82.435 -4.554 QT\n82.435 -4.21 82.201 -3.952 QT\n81.966 -3.695 81.654 -3.695 QT\n54.654 -3.695 L\ncp}def\r\nf-1758447675\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 204.75096] CT\r\nN\r\n/f-2127470435{99.16 10.368 M\n99.16 9.212 L\n99.16 9.102 99.238 8.977 QT\n105.926 1.587 L\n107.441 -0.054 108.379 -1.163 QT\n109.316 -2.273 110.246 -3.718 QT\n111.176 -5.163 111.707 -6.671 QT\n112.238 -8.179 112.238 -9.851 QT\n112.238 -11.617 111.59 -13.226 QT\n110.941 -14.835 109.652 -15.796 QT\n108.363 -16.757 106.535 -16.757 QT\n104.66 -16.757 103.168 -15.632 QT\n101.676 -14.507 101.066 -12.726 QT\n101.238 -12.773 101.535 -12.773 QT\n102.504 -12.773 103.183 -12.124 QT\n103.863 -11.476 103.863 -10.445 QT\n103.863 -9.46 103.183 -8.773 QT\n102.504 -8.085 101.535 -8.085 QT\n100.519 -8.085 99.84 -8.788 QT\n99.16 -9.492 99.16 -10.445 QT\n99.16 -12.054 99.769 -13.476 QT\n100.379 -14.898 101.519 -15.999 QT\n102.66 -17.101 104.105 -17.687 QT\n105.551 -18.273 107.16 -18.273 QT\n109.613 -18.273 111.738 -17.234 QT\n113.863 -16.195 115.098 -14.296 QT\n116.332 -12.398 116.332 -9.851 QT\n116.332 -7.976 115.512 -6.296 QT\n114.691 -4.617 113.418 -3.242 QT\n112.144 -1.867 110.144 -0.124 QT\n108.144 1.618 107.519 2.196 QT\n102.644 6.883 L\n106.785 6.883 L\n109.832 6.883 111.879 6.829 QT\n113.926 6.774 114.051 6.665 QT\n114.551 6.133 115.082 2.712 QT\n116.332 2.712 L\n115.113 10.368 L\n99.16 10.368 L\ncp}def\r\nf-2127470435\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 204.75096] CT\r\nN\r\n/f-2019066066{119.823 3.274 M\n119.823 1.758 L\n133.104 -18.054 L\n133.26 -18.273 133.541 -18.273 QT\n134.182 -18.273 L\n134.666 -18.273 134.666 -17.788 QT\n134.666 1.758 L\n138.885 1.758 L\n138.885 3.274 L\n134.666 3.274 L\n134.666 7.493 L\n134.666 8.368 135.924 8.61 QT\n137.182 8.852 138.838 8.852 QT\n138.838 10.368 L\n126.994 10.368 L\n126.994 8.852 L\n128.651 8.852 129.916 8.61 QT\n131.182 8.368 131.182 7.493 QT\n131.182 3.274 L\n119.823 3.274 L\ncp\n121.244 1.758 M\n131.432 1.758 L\n131.432 -13.46 L\n121.244 1.758 L\ncp}def\r\nf-2019066066\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 204.75096] CT\r\nN\r\n/f-1779188984{144.485 18.118 M\n144.485 17.93 144.657 17.758 QT\n146.204 16.274 147.063 14.321 QT\n147.923 12.368 147.923 10.196 QT\n147.923 9.68 L\n147.235 10.368 146.204 10.368 QT\n145.22 10.368 144.524 9.673 QT\n143.829 8.977 143.829 7.993 QT\n143.829 6.993 144.524 6.321 QT\n145.22 5.649 146.204 5.649 QT\n147.735 5.649 148.384 7.063 QT\n149.032 8.477 149.032 10.196 QT\n149.032 12.587 148.079 14.743 QT\n147.126 16.899 145.391 18.618 QT\n145.22 18.696 145.11 18.696 QT\n144.907 18.696 144.696 18.508 QT\n144.485 18.321 144.485 18.118 QT\ncp}def\r\nf-1779188984\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 204.75096] CT\r\nN\r\n/f2034987691{172.107 18.79 M\n172.107 17.821 172.537 15.977 QT\n172.966 14.133 173.583 12.04 QT\n174.201 9.946 174.638 8.602 QT\n174.81 6.462 174.81 5.368 QT\n174.81 2.602 174.263 0.219 QT\n173.716 -2.163 172.208 -3.773 QT\n170.701 -5.382 167.982 -5.382 QT\n166.56 -5.382 165.138 -4.773 QT\n163.716 -4.163 162.701 -3.07 QT\n161.685 -1.976 161.31 -0.585 QT\n161.232 -0.335 160.966 -0.335 QT\n160.451 -0.335 L\n160.107 -0.335 160.107 -0.726 QT\n160.107 -0.867 L\n160.591 -2.804 161.818 -4.593 QT\n163.044 -6.382 164.826 -7.507 QT\n166.607 -8.632 168.576 -8.632 QT\n170.591 -8.632 172.06 -7.265 QT\n173.529 -5.898 174.412 -3.804 QT\n175.294 -1.71 175.685 0.43 QT\n176.076 2.571 176.076 4.462 QT\n178.232 -1.413 180.919 -6.663 QT\n181.576 -8.038 L\n181.701 -8.179 181.857 -8.179 QT\n182.388 -8.179 L\n182.732 -8.179 182.732 -7.773 QT\n182.732 -7.695 182.638 -7.523 QT\n181.998 -6.179 L\n180.123 -2.46 178.56 1.36 QT\n176.998 5.18 175.888 8.727 QT\n175.716 10.18 175.24 12.696 QT\n174.763 15.212 174.091 17.391 QT\n173.419 19.571 172.748 19.649 QT\n172.107 19.649 172.107 18.79 QT\ncp}def\r\nf2034987691\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 204.75096] CT\r\nN\r\n/f-173962665{184.567 16.848 M\n184.567 15.785 L\n188.317 15.785 188.317 14.848 QT\n188.317 -0.902 L\n186.77 -0.152 184.395 -0.152 QT\n184.395 -1.215 L\n188.067 -1.215 189.942 -3.137 QT\n190.363 -3.137 L\n190.473 -3.137 190.567 -3.051 QT\n190.66 -2.965 190.66 -2.871 QT\n190.66 14.848 L\n190.66 15.785 194.41 15.785 QT\n194.41 16.848 L\n184.567 16.848 L\ncp}def\r\nf-173962665\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 204.75096] CT\r\nN\r\n/f-988291271{214.299 4.649 M\n213.94 4.649 213.714 4.383 QT\n213.487 4.118 213.487 3.79 QT\n213.487 3.446 213.714 3.188 QT\n213.94 2.93 214.299 2.93 QT\n241.299 2.93 L\n241.612 2.93 241.846 3.188 QT\n242.081 3.446 242.081 3.79 QT\n242.081 4.118 241.846 4.383 QT\n241.612 4.649 241.299 4.649 QT\n214.299 4.649 L\ncp\n214.299 -3.695 M\n213.94 -3.695 213.714 -3.952 QT\n213.487 -4.21 213.487 -4.554 QT\n213.487 -4.882 213.714 -5.156 QT\n213.94 -5.429 214.299 -5.429 QT\n241.299 -5.429 L\n241.612 -5.429 241.846 -5.156 QT\n242.081 -4.882 242.081 -4.554 QT\n242.081 -4.21 241.846 -3.952 QT\n241.612 -3.695 241.299 -3.695 QT\n214.299 -3.695 L\ncp}def\r\nf-988291271\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 204.75096] CT\r\nN\r\n/f2141106481{267.415 11.305 M\n262.149 11.305 260.251 6.969 QT\n258.352 2.633 258.352 -3.335 QT\n258.352 -7.085 259.032 -10.382 QT\n259.712 -13.679 261.735 -15.976 QT\n263.759 -18.273 267.415 -18.273 QT\n270.243 -18.273 272.056 -16.89 QT\n273.868 -15.507 274.806 -13.312 QT\n275.743 -11.117 276.095 -8.609 QT\n276.446 -6.101 276.446 -3.335 QT\n276.446 0.352 275.759 3.579 QT\n275.071 6.805 273.079 9.055 QT\n271.087 11.305 267.415 11.305 QT\ncp\n267.415 10.196 M\n269.806 10.196 270.985 7.743 QT\n272.165 5.29 272.438 2.305 QT\n272.712 -0.679 272.712 -4.038 QT\n272.712 -7.273 272.438 -9.999 QT\n272.165 -12.726 271.001 -14.945 QT\n269.837 -17.163 267.415 -17.163 QT\n264.977 -17.163 263.806 -14.937 QT\n262.634 -12.71 262.36 -9.992 QT\n262.087 -7.273 262.087 -4.038 QT\n262.087 -1.648 262.196 0.477 QT\n262.306 2.602 262.813 4.86 QT\n263.321 7.118 264.446 8.657 QT\n265.571 10.196 267.415 10.196 QT\ncp}def\r\nf2141106481\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 204.75096] CT\r\nN\r\n/f-689209901{281.874 7.993 M\n281.874 7.024 282.593 6.337 QT\n283.312 5.649 284.249 5.649 QT\n284.843 5.649 285.406 5.962 QT\n285.968 6.274 286.281 6.844 QT\n286.593 7.415 286.593 7.993 QT\n286.593 8.946 285.906 9.657 QT\n285.218 10.368 284.249 10.368 QT\n283.312 10.368 282.593 9.657 QT\n281.874 8.946 281.874 7.993 QT\ncp}def\r\nf-689209901\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 204.75096] CT\r\nN\r\n/f-830940872{301.015 11.305 M\n298.343 11.305 296.562 9.891 QT\n294.781 8.477 293.804 6.219 QT\n292.828 3.962 292.453 1.485 QT\n292.078 -0.992 292.078 -3.538 QT\n292.078 -6.929 293.398 -10.351 QT\n294.718 -13.773 297.288 -16.023 QT\n299.859 -18.273 303.39 -18.273 QT\n304.859 -18.273 306.132 -17.718 QT\n307.406 -17.163 308.124 -16.077 QT\n308.843 -14.992 308.843 -13.46 QT\n308.843 -12.585 308.249 -11.984 QT\n307.656 -11.382 306.765 -11.382 QT\n305.921 -11.382 305.32 -11.992 QT\n304.718 -12.601 304.718 -13.46 QT\n304.718 -14.304 305.32 -14.913 QT\n305.921 -15.523 306.765 -15.523 QT\n306.999 -15.523 L\n306.453 -16.304 305.453 -16.671 QT\n304.453 -17.038 303.39 -17.038 QT\n302.093 -17.038 300.984 -16.468 QT\n299.874 -15.898 298.999 -14.929 QT\n298.124 -13.96 297.531 -12.796 QT\n296.937 -11.632 296.617 -10.14 QT\n296.296 -8.648 296.21 -7.351 QT\n296.124 -6.054 296.124 -4.085 QT\n296.874 -5.835 298.265 -6.96 QT\n299.656 -8.085 301.39 -8.085 QT\n303.296 -8.085 304.874 -7.312 QT\n306.453 -6.538 307.585 -5.163 QT\n308.718 -3.788 309.32 -2.023 QT\n309.921 -0.257 309.921 1.555 QT\n309.921 4.071 308.796 6.344 QT\n307.671 8.618 305.632 9.962 QT\n303.593 11.305 301.015 11.305 QT\ncp\n301.015 9.946 M\n302.671 9.946 303.679 9.188 QT\n304.687 8.43 305.163 7.18 QT\n305.64 5.93 305.749 4.665 QT\n305.859 3.399 305.859 1.555 QT\n305.859 -0.882 305.632 -2.609 QT\n305.406 -4.335 304.374 -5.648 QT\n303.343 -6.96 301.218 -6.96 QT\n299.484 -6.96 298.359 -5.781 QT\n297.234 -4.601 296.718 -2.804 QT\n296.203 -1.007 296.203 0.649 QT\n296.203 1.212 296.249 1.508 QT\n296.249 1.571 296.242 1.61 QT\n296.234 1.649 296.203 1.712 QT\n296.203 3.571 296.585 5.454 QT\n296.968 7.337 298.038 8.641 QT\n299.109 9.946 301.015 9.946 QT\ncp}def\r\nf-830940872\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n678.003 546.003 M\n758.029 546.003 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 224.62404] CT\r\nN\r\nf-1698885829\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 224.62404] CT\r\nN\r\nf-1758447675\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 224.62404] CT\r\nN\r\nf-2127470435\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 224.62404] CT\r\nN\r\nf-2019066066\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 224.62404] CT\r\nN\r\nf-1779188984\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 224.62404] CT\r\nN\r\nf2034987691\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 224.62404] CT\r\nN\r\nf-173962665\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 224.62404] CT\r\nN\r\nf-988291271\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 224.62404] CT\r\nN\r\nf2141106481\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 224.62404] CT\r\nN\r\nf-689209901\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 224.62404] CT\r\nN\r\n/f2096529930{291.468 3.274 M\n291.468 1.758 L\n304.749 -18.054 L\n304.906 -18.273 305.187 -18.273 QT\n305.828 -18.273 L\n306.312 -18.273 306.312 -17.788 QT\n306.312 1.758 L\n310.531 1.758 L\n310.531 3.274 L\n306.312 3.274 L\n306.312 7.493 L\n306.312 8.368 307.57 8.61 QT\n308.828 8.852 310.484 8.852 QT\n310.484 10.368 L\n298.64 10.368 L\n298.64 8.852 L\n300.296 8.852 301.562 8.61 QT\n302.828 8.368 302.828 7.493 QT\n302.828 3.274 L\n291.468 3.274 L\ncp\n292.89 1.758 M\n303.078 1.758 L\n303.078 -13.46 L\n292.89 1.758 L\ncp}def\r\nf2096529930\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n[20 20] 0 setdash\r\n2 LJ\r\n5.333 LW\r\nN\r\n678.003 598.997 M\n758.029 598.997 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 244.49712] CT\r\nN\r\nf-1698885829\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 244.49712] CT\r\nN\r\nf-1758447675\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 244.49712] CT\r\nN\r\nf-2127470435\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 244.49712] CT\r\nN\r\nf-2019066066\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 244.49712] CT\r\nN\r\nf-1779188984\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 244.49712] CT\r\nN\r\nf2034987691\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 244.49712] CT\r\nN\r\nf-173962665\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 244.49712] CT\r\nN\r\nf-988291271\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 244.49712] CT\r\nN\r\nf2141106481\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 244.49712] CT\r\nN\r\nf-689209901\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 286.51149 244.49712] CT\r\nN\r\nf-830940872\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 1 RC\r\n[20 20] 0 setdash\r\n2 LJ\r\n5.333 LW\r\nN\r\n678.003 651.992 M\n758.029 651.992 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n10.0 ML\r\n0.533 LW\r\nN\r\n670 682 M\n670 463 L\n1084 463 L\n1084 682 L\ncp\r\nS\r\nGR\r\n%%Trailer\r\n%%Pages: 1\r\n%%EOF\r\n"
  },
  {
    "path": "matlab/acc2023/closedloop_performance/figures/openloop-snapshots.eps",
    "content": "%!PS-Adobe-3.0 EPSF-3.0\r\n%%Creator: (MATLAB, The Mathworks, Inc. Version 9.10.0.1649659 \\(R2021a\\) Update 1. Operating System: Windows 10)\r\n%%Title: figures/openloop-snapshots.eps\r\n%%CreationDate: 2023-01-31T03:11:27\r\n%%Pages: (atend)\r\n%%BoundingBox:     1     1   418   302\r\n%%LanguageLevel: 3\r\n%%EndComments\r\n%%BeginProlog\r\n%%BeginResource: procset (Apache XML Graphics Std ProcSet) 1.2 0\r\n%%Version: 1.2 0\r\n%%Copyright: (Copyright 2001-2003,2010 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/bd{bind def}bind def\r\n/ld{load def}bd\r\n/GR/grestore ld\r\n/GS/gsave ld\r\n/RM/rmoveto ld\r\n/C/curveto ld\r\n/t/show ld\r\n/L/lineto ld\r\n/ML/setmiterlimit ld\r\n/CT/concat ld\r\n/f/fill ld\r\n/N/newpath ld\r\n/S/stroke ld\r\n/CC/setcmykcolor ld\r\n/A/ashow ld\r\n/cp/closepath ld\r\n/RC/setrgbcolor ld\r\n/LJ/setlinejoin ld\r\n/GC/setgray ld\r\n/LW/setlinewidth ld\r\n/M/moveto ld\r\n/re {4 2 roll M\r\n1 index 0 rlineto\r\n0 exch rlineto\r\nneg 0 rlineto\r\ncp } bd\r\n/_ctm matrix def\r\n/_tm matrix def\r\n/BT { _ctm currentmatrix pop matrix _tm copy pop 0 0 moveto } bd\r\n/ET { _ctm setmatrix } bd\r\n/iTm { _ctm setmatrix _tm concat } bd\r\n/Tm { _tm astore pop iTm 0 0 moveto } bd\r\n/ux 0.0 def\r\n/uy 0.0 def\r\n/F {\r\n  /Tp exch def\r\n  /Tf exch def\r\n  Tf findfont Tp scalefont setfont\r\n  /cf Tf def  /cs Tp def\r\n} bd\r\n/ULS {currentpoint /uy exch def /ux exch def} bd\r\n/ULE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add moveto  Tcx uy To add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/OLE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs add moveto Tcx uy To add cs add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/SOE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs 10 mul 26 idiv add moveto Tcx uy To add cs 10 mul 26 idiv add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/QT {\r\n/Y22 exch store\r\n/X22 exch store\r\n/Y21 exch store\r\n/X21 exch store\r\ncurrentpoint\r\n/Y21 load 2 mul add 3 div exch\r\n/X21 load 2 mul add 3 div exch\r\n/X21 load 2 mul /X22 load add 3 div\r\n/Y21 load 2 mul /Y22 load add 3 div\r\n/X22 load /Y22 load curveto\r\n} bd\r\n/SSPD {\r\ndup length /d exch dict def\r\n{\r\n/v exch def\r\n/k exch def\r\ncurrentpagedevice k known {\r\n/cpdv currentpagedevice k get def\r\nv cpdv ne {\r\n/upd false def\r\n/nullv v type /nulltype eq def\r\n/nullcpdv cpdv type /nulltype eq def\r\nnullv nullcpdv or\r\n{\r\n/upd true def\r\n} {\r\n/sametype v type cpdv type eq def\r\nsametype {\r\nv type /arraytype eq {\r\n/vlen v length def\r\n/cpdvlen cpdv length def\r\nvlen cpdvlen eq {\r\n0 1 vlen 1 sub {\r\n/i exch def\r\n/obj v i get def\r\n/cpdobj cpdv i get def\r\nobj cpdobj ne {\r\n/upd true def\r\nexit\r\n} if\r\n} for\r\n} {\r\n/upd true def\r\n} ifelse\r\n} {\r\nv type /dicttype eq {\r\nv {\r\n/dv exch def\r\n/dk exch def\r\n/cpddv cpdv dk get def\r\ndv cpddv ne {\r\n/upd true def\r\nexit\r\n} if\r\n} forall\r\n} {\r\n/upd true def\r\n} ifelse\r\n} ifelse\r\n} if\r\n} ifelse\r\nupd true eq {\r\nd k v put\r\n} if\r\n} if\r\n} if\r\n} forall\r\nd length 0 gt {\r\nd setpagedevice\r\n} if\r\n} bd\r\n/RE { % /NewFontName [NewEncodingArray] /FontName RE -\r\n  findfont dup length dict begin\r\n  {\r\n    1 index /FID ne\r\n    {def} {pop pop} ifelse\r\n  } forall\r\n  /Encoding exch def\r\n  /FontName 1 index def\r\n  currentdict definefont pop\r\n  end\r\n} bind def\r\n%%EndResource\r\n%%BeginResource: procset (Apache XML Graphics EPS ProcSet) 1.0 0\r\n%%Version: 1.0 0\r\n%%Copyright: (Copyright 2002-2003 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/BeginEPSF { %def\r\n/b4_Inc_state save def         % Save state for cleanup\r\n/dict_count countdictstack def % Count objects on dict stack\r\n/op_count count 1 sub def      % Count objects on operand stack\r\nuserdict begin                 % Push userdict on dict stack\r\n/showpage { } def              % Redefine showpage, { } = null proc\r\n0 setgray 0 setlinecap         % Prepare graphics state\r\n1 setlinewidth 0 setlinejoin\r\n10 setmiterlimit [ ] 0 setdash newpath\r\n/languagelevel where           % If level not equal to 1 then\r\n{pop languagelevel             % set strokeadjust and\r\n1 ne                           % overprint to their defaults.\r\n{false setstrokeadjust false setoverprint\r\n} if\r\n} if\r\n} bd\r\n/EndEPSF { %def\r\ncount op_count sub {pop} repeat            % Clean up stacks\r\ncountdictstack dict_count sub {end} repeat\r\nb4_Inc_state restore\r\n} bd\r\n%%EndResource\r\n%FOPBeginFontDict\r\n%%IncludeResource: font Courier-Oblique\r\n%%IncludeResource: font Courier-BoldOblique\r\n%%IncludeResource: font Courier-Bold\r\n%%IncludeResource: font ZapfDingbats\r\n%%IncludeResource: font Symbol\r\n%%IncludeResource: font Helvetica\r\n%%IncludeResource: font Helvetica-Oblique\r\n%%IncludeResource: font Helvetica-Bold\r\n%%IncludeResource: font Helvetica-BoldOblique\r\n%%IncludeResource: font Times-Roman\r\n%%IncludeResource: font Times-Italic\r\n%%IncludeResource: font Times-Bold\r\n%%IncludeResource: font Times-BoldItalic\r\n%%IncludeResource: font Courier\r\n%FOPEndFontDict\r\n%%BeginResource: encoding WinAnsiEncoding\r\n/WinAnsiEncoding [\r\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /space /exclam /quotedbl\n/numbersign /dollar /percent /ampersand /quotesingle\n/parenleft /parenright /asterisk /plus /comma\n/hyphen /period /slash /zero /one\n/two /three /four /five /six\n/seven /eight /nine /colon /semicolon\n/less /equal /greater /question /at\n/A /B /C /D /E\n/F /G /H /I /J\n/K /L /M /N /O\n/P /Q /R /S /T\n/U /V /W /X /Y\n/Z /bracketleft /backslash /bracketright /asciicircum\n/underscore /quoteleft /a /b /c\n/d /e /f /g /h\n/i /j /k /l /m\n/n /o /p /q /r\n/s /t /u /v /w\n/x /y /z /braceleft /bar\n/braceright /asciitilde /bullet /Euro /bullet\n/quotesinglbase /florin /quotedblbase /ellipsis /dagger\n/daggerdbl /circumflex /perthousand /Scaron /guilsinglleft\n/OE /bullet /Zcaron /bullet /bullet\n/quoteleft /quoteright /quotedblleft /quotedblright /bullet\n/endash /emdash /asciitilde /trademark /scaron\n/guilsinglright /oe /bullet /zcaron /Ydieresis\n/space /exclamdown /cent /sterling /currency\n/yen /brokenbar /section /dieresis /copyright\n/ordfeminine /guillemotleft /logicalnot /sfthyphen /registered\n/macron /degree /plusminus /twosuperior /threesuperior\n/acute /mu /paragraph /middot /cedilla\n/onesuperior /ordmasculine /guillemotright /onequarter /onehalf\n/threequarters /questiondown /Agrave /Aacute /Acircumflex\n/Atilde /Adieresis /Aring /AE /Ccedilla\n/Egrave /Eacute /Ecircumflex /Edieresis /Igrave\n/Iacute /Icircumflex /Idieresis /Eth /Ntilde\n/Ograve /Oacute /Ocircumflex /Otilde /Odieresis\n/multiply /Oslash /Ugrave /Uacute /Ucircumflex\n/Udieresis /Yacute /Thorn /germandbls /agrave\n/aacute /acircumflex /atilde /adieresis /aring\n/ae /ccedilla /egrave /eacute /ecircumflex\n/edieresis /igrave /iacute /icircumflex /idieresis\n/eth /ntilde /ograve /oacute /ocircumflex\n/otilde /odieresis /divide /oslash /ugrave\n/uacute /ucircumflex /udieresis /yacute /thorn\n/ydieresis\n] def\r\n%%EndResource\r\n%FOPBeginFontReencode\r\n/Courier-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Oblique exch definefont pop\r\n/Courier-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-BoldOblique exch definefont pop\r\n/Courier-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Bold exch definefont pop\r\n/Helvetica findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica exch definefont pop\r\n/Helvetica-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Oblique exch definefont pop\r\n/Helvetica-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Bold exch definefont pop\r\n/Helvetica-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-BoldOblique exch definefont pop\r\n/Times-Roman findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Roman exch definefont pop\r\n/Times-Italic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Italic exch definefont pop\r\n/Times-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Bold exch definefont pop\r\n/Times-BoldItalic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-BoldItalic exch definefont pop\r\n/Courier findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier exch definefont pop\r\n%FOPEndFontReencode\r\n%%EndProlog\r\n%%Page: 1 1\r\n%%PageBoundingBox: 0 0 420 315\r\n%%BeginPageSetup\r\n[1 0 0 -1 0 315] CT\r\n%%EndPageSetup\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n133 698.167 M\n1101 698.167 L\n1101 52.833 L\n133 52.833 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n133 698.167 M\n133 52.833 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n294.333 698.167 M\n294.333 52.833 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n455.667 698.167 M\n455.667 52.833 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n617 698.167 M\n617 52.833 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n778.333 698.167 M\n778.333 52.833 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n939.667 698.167 M\n939.667 52.833 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 698.167 M\n1101 52.833 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 698.167 M\n133 698.167 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 536.833 M\n133 536.833 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 375.5 M\n133 375.5 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 214.167 M\n133 214.167 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.873 GC\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 52.833 M\n133 52.833 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n133 698.167 M\n1101 698.167 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n133 698.167 M\n133 688.487 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n294.333 698.167 M\n294.333 688.487 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n455.667 698.167 M\n455.667 688.487 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n617 698.167 M\n617 688.487 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n778.333 698.167 M\n778.333 688.487 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n939.667 698.167 M\n939.667 688.487 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n1101 698.167 M\n1101 688.487 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 49.875 267.61251] CT\r\n0.149 GC\r\n/Helvetica 50.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-23 51 moveto \r\n1 -1 scale\r\n(-3) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 110.375 267.61251] CT\r\n0.149 GC\r\n/Helvetica 50.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-23 51 moveto \r\n1 -1 scale\r\n(-2) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 170.875 267.61251] CT\r\n0.149 GC\r\n/Helvetica 50.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-23 51 moveto \r\n1 -1 scale\r\n(-1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 231.375 267.61251] CT\r\n0.149 GC\r\n/Helvetica 50.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-14.5 51 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 291.87499 267.61251] CT\r\n0.149 GC\r\n/Helvetica 50.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-14.5 51 moveto \r\n1 -1 scale\r\n(1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 352.37501 267.61251] CT\r\n0.149 GC\r\n/Helvetica 50.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-14.5 51 moveto \r\n1 -1 scale\r\n(2) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.875 267.61251] CT\r\n0.149 GC\r\n/Helvetica 50.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-14.5 51 moveto \r\n1 -1 scale\r\n(3) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 231.37518 292.05] CT\r\n0.149 GC\r\nN\r\n-55.255 43.269 M\n-54.317 44.003 -52.614 44.003 QT\n-50.958 44.003 -49.692 42.409 QT\n-48.426 40.815 -47.958 38.925 QT\n-45.551 29.534 L\n-44.973 26.972 -44.973 26.034 QT\n-44.973 24.722 -45.715 23.737 QT\n-46.458 22.753 -47.77 22.753 QT\n-49.458 22.753 -50.934 23.8 QT\n-52.411 24.847 -53.419 26.464 QT\n-54.426 28.081 -54.833 29.737 QT\n-54.942 30.081 -55.255 30.081 QT\n-55.895 30.081 L\n-56.317 30.081 -56.317 29.581 QT\n-56.317 29.425 L\n-55.801 27.456 -54.559 25.581 QT\n-53.317 23.706 -51.52 22.542 QT\n-49.723 21.378 -47.676 21.378 QT\n-45.723 21.378 -44.161 22.417 QT\n-42.598 23.456 -41.958 25.237 QT\n-41.051 23.612 -39.637 22.495 QT\n-38.223 21.378 -36.551 21.378 QT\n-35.411 21.378 -34.215 21.776 QT\n-33.02 22.175 -32.27 23.003 QT\n-31.52 23.831 -31.52 25.081 QT\n-31.52 26.425 -32.387 27.394 QT\n-33.255 28.362 -34.598 28.362 QT\n-35.458 28.362 -36.028 27.823 QT\n-36.598 27.284 -36.598 26.456 QT\n-36.598 25.331 -35.833 24.495 QT\n-35.067 23.659 -34.005 23.503 QT\n-34.958 22.753 -36.645 22.753 QT\n-38.348 22.753 -39.606 24.331 QT\n-40.864 25.909 -41.38 27.847 QT\n-43.708 37.222 L\n-44.286 39.347 -44.286 40.706 QT\n-44.286 42.05 -43.52 43.026 QT\n-42.755 44.003 -41.489 44.003 QT\n-39.005 44.003 -37.051 41.815 QT\n-35.098 39.628 -34.473 37.003 QT\n-34.364 36.706 -34.067 36.706 QT\n-33.411 36.706 L\n-33.208 36.706 -33.075 36.847 QT\n-32.942 36.987 -32.942 37.159 QT\n-32.942 37.222 -33.005 37.315 QT\n-33.755 40.472 -36.161 42.933 QT\n-38.567 45.394 -41.583 45.394 QT\n-43.536 45.394 -45.098 44.347 QT\n-46.661 43.3 -47.317 41.519 QT\n-48.145 43.065 -49.606 44.229 QT\n-51.067 45.394 -52.723 45.394 QT\n-53.864 45.394 -55.067 44.995 QT\n-56.27 44.597 -57.02 43.769 QT\n-57.77 42.94 -57.77 41.675 QT\n-57.77 40.425 -56.903 39.401 QT\n-56.036 38.378 -54.739 38.378 QT\n-53.864 38.378 -53.262 38.909 QT\n-52.661 39.44 -52.661 40.3 QT\n-52.661 41.409 -53.403 42.237 QT\n-54.145 43.065 -55.255 43.269 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 231.37518 292.05] CT\r\n0.149 GC\r\nN\r\n-12.476 57.94 M\n-15.429 55.612 -17.562 52.597 QT\n-19.695 49.581 -21.054 46.167 QT\n-22.414 42.753 -23.086 39.026 QT\n-23.757 35.3 -23.757 31.55 QT\n-23.757 27.753 -23.086 24.026 QT\n-22.414 20.3 -21.031 16.854 QT\n-19.648 13.409 -17.5 10.409 QT\n-15.351 7.409 -12.476 5.159 QT\n-12.476 5.05 -12.226 5.05 QT\n-11.726 5.05 L\n-11.57 5.05 -11.445 5.19 QT\n-11.32 5.331 -11.32 5.519 QT\n-11.32 5.753 -11.414 5.847 QT\n-14.007 8.394 -15.726 11.292 QT\n-17.445 14.19 -18.492 17.464 QT\n-19.539 20.737 -20.007 24.245 QT\n-20.476 27.753 -20.476 31.55 QT\n-20.476 48.394 -11.476 57.144 QT\n-11.32 57.3 -11.32 57.581 QT\n-11.32 57.706 -11.461 57.878 QT\n-11.601 58.05 -11.726 58.05 QT\n-12.226 58.05 L\n-12.476 58.05 -12.476 57.94 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 231.37518 292.05] CT\r\n0.149 GC\r\nN\r\n-4.079 43.894 M\n-4.079 43.581 -4.032 43.425 QT\n-0.079 27.612 L\n0.311 26.144 0.311 25.034 QT\n0.311 22.753 -1.235 22.753 QT\n-2.892 22.753 -3.696 24.729 QT\n-4.501 26.706 -5.251 29.737 QT\n-5.251 29.894 -5.407 29.987 QT\n-5.564 30.081 -5.689 30.081 QT\n-6.314 30.081 L\n-6.485 30.081 -6.618 29.886 QT\n-6.751 29.69 -6.751 29.534 QT\n-6.173 27.222 -5.649 25.62 QT\n-5.126 24.019 -3.993 22.698 QT\n-2.86 21.378 -1.189 21.378 QT\n0.811 21.378 2.335 22.636 QT\n3.858 23.894 3.858 25.831 QT\n5.436 23.753 7.561 22.565 QT\n9.686 21.378 12.061 21.378 QT\n14.577 21.378 16.397 22.659 QT\n18.218 23.94 18.218 26.3 QT\n19.858 23.987 22.046 22.683 QT\n24.233 21.378 26.811 21.378 QT\n29.561 21.378 31.226 22.87 QT\n32.89 24.362 32.89 27.097 QT\n32.89 29.269 31.921 32.347 QT\n30.952 35.425 29.515 39.237 QT\n28.749 41.065 28.749 42.425 QT\n28.749 44.003 29.999 44.003 QT\n32.061 44.003 33.436 41.776 QT\n34.811 39.55 35.374 37.003 QT\n35.53 36.706 35.827 36.706 QT\n36.436 36.706 L\n36.655 36.706 36.796 36.847 QT\n36.936 36.987 36.936 37.159 QT\n36.936 37.222 36.89 37.315 QT\n36.155 40.315 34.358 42.854 QT\n32.561 45.394 29.874 45.394 QT\n27.999 45.394 26.686 44.112 QT\n25.374 42.831 25.374 41.003 QT\n25.374 40.065 25.811 38.925 QT\n27.311 34.94 28.304 31.808 QT\n29.296 28.675 29.296 26.3 QT\n29.296 24.815 28.702 23.784 QT\n28.108 22.753 26.718 22.753 QT\n23.811 22.753 21.694 24.526 QT\n19.577 26.3 18.015 29.222 QT\n17.921 29.737 17.858 30.019 QT\n14.452 43.628 L\n14.265 44.362 13.632 44.878 QT\n12.999 45.394 12.218 45.394 QT\n11.593 45.394 11.116 44.979 QT\n10.64 44.565 10.64 43.894 QT\n10.64 43.581 10.686 43.425 QT\n14.077 29.925 L\n14.624 27.753 14.624 26.3 QT\n14.624 24.815 14.015 23.784 QT\n13.405 22.753 11.968 22.753 QT\n10.015 22.753 8.39 23.604 QT\n6.765 24.456 5.546 25.87 QT\n4.327 27.284 3.311 29.222 QT\n-0.282 43.628 L\n-0.454 44.362 -1.095 44.878 QT\n-1.735 45.394 -2.501 45.394 QT\n-3.157 45.394 -3.618 44.979 QT\n-4.079 44.565 -4.079 43.894 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 231.37518 292.05] CT\r\n0.149 GC\r\nN\r\n42.092 58.05 M\n41.623 58.05 41.623 57.581 QT\n41.623 57.347 41.733 57.253 QT\n50.795 48.394 50.795 31.55 QT\n50.795 14.706 41.842 5.956 QT\n41.623 5.831 41.623 5.519 QT\n41.623 5.331 41.772 5.19 QT\n41.92 5.05 42.092 5.05 QT\n42.592 5.05 L\n42.748 5.05 42.842 5.159 QT\n46.654 8.159 49.186 12.456 QT\n51.717 16.753 52.897 21.612 QT\n54.076 26.472 54.076 31.55 QT\n54.076 35.3 53.444 38.94 QT\n52.811 42.581 51.428 46.112 QT\n50.045 49.644 47.92 52.628 QT\n45.795 55.612 42.842 57.94 QT\n42.748 58.05 42.592 58.05 QT\n42.092 58.05 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n133 698.167 M\n133 52.833 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n133 698.167 M\n142.68 698.167 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n133 536.833 M\n142.68 536.833 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n133 375.5 M\n142.68 375.5 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n133 214.167 M\n142.68 214.167 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n0.533 LW\r\nN\r\n133 52.833 M\n142.68 52.833 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 44.07499 261.81251] CT\r\n0.149 GC\r\n/Helvetica 50.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-46 19.5 moveto \r\n1 -1 scale\r\n(-2) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 44.07499 201.31249] CT\r\n0.149 GC\r\n/Helvetica 50.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-46 19.5 moveto \r\n1 -1 scale\r\n(-1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 44.07499 140.8125] CT\r\n0.149 GC\r\n/Helvetica 50.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-29 19.5 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 44.07499 80.3125] CT\r\n0.149 GC\r\n/Helvetica 50.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-29 19.5 moveto \r\n1 -1 scale\r\n(1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 44.07499 19.8125] CT\r\n0.149 GC\r\n/Helvetica 50.667 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-29 19.5 moveto \r\n1 -1 scale\r\n(2) t \r\nGR\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.825 140.81239] CT\r\n0.149 GC\r\nN\r\n-53.732 -11.622 M\n-52.623 -9.7 -49.857 -9.7 QT\n-47.342 -9.7 -45.506 -11.458 QT\n-43.67 -13.216 -42.545 -15.716 QT\n-41.42 -18.216 -40.795 -20.825 QT\n-43.154 -18.606 -45.889 -18.606 QT\n-47.982 -18.606 -49.459 -19.333 QT\n-50.935 -20.06 -51.756 -21.497 QT\n-52.576 -22.935 -52.576 -24.966 QT\n-52.576 -26.7 -52.107 -28.528 QT\n-51.639 -30.356 -50.795 -32.591 QT\n-49.951 -34.825 -49.342 -36.481 QT\n-48.639 -38.435 -48.639 -39.669 QT\n-48.639 -41.247 -49.795 -41.247 QT\n-51.904 -41.247 -53.256 -39.091 QT\n-54.607 -36.935 -55.264 -34.263 QT\n-55.357 -33.919 -55.701 -33.919 QT\n-56.326 -33.919 L\n-56.764 -33.919 -56.764 -34.419 QT\n-56.764 -34.575 L\n-55.904 -37.731 -54.146 -40.177 QT\n-52.389 -42.622 -49.701 -42.622 QT\n-47.81 -42.622 -46.506 -41.38 QT\n-45.201 -40.138 -45.201 -38.216 QT\n-45.201 -37.231 -45.639 -36.153 QT\n-45.873 -35.497 -46.701 -33.325 QT\n-47.529 -31.153 -47.967 -29.731 QT\n-48.404 -28.31 -48.685 -26.935 QT\n-48.967 -25.56 -48.967 -24.2 QT\n-48.967 -22.435 -48.217 -21.216 QT\n-47.467 -19.997 -45.842 -19.997 QT\n-42.56 -19.997 -39.935 -24.013 QT\n-35.935 -40.341 L\n-35.748 -41.044 -35.099 -41.544 QT\n-34.451 -42.044 -33.701 -42.044 QT\n-33.06 -42.044 -32.576 -41.63 QT\n-32.092 -41.216 -32.092 -40.544 QT\n-32.092 -40.247 -32.154 -40.138 QT\n-37.404 -19.044 L\n-38.107 -16.325 -39.967 -13.841 QT\n-41.826 -11.356 -44.451 -9.841 QT\n-47.076 -8.325 -49.935 -8.325 QT\n-51.295 -8.325 -52.646 -8.856 QT\n-53.998 -9.388 -54.826 -10.45 QT\n-55.654 -11.513 -55.654 -12.935 QT\n-55.654 -14.388 -54.795 -15.45 QT\n-53.935 -16.513 -52.514 -16.513 QT\n-51.67 -16.513 -51.084 -15.981 QT\n-50.498 -15.45 -50.498 -14.591 QT\n-50.498 -13.372 -51.404 -12.466 QT\n-52.31 -11.56 -53.529 -11.56 QT\n-53.576 -11.591 -53.631 -11.606 QT\n-53.685 -11.622 -53.732 -11.622 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.825 140.81239] CT\r\n0.149 GC\r\nN\r\n-13.686 -6.06 M\n-16.639 -8.388 -18.772 -11.403 QT\n-20.905 -14.419 -22.264 -17.833 QT\n-23.624 -21.247 -24.295 -24.974 QT\n-24.967 -28.7 -24.967 -32.45 QT\n-24.967 -36.247 -24.295 -39.974 QT\n-23.624 -43.7 -22.241 -47.146 QT\n-20.858 -50.591 -18.709 -53.591 QT\n-16.561 -56.591 -13.686 -58.841 QT\n-13.686 -58.95 -13.436 -58.95 QT\n-12.936 -58.95 L\n-12.78 -58.95 -12.655 -58.81 QT\n-12.53 -58.669 -12.53 -58.481 QT\n-12.53 -58.247 -12.624 -58.153 QT\n-15.217 -55.606 -16.936 -52.708 QT\n-18.655 -49.81 -19.702 -46.536 QT\n-20.749 -43.263 -21.217 -39.755 QT\n-21.686 -36.247 -21.686 -32.45 QT\n-21.686 -15.606 -12.686 -6.856 QT\n-12.53 -6.7 -12.53 -6.419 QT\n-12.53 -6.294 -12.67 -6.122 QT\n-12.811 -5.95 -12.936 -5.95 QT\n-13.436 -5.95 L\n-13.686 -5.95 -13.686 -6.06 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.825 140.81239] CT\r\n0.149 GC\r\nN\r\n-5.289 -20.106 M\n-5.289 -20.419 -5.242 -20.575 QT\n-1.289 -36.388 L\n-0.898 -37.856 -0.898 -38.966 QT\n-0.898 -41.247 -2.445 -41.247 QT\n-4.101 -41.247 -4.906 -39.271 QT\n-5.711 -37.294 -6.461 -34.263 QT\n-6.461 -34.106 -6.617 -34.013 QT\n-6.773 -33.919 -6.898 -33.919 QT\n-7.523 -33.919 L\n-7.695 -33.919 -7.828 -34.114 QT\n-7.961 -34.31 -7.961 -34.466 QT\n-7.383 -36.778 -6.859 -38.38 QT\n-6.336 -39.981 -5.203 -41.302 QT\n-4.07 -42.622 -2.398 -42.622 QT\n-0.398 -42.622 1.125 -41.364 QT\n2.649 -40.106 2.649 -38.169 QT\n4.227 -40.247 6.352 -41.435 QT\n8.477 -42.622 10.852 -42.622 QT\n13.367 -42.622 15.188 -41.341 QT\n17.008 -40.06 17.008 -37.7 QT\n18.649 -40.013 20.836 -41.317 QT\n23.024 -42.622 25.602 -42.622 QT\n28.352 -42.622 30.016 -41.13 QT\n31.68 -39.638 31.68 -36.903 QT\n31.68 -34.731 30.711 -31.653 QT\n29.742 -28.575 28.305 -24.763 QT\n27.539 -22.935 27.539 -21.575 QT\n27.539 -19.997 28.789 -19.997 QT\n30.852 -19.997 32.227 -22.224 QT\n33.602 -24.45 34.164 -26.997 QT\n34.32 -27.294 34.617 -27.294 QT\n35.227 -27.294 L\n35.445 -27.294 35.586 -27.153 QT\n35.727 -27.013 35.727 -26.841 QT\n35.727 -26.778 35.68 -26.685 QT\n34.945 -23.685 33.149 -21.146 QT\n31.352 -18.606 28.664 -18.606 QT\n26.789 -18.606 25.477 -19.888 QT\n24.164 -21.169 24.164 -22.997 QT\n24.164 -23.935 24.602 -25.075 QT\n26.102 -29.06 27.094 -32.192 QT\n28.086 -35.325 28.086 -37.7 QT\n28.086 -39.185 27.492 -40.216 QT\n26.899 -41.247 25.508 -41.247 QT\n22.602 -41.247 20.484 -39.474 QT\n18.367 -37.7 16.805 -34.778 QT\n16.711 -34.263 16.649 -33.981 QT\n13.242 -20.372 L\n13.055 -19.638 12.422 -19.122 QT\n11.789 -18.606 11.008 -18.606 QT\n10.383 -18.606 9.906 -19.021 QT\n9.43 -19.435 9.43 -20.106 QT\n9.43 -20.419 9.477 -20.575 QT\n12.867 -34.075 L\n13.414 -36.247 13.414 -37.7 QT\n13.414 -39.185 12.805 -40.216 QT\n12.195 -41.247 10.758 -41.247 QT\n8.805 -41.247 7.18 -40.396 QT\n5.555 -39.544 4.336 -38.13 QT\n3.117 -36.716 2.102 -34.778 QT\n-1.492 -20.372 L\n-1.664 -19.638 -2.305 -19.122 QT\n-2.945 -18.606 -3.711 -18.606 QT\n-4.367 -18.606 -4.828 -19.021 QT\n-5.289 -19.435 -5.289 -20.106 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 23.825 140.81239] CT\r\n0.149 GC\r\nN\r\n40.882 -5.95 M\n40.413 -5.95 40.413 -6.419 QT\n40.413 -6.653 40.523 -6.747 QT\n49.585 -15.606 49.585 -32.45 QT\n49.585 -49.294 40.632 -58.044 QT\n40.413 -58.169 40.413 -58.481 QT\n40.413 -58.669 40.562 -58.81 QT\n40.71 -58.95 40.882 -58.95 QT\n41.382 -58.95 L\n41.538 -58.95 41.632 -58.841 QT\n45.445 -55.841 47.976 -51.544 QT\n50.507 -47.247 51.687 -42.388 QT\n52.867 -37.528 52.867 -32.45 QT\n52.867 -28.7 52.234 -25.06 QT\n51.601 -21.419 50.218 -17.888 QT\n48.835 -14.356 46.71 -11.372 QT\n44.585 -8.388 41.632 -6.06 QT\n41.538 -5.95 41.382 -5.95 QT\n40.882 -5.95 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n5.333 LW\r\nN\r\n778.333 375.5 M\n778.009 365.268 L\n777.035 355.076 L\n775.418 344.967 L\n773.162 334.981 L\n770.278 325.159 L\n766.777 315.538 L\n762.672 306.16 L\n757.981 297.06 L\n752.722 288.277 L\n746.917 279.844 L\n740.589 271.797 L\n733.762 264.167 L\n726.466 256.986 L\n718.729 250.282 L\n710.583 244.082 L\n702.059 238.411 L\n693.193 233.292 L\n684.02 228.746 L\n674.578 224.791 L\n664.903 221.442 L\n655.036 218.714 L\n645.015 216.618 L\n634.882 215.161 L\n624.677 214.349 L\n614.44 214.187 L\n604.214 214.674 L\n594.04 215.809 L\n583.958 217.587 L\n574.009 220 L\n564.233 223.04 L\n554.67 226.694 L\n545.357 230.946 L\n536.333 235.781 L\n527.634 241.179 L\n519.295 247.117 L\n511.349 253.572 L\n503.829 260.519 L\n496.764 267.928 L\n490.183 275.77 L\n484.114 284.014 L\n478.579 292.627 L\n473.601 301.573 L\n469.201 310.817 L\n465.396 320.321 L\n462.202 330.047 L\n459.631 339.957 L\n457.693 350.009 L\n456.397 360.164 L\n455.748 370.381 L\n455.748 380.619 L\n456.397 390.836 L\n457.693 400.991 L\n459.631 411.043 L\n462.202 420.953 L\n465.396 430.679 L\n469.201 440.183 L\n473.601 449.427 L\n478.579 458.373 L\n484.114 466.986 L\n490.183 475.23 L\n496.764 483.072 L\n503.829 490.481 L\n511.349 497.428 L\n519.295 503.883 L\n527.634 509.821 L\n536.333 515.219 L\n545.357 520.054 L\n554.67 524.307 L\n564.233 527.96 L\n574.009 531 L\n583.958 533.413 L\n594.04 535.191 L\n604.214 536.326 L\n614.44 536.813 L\n624.677 536.651 L\n634.882 535.839 L\n645.015 534.382 L\n655.036 532.286 L\n664.903 529.558 L\n674.578 526.209 L\n684.02 522.254 L\n693.193 517.708 L\n702.059 512.589 L\n710.583 506.918 L\n718.729 500.718 L\n726.466 494.014 L\n733.762 486.833 L\n740.589 479.203 L\n746.917 471.156 L\n752.722 462.723 L\n757.981 453.94 L\n762.672 444.84 L\n766.777 435.462 L\n770.278 425.841 L\n773.162 416.019 L\n775.418 406.033 L\n777.035 395.924 L\n778.009 385.732 L\n778.333 375.5 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0.502 0 RC\r\nN\r\n490.183 475.23 M\n496.764 483.072 L\n503.829 490.481 L\n511.349 497.428 L\n519.295 503.883 L\n527.634 509.821 L\n536.333 515.219 L\n545.357 520.054 L\n554.67 524.307 L\n564.233 527.96 L\n574.009 531 L\n583.958 533.413 L\n594.04 535.191 L\n604.214 536.326 L\n614.44 536.813 L\n624.677 536.651 L\n634.882 535.839 L\n645.015 534.382 L\n655.036 532.286 L\n664.903 529.558 L\n674.578 526.209 L\n684.02 522.254 L\n693.193 517.708 L\n702.059 512.589 L\n710.583 506.918 L\n718.729 500.718 L\n726.466 494.014 L\n733.762 486.833 L\n740.589 479.203 L\n746.917 471.156 L\n752.722 462.723 L\n757.981 453.94 L\n762.672 444.84 L\n766.777 435.462 L\n770.278 425.841 L\n773.162 416.019 L\n775.418 406.033 L\n777.035 395.924 L\n778.009 385.732 L\n778.333 375.5 L\n778.009 365.268 L\n777.035 355.076 L\n775.418 344.967 L\n773.162 334.981 L\n770.278 325.159 L\n766.777 315.538 L\n762.672 306.16 L\n757.981 297.06 L\n752.722 288.277 L\n746.917 279.844 L\n740.589 271.797 L\n733.762 264.167 L\n726.466 256.986 L\n718.729 250.282 L\n710.583 244.082 L\n702.059 238.411 L\n693.193 233.292 L\n684.02 228.746 L\n674.578 224.791 L\n664.903 221.442 L\n655.036 218.714 L\n645.015 216.618 L\n634.882 215.161 L\n624.677 214.349 L\n614.44 214.187 L\n604.214 214.674 L\n594.04 215.809 L\n583.958 217.587 L\n574.009 220 L\n564.233 223.04 L\n554.67 226.694 L\n545.357 230.946 L\n536.333 235.781 L\n527.634 241.179 L\n519.295 247.117 L\n511.349 253.572 L\n503.829 260.519 L\n496.764 267.928 L\n490.183 275.77 L\n484.114 284.014 L\n478.579 292.627 L\n473.601 301.573 L\n469.201 310.817 L\n465.396 320.321 L\n462.202 330.047 L\n459.631 339.957 L\n457.693 350.009 L\n456.397 360.164 L\n455.748 370.381 L\n455.748 380.619 L\n456.397 390.836 L\n457.693 400.991 L\n459.631 411.043 L\n462.202 420.953 L\n465.396 430.679 L\n469.201 440.183 L\n473.601 449.427 L\n478.579 458.373 L\n484.114 466.986 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n2 setlinecap\r\n10.0 ML\r\n1.333 LW\r\nN\r\n778.333 375.5 M\n778.009 365.268 L\n777.035 355.076 L\n775.418 344.967 L\n773.162 334.981 L\n770.278 325.159 L\n766.777 315.538 L\n762.672 306.16 L\n757.981 297.06 L\n752.722 288.277 L\n746.917 279.844 L\n740.589 271.797 L\n733.762 264.167 L\n726.466 256.986 L\n718.729 250.282 L\n710.583 244.082 L\n702.059 238.411 L\n693.193 233.292 L\n684.02 228.746 L\n674.578 224.791 L\n664.903 221.442 L\n655.036 218.714 L\n645.015 216.618 L\n634.882 215.161 L\n624.677 214.349 L\n614.44 214.187 L\n604.214 214.674 L\n594.04 215.809 L\n583.958 217.587 L\n574.009 220 L\n564.233 223.04 L\n554.67 226.694 L\n545.357 230.946 L\n536.333 235.781 L\n527.634 241.179 L\n519.295 247.117 L\n511.349 253.572 L\n503.829 260.519 L\n496.764 267.928 L\n490.183 275.77 L\n484.114 284.014 L\n478.579 292.627 L\n473.601 301.573 L\n469.201 310.817 L\n465.396 320.321 L\n462.202 330.047 L\n459.631 339.957 L\n457.693 350.009 L\n456.397 360.164 L\n455.748 370.381 L\n455.748 380.619 L\n456.397 390.836 L\n457.693 400.991 L\n459.631 411.043 L\n462.202 420.953 L\n465.396 430.679 L\n469.201 440.183 L\n473.601 449.427 L\n478.579 458.373 L\n484.114 466.986 L\n490.183 475.23 L\n496.764 483.072 L\n503.829 490.481 L\n511.349 497.428 L\n519.295 503.883 L\n527.634 509.821 L\n536.333 515.219 L\n545.357 520.054 L\n554.67 524.307 L\n564.233 527.96 L\n574.009 531 L\n583.958 533.413 L\n594.04 535.191 L\n604.214 536.326 L\n614.44 536.813 L\n624.677 536.651 L\n634.882 535.839 L\n645.015 534.382 L\n655.036 532.286 L\n664.903 529.558 L\n674.578 526.209 L\n684.02 522.254 L\n693.193 517.708 L\n702.059 512.589 L\n710.583 506.918 L\n718.729 500.718 L\n726.466 494.014 L\n733.762 486.833 L\n740.589 479.203 L\n746.917 471.156 L\n752.722 462.723 L\n757.981 453.94 L\n762.672 444.84 L\n766.777 435.462 L\n770.278 425.841 L\n773.162 416.019 L\n775.418 406.033 L\n777.035 395.924 L\n778.009 385.732 L\n778.333 375.5 L\n778.333 375.5 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 49.875 140.8125] CT\r\n0 0 1 RC\r\n10.0 ML\r\n2.667 LW\r\nN\r\n-8 0 M\n0 10.64 L\n8 0 L\n0 -10.64 L\ncp\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.875 140.8125] CT\r\n1 0 0 RC\r\n10.0 ML\r\n2.667 LW\r\nN\r\n-8 0 M\n0 10.64 L\n8 0 L\n0 -10.64 L\ncp\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n2.667 LW\r\nN\r\n133 375.5 M\n133 375.5 L\n140.853 373.654 L\n156.077 368.315 L\n177.116 359.28 L\n204.989 347.858 L\n236.14 335.214 L\n271.673 322.137 L\n313.271 306.838 L\n357.777 288.674 L\n402.46 267.286 L\n446.991 244.907 L\n492.11 224.784 L\n538.24 210.247 L\n584.617 203.594 L\n629.489 206.163 L\n670.815 216.322 L\n708.788 228.65 L\n743.987 241.064 L\n776.552 252.895 L\n806.595 263.881 L\n834.23 273.927 L\n859.584 283.014 L\n882.795 291.162 L\n904.005 298.412 L\n923.355 304.815 L\n940.983 310.433 L\n957.022 315.328 L\n971.596 319.564 L\n984.823 323.206 L\n996.812 326.317 L\n1007.665 328.959 L\n1017.476 331.188 L\n1026.333 333.058 L\n1034.318 334.619 L\n1041.506 335.914 L\n1047.969 336.983 L\n1053.772 337.862 L\n1058.975 338.58 L\n1063.635 339.166 L\n1067.803 339.641 L\n1071.526 340.025 L\n1074.849 340.334 L\n1077.812 340.583 L\n1080.451 340.782 L\n1082.799 340.94 L\n1084.887 341.067 L\n1086.742 341.167 L\n1088.389 341.247 L\n1089.85 341.31 L\n1091.145 341.36 L\n1092.293 341.399 L\n1093.309 341.43 L\n1094.209 341.454 L\n1095.005 341.473 L\n1095.709 341.488 L\n1096.332 341.5 L\n1096.882 341.509 L\n1097.368 341.517 L\n1097.797 341.522 L\n1098.176 341.527 L\n1098.511 341.53 L\n1098.806 341.533 L\n1099.066 341.535 L\n1099.296 341.536 L\n1099.499 341.538 L\n1099.677 341.539 L\n1099.835 341.539 L\n1099.974 341.54 L\n1100.096 341.54 L\n1100.204 341.541 L\n1100.299 341.541 L\n1100.383 341.541 L\n1100.456 341.542 L\n1100.521 341.542 L\n1100.579 341.542 L\n1100.629 341.542 L\n1100.673 341.542 L\n1100.713 341.542 L\n1100.747 341.542 L\n1100.777 341.542 L\n1100.804 341.542 L\n1100.827 341.542 L\n1100.848 341.542 L\n1100.866 341.542 L\n1100.882 341.542 L\n1100.896 341.542 L\n1100.909 341.542 L\n1100.92 341.542 L\n1100.929 341.542 L\n1100.938 341.542 L\n1100.945 341.542 L\n1100.952 341.542 L\n1100.958 341.542 L\n1100.963 341.542 L\n1100.967 341.542 L\n1100.971 341.542 L\n1100.974 341.542 L\n1100.978 341.542 L\n1100.98 341.542 L\n1100.983 341.542 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 49.875 140.8125] CT\r\nN\r\n0 -4 M\n2.209 -4 4 -2.209 4 0 C\n4 0 L\n4 2.209 2.209 4 0 4 C\n-2.209 4 -4 2.209 -4 0 C\n-4 -2.209 -2.209 -4 0 -4 C\ncp\n0 -6.667 M\n-3.682 -6.667 -6.667 -3.682 -6.667 0 C\n-6.667 3.682 -3.682 6.667 0 6.667 C\n3.682 6.667 6.667 3.682 6.667 0 C\n6.667 0 L\n6.667 -3.682 3.682 -6.667 0 -6.667 C\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 49.875 140.8125] CT\r\nN\r\n/f-1792389198{0 -4 M\n2.209 -4 4 -2.209 4 0 C\n4 0 L\n4 2.209 2.209 4 0 4 C\n-2.209 4 -4 2.209 -4 0 C\n-4 -2.209 -2.209 -4 0 -4 C\ncp\n0 -6.667 M\n-3.682 -6.667 -6.667 -3.682 -6.667 0 C\n-6.667 3.682 -3.682 6.667 0 6.667 C\n3.682 6.667 6.667 3.682 6.667 0 C\n6.667 0 L\n6.667 -3.682 3.682 -6.667 0 -6.667 C\ncp}def\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 52.81999 140.12026] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 58.52871 138.11801] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 66.41841 134.73005] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 76.87071 130.44685] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 88.5524 125.70506] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 101.87727 120.80127] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 117.47675 115.06416] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 134.16656 108.25274] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 150.92249 100.23207] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 167.62165 91.83996] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 184.54131 84.29418] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 201.84002 78.84247] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 219.23151 76.34766] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 236.05854 77.31118] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 251.55547 81.12088] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 265.7956 85.74387] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 278.99494 90.39893] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 291.20707 94.83567] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 302.47327 98.95523] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 312.83629 102.72255] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 322.34404 106.13036] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 331.04816 109.18579] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 339.00179 111.90435] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 346.25805 114.30575] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 352.86861 116.41246] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 358.88317 118.24794] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 364.34857 119.83645] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 369.30874 121.20222] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 373.80464 122.369] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 377.87441 123.35958] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 381.5535 124.19552] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 384.87488 124.89687] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 387.8692 125.48203] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 390.56493 125.96765] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 392.98851 126.36861] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 395.16454 126.69811] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 397.11571 126.96764] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 398.86304 127.18721] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 400.42598 127.36535] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 401.82234 127.50936] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 403.06856 127.62537] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 404.1796 127.71852] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 405.16919 127.79311] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 406.04979 127.85264] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 406.8327 127.90006] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 407.52827 127.93774] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 408.1458 127.96762] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 408.69365 127.99125] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 409.17938 128.00993] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 409.60977 128.02467] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 409.991 128.03626] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 410.32841 128.04539] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 410.62697 128.05256] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 410.89101 128.05817] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 411.12442 128.06258] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 411.33073 128.06602] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 411.51297 128.06873] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 411.67397 128.07083] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 411.81606 128.07248] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 411.94148 128.07377] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.05222 128.07477] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.14986 128.07556] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.23605 128.07616] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.312 128.07663] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.37901 128.07701] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.43806 128.0773] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.49016 128.07751] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.53603 128.07769] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.57649 128.07782] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.61211 128.07793] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.64351 128.07801] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.67116 128.07808] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.69551 128.07812] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.71698 128.07817] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.73589 128.07819] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.75255 128.07821] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.7672 128.07824] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.78011 128.07825] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.79146 128.07826] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.80148 128.07827] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.81027 128.07827] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.81801 128.07828] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.82483 128.07828] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.83083 128.07828] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.83614 128.07828] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.84081 128.07829] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.84488 128.07829] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.8485 128.07829] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.85165 128.07829] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.85445 128.07829] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.85692 128.07829] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.85907 128.07829] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.86099 128.07829] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.86269 128.07829] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.86415 128.07829] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.86543 128.07829] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.86658 128.07829] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.86758 128.07829] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 412.8685 128.07829] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 1 1 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n236.14 335.214 M\n271.673 322.137 L\n312.803 311.451 L\n355.174 299.406 L\n395.525 283.346 L\n432.849 263.393 L\n468.87 243.117 L\n504.988 224.901 L\n542.672 209.148 L\n582.056 197.854 L\n620.712 193.807 L\n657.157 196.677 L\n690.978 202.91 L\n722.125 210.358 L\n750.608 217.769 L\n776.442 224.463 L\n799.648 230.122 L\n820.266 234.665 L\n838.367 238.154 L\n854.06 240.731 L\n867.496 242.574 L\n878.873 243.86 L\n888.439 244.753 L\n896.503 245.387 L\n903.45 245.87 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 1 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n236.14 335.214 M\n271.673 322.137 L\n315.616 308.856 L\n361.543 291.881 L\n404.426 270.071 L\n446.378 246.49 L\n489.255 225.336 L\n533.735 209.818 L\n581.433 201.703 L\n631.217 204.13 L\n676.949 213.181 L\n717.344 223.125 L\n752.328 231.868 L\n782.682 239.204 L\n809.306 245.424 L\n832.808 250.718 L\n853.53 255.146 L\n871.684 258.739 L\n887.445 261.554 L\n900.988 263.682 L\n912.504 265.236 L\n922.204 266.342 L\n930.329 267.119 L\n937.162 267.676 L\n943.042 268.103 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 1 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n236.14 335.214 M\n271.673 322.137 L\n315.617 307.716 L\n361.55 290.154 L\n404.689 268.928 L\n446.673 246.088 L\n489.275 225.469 L\n533.291 210.192 L\n580.499 202.03 L\n629.908 204.13 L\n675.693 213.504 L\n716.615 225.091 L\n752.132 235.683 L\n782.649 244.373 L\n809.129 251.37 L\n832.382 257.032 L\n852.878 261.6 L\n870.863 265.224 L\n886.5 268.023 L\n899.951 270.117 L\n911.393 271.637 L\n921.033 272.714 L\n929.108 273.468 L\n935.899 274.009 L\n941.743 274.423 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n236.14 335.214 M\n271.673 322.137 L\n315.498 306.547 L\n361.646 288.526 L\n405.193 267.353 L\n447.589 244.666 L\n490.561 224.286 L\n534.864 209.355 L\n582.223 201.664 L\n631.532 204.276 L\n676.979 216.064 L\n717.46 231.106 L\n752.438 244.962 L\n782.348 255.969 L\n808.285 264.218 L\n831.163 270.317 L\n851.457 274.834 L\n869.362 278.18 L\n884.985 280.641 L\n898.448 282.425 L\n909.908 283.695 L\n919.565 284.586 L\n927.654 285.209 L\n934.456 285.656 L\n940.307 286.001 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n236.139 335.214 M\n271.672 322.137 L\n315.511 306.729 L\n361.609 288.818 L\n405.068 267.686 L\n447.358 245.007 L\n490.218 224.6 L\n534.415 209.597 L\n581.694 201.784 L\n630.988 204.24 L\n676.614 215.443 L\n717.433 229.731 L\n752.748 242.909 L\n782.893 253.441 L\n808.955 261.434 L\n831.881 267.449 L\n852.18 271.989 L\n870.071 275.407 L\n885.673 277.952 L\n899.112 279.813 L\n910.55 281.144 L\n920.188 282.079 L\n928.26 282.733 L\n935.048 283.202 L\n940.887 283.564 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 83.15 86.3625] CT\r\nN\r\n2.984 7.629 M\n2.984 6.926 3.125 6.285 QT\n6.594 -7.496 L\n1.547 -7.496 L\n1.063 -7.496 1.063 -8.121 QT\n1.25 -9.183 1.688 -9.183 QT\n7.016 -9.183 L\n8.938 -17.011 L\n9.125 -17.636 9.688 -18.082 QT\n10.25 -18.527 10.953 -18.527 QT\n11.563 -18.527 11.969 -18.168 QT\n12.375 -17.808 12.375 -17.199 QT\n12.375 -17.058 12.367 -16.972 QT\n12.359 -16.886 12.328 -16.793 QT\n10.406 -9.183 L\n15.359 -9.183 L\n15.844 -9.183 15.844 -8.543 QT\n15.828 -8.433 15.758 -8.152 QT\n15.688 -7.871 15.57 -7.683 QT\n15.453 -7.496 15.219 -7.496 QT\n9.984 -7.496 L\n6.547 6.379 L\n6.188 7.739 6.188 8.723 QT\n6.188 10.785 7.594 10.785 QT\n9.703 10.785 11.336 8.809 QT\n12.969 6.832 13.828 4.457 QT\n14.016 4.176 14.203 4.176 QT\n14.797 4.176 L\n14.984 4.176 15.102 4.309 QT\n15.219 4.442 15.219 4.598 QT\n15.219 4.692 15.172 4.739 QT\n14.109 7.645 12.094 9.856 QT\n10.078 12.067 7.484 12.067 QT\n5.578 12.067 4.281 10.817 QT\n2.984 9.567 2.984 7.629 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 83.15 86.3625] CT\r\nN\r\n34.276 5.145 M\n33.885 5.145 33.627 4.84 QT\n33.369 4.535 33.369 4.176 QT\n33.369 3.785 33.627 3.504 QT\n33.885 3.223 34.276 3.223 QT\n64.416 3.223 L\n64.776 3.223 65.034 3.504 QT\n65.291 3.785 65.291 4.176 QT\n65.291 4.535 65.034 4.84 QT\n64.776 5.145 64.416 5.145 QT\n34.276 5.145 L\ncp\n34.276 -4.183 M\n33.885 -4.183 33.627 -4.465 QT\n33.369 -4.746 33.369 -5.152 QT\n33.369 -5.496 33.627 -5.8 QT\n33.885 -6.105 34.276 -6.105 QT\n64.416 -6.105 L\n64.776 -6.105 65.034 -5.8 QT\n65.291 -5.496 65.291 -5.152 QT\n65.291 -4.746 65.034 -4.465 QT\n64.776 -4.183 64.416 -4.183 QT\n34.276 -4.183 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 83.15 86.3625] CT\r\nN\r\n93.333 12.582 M\n90.364 12.582 88.372 10.996 QT\n86.38 9.41 85.286 6.887 QT\n84.192 4.364 83.77 1.598 QT\n83.348 -1.168 83.348 -3.996 QT\n83.348 -7.793 84.825 -11.613 QT\n86.302 -15.433 89.177 -17.941 QT\n92.052 -20.449 95.989 -20.449 QT\n97.63 -20.449 99.044 -19.832 QT\n100.458 -19.215 101.27 -18.004 QT\n102.083 -16.793 102.083 -15.09 QT\n102.083 -14.105 101.411 -13.433 QT\n100.739 -12.761 99.755 -12.761 QT\n98.817 -12.761 98.138 -13.441 QT\n97.458 -14.121 97.458 -15.09 QT\n97.458 -16.027 98.138 -16.707 QT\n98.817 -17.386 99.755 -17.386 QT\n100.02 -17.386 L\n99.411 -18.246 98.294 -18.66 QT\n97.177 -19.074 95.989 -19.074 QT\n94.536 -19.074 93.302 -18.441 QT\n92.067 -17.808 91.083 -16.73 QT\n90.098 -15.652 89.442 -14.347 QT\n88.786 -13.043 88.427 -11.379 QT\n88.067 -9.715 87.973 -8.261 QT\n87.88 -6.808 87.88 -4.605 QT\n88.723 -6.574 90.27 -7.832 QT\n91.817 -9.09 93.755 -9.09 QT\n95.895 -9.09 97.653 -8.222 QT\n99.411 -7.355 100.677 -5.816 QT\n101.942 -4.277 102.606 -2.308 QT\n103.27 -0.34 103.27 1.676 QT\n103.27 4.489 102.02 7.028 QT\n100.77 9.567 98.497 11.075 QT\n96.223 12.582 93.333 12.582 QT\ncp\n93.333 11.051 M\n95.192 11.051 96.317 10.207 QT\n97.442 9.364 97.966 7.965 QT\n98.489 6.567 98.622 5.153 QT\n98.755 3.739 98.755 1.676 QT\n98.755 -1.043 98.497 -2.965 QT\n98.239 -4.886 97.091 -6.355 QT\n95.942 -7.824 93.567 -7.824 QT\n91.63 -7.824 90.372 -6.511 QT\n89.114 -5.199 88.544 -3.191 QT\n87.973 -1.183 87.973 0.66 QT\n87.973 1.301 88.02 1.629 QT\n88.02 1.692 88.005 1.739 QT\n87.989 1.785 87.973 1.864 QT\n87.973 3.926 88.395 6.035 QT\n88.817 8.145 90.013 9.598 QT\n91.208 11.051 93.333 11.051 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n1080 676 M\n1080 335 L\n499 335 L\n499 676 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n10.484 6.022 M\n12.063 8.022 14.422 9.178 QT\n16.781 10.334 19.313 10.334 QT\n21.453 10.334 23.273 9.491 QT\n25.094 8.647 26.453 7.147 QT\n27.813 5.647 28.539 3.733 QT\n29.266 1.819 29.266 -0.291 QT\n29.266 -0.65 29.672 -0.65 QT\n30.234 -0.65 L\n30.594 -0.65 30.594 -0.197 QT\n30.594 2.209 29.672 4.444 QT\n28.75 6.678 27.063 8.374 QT\n25.375 10.069 23.188 11.014 QT\n21 11.959 18.625 11.959 QT\n15.313 11.959 12.359 10.624 QT\n9.406 9.288 7.219 6.959 QT\n5.031 4.631 3.805 1.577 QT\n2.578 -1.478 2.578 -4.775 QT\n2.578 -8.087 3.805 -11.142 QT\n5.031 -14.197 7.219 -16.533 QT\n9.406 -18.869 12.359 -20.181 QT\n15.313 -21.494 18.625 -21.494 QT\n20.984 -21.494 23.141 -20.47 QT\n25.297 -19.447 26.906 -17.587 QT\n29.578 -21.353 L\n29.844 -21.494 29.891 -21.494 QT\n30.234 -21.494 L\n30.375 -21.494 30.484 -21.376 QT\n30.594 -21.259 30.594 -21.103 QT\n30.594 -8.681 L\n30.594 -8.291 30.234 -8.291 QT\n29.406 -8.291 L\n28.969 -8.291 28.969 -8.681 QT\n28.969 -10.009 28.445 -11.65 QT\n27.922 -13.291 27.102 -14.759 QT\n26.281 -16.228 25.203 -17.353 QT\n22.625 -19.869 19.266 -19.869 QT\n16.734 -19.869 14.406 -18.728 QT\n12.078 -17.587 10.484 -15.556 QT\n8.813 -13.4 8.156 -10.65 QT\n7.5 -7.9 7.5 -4.775 QT\n7.5 -1.65 8.156 1.108 QT\n8.813 3.866 10.484 6.022 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n34.355 10.944 M\n34.355 9.319 L\n35.918 9.319 36.933 9.077 QT\n37.949 8.834 37.949 7.866 QT\n37.949 -16.275 L\n37.949 -17.509 37.574 -18.064 QT\n37.199 -18.619 36.504 -18.744 QT\n35.808 -18.869 34.355 -18.869 QT\n34.355 -20.478 L\n41.183 -20.978 L\n41.183 7.866 L\n41.183 8.834 42.191 9.077 QT\n43.199 9.319 44.746 9.319 QT\n44.746 10.944 L\n34.355 10.944 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n57.1 11.459 M\n54.334 11.459 51.975 10.053 QT\n49.616 8.647 48.249 6.288 QT\n46.881 3.928 46.881 1.147 QT\n46.881 -0.962 47.631 -2.916 QT\n48.381 -4.869 49.788 -6.408 QT\n51.194 -7.947 53.061 -8.814 QT\n54.928 -9.681 57.1 -9.681 QT\n59.928 -9.681 62.256 -8.181 QT\n64.584 -6.681 65.928 -4.181 QT\n67.272 -1.681 67.272 1.147 QT\n67.272 3.913 65.905 6.28 QT\n64.538 8.647 62.186 10.053 QT\n59.834 11.459 57.1 11.459 QT\ncp\n57.1 10.116 M\n60.788 10.116 62.022 7.444 QT\n63.256 4.772 63.256 0.631 QT\n63.256 -1.681 63.006 -3.197 QT\n62.756 -4.712 61.928 -5.947 QT\n61.413 -6.712 60.616 -7.283 QT\n59.819 -7.853 58.928 -8.158 QT\n58.038 -8.462 57.1 -8.462 QT\n55.663 -8.462 54.374 -7.814 QT\n53.084 -7.166 52.225 -5.947 QT\n51.366 -4.65 51.131 -3.087 QT\n50.897 -1.525 50.897 0.631 QT\n50.897 3.209 51.35 5.272 QT\n51.803 7.334 53.163 8.725 QT\n54.522 10.116 57.1 10.116 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n69.931 11.084 M\n69.931 3.569 L\n69.931 3.209 70.338 3.209 QT\n70.9 3.209 L\n71.166 3.209 71.26 3.569 QT\n72.541 10.241 77.447 10.241 QT\n79.635 10.241 81.103 9.256 QT\n82.572 8.272 82.572 6.209 QT\n82.572 4.725 81.424 3.678 QT\n80.275 2.631 78.713 2.256 QT\n75.635 1.647 L\n74.088 1.303 72.814 0.608 QT\n71.541 -0.087 70.736 -1.244 QT\n69.931 -2.4 69.931 -3.931 QT\n69.931 -5.947 70.994 -7.236 QT\n72.056 -8.525 73.767 -9.103 QT\n75.478 -9.681 77.447 -9.681 QT\n79.806 -9.681 81.556 -8.416 QT\n82.885 -9.556 L\n82.885 -9.681 83.119 -9.681 QT\n83.447 -9.681 L\n83.588 -9.681 83.697 -9.556 QT\n83.806 -9.431 83.806 -9.291 QT\n83.806 -3.275 L\n83.806 -2.853 83.447 -2.853 QT\n82.885 -2.853 L\n82.478 -2.853 82.478 -3.275 QT\n82.478 -5.681 81.142 -7.142 QT\n79.806 -8.603 77.4 -8.603 QT\n75.338 -8.603 73.822 -7.837 QT\n72.306 -7.072 72.306 -5.212 QT\n72.306 -3.931 73.4 -3.111 QT\n74.494 -2.291 75.947 -1.931 QT\n79.072 -1.337 L\n80.635 -0.978 81.994 -0.126 QT\n83.353 0.725 84.15 2.03 QT\n84.947 3.334 84.947 4.975 QT\n84.947 6.631 84.377 7.858 QT\n83.806 9.084 82.783 9.889 QT\n81.76 10.694 80.369 11.077 QT\n78.978 11.459 77.447 11.459 QT\n74.572 11.459 72.541 9.522 QT\n70.853 11.35 L\n70.853 11.459 70.603 11.459 QT\n70.338 11.459 L\n69.931 11.459 69.931 11.084 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n97.84 11.459 M\n95.027 11.459 92.684 9.991 QT\n90.34 8.522 89.004 6.061 QT\n87.668 3.6 87.668 0.866 QT\n87.668 -1.837 88.895 -4.259 QT\n90.121 -6.681 92.309 -8.181 QT\n94.496 -9.681 97.184 -9.681 QT\n99.309 -9.681 100.863 -8.97 QT\n102.418 -8.259 103.434 -7.001 QT\n104.449 -5.744 104.965 -4.041 QT\n105.481 -2.337 105.481 -0.291 QT\n105.481 0.319 105.012 0.319 QT\n91.684 0.319 L\n91.684 0.819 L\n91.684 4.631 93.223 7.374 QT\n94.762 10.116 98.246 10.116 QT\n99.668 10.116 100.863 9.483 QT\n102.059 8.85 102.949 7.733 QT\n103.84 6.616 104.152 5.334 QT\n104.199 5.178 104.324 5.053 QT\n104.449 4.928 104.606 4.928 QT\n105.012 4.928 L\n105.481 4.928 105.481 5.506 QT\n104.824 8.116 102.668 9.788 QT\n100.512 11.459 97.84 11.459 QT\ncp\n91.731 -0.822 M\n102.215 -0.822 L\n102.215 -2.556 101.738 -4.33 QT\n101.262 -6.103 100.137 -7.283 QT\n99.012 -8.462 97.184 -8.462 QT\n94.59 -8.462 93.16 -6.025 QT\n91.731 -3.587 91.731 -0.822 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n117.888 11.459 M\n115.169 11.459 112.919 9.991 QT\n110.669 8.522 109.427 6.116 QT\n108.185 3.709 108.185 1.022 QT\n108.185 -1.775 109.544 -4.166 QT\n110.903 -6.556 113.239 -7.97 QT\n115.575 -9.384 118.372 -9.384 QT\n120.06 -9.384 121.568 -8.673 QT\n123.075 -7.962 124.169 -6.712 QT\n124.169 -16.275 L\n124.169 -17.509 123.802 -18.064 QT\n123.435 -18.619 122.747 -18.744 QT\n122.06 -18.869 120.607 -18.869 QT\n120.607 -20.478 L\n127.403 -20.978 L\n127.403 6.772 L\n127.403 7.975 127.778 8.53 QT\n128.153 9.084 128.833 9.202 QT\n129.513 9.319 130.982 9.319 QT\n130.982 10.944 L\n124.044 11.459 L\n124.044 8.569 L\n122.841 9.928 121.208 10.694 QT\n119.575 11.459 117.888 11.459 QT\ncp\n113.185 6.944 M\n113.982 8.444 115.294 9.342 QT\n116.607 10.241 118.153 10.241 QT\n120.06 10.241 121.653 9.147 QT\n123.247 8.053 124.044 6.288 QT\n124.044 -4.728 L\n123.497 -5.744 122.677 -6.541 QT\n121.857 -7.337 120.833 -7.767 QT\n119.81 -8.197 118.669 -8.197 QT\n116.263 -8.197 114.802 -6.837 QT\n113.341 -5.478 112.763 -3.369 QT\n112.185 -1.259 112.185 1.053 QT\n112.185 2.897 112.372 4.272 QT\n112.56 5.647 113.185 6.944 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n132.503 2.428 M\n132.503 -0.416 L\n144.674 -0.416 L\n144.674 2.428 L\n132.503 2.428 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n148.609 10.944 M\n148.609 9.319 L\n150.171 9.319 151.187 9.077 QT\n152.202 8.834 152.202 7.866 QT\n152.202 -16.275 L\n152.202 -17.509 151.827 -18.064 QT\n151.452 -18.619 150.757 -18.744 QT\n150.062 -18.869 148.609 -18.869 QT\n148.609 -20.478 L\n155.437 -20.978 L\n155.437 7.866 L\n155.437 8.834 156.445 9.077 QT\n157.452 9.319 158.999 9.319 QT\n158.999 10.944 L\n148.609 10.944 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n171.354 11.459 M\n168.588 11.459 166.229 10.053 QT\n163.869 8.647 162.502 6.288 QT\n161.135 3.928 161.135 1.147 QT\n161.135 -0.962 161.885 -2.916 QT\n162.635 -4.869 164.041 -6.408 QT\n165.447 -7.947 167.314 -8.814 QT\n169.182 -9.681 171.354 -9.681 QT\n174.182 -9.681 176.51 -8.181 QT\n178.838 -6.681 180.182 -4.181 QT\n181.525 -1.681 181.525 1.147 QT\n181.525 3.913 180.158 6.28 QT\n178.791 8.647 176.439 10.053 QT\n174.088 11.459 171.354 11.459 QT\ncp\n171.354 10.116 M\n175.041 10.116 176.275 7.444 QT\n177.51 4.772 177.51 0.631 QT\n177.51 -1.681 177.26 -3.197 QT\n177.01 -4.712 176.182 -5.947 QT\n175.666 -6.712 174.869 -7.283 QT\n174.072 -7.853 173.182 -8.158 QT\n172.291 -8.462 171.354 -8.462 QT\n169.916 -8.462 168.627 -7.814 QT\n167.338 -7.166 166.479 -5.947 QT\n165.619 -4.65 165.385 -3.087 QT\n165.15 -1.525 165.15 0.631 QT\n165.15 3.209 165.604 5.272 QT\n166.057 7.334 167.416 8.725 QT\n168.775 10.116 171.354 10.116 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n195.42 11.459 M\n192.655 11.459 190.295 10.053 QT\n187.936 8.647 186.569 6.288 QT\n185.202 3.928 185.202 1.147 QT\n185.202 -0.962 185.952 -2.916 QT\n186.702 -4.869 188.108 -6.408 QT\n189.514 -7.947 191.381 -8.814 QT\n193.248 -9.681 195.42 -9.681 QT\n198.248 -9.681 200.577 -8.181 QT\n202.905 -6.681 204.248 -4.181 QT\n205.592 -1.681 205.592 1.147 QT\n205.592 3.913 204.225 6.28 QT\n202.858 8.647 200.506 10.053 QT\n198.155 11.459 195.42 11.459 QT\ncp\n195.42 10.116 M\n199.108 10.116 200.342 7.444 QT\n201.577 4.772 201.577 0.631 QT\n201.577 -1.681 201.327 -3.197 QT\n201.077 -4.712 200.248 -5.947 QT\n199.733 -6.712 198.936 -7.283 QT\n198.139 -7.853 197.248 -8.158 QT\n196.358 -8.462 195.42 -8.462 QT\n193.983 -8.462 192.694 -7.814 QT\n191.405 -7.166 190.545 -5.947 QT\n189.686 -4.65 189.452 -3.087 QT\n189.217 -1.525 189.217 0.631 QT\n189.217 3.209 189.67 5.272 QT\n190.123 7.334 191.483 8.725 QT\n192.842 10.116 195.42 10.116 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n207.908 19.866 M\n207.908 18.272 L\n209.486 18.272 210.494 17.999 QT\n211.502 17.725 211.502 16.788 QT\n211.502 -5.384 L\n211.502 -6.65 210.603 -6.962 QT\n209.705 -7.275 207.908 -7.275 QT\n207.908 -8.884 L\n214.72 -9.384 L\n214.72 -6.525 L\n215.97 -7.931 217.642 -8.658 QT\n219.314 -9.384 221.205 -9.384 QT\n223.924 -9.384 226.103 -7.916 QT\n228.283 -6.447 229.509 -4.048 QT\n230.736 -1.65 230.736 1.022 QT\n230.736 3.803 229.377 6.202 QT\n228.017 8.6 225.666 10.03 QT\n223.314 11.459 220.517 11.459 QT\n217.158 11.459 214.845 8.741 QT\n214.845 16.788 L\n214.845 17.725 215.869 17.999 QT\n216.892 18.272 218.439 18.272 QT\n218.439 19.866 L\n207.908 19.866 L\ncp\n214.845 6.475 M\n215.658 8.116 217.095 9.178 QT\n218.533 10.241 220.236 10.241 QT\n221.83 10.241 223.056 9.389 QT\n224.283 8.538 225.119 7.1 QT\n225.955 5.663 226.345 4.077 QT\n226.736 2.491 226.736 1.022 QT\n226.736 -0.822 226.072 -2.97 QT\n225.408 -5.119 224.049 -6.587 QT\n222.689 -8.056 220.752 -8.056 QT\n218.892 -8.056 217.33 -7.103 QT\n215.767 -6.15 214.845 -4.509 QT\n214.845 6.475 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n261.519 22.35 M\n258.957 20.334 257.105 17.717 QT\n255.254 15.1 254.074 12.131 QT\n252.894 9.163 252.308 5.928 QT\n251.723 2.694 251.723 -0.556 QT\n251.723 -3.853 252.308 -7.087 QT\n252.894 -10.322 254.098 -13.314 QT\n255.301 -16.306 257.16 -18.908 QT\n259.019 -21.509 261.519 -23.462 QT\n261.519 -23.556 261.738 -23.556 QT\n262.176 -23.556 L\n262.301 -23.556 262.418 -23.431 QT\n262.535 -23.306 262.535 -23.15 QT\n262.535 -22.947 262.441 -22.853 QT\n260.191 -20.666 258.699 -18.15 QT\n257.207 -15.634 256.293 -12.791 QT\n255.379 -9.947 254.98 -6.9 QT\n254.582 -3.853 254.582 -0.556 QT\n254.582 14.069 262.394 21.663 QT\n262.535 21.788 262.535 22.038 QT\n262.535 22.147 262.41 22.295 QT\n262.285 22.444 262.176 22.444 QT\n261.738 22.444 L\n261.519 22.444 261.519 22.35 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n267.847 7.209 M\n267.847 6.538 267.972 5.928 QT\n271.3 -7.275 L\n266.472 -7.275 L\n266.003 -7.275 266.003 -7.884 QT\n266.175 -8.884 266.612 -8.884 QT\n271.706 -8.884 L\n273.55 -16.384 L\n273.722 -16.994 274.261 -17.423 QT\n274.8 -17.853 275.472 -17.853 QT\n276.065 -17.853 276.456 -17.501 QT\n276.847 -17.15 276.847 -16.572 QT\n276.847 -16.431 276.839 -16.353 QT\n276.831 -16.275 276.8 -16.197 QT\n274.956 -8.884 L\n279.706 -8.884 L\n280.175 -8.884 280.175 -8.291 QT\n280.143 -8.166 280.081 -7.9 QT\n280.018 -7.634 279.901 -7.455 QT\n279.784 -7.275 279.565 -7.275 QT\n274.55 -7.275 L\n271.253 6.022 L\n270.925 7.334 270.925 8.272 QT\n270.925 10.241 272.268 10.241 QT\n274.284 10.241 275.847 8.342 QT\n277.409 6.444 278.237 4.178 QT\n278.425 3.913 278.597 3.913 QT\n279.159 3.913 L\n279.347 3.913 279.456 4.038 QT\n279.565 4.163 279.565 4.319 QT\n279.565 4.413 279.518 4.459 QT\n278.503 7.241 276.573 9.35 QT\n274.643 11.459 272.159 11.459 QT\n270.331 11.459 269.089 10.272 QT\n267.847 9.084 267.847 7.209 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n282.516 17.878 M\n282.516 12.659 L\n282.516 12.409 282.798 12.409 QT\n283.188 12.409 L\n283.376 12.409 283.438 12.659 QT\n284.329 17.299 287.751 17.299 QT\n289.266 17.299 290.29 16.612 QT\n291.313 15.924 291.313 14.487 QT\n291.313 13.456 290.516 12.729 QT\n289.72 12.003 288.626 11.737 QT\n286.485 11.315 L\n285.407 11.081 284.524 10.596 QT\n283.641 10.112 283.079 9.307 QT\n282.516 8.503 282.516 7.44 QT\n282.516 6.034 283.259 5.135 QT\n284.001 4.237 285.188 3.838 QT\n286.376 3.44 287.751 3.44 QT\n289.391 3.44 290.61 4.315 QT\n291.532 3.518 L\n291.532 3.44 291.688 3.44 QT\n291.923 3.44 L\n292.016 3.44 292.095 3.526 QT\n292.173 3.612 292.173 3.706 QT\n292.173 7.893 L\n292.173 8.19 291.923 8.19 QT\n291.532 8.19 L\n291.251 8.19 291.251 7.893 QT\n291.251 6.221 290.321 5.206 QT\n289.391 4.19 287.72 4.19 QT\n286.282 4.19 285.227 4.721 QT\n284.173 5.253 284.173 6.549 QT\n284.173 7.44 284.93 8.01 QT\n285.688 8.581 286.704 8.831 QT\n288.876 9.237 L\n289.97 9.487 290.915 10.081 QT\n291.86 10.674 292.415 11.581 QT\n292.97 12.487 292.97 13.628 QT\n292.97 14.784 292.571 15.635 QT\n292.173 16.487 291.462 17.049 QT\n290.751 17.612 289.782 17.878 QT\n288.813 18.143 287.751 18.143 QT\n285.751 18.143 284.329 16.799 QT\n283.157 18.065 L\n283.157 18.143 282.985 18.143 QT\n282.798 18.143 L\n282.516 18.143 282.516 17.878 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n295.029 17.784 M\n295.029 16.659 L\n296.123 16.659 296.826 16.487 QT\n297.529 16.315 297.529 15.643 QT\n297.529 6.909 L\n297.529 5.674 297.052 5.393 QT\n296.576 5.112 295.17 5.112 QT\n295.17 3.987 L\n299.779 3.643 L\n299.779 15.643 L\n299.779 16.315 300.388 16.487 QT\n300.998 16.659 302.013 16.659 QT\n302.013 17.784 L\n295.029 17.784 L\ncp\n296.388 -1.857 M\n296.388 -2.56 296.92 -3.091 QT\n297.451 -3.622 298.138 -3.622 QT\n298.591 -3.622 299.013 -3.388 QT\n299.435 -3.154 299.67 -2.732 QT\n299.904 -2.31 299.904 -1.857 QT\n299.904 -1.169 299.373 -0.638 QT\n298.841 -0.107 298.138 -0.107 QT\n297.451 -0.107 296.92 -0.638 QT\n296.388 -1.169 296.388 -1.857 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n303.864 17.784 M\n303.864 16.659 L\n304.958 16.659 305.661 16.487 QT\n306.364 16.315 306.364 15.643 QT\n306.364 6.909 L\n306.364 6.049 306.107 5.667 QT\n305.849 5.284 305.364 5.198 QT\n304.88 5.112 303.864 5.112 QT\n303.864 3.987 L\n308.505 3.643 L\n308.505 6.768 L\n309.146 5.393 310.403 4.518 QT\n311.661 3.643 313.146 3.643 QT\n316.833 3.643 317.474 6.643 QT\n318.114 5.299 319.349 4.471 QT\n320.583 3.643 322.052 3.643 QT\n323.505 3.643 324.497 4.112 QT\n325.489 4.581 325.989 5.542 QT\n326.489 6.503 326.489 7.956 QT\n326.489 15.643 L\n326.489 16.315 327.2 16.487 QT\n327.911 16.659 328.989 16.659 QT\n328.989 17.784 L\n321.661 17.784 L\n321.661 16.659 L\n322.755 16.659 323.458 16.487 QT\n324.161 16.315 324.161 15.643 QT\n324.161 8.049 L\n324.161 6.44 323.708 5.456 QT\n323.255 4.471 321.849 4.471 QT\n320.005 4.471 318.802 5.956 QT\n317.599 7.44 317.599 9.331 QT\n317.599 15.643 L\n317.599 16.315 318.302 16.487 QT\n319.005 16.659 320.099 16.659 QT\n320.099 17.784 L\n312.771 17.784 L\n312.771 16.659 L\n313.864 16.659 314.567 16.487 QT\n315.271 16.315 315.271 15.643 QT\n315.271 8.049 L\n315.271 6.487 314.817 5.479 QT\n314.364 4.471 312.958 4.471 QT\n311.099 4.471 309.903 5.956 QT\n308.708 7.44 308.708 9.331 QT\n308.708 15.643 L\n308.708 16.315 309.411 16.487 QT\n310.114 16.659 311.192 16.659 QT\n311.192 17.784 L\n303.864 17.784 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n347.911 4.834 M\n347.536 4.834 347.286 4.545 QT\n347.036 4.256 347.036 3.913 QT\n347.036 3.538 347.286 3.264 QT\n347.536 2.991 347.911 2.991 QT\n376.801 2.991 L\n377.145 2.991 377.387 3.264 QT\n377.629 3.538 377.629 3.913 QT\n377.629 4.256 377.387 4.545 QT\n377.145 4.834 376.801 4.834 QT\n347.911 4.834 L\ncp\n347.911 -4.103 M\n347.536 -4.103 347.286 -4.376 QT\n347.036 -4.65 347.036 -5.025 QT\n347.036 -5.369 347.286 -5.658 QT\n347.536 -5.947 347.911 -5.947 QT\n376.801 -5.947 L\n377.145 -5.947 377.387 -5.658 QT\n377.629 -5.369 377.629 -5.025 QT\n377.629 -4.65 377.387 -4.376 QT\n377.145 -4.103 376.801 -4.103 QT\n347.911 -4.103 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n396.856 10.944 M\n396.856 9.319 L\n402.606 9.319 402.606 7.866 QT\n402.606 -16.275 L\n400.231 -15.134 396.591 -15.134 QT\n396.591 -16.744 L\n402.231 -16.744 405.106 -19.697 QT\n405.747 -19.697 L\n405.903 -19.697 406.052 -19.572 QT\n406.2 -19.447 406.2 -19.291 QT\n406.2 7.866 L\n406.2 9.319 411.95 9.319 QT\n411.95 10.944 L\n396.856 10.944 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n426.891 11.959 M\n421.25 11.959 419.219 7.319 QT\n417.188 2.678 417.188 -3.728 QT\n417.188 -7.728 417.914 -11.251 QT\n418.641 -14.775 420.813 -17.236 QT\n422.985 -19.697 426.891 -19.697 QT\n429.922 -19.697 431.852 -18.212 QT\n433.781 -16.728 434.797 -14.384 QT\n435.813 -12.041 436.18 -9.353 QT\n436.547 -6.666 436.547 -3.728 QT\n436.547 0.225 435.82 3.678 QT\n435.094 7.131 432.961 9.545 QT\n430.828 11.959 426.891 11.959 QT\ncp\n426.891 10.756 M\n429.453 10.756 430.711 8.131 QT\n431.969 5.506 432.258 2.319 QT\n432.547 -0.869 432.547 -4.462 QT\n432.547 -7.931 432.258 -10.845 QT\n431.969 -13.759 430.719 -16.134 QT\n429.469 -18.509 426.891 -18.509 QT\n424.281 -18.509 423.024 -16.126 QT\n421.766 -13.744 421.477 -10.837 QT\n421.188 -7.931 421.188 -4.462 QT\n421.188 -1.9 421.313 0.366 QT\n421.438 2.631 421.977 5.045 QT\n422.516 7.459 423.719 9.108 QT\n424.922 10.756 426.891 10.756 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n449.691 11.959 M\n444.05 11.959 442.019 7.319 QT\n439.988 2.678 439.988 -3.728 QT\n439.988 -7.728 440.714 -11.251 QT\n441.441 -14.775 443.613 -17.236 QT\n445.785 -19.697 449.691 -19.697 QT\n452.722 -19.697 454.652 -18.212 QT\n456.582 -16.728 457.597 -14.384 QT\n458.613 -12.041 458.98 -9.353 QT\n459.347 -6.666 459.347 -3.728 QT\n459.347 0.225 458.621 3.678 QT\n457.894 7.131 455.761 9.545 QT\n453.628 11.959 449.691 11.959 QT\ncp\n449.691 10.756 M\n452.253 10.756 453.511 8.131 QT\n454.769 5.506 455.058 2.319 QT\n455.347 -0.869 455.347 -4.462 QT\n455.347 -7.931 455.058 -10.845 QT\n454.769 -13.759 453.519 -16.134 QT\n452.269 -18.509 449.691 -18.509 QT\n447.082 -18.509 445.824 -16.126 QT\n444.566 -13.744 444.277 -10.837 QT\n443.988 -7.931 443.988 -4.462 QT\n443.988 -1.9 444.113 0.366 QT\n444.238 2.631 444.777 5.045 QT\n445.316 7.459 446.519 9.108 QT\n447.722 10.756 449.691 10.756 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 137.37397] CT\r\nN\r\n463.975 22.444 M\n463.569 22.444 463.569 22.038 QT\n463.569 21.834 463.663 21.741 QT\n471.522 14.069 471.522 -0.556 QT\n471.522 -15.181 463.757 -22.775 QT\n463.569 -22.884 463.569 -23.15 QT\n463.569 -23.306 463.694 -23.431 QT\n463.819 -23.556 463.975 -23.556 QT\n464.413 -23.556 L\n464.538 -23.556 464.632 -23.462 QT\n467.928 -20.869 470.132 -17.134 QT\n472.335 -13.4 473.358 -9.181 QT\n474.382 -4.962 474.382 -0.556 QT\n474.382 2.694 473.827 5.85 QT\n473.272 9.006 472.077 12.077 QT\n470.882 15.147 469.038 17.741 QT\n467.194 20.334 464.632 22.35 QT\n464.538 22.444 464.413 22.444 QT\n463.975 22.444 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n2.667 LW\r\nN\r\n507.004 366.331 M\n587.042 366.331 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 205.13354 137.37397] CT\r\nN\r\nf-1792389198\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 158.24938] CT\r\nN\r\n17.906 11.959 M\n13.516 11.959 10.023 9.631 QT\n6.531 7.303 4.555 3.452 QT\n2.578 -0.4 2.578 -4.65 QT\n2.578 -7.791 3.719 -10.869 QT\n4.859 -13.947 6.891 -16.33 QT\n8.922 -18.712 11.773 -20.103 QT\n14.625 -21.494 17.906 -21.494 QT\n21.156 -21.494 24.023 -20.087 QT\n26.891 -18.681 28.93 -16.275 QT\n30.969 -13.869 32.07 -10.884 QT\n33.172 -7.9 33.172 -4.65 QT\n33.172 -0.4 31.195 3.452 QT\n29.219 7.303 25.719 9.631 QT\n22.219 11.959 17.906 11.959 QT\ncp\n10.266 5.975 M\n11.609 8.084 13.586 9.334 QT\n15.563 10.584 17.906 10.584 QT\n19.406 10.584 20.852 9.975 QT\n22.297 9.366 23.477 8.311 QT\n24.656 7.256 25.5 5.975 QT\n28.234 1.85 28.234 -5.384 QT\n28.234 -12.009 25.5 -15.869 QT\n24.141 -17.806 22.133 -18.978 QT\n20.125 -20.15 17.906 -20.15 QT\n15.656 -20.15 13.633 -18.978 QT\n11.609 -17.806 10.266 -15.869 QT\n9.188 -14.369 8.594 -12.673 QT\n8 -10.978 7.75 -9.158 QT\n7.5 -7.337 7.5 -5.384 QT\n7.5 -3.291 7.734 -1.306 QT\n7.969 0.678 8.609 2.584 QT\n9.25 4.491 10.266 5.975 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 158.24938] CT\r\nN\r\n36.654 19.866 M\n36.654 18.272 L\n38.232 18.272 39.24 17.999 QT\n40.248 17.725 40.248 16.788 QT\n40.248 -5.384 L\n40.248 -6.65 39.35 -6.962 QT\n38.451 -7.275 36.654 -7.275 QT\n36.654 -8.884 L\n43.467 -9.384 L\n43.467 -6.525 L\n44.717 -7.931 46.389 -8.658 QT\n48.061 -9.384 49.951 -9.384 QT\n52.67 -9.384 54.85 -7.916 QT\n57.029 -6.447 58.256 -4.048 QT\n59.482 -1.65 59.482 1.022 QT\n59.482 3.803 58.123 6.202 QT\n56.764 8.6 54.412 10.03 QT\n52.061 11.459 49.264 11.459 QT\n45.904 11.459 43.592 8.741 QT\n43.592 16.788 L\n43.592 17.725 44.615 17.999 QT\n45.639 18.272 47.186 18.272 QT\n47.186 19.866 L\n36.654 19.866 L\ncp\n43.592 6.475 M\n44.404 8.116 45.842 9.178 QT\n47.279 10.241 48.982 10.241 QT\n50.576 10.241 51.803 9.389 QT\n53.029 8.538 53.865 7.1 QT\n54.701 5.663 55.092 4.077 QT\n55.482 2.491 55.482 1.022 QT\n55.482 -0.822 54.818 -2.97 QT\n54.154 -5.119 52.795 -6.587 QT\n51.436 -8.056 49.498 -8.056 QT\n47.639 -8.056 46.076 -7.103 QT\n44.514 -6.15 43.592 -4.509 QT\n43.592 6.475 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 158.24938] CT\r\nN\r\n73.52 11.459 M\n70.708 11.459 68.364 9.991 QT\n66.02 8.522 64.684 6.061 QT\n63.348 3.6 63.348 0.866 QT\n63.348 -1.837 64.575 -4.259 QT\n65.801 -6.681 67.989 -8.181 QT\n70.176 -9.681 72.864 -9.681 QT\n74.989 -9.681 76.543 -8.97 QT\n78.098 -8.259 79.114 -7.001 QT\n80.129 -5.744 80.645 -4.041 QT\n81.161 -2.337 81.161 -0.291 QT\n81.161 0.319 80.692 0.319 QT\n67.364 0.319 L\n67.364 0.819 L\n67.364 4.631 68.903 7.374 QT\n70.442 10.116 73.926 10.116 QT\n75.348 10.116 76.543 9.483 QT\n77.739 8.85 78.629 7.733 QT\n79.52 6.616 79.833 5.334 QT\n79.879 5.178 80.004 5.053 QT\n80.129 4.928 80.286 4.928 QT\n80.692 4.928 L\n81.161 4.928 81.161 5.506 QT\n80.504 8.116 78.348 9.788 QT\n76.192 11.459 73.52 11.459 QT\ncp\n67.411 -0.822 M\n77.895 -0.822 L\n77.895 -2.556 77.418 -4.33 QT\n76.942 -6.103 75.817 -7.283 QT\n74.692 -8.462 72.864 -8.462 QT\n70.27 -8.462 68.84 -6.025 QT\n67.411 -3.587 67.411 -0.822 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 158.24938] CT\r\nN\r\n83.709 10.944 M\n83.709 9.319 L\n85.271 9.319 86.287 9.077 QT\n87.302 8.834 87.302 7.866 QT\n87.302 -4.697 L\n87.302 -5.931 86.927 -6.478 QT\n86.552 -7.025 85.857 -7.15 QT\n85.162 -7.275 83.709 -7.275 QT\n83.709 -8.884 L\n90.38 -9.384 L\n90.38 -4.884 L\n91.302 -6.869 93.107 -8.126 QT\n94.912 -9.384 97.052 -9.384 QT\n100.24 -9.384 101.841 -7.853 QT\n103.443 -6.322 103.443 -3.181 QT\n103.443 7.866 L\n103.443 8.834 104.459 9.077 QT\n105.474 9.319 107.037 9.319 QT\n107.037 10.944 L\n96.505 10.944 L\n96.505 9.319 L\n98.084 9.319 99.091 9.077 QT\n100.099 8.834 100.099 7.866 QT\n100.099 -3.056 L\n100.099 -5.291 99.451 -6.744 QT\n98.802 -8.197 96.771 -8.197 QT\n94.099 -8.197 92.38 -6.064 QT\n90.662 -3.931 90.662 -1.212 QT\n90.662 7.866 L\n90.662 8.834 91.677 9.077 QT\n92.693 9.319 94.24 9.319 QT\n94.24 10.944 L\n83.709 10.944 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 158.24938] CT\r\nN\r\n108.183 2.428 M\n108.183 -0.416 L\n120.354 -0.416 L\n120.354 2.428 L\n108.183 2.428 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 158.24938] CT\r\nN\r\n124.289 10.944 M\n124.289 9.319 L\n125.851 9.319 126.867 9.077 QT\n127.883 8.834 127.883 7.866 QT\n127.883 -16.275 L\n127.883 -17.509 127.508 -18.064 QT\n127.133 -18.619 126.437 -18.744 QT\n125.742 -18.869 124.289 -18.869 QT\n124.289 -20.478 L\n131.117 -20.978 L\n131.117 7.866 L\n131.117 8.834 132.125 9.077 QT\n133.133 9.319 134.679 9.319 QT\n134.679 10.944 L\n124.289 10.944 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 158.24938] CT\r\nN\r\n147.034 11.459 M\n144.268 11.459 141.909 10.053 QT\n139.549 8.647 138.182 6.288 QT\n136.815 3.928 136.815 1.147 QT\n136.815 -0.962 137.565 -2.916 QT\n138.315 -4.869 139.721 -6.408 QT\n141.127 -7.947 142.995 -8.814 QT\n144.862 -9.681 147.034 -9.681 QT\n149.862 -9.681 152.19 -8.181 QT\n154.518 -6.681 155.862 -4.181 QT\n157.206 -1.681 157.206 1.147 QT\n157.206 3.913 155.838 6.28 QT\n154.471 8.647 152.12 10.053 QT\n149.768 11.459 147.034 11.459 QT\ncp\n147.034 10.116 M\n150.721 10.116 151.956 7.444 QT\n153.19 4.772 153.19 0.631 QT\n153.19 -1.681 152.94 -3.197 QT\n152.69 -4.712 151.862 -5.947 QT\n151.346 -6.712 150.549 -7.283 QT\n149.752 -7.853 148.862 -8.158 QT\n147.971 -8.462 147.034 -8.462 QT\n145.596 -8.462 144.307 -7.814 QT\n143.018 -7.166 142.159 -5.947 QT\n141.299 -4.65 141.065 -3.087 QT\n140.831 -1.525 140.831 0.631 QT\n140.831 3.209 141.284 5.272 QT\n141.737 7.334 143.096 8.725 QT\n144.456 10.116 147.034 10.116 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 158.24938] CT\r\nN\r\n171.1 11.459 M\n168.335 11.459 165.975 10.053 QT\n163.616 8.647 162.249 6.288 QT\n160.882 3.928 160.882 1.147 QT\n160.882 -0.962 161.632 -2.916 QT\n162.382 -4.869 163.788 -6.408 QT\n165.194 -7.947 167.061 -8.814 QT\n168.929 -9.681 171.1 -9.681 QT\n173.929 -9.681 176.257 -8.181 QT\n178.585 -6.681 179.929 -4.181 QT\n181.272 -1.681 181.272 1.147 QT\n181.272 3.913 179.905 6.28 QT\n178.538 8.647 176.186 10.053 QT\n173.835 11.459 171.1 11.459 QT\ncp\n171.1 10.116 M\n174.788 10.116 176.022 7.444 QT\n177.257 4.772 177.257 0.631 QT\n177.257 -1.681 177.007 -3.197 QT\n176.757 -4.712 175.929 -5.947 QT\n175.413 -6.712 174.616 -7.283 QT\n173.819 -7.853 172.929 -8.158 QT\n172.038 -8.462 171.1 -8.462 QT\n169.663 -8.462 168.374 -7.814 QT\n167.085 -7.166 166.225 -5.947 QT\n165.366 -4.65 165.132 -3.087 QT\n164.897 -1.525 164.897 0.631 QT\n164.897 3.209 165.35 5.272 QT\n165.804 7.334 167.163 8.725 QT\n168.522 10.116 171.1 10.116 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 158.24938] CT\r\nN\r\n183.588 19.866 M\n183.588 18.272 L\n185.166 18.272 186.174 17.999 QT\n187.182 17.725 187.182 16.788 QT\n187.182 -5.384 L\n187.182 -6.65 186.283 -6.962 QT\n185.385 -7.275 183.588 -7.275 QT\n183.588 -8.884 L\n190.4 -9.384 L\n190.4 -6.525 L\n191.65 -7.931 193.322 -8.658 QT\n194.994 -9.384 196.885 -9.384 QT\n199.604 -9.384 201.783 -7.916 QT\n203.963 -6.447 205.19 -4.048 QT\n206.416 -1.65 206.416 1.022 QT\n206.416 3.803 205.057 6.202 QT\n203.697 8.6 201.346 10.03 QT\n198.994 11.459 196.197 11.459 QT\n192.838 11.459 190.525 8.741 QT\n190.525 16.788 L\n190.525 17.725 191.549 17.999 QT\n192.572 18.272 194.119 18.272 QT\n194.119 19.866 L\n183.588 19.866 L\ncp\n190.525 6.475 M\n191.338 8.116 192.775 9.178 QT\n194.213 10.241 195.916 10.241 QT\n197.51 10.241 198.736 9.389 QT\n199.963 8.538 200.799 7.1 QT\n201.635 5.663 202.025 4.077 QT\n202.416 2.491 202.416 1.022 QT\n202.416 -0.822 201.752 -2.97 QT\n201.088 -5.119 199.729 -6.587 QT\n198.369 -8.056 196.432 -8.056 QT\n194.572 -8.056 193.01 -7.103 QT\n191.447 -6.15 190.525 -4.509 QT\n190.525 6.475 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 158.24938] CT\r\nN\r\n237.2 22.35 M\n234.637 20.334 232.785 17.717 QT\n230.934 15.1 229.754 12.131 QT\n228.575 9.163 227.989 5.928 QT\n227.403 2.694 227.403 -0.556 QT\n227.403 -3.853 227.989 -7.087 QT\n228.575 -10.322 229.778 -13.314 QT\n230.981 -16.306 232.84 -18.908 QT\n234.7 -21.509 237.2 -23.462 QT\n237.2 -23.556 237.418 -23.556 QT\n237.856 -23.556 L\n237.981 -23.556 238.098 -23.431 QT\n238.215 -23.306 238.215 -23.15 QT\n238.215 -22.947 238.121 -22.853 QT\n235.871 -20.666 234.379 -18.15 QT\n232.887 -15.634 231.973 -12.791 QT\n231.059 -9.947 230.66 -6.9 QT\n230.262 -3.853 230.262 -0.556 QT\n230.262 14.069 238.075 21.663 QT\n238.215 21.788 238.215 22.038 QT\n238.215 22.147 238.09 22.295 QT\n237.965 22.444 237.856 22.444 QT\n237.418 22.444 L\n237.2 22.444 237.2 22.35 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 158.24938] CT\r\nN\r\n240.058 17.475 M\n240.058 16.35 240.831 15.538 QT\n241.605 14.725 242.73 14.725 QT\n243.48 14.725 243.98 15.178 QT\n244.48 15.631 244.48 16.381 QT\n244.48 17.256 243.933 17.967 QT\n243.386 18.678 242.558 18.897 QT\n243.37 19.194 244.167 19.194 QT\n246.12 19.194 247.558 17.381 QT\n248.995 15.569 249.589 13.319 QT\n253.917 -3.978 L\n254.23 -5.291 254.23 -6.212 QT\n254.23 -8.197 252.87 -8.197 QT\n250.839 -8.197 249.324 -6.361 QT\n247.808 -4.525 246.87 -2.134 QT\n246.777 -1.837 246.511 -1.837 QT\n245.964 -1.837 L\n245.589 -1.837 245.589 -2.259 QT\n245.589 -2.4 L\n246.62 -5.166 248.527 -7.275 QT\n250.433 -9.384 252.949 -9.384 QT\n254.87 -9.384 256.089 -8.197 QT\n257.308 -7.009 257.308 -5.166 QT\n257.308 -4.509 257.183 -3.853 QT\n252.824 13.616 L\n252.355 15.475 251.027 17.03 QT\n249.699 18.584 247.855 19.483 QT\n246.011 20.381 244.089 20.381 QT\n242.527 20.381 241.292 19.639 QT\n240.058 18.897 240.058 17.475 QT\ncp\n254.62 -16.931 M\n254.62 -17.947 255.402 -18.705 QT\n256.183 -19.462 257.183 -19.462 QT\n257.964 -19.462 258.472 -18.986 QT\n258.98 -18.509 258.98 -17.759 QT\n258.98 -16.728 258.159 -15.955 QT\n257.339 -15.181 256.339 -15.181 QT\n255.605 -15.181 255.113 -15.697 QT\n254.62 -16.212 254.62 -16.931 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 158.24938] CT\r\nN\r\n278.175 4.834 M\n277.8 4.834 277.55 4.545 QT\n277.3 4.256 277.3 3.913 QT\n277.3 3.538 277.55 3.264 QT\n277.8 2.991 278.175 2.991 QT\n307.066 2.991 L\n307.41 2.991 307.652 3.264 QT\n307.894 3.538 307.894 3.913 QT\n307.894 4.256 307.652 4.545 QT\n307.41 4.834 307.066 4.834 QT\n278.175 4.834 L\ncp\n278.175 -4.103 M\n277.8 -4.103 277.55 -4.376 QT\n277.3 -4.65 277.3 -5.025 QT\n277.3 -5.369 277.55 -5.658 QT\n277.8 -5.947 278.175 -5.947 QT\n307.066 -5.947 L\n307.41 -5.947 307.652 -5.658 QT\n307.894 -5.369 307.894 -5.025 QT\n307.894 -4.65 307.652 -4.376 QT\n307.41 -4.103 307.066 -4.103 QT\n278.175 -4.103 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 158.24938] CT\r\nN\r\n327.121 10.944 M\n327.121 9.319 L\n332.871 9.319 332.871 7.866 QT\n332.871 -16.275 L\n330.496 -15.134 326.855 -15.134 QT\n326.855 -16.744 L\n332.496 -16.744 335.371 -19.697 QT\n336.012 -19.697 L\n336.168 -19.697 336.316 -19.572 QT\n336.465 -19.447 336.465 -19.291 QT\n336.465 7.866 L\n336.465 9.319 342.215 9.319 QT\n342.215 10.944 L\n327.121 10.944 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 158.24938] CT\r\nN\r\n348.64 22.444 M\n348.234 22.444 348.234 22.038 QT\n348.234 21.834 348.327 21.741 QT\n356.187 14.069 356.187 -0.556 QT\n356.187 -15.181 348.421 -22.775 QT\n348.234 -22.884 348.234 -23.15 QT\n348.234 -23.306 348.359 -23.431 QT\n348.484 -23.556 348.64 -23.556 QT\n349.077 -23.556 L\n349.202 -23.556 349.296 -23.462 QT\n352.593 -20.869 354.796 -17.134 QT\n356.999 -13.4 358.023 -9.181 QT\n359.046 -4.962 359.046 -0.556 QT\n359.046 2.694 358.491 5.85 QT\n357.937 9.006 356.741 12.077 QT\n355.546 15.147 353.702 17.741 QT\n351.859 20.334 349.296 22.35 QT\n349.202 22.444 349.077 22.444 QT\n348.64 22.444 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 1 1 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n507.004 421.998 M\n587.042 421.998 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 179.1248] CT\r\nN\r\n/f-610650052{17.906 11.959 M\n13.516 11.959 10.023 9.631 QT\n6.531 7.303 4.555 3.452 QT\n2.578 -0.4 2.578 -4.65 QT\n2.578 -7.791 3.719 -10.869 QT\n4.859 -13.947 6.891 -16.33 QT\n8.922 -18.712 11.773 -20.103 QT\n14.625 -21.494 17.906 -21.494 QT\n21.156 -21.494 24.023 -20.087 QT\n26.891 -18.681 28.93 -16.275 QT\n30.969 -13.869 32.07 -10.884 QT\n33.172 -7.9 33.172 -4.65 QT\n33.172 -0.4 31.195 3.452 QT\n29.219 7.303 25.719 9.631 QT\n22.219 11.959 17.906 11.959 QT\ncp\n10.266 5.975 M\n11.609 8.084 13.586 9.334 QT\n15.563 10.584 17.906 10.584 QT\n19.406 10.584 20.852 9.975 QT\n22.297 9.366 23.477 8.311 QT\n24.656 7.256 25.5 5.975 QT\n28.234 1.85 28.234 -5.384 QT\n28.234 -12.009 25.5 -15.869 QT\n24.141 -17.806 22.133 -18.978 QT\n20.125 -20.15 17.906 -20.15 QT\n15.656 -20.15 13.633 -18.978 QT\n11.609 -17.806 10.266 -15.869 QT\n9.188 -14.369 8.594 -12.673 QT\n8 -10.978 7.75 -9.158 QT\n7.5 -7.337 7.5 -5.384 QT\n7.5 -3.291 7.734 -1.306 QT\n7.969 0.678 8.609 2.584 QT\n9.25 4.491 10.266 5.975 QT\ncp}def\r\nf-610650052\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 179.1248] CT\r\nN\r\n/f-1720655246{36.654 19.866 M\n36.654 18.272 L\n38.232 18.272 39.24 17.999 QT\n40.248 17.725 40.248 16.788 QT\n40.248 -5.384 L\n40.248 -6.65 39.35 -6.962 QT\n38.451 -7.275 36.654 -7.275 QT\n36.654 -8.884 L\n43.467 -9.384 L\n43.467 -6.525 L\n44.717 -7.931 46.389 -8.658 QT\n48.061 -9.384 49.951 -9.384 QT\n52.67 -9.384 54.85 -7.916 QT\n57.029 -6.447 58.256 -4.048 QT\n59.482 -1.65 59.482 1.022 QT\n59.482 3.803 58.123 6.202 QT\n56.764 8.6 54.412 10.03 QT\n52.061 11.459 49.264 11.459 QT\n45.904 11.459 43.592 8.741 QT\n43.592 16.788 L\n43.592 17.725 44.615 17.999 QT\n45.639 18.272 47.186 18.272 QT\n47.186 19.866 L\n36.654 19.866 L\ncp\n43.592 6.475 M\n44.404 8.116 45.842 9.178 QT\n47.279 10.241 48.982 10.241 QT\n50.576 10.241 51.803 9.389 QT\n53.029 8.538 53.865 7.1 QT\n54.701 5.663 55.092 4.077 QT\n55.482 2.491 55.482 1.022 QT\n55.482 -0.822 54.818 -2.97 QT\n54.154 -5.119 52.795 -6.587 QT\n51.436 -8.056 49.498 -8.056 QT\n47.639 -8.056 46.076 -7.103 QT\n44.514 -6.15 43.592 -4.509 QT\n43.592 6.475 L\ncp}def\r\nf-1720655246\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 179.1248] CT\r\nN\r\n/f-1742318283{73.52 11.459 M\n70.708 11.459 68.364 9.991 QT\n66.02 8.522 64.684 6.061 QT\n63.348 3.6 63.348 0.866 QT\n63.348 -1.837 64.575 -4.259 QT\n65.801 -6.681 67.989 -8.181 QT\n70.176 -9.681 72.864 -9.681 QT\n74.989 -9.681 76.543 -8.97 QT\n78.098 -8.259 79.114 -7.001 QT\n80.129 -5.744 80.645 -4.041 QT\n81.161 -2.337 81.161 -0.291 QT\n81.161 0.319 80.692 0.319 QT\n67.364 0.319 L\n67.364 0.819 L\n67.364 4.631 68.903 7.374 QT\n70.442 10.116 73.926 10.116 QT\n75.348 10.116 76.543 9.483 QT\n77.739 8.85 78.629 7.733 QT\n79.52 6.616 79.833 5.334 QT\n79.879 5.178 80.004 5.053 QT\n80.129 4.928 80.286 4.928 QT\n80.692 4.928 L\n81.161 4.928 81.161 5.506 QT\n80.504 8.116 78.348 9.788 QT\n76.192 11.459 73.52 11.459 QT\ncp\n67.411 -0.822 M\n77.895 -0.822 L\n77.895 -2.556 77.418 -4.33 QT\n76.942 -6.103 75.817 -7.283 QT\n74.692 -8.462 72.864 -8.462 QT\n70.27 -8.462 68.84 -6.025 QT\n67.411 -3.587 67.411 -0.822 QT\ncp}def\r\nf-1742318283\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 179.1248] CT\r\nN\r\n/f-1076963521{83.709 10.944 M\n83.709 9.319 L\n85.271 9.319 86.287 9.077 QT\n87.302 8.834 87.302 7.866 QT\n87.302 -4.697 L\n87.302 -5.931 86.927 -6.478 QT\n86.552 -7.025 85.857 -7.15 QT\n85.162 -7.275 83.709 -7.275 QT\n83.709 -8.884 L\n90.38 -9.384 L\n90.38 -4.884 L\n91.302 -6.869 93.107 -8.126 QT\n94.912 -9.384 97.052 -9.384 QT\n100.24 -9.384 101.841 -7.853 QT\n103.443 -6.322 103.443 -3.181 QT\n103.443 7.866 L\n103.443 8.834 104.459 9.077 QT\n105.474 9.319 107.037 9.319 QT\n107.037 10.944 L\n96.505 10.944 L\n96.505 9.319 L\n98.084 9.319 99.091 9.077 QT\n100.099 8.834 100.099 7.866 QT\n100.099 -3.056 L\n100.099 -5.291 99.451 -6.744 QT\n98.802 -8.197 96.771 -8.197 QT\n94.099 -8.197 92.38 -6.064 QT\n90.662 -3.931 90.662 -1.212 QT\n90.662 7.866 L\n90.662 8.834 91.677 9.077 QT\n92.693 9.319 94.24 9.319 QT\n94.24 10.944 L\n83.709 10.944 L\ncp}def\r\nf-1076963521\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 179.1248] CT\r\nN\r\n/f-11361369{108.183 2.428 M\n108.183 -0.416 L\n120.354 -0.416 L\n120.354 2.428 L\n108.183 2.428 L\ncp}def\r\nf-11361369\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 179.1248] CT\r\nN\r\n/f339891938{124.289 10.944 M\n124.289 9.319 L\n125.851 9.319 126.867 9.077 QT\n127.883 8.834 127.883 7.866 QT\n127.883 -16.275 L\n127.883 -17.509 127.508 -18.064 QT\n127.133 -18.619 126.437 -18.744 QT\n125.742 -18.869 124.289 -18.869 QT\n124.289 -20.478 L\n131.117 -20.978 L\n131.117 7.866 L\n131.117 8.834 132.125 9.077 QT\n133.133 9.319 134.679 9.319 QT\n134.679 10.944 L\n124.289 10.944 L\ncp}def\r\nf339891938\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 179.1248] CT\r\nN\r\n/f-2132429885{147.034 11.459 M\n144.268 11.459 141.909 10.053 QT\n139.549 8.647 138.182 6.288 QT\n136.815 3.928 136.815 1.147 QT\n136.815 -0.962 137.565 -2.916 QT\n138.315 -4.869 139.721 -6.408 QT\n141.127 -7.947 142.995 -8.814 QT\n144.862 -9.681 147.034 -9.681 QT\n149.862 -9.681 152.19 -8.181 QT\n154.518 -6.681 155.862 -4.181 QT\n157.206 -1.681 157.206 1.147 QT\n157.206 3.913 155.838 6.28 QT\n154.471 8.647 152.12 10.053 QT\n149.768 11.459 147.034 11.459 QT\ncp\n147.034 10.116 M\n150.721 10.116 151.956 7.444 QT\n153.19 4.772 153.19 0.631 QT\n153.19 -1.681 152.94 -3.197 QT\n152.69 -4.712 151.862 -5.947 QT\n151.346 -6.712 150.549 -7.283 QT\n149.752 -7.853 148.862 -8.158 QT\n147.971 -8.462 147.034 -8.462 QT\n145.596 -8.462 144.307 -7.814 QT\n143.018 -7.166 142.159 -5.947 QT\n141.299 -4.65 141.065 -3.087 QT\n140.831 -1.525 140.831 0.631 QT\n140.831 3.209 141.284 5.272 QT\n141.737 7.334 143.096 8.725 QT\n144.456 10.116 147.034 10.116 QT\ncp}def\r\nf-2132429885\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 179.1248] CT\r\nN\r\n/f1863324703{171.1 11.459 M\n168.335 11.459 165.975 10.053 QT\n163.616 8.647 162.249 6.288 QT\n160.882 3.928 160.882 1.147 QT\n160.882 -0.962 161.632 -2.916 QT\n162.382 -4.869 163.788 -6.408 QT\n165.194 -7.947 167.061 -8.814 QT\n168.929 -9.681 171.1 -9.681 QT\n173.929 -9.681 176.257 -8.181 QT\n178.585 -6.681 179.929 -4.181 QT\n181.272 -1.681 181.272 1.147 QT\n181.272 3.913 179.905 6.28 QT\n178.538 8.647 176.186 10.053 QT\n173.835 11.459 171.1 11.459 QT\ncp\n171.1 10.116 M\n174.788 10.116 176.022 7.444 QT\n177.257 4.772 177.257 0.631 QT\n177.257 -1.681 177.007 -3.197 QT\n176.757 -4.712 175.929 -5.947 QT\n175.413 -6.712 174.616 -7.283 QT\n173.819 -7.853 172.929 -8.158 QT\n172.038 -8.462 171.1 -8.462 QT\n169.663 -8.462 168.374 -7.814 QT\n167.085 -7.166 166.225 -5.947 QT\n165.366 -4.65 165.132 -3.087 QT\n164.897 -1.525 164.897 0.631 QT\n164.897 3.209 165.35 5.272 QT\n165.804 7.334 167.163 8.725 QT\n168.522 10.116 171.1 10.116 QT\ncp}def\r\nf1863324703\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 179.1248] CT\r\nN\r\n/f381148119{183.588 19.866 M\n183.588 18.272 L\n185.166 18.272 186.174 17.999 QT\n187.182 17.725 187.182 16.788 QT\n187.182 -5.384 L\n187.182 -6.65 186.283 -6.962 QT\n185.385 -7.275 183.588 -7.275 QT\n183.588 -8.884 L\n190.4 -9.384 L\n190.4 -6.525 L\n191.65 -7.931 193.322 -8.658 QT\n194.994 -9.384 196.885 -9.384 QT\n199.604 -9.384 201.783 -7.916 QT\n203.963 -6.447 205.19 -4.048 QT\n206.416 -1.65 206.416 1.022 QT\n206.416 3.803 205.057 6.202 QT\n203.697 8.6 201.346 10.03 QT\n198.994 11.459 196.197 11.459 QT\n192.838 11.459 190.525 8.741 QT\n190.525 16.788 L\n190.525 17.725 191.549 17.999 QT\n192.572 18.272 194.119 18.272 QT\n194.119 19.866 L\n183.588 19.866 L\ncp\n190.525 6.475 M\n191.338 8.116 192.775 9.178 QT\n194.213 10.241 195.916 10.241 QT\n197.51 10.241 198.736 9.389 QT\n199.963 8.538 200.799 7.1 QT\n201.635 5.663 202.025 4.077 QT\n202.416 2.491 202.416 1.022 QT\n202.416 -0.822 201.752 -2.97 QT\n201.088 -5.119 199.729 -6.587 QT\n198.369 -8.056 196.432 -8.056 QT\n194.572 -8.056 193.01 -7.103 QT\n191.447 -6.15 190.525 -4.509 QT\n190.525 6.475 L\ncp}def\r\nf381148119\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 179.1248] CT\r\nN\r\n/f350766748{237.2 22.35 M\n234.637 20.334 232.785 17.717 QT\n230.934 15.1 229.754 12.131 QT\n228.575 9.163 227.989 5.928 QT\n227.403 2.694 227.403 -0.556 QT\n227.403 -3.853 227.989 -7.087 QT\n228.575 -10.322 229.778 -13.314 QT\n230.981 -16.306 232.84 -18.908 QT\n234.7 -21.509 237.2 -23.462 QT\n237.2 -23.556 237.418 -23.556 QT\n237.856 -23.556 L\n237.981 -23.556 238.098 -23.431 QT\n238.215 -23.306 238.215 -23.15 QT\n238.215 -22.947 238.121 -22.853 QT\n235.871 -20.666 234.379 -18.15 QT\n232.887 -15.634 231.973 -12.791 QT\n231.059 -9.947 230.66 -6.9 QT\n230.262 -3.853 230.262 -0.556 QT\n230.262 14.069 238.075 21.663 QT\n238.215 21.788 238.215 22.038 QT\n238.215 22.147 238.09 22.295 QT\n237.965 22.444 237.856 22.444 QT\n237.418 22.444 L\n237.2 22.444 237.2 22.35 QT\ncp}def\r\nf350766748\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 179.1248] CT\r\nN\r\n/f1959131010{240.058 17.475 M\n240.058 16.35 240.831 15.538 QT\n241.605 14.725 242.73 14.725 QT\n243.48 14.725 243.98 15.178 QT\n244.48 15.631 244.48 16.381 QT\n244.48 17.256 243.933 17.967 QT\n243.386 18.678 242.558 18.897 QT\n243.37 19.194 244.167 19.194 QT\n246.12 19.194 247.558 17.381 QT\n248.995 15.569 249.589 13.319 QT\n253.917 -3.978 L\n254.23 -5.291 254.23 -6.212 QT\n254.23 -8.197 252.87 -8.197 QT\n250.839 -8.197 249.324 -6.361 QT\n247.808 -4.525 246.87 -2.134 QT\n246.777 -1.837 246.511 -1.837 QT\n245.964 -1.837 L\n245.589 -1.837 245.589 -2.259 QT\n245.589 -2.4 L\n246.62 -5.166 248.527 -7.275 QT\n250.433 -9.384 252.949 -9.384 QT\n254.87 -9.384 256.089 -8.197 QT\n257.308 -7.009 257.308 -5.166 QT\n257.308 -4.509 257.183 -3.853 QT\n252.824 13.616 L\n252.355 15.475 251.027 17.03 QT\n249.699 18.584 247.855 19.483 QT\n246.011 20.381 244.089 20.381 QT\n242.527 20.381 241.292 19.639 QT\n240.058 18.897 240.058 17.475 QT\ncp\n254.62 -16.931 M\n254.62 -17.947 255.402 -18.705 QT\n256.183 -19.462 257.183 -19.462 QT\n257.964 -19.462 258.472 -18.986 QT\n258.98 -18.509 258.98 -17.759 QT\n258.98 -16.728 258.159 -15.955 QT\n257.339 -15.181 256.339 -15.181 QT\n255.605 -15.181 255.113 -15.697 QT\n254.62 -16.212 254.62 -16.931 QT\ncp}def\r\nf1959131010\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 179.1248] CT\r\nN\r\n/f1819598228{278.175 4.834 M\n277.8 4.834 277.55 4.545 QT\n277.3 4.256 277.3 3.913 QT\n277.3 3.538 277.55 3.264 QT\n277.8 2.991 278.175 2.991 QT\n307.066 2.991 L\n307.41 2.991 307.652 3.264 QT\n307.894 3.538 307.894 3.913 QT\n307.894 4.256 307.652 4.545 QT\n307.41 4.834 307.066 4.834 QT\n278.175 4.834 L\ncp\n278.175 -4.103 M\n277.8 -4.103 277.55 -4.376 QT\n277.3 -4.65 277.3 -5.025 QT\n277.3 -5.369 277.55 -5.658 QT\n277.8 -5.947 278.175 -5.947 QT\n307.066 -5.947 L\n307.41 -5.947 307.652 -5.658 QT\n307.894 -5.369 307.894 -5.025 QT\n307.894 -4.65 307.652 -4.376 QT\n307.41 -4.103 307.066 -4.103 QT\n278.175 -4.103 L\ncp}def\r\nf1819598228\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 179.1248] CT\r\nN\r\n/f511004193{327.23 7.397 M\n328.309 8.959 330.129 9.725 QT\n331.949 10.491 334.043 10.491 QT\n336.715 10.491 337.84 8.209 QT\n338.965 5.928 338.965 3.038 QT\n338.965 1.741 338.73 0.436 QT\n338.496 -0.869 337.934 -1.994 QT\n337.371 -3.119 336.394 -3.791 QT\n335.418 -4.462 333.996 -4.462 QT\n330.949 -4.462 L\n330.543 -4.462 330.543 -4.884 QT\n330.543 -5.291 L\n330.543 -5.65 330.949 -5.65 QT\n333.48 -5.853 L\n335.09 -5.853 336.16 -7.072 QT\n337.23 -8.291 337.723 -10.025 QT\n338.215 -11.759 338.215 -13.337 QT\n338.215 -15.541 337.184 -16.955 QT\n336.152 -18.369 334.043 -18.369 QT\n332.293 -18.369 330.699 -17.705 QT\n329.105 -17.041 328.152 -15.697 QT\n328.246 -15.712 328.316 -15.728 QT\n328.387 -15.744 328.465 -15.744 QT\n329.512 -15.744 330.207 -15.025 QT\n330.902 -14.306 330.902 -13.291 QT\n330.902 -12.306 330.207 -11.587 QT\n329.512 -10.869 328.465 -10.869 QT\n327.465 -10.869 326.746 -11.587 QT\n326.027 -12.306 326.027 -13.291 QT\n326.027 -15.275 327.215 -16.728 QT\n328.402 -18.181 330.277 -18.939 QT\n332.152 -19.697 334.043 -19.697 QT\n335.434 -19.697 336.98 -19.283 QT\n338.527 -18.869 339.785 -18.087 QT\n341.043 -17.306 341.84 -16.095 QT\n342.637 -14.884 342.637 -13.337 QT\n342.637 -11.4 341.777 -9.759 QT\n340.918 -8.119 339.41 -6.931 QT\n337.902 -5.744 336.105 -5.166 QT\n338.105 -4.775 339.902 -3.658 QT\n341.699 -2.541 342.793 -0.783 QT\n343.887 0.975 343.887 2.991 QT\n343.887 5.538 342.488 7.592 QT\n341.09 9.647 338.824 10.803 QT\n336.559 11.959 334.043 11.959 QT\n331.887 11.959 329.715 11.139 QT\n327.543 10.319 326.168 8.678 QT\n324.793 7.038 324.793 4.741 QT\n324.793 3.6 325.551 2.834 QT\n326.309 2.069 327.465 2.069 QT\n328.199 2.069 328.816 2.42 QT\n329.434 2.772 329.785 3.397 QT\n330.137 4.022 330.137 4.741 QT\n330.137 5.866 329.348 6.631 QT\n328.559 7.397 327.465 7.397 QT\n327.23 7.397 L\ncp}def\r\nf511004193\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 179.1248] CT\r\nN\r\n/f-1239821374{348.64 22.444 M\n348.234 22.444 348.234 22.038 QT\n348.234 21.834 348.327 21.741 QT\n356.187 14.069 356.187 -0.556 QT\n356.187 -15.181 348.421 -22.775 QT\n348.234 -22.884 348.234 -23.15 QT\n348.234 -23.306 348.359 -23.431 QT\n348.484 -23.556 348.64 -23.556 QT\n349.077 -23.556 L\n349.202 -23.556 349.296 -23.462 QT\n352.593 -20.869 354.796 -17.134 QT\n356.999 -13.4 358.023 -9.181 QT\n359.046 -4.962 359.046 -0.556 QT\n359.046 2.694 358.491 5.85 QT\n357.937 9.006 356.741 12.077 QT\n355.546 15.147 353.702 17.741 QT\n351.859 20.334 349.296 22.35 QT\n349.202 22.444 349.077 22.444 QT\n348.64 22.444 L\ncp}def\r\nf-1239821374\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 1 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n507.004 477.666 M\n587.042 477.666 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 200.0002] CT\r\nN\r\nf-610650052\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 200.0002] CT\r\nN\r\nf-1720655246\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 200.0002] CT\r\nN\r\nf-1742318283\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 200.0002] CT\r\nN\r\nf-1076963521\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 200.0002] CT\r\nN\r\nf-11361369\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 200.0002] CT\r\nN\r\nf339891938\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 200.0002] CT\r\nN\r\nf-2132429885\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 200.0002] CT\r\nN\r\nf1863324703\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 200.0002] CT\r\nN\r\nf381148119\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 200.0002] CT\r\nN\r\nf350766748\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 200.0002] CT\r\nN\r\nf1959131010\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 200.0002] CT\r\nN\r\nf1819598228\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 200.0002] CT\r\nN\r\n/f-1453073065{326.855 5.709 M\n327.324 7.053 328.301 8.155 QT\n329.277 9.256 330.613 9.874 QT\n331.949 10.491 333.387 10.491 QT\n336.715 10.491 337.973 7.913 QT\n339.23 5.334 339.23 1.647 QT\n339.23 0.053 339.176 -1.041 QT\n339.121 -2.134 338.871 -3.134 QT\n338.449 -4.759 337.379 -5.97 QT\n336.309 -7.181 334.762 -7.181 QT\n333.215 -7.181 332.098 -6.712 QT\n330.98 -6.244 330.285 -5.611 QT\n329.59 -4.978 329.051 -4.283 QT\n328.512 -3.587 328.387 -3.541 QT\n327.871 -3.541 L\n327.746 -3.541 327.582 -3.689 QT\n327.418 -3.837 327.418 -3.978 QT\n327.418 -19.337 L\n327.418 -19.447 327.566 -19.572 QT\n327.715 -19.697 327.871 -19.697 QT\n327.996 -19.697 L\n331.105 -18.212 334.574 -18.212 QT\n337.996 -18.212 341.168 -19.697 QT\n341.293 -19.697 L\n341.449 -19.697 341.59 -19.58 QT\n341.73 -19.462 341.73 -19.337 QT\n341.73 -18.9 L\n341.73 -18.681 341.637 -18.681 QT\n340.059 -16.587 337.691 -15.423 QT\n335.324 -14.259 332.777 -14.259 QT\n330.949 -14.259 329.012 -14.775 QT\n329.012 -6.087 L\n330.543 -7.322 331.738 -7.845 QT\n332.934 -8.369 334.809 -8.369 QT\n337.34 -8.369 339.355 -6.908 QT\n341.371 -5.447 342.449 -3.103 QT\n343.527 -0.759 343.527 1.694 QT\n343.527 4.459 342.168 6.811 QT\n340.809 9.163 338.473 10.561 QT\n336.137 11.959 333.387 11.959 QT\n331.121 11.959 329.223 10.788 QT\n327.324 9.616 326.238 7.639 QT\n325.152 5.663 325.152 3.444 QT\n325.152 2.413 325.824 1.756 QT\n326.496 1.1 327.512 1.1 QT\n328.512 1.1 329.199 1.764 QT\n329.887 2.428 329.887 3.444 QT\n329.887 4.428 329.199 5.116 QT\n328.512 5.803 327.512 5.803 QT\n327.355 5.803 327.152 5.764 QT\n326.949 5.725 326.855 5.709 QT\ncp}def\r\nf-1453073065\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 200.0002] CT\r\nN\r\nf-1239821374\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 1 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n507.004 533.334 M\n587.042 533.334 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 220.87562] CT\r\nN\r\nf-610650052\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 220.87562] CT\r\nN\r\nf-1720655246\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 220.87562] CT\r\nN\r\nf-1742318283\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 220.87562] CT\r\nN\r\nf-1076963521\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 220.87562] CT\r\nN\r\nf-11361369\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 220.87562] CT\r\nN\r\nf339891938\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 220.87562] CT\r\nN\r\nf-2132429885\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 220.87562] CT\r\nN\r\nf1863324703\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 220.87562] CT\r\nN\r\nf381148119\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 220.87562] CT\r\nN\r\nf350766748\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 220.87562] CT\r\nN\r\nf1959131010\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 220.87562] CT\r\nN\r\nf1819598228\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 220.87562] CT\r\nN\r\n/f345066735{327.121 10.944 M\n327.121 9.319 L\n332.871 9.319 332.871 7.866 QT\n332.871 -16.275 L\n330.496 -15.134 326.855 -15.134 QT\n326.855 -16.744 L\n332.496 -16.744 335.371 -19.697 QT\n336.012 -19.697 L\n336.168 -19.697 336.316 -19.572 QT\n336.465 -19.447 336.465 -19.291 QT\n336.465 7.866 L\n336.465 9.319 342.215 9.319 QT\n342.215 10.944 L\n327.121 10.944 L\ncp}def\r\nf345066735\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 220.87562] CT\r\nN\r\n/f1539953465{357.155 11.959 M\n351.515 11.959 349.484 7.319 QT\n347.452 2.678 347.452 -3.728 QT\n347.452 -7.728 348.179 -11.251 QT\n348.905 -14.775 351.077 -17.236 QT\n353.249 -19.697 357.155 -19.697 QT\n360.187 -19.697 362.116 -18.212 QT\n364.046 -16.728 365.062 -14.384 QT\n366.077 -12.041 366.445 -9.353 QT\n366.812 -6.666 366.812 -3.728 QT\n366.812 0.225 366.085 3.678 QT\n365.359 7.131 363.226 9.545 QT\n361.093 11.959 357.155 11.959 QT\ncp\n357.155 10.756 M\n359.718 10.756 360.976 8.131 QT\n362.234 5.506 362.523 2.319 QT\n362.812 -0.869 362.812 -4.462 QT\n362.812 -7.931 362.523 -10.845 QT\n362.234 -13.759 360.984 -16.134 QT\n359.734 -18.509 357.155 -18.509 QT\n354.546 -18.509 353.288 -16.126 QT\n352.03 -13.744 351.741 -10.837 QT\n351.452 -7.931 351.452 -4.462 QT\n351.452 -1.9 351.577 0.366 QT\n351.702 2.631 352.241 5.045 QT\n352.78 7.459 353.984 9.108 QT\n355.187 10.756 357.155 10.756 QT\ncp}def\r\nf1539953465\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 220.87562] CT\r\nN\r\n/f-878458323{371.44 22.444 M\n371.034 22.444 371.034 22.038 QT\n371.034 21.834 371.127 21.741 QT\n378.987 14.069 378.987 -0.556 QT\n378.987 -15.181 371.221 -22.775 QT\n371.034 -22.884 371.034 -23.15 QT\n371.034 -23.306 371.159 -23.431 QT\n371.284 -23.556 371.44 -23.556 QT\n371.877 -23.556 L\n372.002 -23.556 372.096 -23.462 QT\n375.393 -20.869 377.596 -17.134 QT\n379.799 -13.4 380.823 -9.181 QT\n381.846 -4.962 381.846 -0.556 QT\n381.846 2.694 381.292 5.85 QT\n380.737 9.006 379.542 12.077 QT\n378.346 15.147 376.502 17.741 QT\n374.659 20.334 372.096 22.35 QT\n372.002 22.444 371.877 22.444 QT\n371.44 22.444 L\ncp}def\r\nf-878458323\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n507.004 589.002 M\n587.042 589.002 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 241.75101] CT\r\nN\r\nf-610650052\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 241.75101] CT\r\nN\r\nf-1720655246\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 241.75101] CT\r\nN\r\nf-1742318283\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 241.75101] CT\r\nN\r\nf-1076963521\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 241.75101] CT\r\nN\r\nf-11361369\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 241.75101] CT\r\nN\r\nf339891938\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 241.75101] CT\r\nN\r\nf-2132429885\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 241.75101] CT\r\nN\r\nf1863324703\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 241.75101] CT\r\nN\r\nf381148119\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 241.75101] CT\r\nN\r\nf350766748\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 241.75101] CT\r\nN\r\nf1959131010\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 241.75101] CT\r\nN\r\nf1819598228\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 241.75101] CT\r\nN\r\nf511004193\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 241.75101] CT\r\nN\r\n/f-25623620{347.952 10.944 M\n347.952 9.709 L\n347.952 9.6 348.03 9.459 QT\n355.187 1.553 L\n356.796 -0.197 357.804 -1.384 QT\n358.812 -2.572 359.804 -4.126 QT\n360.796 -5.681 361.366 -7.283 QT\n361.937 -8.884 361.937 -10.681 QT\n361.937 -12.572 361.241 -14.291 QT\n360.546 -16.009 359.163 -17.041 QT\n357.78 -18.072 355.827 -18.072 QT\n353.827 -18.072 352.234 -16.869 QT\n350.64 -15.666 349.984 -13.759 QT\n350.171 -13.806 350.484 -13.806 QT\n351.515 -13.806 352.249 -13.111 QT\n352.984 -12.416 352.984 -11.322 QT\n352.984 -10.259 352.249 -9.533 QT\n351.515 -8.806 350.484 -8.806 QT\n349.405 -8.806 348.679 -9.556 QT\n347.952 -10.306 347.952 -11.322 QT\n347.952 -13.041 348.601 -14.556 QT\n349.249 -16.072 350.476 -17.251 QT\n351.702 -18.431 353.241 -19.064 QT\n354.78 -19.697 356.499 -19.697 QT\n359.14 -19.697 361.405 -18.58 QT\n363.671 -17.462 364.999 -15.431 QT\n366.327 -13.4 366.327 -10.681 QT\n366.327 -8.681 365.445 -6.884 QT\n364.562 -5.087 363.195 -3.619 QT\n361.827 -2.15 359.695 -0.283 QT\n357.562 1.584 356.89 2.209 QT\n351.671 7.209 L\n356.093 7.209 L\n359.359 7.209 361.546 7.155 QT\n363.734 7.1 363.874 6.991 QT\n364.405 6.413 364.968 2.741 QT\n366.327 2.741 L\n365.015 10.944 L\n347.952 10.944 L\ncp}def\r\nf-25623620\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.39173 241.75101] CT\r\nN\r\nf-878458323\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n507.004 644.669 M\n587.042 644.669 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n10.0 ML\r\n0.533 LW\r\nN\r\n499 676 M\n499 335 L\n1080 335 L\n1080 676 L\ncp\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n235.2 252 M\n235.2 318.667 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n245.2 309.333 M\n235.2 336 L\n235.2 318.667 L\n245.2 309.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n235.2 336 M\n225.2 309.333 L\n235.2 318.667 L\n235.2 336 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\nN\r\n235.2 336 M\n245.2 309.333 L\n235.2 318.667 L\n225.2 309.333 L\ncp\r\nf\r\nGR\r\n%%Trailer\r\n%%Pages: 1\r\n%%EOF\r\n"
  },
  {
    "path": "matlab/acc2023/closedloop_performance/figures/state-converge-1.eps",
    "content": "%!PS-Adobe-3.0 EPSF-3.0\r\n%%Creator: (MATLAB, The Mathworks, Inc. Version 9.10.0.1649659 \\(R2021a\\) Update 1. Operating System: Windows 10)\r\n%%Title: figures/state-converge-1.eps\r\n%%CreationDate: 2023-01-31T03:12:01\r\n%%Pages: (atend)\r\n%%BoundingBox:     7     6   382   298\r\n%%LanguageLevel: 3\r\n%%EndComments\r\n%%BeginProlog\r\n%%BeginResource: procset (Apache XML Graphics Std ProcSet) 1.2 0\r\n%%Version: 1.2 0\r\n%%Copyright: (Copyright 2001-2003,2010 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/bd{bind def}bind def\r\n/ld{load def}bd\r\n/GR/grestore ld\r\n/GS/gsave ld\r\n/RM/rmoveto ld\r\n/C/curveto ld\r\n/t/show ld\r\n/L/lineto ld\r\n/ML/setmiterlimit ld\r\n/CT/concat ld\r\n/f/fill ld\r\n/N/newpath ld\r\n/S/stroke ld\r\n/CC/setcmykcolor ld\r\n/A/ashow ld\r\n/cp/closepath ld\r\n/RC/setrgbcolor ld\r\n/LJ/setlinejoin ld\r\n/GC/setgray ld\r\n/LW/setlinewidth ld\r\n/M/moveto ld\r\n/re {4 2 roll M\r\n1 index 0 rlineto\r\n0 exch rlineto\r\nneg 0 rlineto\r\ncp } bd\r\n/_ctm matrix def\r\n/_tm matrix def\r\n/BT { _ctm currentmatrix pop matrix _tm copy pop 0 0 moveto } bd\r\n/ET { _ctm setmatrix } bd\r\n/iTm { _ctm setmatrix _tm concat } bd\r\n/Tm { _tm astore pop iTm 0 0 moveto } bd\r\n/ux 0.0 def\r\n/uy 0.0 def\r\n/F {\r\n  /Tp exch def\r\n  /Tf exch def\r\n  Tf findfont Tp scalefont setfont\r\n  /cf Tf def  /cs Tp def\r\n} bd\r\n/ULS {currentpoint /uy exch def /ux exch def} bd\r\n/ULE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add moveto  Tcx uy To add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/OLE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs add moveto Tcx uy To add cs add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/SOE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs 10 mul 26 idiv add moveto Tcx uy To add cs 10 mul 26 idiv add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/QT {\r\n/Y22 exch store\r\n/X22 exch store\r\n/Y21 exch store\r\n/X21 exch store\r\ncurrentpoint\r\n/Y21 load 2 mul add 3 div exch\r\n/X21 load 2 mul add 3 div exch\r\n/X21 load 2 mul /X22 load add 3 div\r\n/Y21 load 2 mul /Y22 load add 3 div\r\n/X22 load /Y22 load curveto\r\n} bd\r\n/SSPD {\r\ndup length /d exch dict def\r\n{\r\n/v exch def\r\n/k exch def\r\ncurrentpagedevice k known {\r\n/cpdv currentpagedevice k get def\r\nv cpdv ne {\r\n/upd false def\r\n/nullv v type /nulltype eq def\r\n/nullcpdv cpdv type /nulltype eq def\r\nnullv nullcpdv or\r\n{\r\n/upd true def\r\n} {\r\n/sametype v type cpdv type eq def\r\nsametype {\r\nv type /arraytype eq {\r\n/vlen v length def\r\n/cpdvlen cpdv length def\r\nvlen cpdvlen eq {\r\n0 1 vlen 1 sub {\r\n/i exch def\r\n/obj v i get def\r\n/cpdobj cpdv i get def\r\nobj cpdobj ne {\r\n/upd true def\r\nexit\r\n} if\r\n} for\r\n} {\r\n/upd true def\r\n} ifelse\r\n} {\r\nv type /dicttype eq {\r\nv {\r\n/dv exch def\r\n/dk exch def\r\n/cpddv cpdv dk get def\r\ndv cpddv ne {\r\n/upd true def\r\nexit\r\n} if\r\n} forall\r\n} {\r\n/upd true def\r\n} ifelse\r\n} ifelse\r\n} if\r\n} ifelse\r\nupd true eq {\r\nd k v put\r\n} if\r\n} if\r\n} if\r\n} forall\r\nd length 0 gt {\r\nd setpagedevice\r\n} if\r\n} bd\r\n/RE { % /NewFontName [NewEncodingArray] /FontName RE -\r\n  findfont dup length dict begin\r\n  {\r\n    1 index /FID ne\r\n    {def} {pop pop} ifelse\r\n  } forall\r\n  /Encoding exch def\r\n  /FontName 1 index def\r\n  currentdict definefont pop\r\n  end\r\n} bind def\r\n%%EndResource\r\n%%BeginResource: procset (Apache XML Graphics EPS ProcSet) 1.0 0\r\n%%Version: 1.0 0\r\n%%Copyright: (Copyright 2002-2003 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/BeginEPSF { %def\r\n/b4_Inc_state save def         % Save state for cleanup\r\n/dict_count countdictstack def % Count objects on dict stack\r\n/op_count count 1 sub def      % Count objects on operand stack\r\nuserdict begin                 % Push userdict on dict stack\r\n/showpage { } def              % Redefine showpage, { } = null proc\r\n0 setgray 0 setlinecap         % Prepare graphics state\r\n1 setlinewidth 0 setlinejoin\r\n10 setmiterlimit [ ] 0 setdash newpath\r\n/languagelevel where           % If level not equal to 1 then\r\n{pop languagelevel             % set strokeadjust and\r\n1 ne                           % overprint to their defaults.\r\n{false setstrokeadjust false setoverprint\r\n} if\r\n} if\r\n} bd\r\n/EndEPSF { %def\r\ncount op_count sub {pop} repeat            % Clean up stacks\r\ncountdictstack dict_count sub {end} repeat\r\nb4_Inc_state restore\r\n} bd\r\n%%EndResource\r\n%FOPBeginFontDict\r\n%%IncludeResource: font Courier-Oblique\r\n%%IncludeResource: font Courier-BoldOblique\r\n%%IncludeResource: font Courier-Bold\r\n%%IncludeResource: font ZapfDingbats\r\n%%IncludeResource: font Symbol\r\n%%IncludeResource: font Helvetica\r\n%%IncludeResource: font Helvetica-Oblique\r\n%%IncludeResource: font Helvetica-Bold\r\n%%IncludeResource: font Helvetica-BoldOblique\r\n%%IncludeResource: font Times-Roman\r\n%%IncludeResource: font Times-Italic\r\n%%IncludeResource: font Times-Bold\r\n%%IncludeResource: font Times-BoldItalic\r\n%%IncludeResource: font Courier\r\n%FOPEndFontDict\r\n%%BeginResource: encoding WinAnsiEncoding\r\n/WinAnsiEncoding [\r\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /space /exclam /quotedbl\n/numbersign /dollar /percent /ampersand /quotesingle\n/parenleft /parenright /asterisk /plus /comma\n/hyphen /period /slash /zero /one\n/two /three /four /five /six\n/seven /eight /nine /colon /semicolon\n/less /equal /greater /question /at\n/A /B /C /D /E\n/F /G /H /I /J\n/K /L /M /N /O\n/P /Q /R /S /T\n/U /V /W /X /Y\n/Z /bracketleft /backslash /bracketright /asciicircum\n/underscore /quoteleft /a /b /c\n/d /e /f /g /h\n/i /j /k /l /m\n/n /o /p /q /r\n/s /t /u /v /w\n/x /y /z /braceleft /bar\n/braceright /asciitilde /bullet /Euro /bullet\n/quotesinglbase /florin /quotedblbase /ellipsis /dagger\n/daggerdbl /circumflex /perthousand /Scaron /guilsinglleft\n/OE /bullet /Zcaron /bullet /bullet\n/quoteleft /quoteright /quotedblleft /quotedblright /bullet\n/endash /emdash /asciitilde /trademark /scaron\n/guilsinglright /oe /bullet /zcaron /Ydieresis\n/space /exclamdown /cent /sterling /currency\n/yen /brokenbar /section /dieresis /copyright\n/ordfeminine /guillemotleft /logicalnot /sfthyphen /registered\n/macron /degree /plusminus /twosuperior /threesuperior\n/acute /mu /paragraph /middot /cedilla\n/onesuperior /ordmasculine /guillemotright /onequarter /onehalf\n/threequarters /questiondown /Agrave /Aacute /Acircumflex\n/Atilde /Adieresis /Aring /AE /Ccedilla\n/Egrave /Eacute /Ecircumflex /Edieresis /Igrave\n/Iacute /Icircumflex /Idieresis /Eth /Ntilde\n/Ograve /Oacute /Ocircumflex /Otilde /Odieresis\n/multiply /Oslash /Ugrave /Uacute /Ucircumflex\n/Udieresis /Yacute /Thorn /germandbls /agrave\n/aacute /acircumflex /atilde /adieresis /aring\n/ae /ccedilla /egrave /eacute /ecircumflex\n/edieresis /igrave /iacute /icircumflex /idieresis\n/eth /ntilde /ograve /oacute /ocircumflex\n/otilde /odieresis /divide /oslash /ugrave\n/uacute /ucircumflex /udieresis /yacute /thorn\n/ydieresis\n] def\r\n%%EndResource\r\n%FOPBeginFontReencode\r\n/Courier-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Oblique exch definefont pop\r\n/Courier-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-BoldOblique exch definefont pop\r\n/Courier-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Bold exch definefont pop\r\n/Helvetica findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica exch definefont pop\r\n/Helvetica-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Oblique exch definefont pop\r\n/Helvetica-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Bold exch definefont pop\r\n/Helvetica-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-BoldOblique exch definefont pop\r\n/Times-Roman findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Roman exch definefont pop\r\n/Times-Italic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Italic exch definefont pop\r\n/Times-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Bold exch definefont pop\r\n/Times-BoldItalic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-BoldItalic exch definefont pop\r\n/Courier findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier exch definefont pop\r\n%FOPEndFontReencode\r\n%%EndProlog\r\n%%Page: 1 1\r\n%%PageBoundingBox: 0 0 420 315\r\n%%BeginPageSetup\r\n[1 0 0 -1 0 315] CT\r\n%%EndPageSetup\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n146 698 M\n1014 698 L\n1014 63 L\n146 63 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n146 698 M\n1014 698 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n146 63 M\n1014 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n146 698 M\n146 689.32 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n326.833 698 M\n326.833 689.32 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n507.667 698 M\n507.667 689.32 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n688.5 698 M\n688.5 689.32 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n869.333 698 M\n869.333 689.32 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n146 63 M\n146 71.68 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n326.833 63 M\n326.833 71.68 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n507.667 63 M\n507.667 71.68 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n688.5 63 M\n688.5 71.68 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n869.333 63 M\n869.333 71.68 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 54.75 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-13.5 49 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 122.5625 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-13.5 49 moveto \r\n1 -1 scale\r\n(5) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 190.375 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(10) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 258.1875 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(15) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 325.99999 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(20) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 217.50016 291] CT\r\n0.149 GC\r\nN\r\n-11.894 43.847 M\n-11.894 43.534 -11.847 43.378 QT\n-4.16 12.737 L\n-3.957 11.831 -3.91 11.315 QT\n-3.91 10.456 -7.347 10.456 QT\n-7.894 10.456 -7.894 9.753 QT\n-7.863 9.628 -7.769 9.292 QT\n-7.675 8.956 -7.535 8.776 QT\n-7.394 8.597 -7.144 8.597 QT\n-0.003 8.019 L\n0.153 8.019 L\n0.153 8.081 0.34 8.167 QT\n0.528 8.253 0.543 8.284 QT\n0.653 8.55 0.653 8.706 QT\n-4.91 30.847 L\n-3.003 30.05 -0.089 27.034 QT\n2.825 24.019 4.465 22.698 QT\n6.106 21.378 8.59 21.378 QT\n10.075 21.378 11.106 22.386 QT\n12.137 23.394 12.137 24.878 QT\n12.137 25.8 11.754 26.589 QT\n11.372 27.378 10.668 27.87 QT\n9.965 28.362 9.028 28.362 QT\n8.184 28.362 7.598 27.831 QT\n7.012 27.3 7.012 26.456 QT\n7.012 25.19 7.911 24.323 QT\n8.809 23.456 10.075 23.456 QT\n9.559 22.753 8.497 22.753 QT\n6.918 22.753 5.45 23.659 QT\n3.981 24.565 2.293 26.261 QT\n0.606 27.956 -0.793 29.362 QT\n-2.191 30.769 -3.394 31.503 QT\n-0.253 31.862 2.051 33.144 QT\n4.356 34.425 4.356 37.065 QT\n4.356 37.612 4.137 38.44 QT\n3.684 40.425 3.684 41.612 QT\n3.684 44.003 5.309 44.003 QT\n7.231 44.003 8.223 41.901 QT\n9.215 39.8 9.856 37.003 QT\n9.965 36.706 10.309 36.706 QT\n10.918 36.706 L\n11.137 36.706 11.278 36.831 QT\n11.418 36.956 11.418 37.159 QT\n11.418 37.222 11.372 37.315 QT\n9.372 45.394 5.2 45.394 QT\n3.7 45.394 2.551 44.698 QT\n1.403 44.003 0.778 42.8 QT\n0.153 41.597 0.153 40.097 QT\n0.153 39.237 0.387 38.331 QT\n0.543 37.706 0.543 37.159 QT\n0.543 35.128 -1.269 34.065 QT\n-3.082 33.003 -5.41 32.769 QT\n-8.097 43.581 L\n-8.3 44.378 -8.894 44.886 QT\n-9.488 45.394 -10.269 45.394 QT\n-10.941 45.394 -11.418 44.94 QT\n-11.894 44.487 -11.894 43.847 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n146 698 M\n146 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 698 M\n1014 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n146 698 M\n154.68 698 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n146 592.167 M\n154.68 592.167 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n146 486.333 M\n154.68 486.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n146 380.5 M\n154.68 380.5 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n146 274.667 M\n154.68 274.667 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n146 168.833 M\n154.68 168.833 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n146 63 M\n154.68 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 698 M\n1005.32 698 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 592.167 M\n1005.32 592.167 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 486.333 M\n1005.32 486.333 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 380.5 M\n1005.32 380.5 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 274.667 M\n1005.32 274.667 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 168.833 M\n1005.32 168.833 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 63 M\n1005.32 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 49.15 261.75] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-43 19 moveto \r\n1 -1 scale\r\n(-3) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 49.15 222.06251] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-43 19 moveto \r\n1 -1 scale\r\n(-2) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 49.15 182.375] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-43 19 moveto \r\n1 -1 scale\r\n(-1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 49.15 142.6875] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 19 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 49.15 103] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 19 moveto \r\n1 -1 scale\r\n(1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 49.15 63.3125] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 19 moveto \r\n1 -1 scale\r\n(2) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 49.15 23.625] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 19 moveto \r\n1 -1 scale\r\n(3) t \r\nGR\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 30.025 142.68739] CT\r\n0.149 GC\r\nN\r\n-55.255 -20.731 M\n-54.317 -19.997 -52.614 -19.997 QT\n-50.958 -19.997 -49.692 -21.591 QT\n-48.426 -23.185 -47.958 -25.075 QT\n-45.551 -34.466 L\n-44.973 -37.028 -44.973 -37.966 QT\n-44.973 -39.278 -45.715 -40.263 QT\n-46.458 -41.247 -47.77 -41.247 QT\n-49.458 -41.247 -50.934 -40.2 QT\n-52.411 -39.153 -53.419 -37.536 QT\n-54.426 -35.919 -54.833 -34.263 QT\n-54.942 -33.919 -55.255 -33.919 QT\n-55.895 -33.919 L\n-56.317 -33.919 -56.317 -34.419 QT\n-56.317 -34.575 L\n-55.801 -36.544 -54.559 -38.419 QT\n-53.317 -40.294 -51.52 -41.458 QT\n-49.723 -42.622 -47.676 -42.622 QT\n-45.723 -42.622 -44.161 -41.583 QT\n-42.598 -40.544 -41.958 -38.763 QT\n-41.051 -40.388 -39.637 -41.505 QT\n-38.223 -42.622 -36.551 -42.622 QT\n-35.411 -42.622 -34.215 -42.224 QT\n-33.02 -41.825 -32.27 -40.997 QT\n-31.52 -40.169 -31.52 -38.919 QT\n-31.52 -37.575 -32.387 -36.606 QT\n-33.255 -35.638 -34.598 -35.638 QT\n-35.458 -35.638 -36.028 -36.177 QT\n-36.598 -36.716 -36.598 -37.544 QT\n-36.598 -38.669 -35.833 -39.505 QT\n-35.067 -40.341 -34.005 -40.497 QT\n-34.958 -41.247 -36.645 -41.247 QT\n-38.348 -41.247 -39.606 -39.669 QT\n-40.864 -38.091 -41.38 -36.153 QT\n-43.708 -26.778 L\n-44.286 -24.653 -44.286 -23.294 QT\n-44.286 -21.95 -43.52 -20.974 QT\n-42.755 -19.997 -41.489 -19.997 QT\n-39.005 -19.997 -37.051 -22.185 QT\n-35.098 -24.372 -34.473 -26.997 QT\n-34.364 -27.294 -34.067 -27.294 QT\n-33.411 -27.294 L\n-33.208 -27.294 -33.075 -27.153 QT\n-32.942 -27.013 -32.942 -26.841 QT\n-32.942 -26.778 -33.005 -26.685 QT\n-33.755 -23.528 -36.161 -21.067 QT\n-38.567 -18.606 -41.583 -18.606 QT\n-43.536 -18.606 -45.098 -19.653 QT\n-46.661 -20.7 -47.317 -22.481 QT\n-48.145 -20.935 -49.606 -19.771 QT\n-51.067 -18.606 -52.723 -18.606 QT\n-53.864 -18.606 -55.067 -19.005 QT\n-56.27 -19.403 -57.02 -20.231 QT\n-57.77 -21.06 -57.77 -22.325 QT\n-57.77 -23.575 -56.903 -24.599 QT\n-56.036 -25.622 -54.739 -25.622 QT\n-53.864 -25.622 -53.262 -25.091 QT\n-52.661 -24.56 -52.661 -23.7 QT\n-52.661 -22.591 -53.403 -21.763 QT\n-54.145 -20.935 -55.255 -20.731 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 30.025 142.68739] CT\r\n0.149 GC\r\nN\r\n-12.476 -6.06 M\n-15.429 -8.388 -17.562 -11.403 QT\n-19.695 -14.419 -21.054 -17.833 QT\n-22.414 -21.247 -23.086 -24.974 QT\n-23.757 -28.7 -23.757 -32.45 QT\n-23.757 -36.247 -23.086 -39.974 QT\n-22.414 -43.7 -21.031 -47.146 QT\n-19.648 -50.591 -17.5 -53.591 QT\n-15.351 -56.591 -12.476 -58.841 QT\n-12.476 -58.95 -12.226 -58.95 QT\n-11.726 -58.95 L\n-11.57 -58.95 -11.445 -58.81 QT\n-11.32 -58.669 -11.32 -58.481 QT\n-11.32 -58.247 -11.414 -58.153 QT\n-14.007 -55.606 -15.726 -52.708 QT\n-17.445 -49.81 -18.492 -46.536 QT\n-19.539 -43.263 -20.007 -39.755 QT\n-20.476 -36.247 -20.476 -32.45 QT\n-20.476 -15.606 -11.476 -6.856 QT\n-11.32 -6.7 -11.32 -6.419 QT\n-11.32 -6.294 -11.461 -6.122 QT\n-11.601 -5.95 -11.726 -5.95 QT\n-12.226 -5.95 L\n-12.476 -5.95 -12.476 -6.06 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 30.025 142.68739] CT\r\n0.149 GC\r\nN\r\n-4.079 -20.106 M\n-4.079 -20.419 -4.032 -20.575 QT\n-0.079 -36.388 L\n0.311 -37.856 0.311 -38.966 QT\n0.311 -41.247 -1.235 -41.247 QT\n-2.892 -41.247 -3.696 -39.271 QT\n-4.501 -37.294 -5.251 -34.263 QT\n-5.251 -34.106 -5.407 -34.013 QT\n-5.564 -33.919 -5.689 -33.919 QT\n-6.314 -33.919 L\n-6.485 -33.919 -6.618 -34.114 QT\n-6.751 -34.31 -6.751 -34.466 QT\n-6.173 -36.778 -5.649 -38.38 QT\n-5.126 -39.981 -3.993 -41.302 QT\n-2.86 -42.622 -1.189 -42.622 QT\n0.811 -42.622 2.335 -41.364 QT\n3.858 -40.106 3.858 -38.169 QT\n5.436 -40.247 7.561 -41.435 QT\n9.686 -42.622 12.061 -42.622 QT\n14.577 -42.622 16.397 -41.341 QT\n18.218 -40.06 18.218 -37.7 QT\n19.858 -40.013 22.046 -41.317 QT\n24.233 -42.622 26.811 -42.622 QT\n29.561 -42.622 31.226 -41.13 QT\n32.89 -39.638 32.89 -36.903 QT\n32.89 -34.731 31.921 -31.653 QT\n30.952 -28.575 29.515 -24.763 QT\n28.749 -22.935 28.749 -21.575 QT\n28.749 -19.997 29.999 -19.997 QT\n32.061 -19.997 33.436 -22.224 QT\n34.811 -24.45 35.374 -26.997 QT\n35.53 -27.294 35.827 -27.294 QT\n36.436 -27.294 L\n36.655 -27.294 36.796 -27.153 QT\n36.936 -27.013 36.936 -26.841 QT\n36.936 -26.778 36.89 -26.685 QT\n36.155 -23.685 34.358 -21.146 QT\n32.561 -18.606 29.874 -18.606 QT\n27.999 -18.606 26.686 -19.888 QT\n25.374 -21.169 25.374 -22.997 QT\n25.374 -23.935 25.811 -25.075 QT\n27.311 -29.06 28.304 -32.192 QT\n29.296 -35.325 29.296 -37.7 QT\n29.296 -39.185 28.702 -40.216 QT\n28.108 -41.247 26.718 -41.247 QT\n23.811 -41.247 21.694 -39.474 QT\n19.577 -37.7 18.015 -34.778 QT\n17.921 -34.263 17.858 -33.981 QT\n14.452 -20.372 L\n14.265 -19.638 13.632 -19.122 QT\n12.999 -18.606 12.218 -18.606 QT\n11.593 -18.606 11.116 -19.021 QT\n10.64 -19.435 10.64 -20.106 QT\n10.64 -20.419 10.686 -20.575 QT\n14.077 -34.075 L\n14.624 -36.247 14.624 -37.7 QT\n14.624 -39.185 14.015 -40.216 QT\n13.405 -41.247 11.968 -41.247 QT\n10.015 -41.247 8.39 -40.396 QT\n6.765 -39.544 5.546 -38.13 QT\n4.327 -36.716 3.311 -34.778 QT\n-0.282 -20.372 L\n-0.454 -19.638 -1.095 -19.122 QT\n-1.735 -18.606 -2.501 -18.606 QT\n-3.157 -18.606 -3.618 -19.021 QT\n-4.079 -19.435 -4.079 -20.106 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 30.025 142.68739] CT\r\n0.149 GC\r\nN\r\n42.092 -5.95 M\n41.623 -5.95 41.623 -6.419 QT\n41.623 -6.653 41.733 -6.747 QT\n50.795 -15.606 50.795 -32.45 QT\n50.795 -49.294 41.842 -58.044 QT\n41.623 -58.169 41.623 -58.481 QT\n41.623 -58.669 41.772 -58.81 QT\n41.92 -58.95 42.092 -58.95 QT\n42.592 -58.95 L\n42.748 -58.95 42.842 -58.841 QT\n46.654 -55.841 49.186 -51.544 QT\n51.717 -47.247 52.897 -42.388 QT\n54.076 -37.528 54.076 -32.45 QT\n54.076 -28.7 53.444 -25.06 QT\n52.811 -21.419 51.428 -17.888 QT\n50.045 -14.356 47.92 -11.372 QT\n45.795 -8.388 42.842 -6.06 QT\n42.748 -5.95 42.592 -5.95 QT\n42.092 -5.95 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 580.051 L\n254.5 552.256 L\n290.667 525.786 L\n326.833 501.301 L\n363 477.672 L\n399.167 453.979 L\n435.333 429.259 L\n471.5 403.423 L\n507.667 378.065 L\n543.833 354.157 L\n580 331.971 L\n616.167 311.539 L\n652.333 292.854 L\n688.5 275.908 L\n724.667 260.685 L\n760.833 247.159 L\n797 235.285 L\n833.167 224.99 L\n869.333 216.176 L\n905.5 208.713 L\n941.667 202.438 L\n977.833 197.148 L\n1014 192.591 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 579.313 L\n254.5 549.676 L\n290.667 519.792 L\n326.833 490.174 L\n363 460.435 L\n399.167 430.126 L\n435.333 398.168 L\n471.5 365.311 L\n507.667 336.129 L\n543.833 312.537 L\n580 292.529 L\n616.167 274.663 L\n652.333 258.369 L\n688.5 243.536 L\n724.667 230.193 L\n760.833 218.362 L\n797 208.017 L\n833.167 199.09 L\n869.333 191.478 L\n905.5 185.053 L\n941.667 179.665 L\n977.833 175.13 L\n1014 171.226 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.205 L\n254.5 548.077 L\n290.667 519.947 L\n326.833 492.426 L\n363 464.3 L\n399.167 435.121 L\n435.333 403.832 L\n471.5 371.174 L\n507.667 341.174 L\n543.833 314.675 L\n580 291.726 L\n616.167 271.814 L\n652.333 254.349 L\n688.5 238.932 L\n724.667 225.338 L\n760.833 213.43 L\n797 203.091 L\n833.167 194.206 L\n869.333 186.652 L\n905.5 180.289 L\n941.667 174.959 L\n977.833 170.476 L\n1014 166.619 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.542 L\n254.5 548.142 L\n290.667 519.17 L\n326.833 491.019 L\n363 462.48 L\n399.167 433.109 L\n435.333 401.791 L\n471.5 369.347 L\n507.667 340.084 L\n543.833 314.734 L\n580 293.013 L\n616.167 274.191 L\n652.333 257.542 L\n688.5 242.641 L\n724.667 229.326 L\n760.833 217.541 L\n797 207.243 L\n833.167 198.359 L\n869.333 190.789 L\n905.5 184.404 L\n941.667 179.05 L\n977.833 174.545 L\n1014 170.668 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.205 L\n254.5 548.073 L\n290.667 519.774 L\n326.833 492.233 L\n363 464.286 L\n399.167 435.412 L\n435.333 404.445 L\n471.5 372.032 L\n507.667 341.998 L\n543.833 315.154 L\n580 291.854 L\n616.167 271.835 L\n652.333 254.465 L\n688.5 239.211 L\n724.667 225.766 L\n760.833 213.968 L\n797 203.71 L\n833.167 194.887 L\n869.333 187.381 L\n905.5 181.057 L\n941.667 175.76 L\n977.833 171.305 L\n1014 167.471 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.351 L\n254.5 547.999 L\n290.667 519.291 L\n326.833 491.329 L\n363 462.985 L\n399.167 433.777 L\n435.333 402.596 L\n471.5 370.208 L\n507.667 340.654 L\n543.833 314.625 L\n580 292.197 L\n616.167 272.913 L\n652.333 256.055 L\n688.5 241.095 L\n724.667 227.779 L\n760.833 216.013 L\n797 205.737 L\n833.167 196.878 L\n869.333 189.332 L\n905.5 182.971 L\n941.667 177.642 L\n977.833 173.159 L\n1014 169.303 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.24 L\n254.5 548.063 L\n290.667 519.665 L\n326.833 492.041 L\n363 464.034 L\n399.167 435.128 L\n435.333 404.16 L\n471.5 371.796 L\n507.667 341.754 L\n543.833 314.823 L\n580 291.471 L\n616.167 271.497 L\n652.333 254.234 L\n688.5 239.087 L\n724.667 225.719 L\n760.833 213.969 L\n797 203.74 L\n833.167 194.935 L\n869.333 187.443 L\n905.5 181.13 L\n941.667 175.843 L\n977.833 171.397 L\n1014 167.571 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.299 L\n254.5 548 L\n290.667 519.388 L\n326.833 491.525 L\n363 463.282 L\n399.167 434.168 L\n435.333 403.061 L\n471.5 370.701 L\n507.667 340.978 L\n543.833 314.602 L\n580 291.832 L\n616.167 272.326 L\n652.333 255.367 L\n688.5 240.377 L\n724.667 227.065 L\n760.833 215.312 L\n797 205.053 L\n833.167 196.212 L\n869.333 188.684 L\n905.5 182.34 L\n941.667 177.025 L\n977.833 172.556 L\n1014 168.712 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.26 L\n254.5 548.057 L\n290.667 519.615 L\n326.833 491.946 L\n363 463.904 L\n399.167 434.973 L\n435.333 403.997 L\n471.5 371.652 L\n507.667 341.633 L\n543.833 314.712 L\n580 291.388 L\n616.167 271.472 L\n652.333 254.272 L\n688.5 239.176 L\n724.667 225.837 L\n760.833 214.1 L\n797 203.875 L\n833.167 195.07 L\n869.333 187.578 L\n905.5 181.265 L\n941.667 175.978 L\n977.833 171.531 L\n1014 167.706 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.283 L\n254.5 548.01 L\n290.667 519.444 L\n326.833 491.632 L\n363 463.443 L\n399.167 434.38 L\n435.333 403.314 L\n471.5 370.967 L\n507.667 341.154 L\n543.833 314.599 L\n580 291.654 L\n616.167 272.033 L\n652.333 255.019 L\n688.5 240.011 L\n724.667 226.698 L\n760.833 214.953 L\n797 204.704 L\n833.167 195.873 L\n869.333 188.355 L\n905.5 182.02 L\n941.667 176.714 L\n977.833 172.252 L\n1014 168.413 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.268 L\n254.5 548.051 L\n290.667 519.583 L\n326.833 491.887 L\n363 463.819 L\n399.167 434.869 L\n435.333 403.882 L\n471.5 371.544 L\n507.667 341.55 L\n543.833 314.664 L\n580 291.383 L\n616.167 271.513 L\n652.333 254.353 L\n688.5 239.281 L\n724.667 225.955 L\n760.833 214.221 L\n797 203.994 L\n833.167 195.187 L\n869.333 187.691 L\n905.5 181.376 L\n941.667 176.087 L\n977.833 171.639 L\n1014 167.813 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.278 L\n254.5 548.019 L\n290.667 519.476 L\n326.833 491.693 L\n363 463.534 L\n399.167 434.5 L\n435.333 403.455 L\n471.5 371.114 L\n507.667 341.252 L\n543.833 314.602 L\n580 291.563 L\n616.167 271.879 L\n652.333 254.832 L\n688.5 239.813 L\n724.667 226.5 L\n760.833 214.758 L\n797 204.515 L\n833.167 195.69 L\n869.333 188.178 L\n905.5 181.848 L\n941.667 176.546 L\n977.833 172.088 L\n1014 168.253 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.271 L\n254.5 548.045 L\n290.667 519.562 L\n326.833 491.849 L\n363 463.765 L\n399.167 434.8 L\n435.333 403.803 L\n471.5 371.467 L\n507.667 341.494 L\n543.833 314.642 L\n580 291.397 L\n616.167 271.56 L\n652.333 254.424 L\n688.5 239.366 L\n724.667 226.045 L\n760.833 214.311 L\n797 204.082 L\n833.167 195.272 L\n869.333 187.774 L\n905.5 181.457 L\n941.667 176.166 L\n977.833 171.716 L\n1014 167.889 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.276 L\n254.5 548.024 L\n290.667 519.496 L\n326.833 491.729 L\n363 463.587 L\n399.167 434.57 L\n435.333 403.537 L\n471.5 371.199 L\n507.667 341.309 L\n543.833 314.606 L\n580 291.515 L\n616.167 271.794 L\n652.333 254.728 L\n688.5 239.702 L\n724.667 226.388 L\n760.833 214.648 L\n797 204.409 L\n833.167 195.587 L\n869.333 188.078 L\n905.5 181.752 L\n941.667 176.452 L\n977.833 171.997 L\n1014 168.163 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.273 L\n254.5 548.042 L\n290.667 519.549 L\n326.833 491.825 L\n363 463.729 L\n399.167 434.754 L\n435.333 403.752 L\n471.5 371.416 L\n507.667 341.458 L\n543.833 314.631 L\n580 291.413 L\n616.167 271.598 L\n652.333 254.477 L\n688.5 239.427 L\n724.667 226.108 L\n760.833 214.373 L\n797 204.142 L\n833.167 195.33 L\n869.333 187.83 L\n905.5 181.512 L\n941.667 176.219 L\n977.833 171.768 L\n1014 167.94 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.275 L\n254.5 548.028 L\n290.667 519.507 L\n326.833 491.75 L\n363 463.619 L\n399.167 434.611 L\n435.333 403.586 L\n471.5 371.248 L\n507.667 341.342 L\n543.833 314.61 L\n580 291.488 L\n616.167 271.746 L\n652.333 254.668 L\n688.5 239.637 L\n724.667 226.322 L\n760.833 214.584 L\n797 204.346 L\n833.167 195.527 L\n869.333 188.02 L\n905.5 181.696 L\n941.667 176.398 L\n977.833 171.943 L\n1014 168.111 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.273 L\n254.5 548.039 L\n290.667 519.54 L\n326.833 491.81 L\n363 463.707 L\n399.167 434.726 L\n435.333 403.719 L\n471.5 371.383 L\n507.667 341.435 L\n543.833 314.625 L\n580 291.425 L\n616.167 271.625 L\n652.333 254.513 L\n688.5 239.467 L\n724.667 226.149 L\n760.833 214.414 L\n797 204.182 L\n833.167 195.368 L\n869.333 187.867 L\n905.5 181.547 L\n941.667 176.254 L\n977.833 171.803 L\n1014 167.973 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.274 L\n254.5 548.03 L\n290.667 519.515 L\n326.833 491.763 L\n363 463.638 L\n399.167 434.636 L\n435.333 403.615 L\n471.5 371.278 L\n507.667 341.363 L\n543.833 314.612 L\n580 291.473 L\n616.167 271.718 L\n652.333 254.633 L\n688.5 239.599 L\n724.667 226.283 L\n760.833 214.546 L\n797 204.309 L\n833.167 195.491 L\n869.333 187.986 L\n905.5 181.662 L\n941.667 176.365 L\n977.833 171.912 L\n1014 168.08 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.274 L\n254.5 548.037 L\n290.667 519.535 L\n326.833 491.8 L\n363 463.693 L\n399.167 434.707 L\n435.333 403.697 L\n471.5 371.362 L\n507.667 341.42 L\n543.833 314.622 L\n580 291.434 L\n616.167 271.642 L\n652.333 254.536 L\n688.5 239.493 L\n724.667 226.176 L\n760.833 214.441 L\n797 204.208 L\n833.167 195.393 L\n869.333 187.891 L\n905.5 181.57 L\n941.667 176.276 L\n977.833 171.824 L\n1014 167.995 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.274 L\n254.5 548.032 L\n290.667 519.519 L\n326.833 491.771 L\n363 463.65 L\n399.167 434.652 L\n435.333 403.633 L\n471.5 371.297 L\n507.667 341.375 L\n543.833 314.614 L\n580 291.464 L\n616.167 271.701 L\n652.333 254.611 L\n688.5 239.575 L\n724.667 226.26 L\n760.833 214.523 L\n797 204.287 L\n833.167 195.47 L\n869.333 187.965 L\n905.5 181.642 L\n941.667 176.346 L\n977.833 171.892 L\n1014 168.061 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.274 L\n254.5 548.036 L\n290.667 519.532 L\n326.833 491.794 L\n363 463.684 L\n399.167 434.696 L\n435.333 403.684 L\n471.5 371.349 L\n507.667 341.411 L\n543.833 314.62 L\n580 291.44 L\n616.167 271.654 L\n652.333 254.551 L\n688.5 239.51 L\n724.667 226.193 L\n760.833 214.458 L\n797 204.224 L\n833.167 195.409 L\n869.333 187.906 L\n905.5 181.585 L\n941.667 176.29 L\n977.833 171.838 L\n1014 168.008 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.274 L\n254.5 548.033 L\n290.667 519.522 L\n326.833 491.776 L\n363 463.657 L\n399.167 434.661 L\n435.333 403.644 L\n471.5 371.308 L\n507.667 341.383 L\n543.833 314.615 L\n580 291.458 L\n616.167 271.69 L\n652.333 254.598 L\n688.5 239.561 L\n724.667 226.245 L\n760.833 214.509 L\n797 204.273 L\n833.167 195.457 L\n869.333 187.952 L\n905.5 181.63 L\n941.667 176.334 L\n977.833 171.881 L\n1014 168.05 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.274 L\n254.5 548.035 L\n290.667 519.53 L\n326.833 491.791 L\n363 463.678 L\n399.167 434.689 L\n435.333 403.676 L\n471.5 371.34 L\n507.667 341.405 L\n543.833 314.619 L\n580 291.443 L\n616.167 271.661 L\n652.333 254.561 L\n688.5 239.52 L\n724.667 226.204 L\n760.833 214.468 L\n797 204.234 L\n833.167 195.419 L\n869.333 187.916 L\n905.5 181.594 L\n941.667 176.299 L\n977.833 171.847 L\n1014 168.017 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.274 L\n254.5 548.033 L\n290.667 519.523 L\n326.833 491.779 L\n363 463.662 L\n399.167 434.667 L\n435.333 403.651 L\n471.5 371.315 L\n507.667 341.387 L\n543.833 314.616 L\n580 291.455 L\n616.167 271.684 L\n652.333 254.59 L\n688.5 239.552 L\n724.667 226.236 L\n760.833 214.5 L\n797 204.265 L\n833.167 195.448 L\n869.333 187.944 L\n905.5 181.622 L\n941.667 176.326 L\n977.833 171.874 L\n1014 168.043 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.274 L\n254.5 548.035 L\n290.667 519.528 L\n326.833 491.788 L\n363 463.675 L\n399.167 434.684 L\n435.333 403.671 L\n471.5 371.335 L\n507.667 341.401 L\n543.833 314.618 L\n580 291.446 L\n616.167 271.666 L\n652.333 254.567 L\n688.5 239.527 L\n724.667 226.211 L\n760.833 214.475 L\n797 204.24 L\n833.167 195.425 L\n869.333 187.922 L\n905.5 181.6 L\n941.667 176.305 L\n977.833 171.853 L\n1014 168.022 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.274 L\n254.5 548.034 L\n290.667 519.524 L\n326.833 491.781 L\n363 463.665 L\n399.167 434.671 L\n435.333 403.655 L\n471.5 371.319 L\n507.667 341.39 L\n543.833 314.616 L\n580 291.453 L\n616.167 271.68 L\n652.333 254.585 L\n688.5 239.547 L\n724.667 226.231 L\n760.833 214.495 L\n797 204.26 L\n833.167 195.443 L\n869.333 187.939 L\n905.5 181.617 L\n941.667 176.322 L\n977.833 171.869 L\n1014 168.038 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.274 L\n254.5 548.035 L\n290.667 519.527 L\n326.833 491.787 L\n363 463.673 L\n399.167 434.681 L\n435.333 403.667 L\n471.5 371.331 L\n507.667 341.399 L\n543.833 314.618 L\n580 291.447 L\n616.167 271.669 L\n652.333 254.571 L\n688.5 239.531 L\n724.667 226.215 L\n760.833 214.479 L\n797 204.244 L\n833.167 195.429 L\n869.333 187.925 L\n905.5 181.604 L\n941.667 176.308 L\n977.833 171.856 L\n1014 168.026 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.274 L\n254.5 548.034 L\n290.667 519.525 L\n326.833 491.782 L\n363 463.666 L\n399.167 434.673 L\n435.333 403.658 L\n471.5 371.322 L\n507.667 341.392 L\n543.833 314.617 L\n580 291.452 L\n616.167 271.678 L\n652.333 254.582 L\n688.5 239.544 L\n724.667 226.227 L\n760.833 214.491 L\n797 204.256 L\n833.167 195.44 L\n869.333 187.936 L\n905.5 181.614 L\n941.667 176.319 L\n977.833 171.866 L\n1014 168.036 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.274 L\n254.5 548.035 L\n290.667 519.527 L\n326.833 491.786 L\n363 463.672 L\n399.167 434.68 L\n435.333 403.665 L\n471.5 371.329 L\n507.667 341.397 L\n543.833 314.617 L\n580 291.448 L\n616.167 271.671 L\n652.333 254.573 L\n688.5 239.534 L\n724.667 226.217 L\n760.833 214.481 L\n797 204.247 L\n833.167 195.431 L\n869.333 187.928 L\n905.5 181.606 L\n941.667 176.311 L\n977.833 171.858 L\n1014 168.028 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.274 L\n254.5 548.034 L\n290.667 519.525 L\n326.833 491.783 L\n363 463.668 L\n399.167 434.674 L\n435.333 403.659 L\n471.5 371.323 L\n507.667 341.393 L\n543.833 314.617 L\n580 291.451 L\n616.167 271.676 L\n652.333 254.58 L\n688.5 239.541 L\n724.667 226.225 L\n760.833 214.489 L\n797 204.254 L\n833.167 195.438 L\n869.333 187.935 L\n905.5 181.613 L\n941.667 176.317 L\n977.833 171.864 L\n1014 168.034 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.274 L\n254.5 548.035 L\n290.667 519.527 L\n326.833 491.785 L\n363 463.671 L\n399.167 434.679 L\n435.333 403.664 L\n471.5 371.328 L\n507.667 341.397 L\n543.833 314.617 L\n580 291.449 L\n616.167 271.672 L\n652.333 254.575 L\n688.5 239.535 L\n724.667 226.219 L\n760.833 214.483 L\n797 204.248 L\n833.167 195.432 L\n869.333 187.929 L\n905.5 181.607 L\n941.667 176.312 L\n977.833 171.859 L\n1014 168.029 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n146 630.341 M\n182.167 607.032 L\n218.333 578.274 L\n254.5 548.034 L\n290.667 519.526 L\n326.833 491.784 L\n363 463.668 L\n399.167 434.675 L\n435.333 403.66 L\n471.5 371.324 L\n507.667 341.394 L\n543.833 314.617 L\n580 291.45 L\n616.167 271.675 L\n652.333 254.579 L\n688.5 239.54 L\n724.667 226.224 L\n760.833 214.488 L\n797 204.253 L\n833.167 195.437 L\n869.333 187.933 L\n905.5 181.611 L\n941.667 176.316 L\n977.833 171.863 L\n1014 168.033 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 312.43751 120.85937] CT\r\nN\r\n-0.641 18.348 M\n-0.641 17.176 0.172 16.317 QT\n0.984 15.457 2.156 15.457 QT\n2.938 15.457 3.461 15.942 QT\n3.984 16.426 3.984 17.192 QT\n3.984 18.114 3.414 18.848 QT\n2.844 19.582 1.969 19.817 QT\n2.813 20.129 3.656 20.129 QT\n5.703 20.129 7.203 18.239 QT\n8.703 16.348 9.313 14.004 QT\n13.828 -4.043 L\n14.156 -5.433 14.156 -6.386 QT\n14.156 -8.449 12.734 -8.449 QT\n10.625 -8.449 9.039 -6.543 QT\n7.453 -4.636 6.469 -2.121 QT\n6.375 -1.824 6.094 -1.824 QT\n5.531 -1.824 L\n5.141 -1.824 5.141 -2.261 QT\n5.141 -2.402 L\n6.219 -5.293 8.211 -7.496 QT\n10.203 -9.699 12.828 -9.699 QT\n14.813 -9.699 16.094 -8.457 QT\n17.375 -7.215 17.375 -5.293 QT\n17.375 -4.605 17.234 -3.933 QT\n12.688 14.317 L\n12.188 16.254 10.805 17.871 QT\n9.422 19.489 7.5 20.426 QT\n5.578 21.364 3.563 21.364 QT\n1.953 21.364 0.656 20.59 QT\n-0.641 19.817 -0.641 18.348 QT\ncp\n14.563 -17.574 M\n14.563 -18.621 15.383 -19.418 QT\n16.203 -20.215 17.234 -20.215 QT\n18.047 -20.215 18.578 -19.715 QT\n19.109 -19.215 19.109 -18.433 QT\n19.109 -17.355 18.25 -16.55 QT\n17.391 -15.746 16.359 -15.746 QT\n15.594 -15.746 15.078 -16.285 QT\n14.563 -16.824 14.563 -17.574 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 312.43751 120.85937] CT\r\nN\r\n39.457 5.145 M\n39.066 5.145 38.808 4.84 QT\n38.55 4.535 38.55 4.176 QT\n38.55 3.785 38.808 3.504 QT\n39.066 3.223 39.457 3.223 QT\n69.597 3.223 L\n69.957 3.223 70.215 3.504 QT\n70.472 3.785 70.472 4.176 QT\n70.472 4.535 70.215 4.84 QT\n69.957 5.145 69.597 5.145 QT\n39.457 5.145 L\ncp\n39.457 -4.183 M\n39.066 -4.183 38.808 -4.465 QT\n38.55 -4.746 38.55 -5.152 QT\n38.55 -5.496 38.808 -5.8 QT\n39.066 -6.105 39.457 -6.105 QT\n69.597 -6.105 L\n69.957 -6.105 70.215 -5.8 QT\n70.472 -5.496 70.472 -5.152 QT\n70.472 -4.746 70.215 -4.465 QT\n69.957 -4.183 69.597 -4.183 QT\n39.457 -4.183 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 312.43751 120.85937] CT\r\nN\r\n90.967 11.52 M\n90.967 9.832 L\n96.967 9.832 96.967 8.301 QT\n96.967 -16.886 L\n94.483 -15.699 90.686 -15.699 QT\n90.686 -17.386 L\n96.576 -17.386 99.576 -20.449 QT\n100.248 -20.449 L\n100.42 -20.449 100.569 -20.324 QT\n100.717 -20.199 100.717 -20.027 QT\n100.717 8.301 L\n100.717 9.832 106.717 9.832 QT\n106.717 11.52 L\n90.967 11.52 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 126.63126 118.875] CT\r\nN\r\n/f946251025{-0.641 18.348 M\n-0.641 17.176 0.172 16.317 QT\n0.984 15.457 2.156 15.457 QT\n2.938 15.457 3.461 15.942 QT\n3.984 16.426 3.984 17.192 QT\n3.984 18.114 3.414 18.848 QT\n2.844 19.582 1.969 19.817 QT\n2.813 20.129 3.656 20.129 QT\n5.703 20.129 7.203 18.239 QT\n8.703 16.348 9.313 14.004 QT\n13.828 -4.043 L\n14.156 -5.433 14.156 -6.386 QT\n14.156 -8.449 12.734 -8.449 QT\n10.625 -8.449 9.039 -6.543 QT\n7.453 -4.636 6.469 -2.121 QT\n6.375 -1.824 6.094 -1.824 QT\n5.531 -1.824 L\n5.141 -1.824 5.141 -2.261 QT\n5.141 -2.402 L\n6.219 -5.293 8.211 -7.496 QT\n10.203 -9.699 12.828 -9.699 QT\n14.813 -9.699 16.094 -8.457 QT\n17.375 -7.215 17.375 -5.293 QT\n17.375 -4.605 17.234 -3.933 QT\n12.688 14.317 L\n12.188 16.254 10.805 17.871 QT\n9.422 19.489 7.5 20.426 QT\n5.578 21.364 3.563 21.364 QT\n1.953 21.364 0.656 20.59 QT\n-0.641 19.817 -0.641 18.348 QT\ncp\n14.563 -17.574 M\n14.563 -18.621 15.383 -19.418 QT\n16.203 -20.215 17.234 -20.215 QT\n18.047 -20.215 18.578 -19.715 QT\n19.109 -19.215 19.109 -18.433 QT\n19.109 -17.355 18.25 -16.55 QT\n17.391 -15.746 16.359 -15.746 QT\n15.594 -15.746 15.078 -16.285 QT\n14.563 -16.824 14.563 -17.574 QT\ncp}def\r\nf946251025\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 126.63126 118.875] CT\r\nN\r\n/f-1792154824{39.457 5.145 M\n39.066 5.145 38.808 4.84 QT\n38.55 4.535 38.55 4.176 QT\n38.55 3.785 38.808 3.504 QT\n39.066 3.223 39.457 3.223 QT\n69.597 3.223 L\n69.957 3.223 70.215 3.504 QT\n70.472 3.785 70.472 4.176 QT\n70.472 4.535 70.215 4.84 QT\n69.957 5.145 69.597 5.145 QT\n39.457 5.145 L\ncp\n39.457 -4.183 M\n39.066 -4.183 38.808 -4.465 QT\n38.55 -4.746 38.55 -5.152 QT\n38.55 -5.496 38.808 -5.8 QT\n39.066 -6.105 39.457 -6.105 QT\n69.597 -6.105 L\n69.957 -6.105 70.215 -5.8 QT\n70.472 -5.496 70.472 -5.152 QT\n70.472 -4.746 70.215 -4.465 QT\n69.957 -4.183 69.597 -4.183 QT\n39.457 -4.183 L\ncp}def\r\nf-1792154824\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 126.63126 118.875] CT\r\nN\r\n/f1600933324{88.904 11.52 M\n88.904 10.223 L\n88.904 10.114 88.998 9.973 QT\n96.451 1.723 L\n98.139 -0.105 99.194 -1.347 QT\n100.248 -2.59 101.279 -4.207 QT\n102.311 -5.824 102.912 -7.504 QT\n103.514 -9.183 103.514 -11.058 QT\n103.514 -13.027 102.787 -14.816 QT\n102.061 -16.605 100.615 -17.683 QT\n99.17 -18.761 97.139 -18.761 QT\n95.045 -18.761 93.381 -17.511 QT\n91.717 -16.261 91.045 -14.261 QT\n91.233 -14.308 91.561 -14.308 QT\n92.639 -14.308 93.397 -13.582 QT\n94.154 -12.855 94.154 -11.715 QT\n94.154 -10.605 93.397 -9.847 QT\n92.639 -9.09 91.561 -9.09 QT\n90.436 -9.09 89.67 -9.871 QT\n88.904 -10.652 88.904 -11.715 QT\n88.904 -13.511 89.584 -15.097 QT\n90.264 -16.683 91.545 -17.91 QT\n92.826 -19.136 94.428 -19.793 QT\n96.029 -20.449 97.842 -20.449 QT\n100.576 -20.449 102.944 -19.293 QT\n105.311 -18.136 106.694 -16.011 QT\n108.076 -13.886 108.076 -11.058 QT\n108.076 -8.965 107.162 -7.09 QT\n106.248 -5.215 104.819 -3.683 QT\n103.389 -2.152 101.162 -0.207 QT\n98.936 1.739 98.233 2.395 QT\n92.795 7.629 L\n97.42 7.629 L\n100.811 7.629 103.1 7.567 QT\n105.389 7.504 105.529 7.395 QT\n106.092 6.785 106.67 2.957 QT\n108.076 2.957 L\n106.717 11.52 L\n88.904 11.52 L\ncp}def\r\nf1600933324\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n993 677 M\n993 553 L\n379 553 L\n379 677 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f1636705084{10.953 6.379 M\n12.594 8.473 15.055 9.676 QT\n17.516 10.879 20.156 10.879 QT\n22.391 10.879 24.289 10.004 QT\n26.188 9.129 27.602 7.559 QT\n29.016 5.989 29.781 3.996 QT\n30.547 2.004 30.547 -0.199 QT\n30.547 -0.574 30.969 -0.574 QT\n31.547 -0.574 L\n31.922 -0.574 31.922 -0.105 QT\n31.922 2.395 30.961 4.731 QT\n30 7.067 28.242 8.832 QT\n26.484 10.598 24.203 11.59 QT\n21.922 12.582 19.438 12.582 QT\n15.984 12.582 12.906 11.184 QT\n9.828 9.785 7.539 7.356 QT\n5.25 4.926 3.977 1.739 QT\n2.703 -1.449 2.703 -4.886 QT\n2.703 -8.34 3.977 -11.527 QT\n5.25 -14.715 7.539 -17.152 QT\n9.828 -19.59 12.906 -20.957 QT\n15.984 -22.324 19.438 -22.324 QT\n21.891 -22.324 24.141 -21.261 QT\n26.391 -20.199 28.078 -18.246 QT\n30.875 -22.183 L\n31.156 -22.324 31.203 -22.324 QT\n31.547 -22.324 L\n31.688 -22.324 31.805 -22.207 QT\n31.922 -22.09 31.922 -21.933 QT\n31.922 -8.965 L\n31.922 -8.543 31.547 -8.543 QT\n30.688 -8.543 L\n30.234 -8.543 30.234 -8.965 QT\n30.234 -10.355 29.688 -12.066 QT\n29.141 -13.777 28.281 -15.308 QT\n27.422 -16.84 26.297 -18.011 QT\n23.609 -20.636 20.109 -20.636 QT\n17.469 -20.636 15.039 -19.441 QT\n12.609 -18.246 10.953 -16.136 QT\n9.188 -13.886 8.508 -11.019 QT\n7.828 -8.152 7.828 -4.886 QT\n7.828 -1.636 8.508 1.246 QT\n9.188 4.129 10.953 6.379 QT\ncp}def\r\nf1636705084\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f-518588683{46.667 12.067 M\n43.792 12.067 41.331 10.598 QT\n38.87 9.129 37.44 6.668 QT\n36.01 4.207 36.01 1.301 QT\n36.01 -0.902 36.792 -2.941 QT\n37.573 -4.98 39.042 -6.59 QT\n40.51 -8.199 42.456 -9.097 QT\n44.401 -9.996 46.667 -9.996 QT\n49.62 -9.996 52.05 -8.441 QT\n54.479 -6.886 55.885 -4.269 QT\n57.292 -1.652 57.292 1.301 QT\n57.292 4.176 55.862 6.653 QT\n54.432 9.129 51.979 10.598 QT\n49.526 12.067 46.667 12.067 QT\ncp\n46.667 10.645 M\n50.51 10.645 51.8 7.856 QT\n53.089 5.067 53.089 0.754 QT\n53.089 -1.652 52.831 -3.238 QT\n52.573 -4.824 51.714 -6.105 QT\n51.167 -6.902 50.339 -7.504 QT\n49.51 -8.105 48.581 -8.418 QT\n47.651 -8.73 46.667 -8.73 QT\n45.167 -8.73 43.823 -8.05 QT\n42.479 -7.371 41.589 -6.105 QT\n40.698 -4.746 40.448 -3.121 QT\n40.198 -1.496 40.198 0.754 QT\n40.198 3.457 40.667 5.598 QT\n41.135 7.739 42.557 9.192 QT\n43.979 10.645 46.667 10.645 QT\ncp}def\r\nf-518588683\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f763322885{60.104 11.52 M\n60.104 9.832 L\n61.745 9.832 62.8 9.575 QT\n63.854 9.317 63.854 8.301 QT\n63.854 -4.793 L\n63.854 -6.09 63.464 -6.66 QT\n63.073 -7.23 62.346 -7.363 QT\n61.62 -7.496 60.104 -7.496 QT\n60.104 -9.183 L\n67.057 -9.699 L\n67.057 -5.011 L\n68.026 -7.074 69.909 -8.386 QT\n71.792 -9.699 74.026 -9.699 QT\n77.354 -9.699 79.026 -8.105 QT\n80.698 -6.511 80.698 -3.23 QT\n80.698 8.301 L\n80.698 9.317 81.753 9.575 QT\n82.807 9.832 84.448 9.832 QT\n84.448 11.52 L\n73.464 11.52 L\n73.464 9.832 L\n75.104 9.832 76.159 9.575 QT\n77.214 9.317 77.214 8.301 QT\n77.214 -3.09 L\n77.214 -5.433 76.534 -6.941 QT\n75.854 -8.449 73.745 -8.449 QT\n70.948 -8.449 69.159 -6.222 QT\n67.37 -3.996 67.37 -1.168 QT\n67.37 8.301 L\n67.37 9.317 68.425 9.575 QT\n69.479 9.832 71.089 9.832 QT\n71.089 11.52 L\n60.104 11.52 L\ncp}def\r\nf763322885\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f1813278697{95.719 11.52 M\n88.719 -6.105 L\n88.266 -6.996 87.344 -7.246 QT\n86.422 -7.496 84.922 -7.496 QT\n84.922 -9.183 L\n95 -9.183 L\n95 -7.496 L\n92.297 -7.496 92.297 -6.34 QT\n92.297 -6.152 92.344 -6.058 QT\n97.735 7.489 L\n102.594 -4.746 L\n102.735 -5.121 102.735 -5.527 QT\n102.735 -6.433 102.039 -6.965 QT\n101.344 -7.496 100.406 -7.496 QT\n100.406 -9.183 L\n108.375 -9.183 L\n108.375 -7.496 L\n106.906 -7.496 105.789 -6.816 QT\n104.672 -6.136 104.063 -4.793 QT\n97.594 11.52 L\n97.406 12.067 96.828 12.067 QT\n96.469 12.067 L\n95.891 12.067 95.719 11.52 QT\ncp}def\r\nf1813278697\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f1730672616{119.953 12.067 M\n117.031 12.067 114.578 10.528 QT\n112.125 8.989 110.735 6.418 QT\n109.344 3.848 109.344 0.989 QT\n109.344 -1.824 110.617 -4.355 QT\n111.891 -6.886 114.18 -8.441 QT\n116.469 -9.996 119.281 -9.996 QT\n121.485 -9.996 123.11 -9.261 QT\n124.735 -8.527 125.789 -7.215 QT\n126.844 -5.902 127.383 -4.121 QT\n127.922 -2.34 127.922 -0.199 QT\n127.922 0.426 127.438 0.426 QT\n113.531 0.426 L\n113.531 0.942 L\n113.531 4.926 115.141 7.785 QT\n116.75 10.645 120.375 10.645 QT\n121.86 10.645 123.11 9.989 QT\n124.36 9.332 125.289 8.16 QT\n126.219 6.989 126.547 5.66 QT\n126.594 5.489 126.719 5.364 QT\n126.844 5.239 127.016 5.239 QT\n127.438 5.239 L\n127.922 5.239 127.922 5.848 QT\n127.25 8.567 125 10.317 QT\n122.75 12.067 119.953 12.067 QT\ncp\n113.578 -0.761 M\n124.531 -0.761 L\n124.531 -2.574 124.024 -4.425 QT\n123.516 -6.277 122.344 -7.504 QT\n121.172 -8.73 119.281 -8.73 QT\n116.563 -8.73 115.071 -6.191 QT\n113.578 -3.652 113.578 -0.761 QT\ncp}def\r\nf1730672616\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f1581324804{130.584 11.52 M\n130.584 9.832 L\n132.224 9.832 133.279 9.575 QT\n134.334 9.317 134.334 8.301 QT\n134.334 -4.793 L\n134.334 -6.09 133.943 -6.66 QT\n133.552 -7.23 132.826 -7.363 QT\n132.099 -7.496 130.584 -7.496 QT\n130.584 -9.183 L\n137.443 -9.699 L\n137.443 -5.011 L\n138.224 -7.09 139.654 -8.394 QT\n141.084 -9.699 143.115 -9.699 QT\n144.552 -9.699 145.677 -8.855 QT\n146.802 -8.011 146.802 -6.621 QT\n146.802 -5.761 146.177 -5.113 QT\n145.552 -4.465 144.646 -4.465 QT\n143.755 -4.465 143.123 -5.097 QT\n142.49 -5.73 142.49 -6.621 QT\n142.49 -7.918 143.396 -8.449 QT\n143.115 -8.449 L\n141.177 -8.449 139.943 -7.043 QT\n138.709 -5.636 138.193 -3.55 QT\n137.677 -1.465 137.677 0.426 QT\n137.677 8.301 L\n137.677 9.832 142.349 9.832 QT\n142.349 11.52 L\n130.584 11.52 L\ncp}def\r\nf1581324804\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f-1655348641{149.477 15.27 M\n149.477 13.567 150.72 12.285 QT\n151.962 11.004 153.665 10.457 QT\n152.712 9.739 152.204 8.637 QT\n151.696 7.535 151.696 6.285 QT\n151.696 4.035 153.134 2.301 QT\n150.93 0.145 150.93 -2.636 QT\n150.93 -4.136 151.571 -5.449 QT\n152.212 -6.761 153.36 -7.722 QT\n154.509 -8.683 155.915 -9.191 QT\n157.321 -9.699 158.805 -9.699 QT\n161.665 -9.699 163.93 -8.027 QT\n164.915 -9.09 166.266 -9.66 QT\n167.618 -10.23 169.071 -10.23 QT\n170.102 -10.23 170.759 -9.496 QT\n171.415 -8.761 171.415 -7.73 QT\n171.415 -7.136 170.97 -6.691 QT\n170.524 -6.246 169.93 -6.246 QT\n169.321 -6.246 168.876 -6.691 QT\n168.43 -7.136 168.43 -7.73 QT\n168.43 -8.621 169.024 -8.965 QT\n166.54 -8.965 164.759 -7.261 QT\n165.618 -6.386 166.149 -5.136 QT\n166.68 -3.886 166.68 -2.636 QT\n166.68 -0.605 165.555 1.028 QT\n164.43 2.66 162.587 3.559 QT\n160.743 4.457 158.805 4.457 QT\n156.18 4.457 153.993 3.035 QT\n153.321 3.973 153.321 5.145 QT\n153.321 6.41 154.149 7.356 QT\n154.977 8.301 156.243 8.301 QT\n160.18 8.301 L\n163.04 8.301 165.337 8.817 QT\n167.634 9.332 169.196 10.887 QT\n170.759 12.442 170.759 15.27 QT\n170.759 17.379 168.977 18.778 QT\n167.196 20.176 164.72 20.793 QT\n162.243 21.41 160.134 21.41 QT\n158.009 21.41 155.524 20.793 QT\n153.04 20.176 151.259 18.778 QT\n149.477 17.379 149.477 15.27 QT\ncp\n152.165 15.27 M\n152.165 16.895 153.477 17.981 QT\n154.79 19.067 156.641 19.598 QT\n158.493 20.129 160.134 20.129 QT\n161.759 20.129 163.61 19.598 QT\n165.462 19.067 166.759 17.981 QT\n168.055 16.895 168.055 15.27 QT\n168.055 12.77 165.759 12.028 QT\n163.462 11.285 160.18 11.285 QT\n156.243 11.285 L\n155.149 11.285 154.22 11.817 QT\n153.29 12.348 152.727 13.293 QT\n152.165 14.239 152.165 15.27 QT\ncp\n158.805 3.176 M\n162.884 3.176 162.884 -2.636 QT\n162.884 -5.152 162.016 -6.777 QT\n161.149 -8.402 158.805 -8.402 QT\n156.462 -8.402 155.595 -6.777 QT\n154.727 -5.152 154.727 -2.636 QT\n154.727 -1.043 155.055 0.246 QT\n155.384 1.535 156.274 2.356 QT\n157.165 3.176 158.805 3.176 QT\ncp}def\r\nf-1655348641\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f402514587{184.087 12.067 M\n181.165 12.067 178.712 10.528 QT\n176.259 8.989 174.868 6.418 QT\n173.477 3.848 173.477 0.989 QT\n173.477 -1.824 174.751 -4.355 QT\n176.024 -6.886 178.313 -8.441 QT\n180.602 -9.996 183.415 -9.996 QT\n185.618 -9.996 187.243 -9.261 QT\n188.868 -8.527 189.923 -7.215 QT\n190.977 -5.902 191.516 -4.121 QT\n192.056 -2.34 192.056 -0.199 QT\n192.056 0.426 191.571 0.426 QT\n177.665 0.426 L\n177.665 0.942 L\n177.665 4.926 179.274 7.785 QT\n180.884 10.645 184.509 10.645 QT\n185.993 10.645 187.243 9.989 QT\n188.493 9.332 189.423 8.16 QT\n190.352 6.989 190.681 5.66 QT\n190.727 5.489 190.852 5.364 QT\n190.977 5.239 191.149 5.239 QT\n191.571 5.239 L\n192.056 5.239 192.056 5.848 QT\n191.384 8.567 189.134 10.317 QT\n186.884 12.067 184.087 12.067 QT\ncp\n177.712 -0.761 M\n188.665 -0.761 L\n188.665 -2.574 188.157 -4.425 QT\n187.649 -6.277 186.477 -7.504 QT\n185.306 -8.73 183.415 -8.73 QT\n180.696 -8.73 179.204 -6.191 QT\n177.712 -3.652 177.712 -0.761 QT\ncp}def\r\nf402514587\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f909272395{205.186 12.067 M\n202.358 12.067 200.014 10.528 QT\n197.67 8.989 196.365 6.481 QT\n195.061 3.973 195.061 1.16 QT\n195.061 -1.746 196.483 -4.246 QT\n197.904 -6.746 200.342 -8.222 QT\n202.779 -9.699 205.701 -9.699 QT\n207.467 -9.699 209.037 -8.957 QT\n210.608 -8.215 211.748 -6.902 QT\n211.748 -16.886 L\n211.748 -18.183 211.365 -18.754 QT\n210.983 -19.324 210.264 -19.457 QT\n209.545 -19.59 208.029 -19.59 QT\n208.029 -21.277 L\n215.123 -21.793 L\n215.123 7.16 L\n215.123 8.426 215.514 8.996 QT\n215.904 9.567 216.615 9.7 QT\n217.326 9.832 218.858 9.832 QT\n218.858 11.52 L\n211.608 12.067 L\n211.608 9.035 L\n210.373 10.457 208.662 11.262 QT\n206.951 12.067 205.186 12.067 QT\ncp\n200.295 7.348 M\n201.108 8.91 202.483 9.848 QT\n203.858 10.785 205.467 10.785 QT\n207.467 10.785 209.131 9.637 QT\n210.795 8.489 211.608 6.66 QT\n211.608 -4.84 L\n211.045 -5.902 210.194 -6.73 QT\n209.342 -7.558 208.272 -8.004 QT\n207.201 -8.449 206.014 -8.449 QT\n203.498 -8.449 201.975 -7.035 QT\n200.451 -5.621 199.842 -3.418 QT\n199.233 -1.215 199.233 1.207 QT\n199.233 3.129 199.436 4.559 QT\n199.639 5.989 200.295 7.348 QT\ncp}def\r\nf909272395\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f-583193730{251.024 23.426 M\n248.352 21.317 246.415 18.59 QT\n244.477 15.864 243.251 12.762 QT\n242.024 9.66 241.415 6.285 QT\n240.806 2.91 240.806 -0.48 QT\n240.806 -3.933 241.415 -7.308 QT\n242.024 -10.683 243.274 -13.8 QT\n244.524 -16.918 246.47 -19.636 QT\n248.415 -22.355 251.024 -24.386 QT\n251.024 -24.48 251.259 -24.48 QT\n251.696 -24.48 L\n251.837 -24.48 251.954 -24.355 QT\n252.071 -24.23 252.071 -24.058 QT\n252.071 -23.855 251.977 -23.761 QT\n249.634 -21.465 248.079 -18.84 QT\n246.524 -16.215 245.571 -13.246 QT\n244.618 -10.277 244.196 -7.105 QT\n243.774 -3.933 243.774 -0.48 QT\n243.774 14.785 251.931 22.707 QT\n252.071 22.848 252.071 23.098 QT\n252.071 23.223 251.946 23.371 QT\n251.821 23.52 251.696 23.52 QT\n251.259 23.52 L\n251.024 23.52 251.024 23.426 QT\ncp}def\r\nf-583193730\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f-129920944{254.16 18.348 M\n254.16 17.176 254.972 16.317 QT\n255.785 15.457 256.957 15.457 QT\n257.738 15.457 258.261 15.942 QT\n258.785 16.426 258.785 17.192 QT\n258.785 18.114 258.214 18.848 QT\n257.644 19.582 256.769 19.817 QT\n257.613 20.129 258.457 20.129 QT\n260.504 20.129 262.004 18.239 QT\n263.504 16.348 264.113 14.004 QT\n268.629 -4.043 L\n268.957 -5.433 268.957 -6.386 QT\n268.957 -8.449 267.535 -8.449 QT\n265.425 -8.449 263.839 -6.543 QT\n262.254 -4.636 261.269 -2.121 QT\n261.175 -1.824 260.894 -1.824 QT\n260.332 -1.824 L\n259.941 -1.824 259.941 -2.261 QT\n259.941 -2.402 L\n261.019 -5.293 263.011 -7.496 QT\n265.004 -9.699 267.629 -9.699 QT\n269.613 -9.699 270.894 -8.457 QT\n272.175 -7.215 272.175 -5.293 QT\n272.175 -4.605 272.035 -3.933 QT\n267.488 14.317 L\n266.988 16.254 265.605 17.871 QT\n264.222 19.489 262.3 20.426 QT\n260.379 21.364 258.363 21.364 QT\n256.754 21.364 255.457 20.59 QT\n254.16 19.817 254.16 18.348 QT\ncp\n269.363 -17.574 M\n269.363 -18.621 270.183 -19.418 QT\n271.004 -20.215 272.035 -20.215 QT\n272.847 -20.215 273.379 -19.715 QT\n273.91 -19.215 273.91 -18.433 QT\n273.91 -17.355 273.05 -16.55 QT\n272.191 -15.746 271.16 -15.746 QT\n270.394 -15.746 269.879 -16.285 QT\n269.363 -16.824 269.363 -17.574 QT\ncp}def\r\nf-129920944\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f730600524{294.257 5.145 M\n293.867 5.145 293.609 4.84 QT\n293.351 4.535 293.351 4.176 QT\n293.351 3.785 293.609 3.504 QT\n293.867 3.223 294.257 3.223 QT\n324.398 3.223 L\n324.757 3.223 325.015 3.504 QT\n325.273 3.785 325.273 4.176 QT\n325.273 4.535 325.015 4.84 QT\n324.757 5.145 324.398 5.145 QT\n294.257 5.145 L\ncp\n294.257 -4.183 M\n293.867 -4.183 293.609 -4.465 QT\n293.351 -4.746 293.351 -5.152 QT\n293.351 -5.496 293.609 -5.8 QT\n293.867 -6.105 294.257 -6.105 QT\n324.398 -6.105 L\n324.757 -6.105 325.015 -5.8 QT\n325.273 -5.496 325.273 -5.152 QT\n325.273 -4.746 325.015 -4.465 QT\n324.757 -4.183 324.398 -4.183 QT\n294.257 -4.183 L\ncp}def\r\nf730600524\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f704190049{345.892 7.817 M\n347.017 9.457 348.916 10.254 QT\n350.814 11.051 352.986 11.051 QT\n355.783 11.051 356.955 8.668 QT\n358.127 6.285 358.127 3.27 QT\n358.127 1.91 357.877 0.551 QT\n357.627 -0.808 357.041 -1.98 QT\n356.455 -3.152 355.439 -3.855 QT\n354.424 -4.558 352.939 -4.558 QT\n349.752 -4.558 L\n349.33 -4.558 349.33 -5.011 QT\n349.33 -5.433 L\n349.33 -5.808 349.752 -5.808 QT\n352.408 -6.011 L\n354.095 -6.011 355.205 -7.277 QT\n356.314 -8.543 356.83 -10.363 QT\n357.345 -12.183 357.345 -13.824 QT\n357.345 -16.121 356.267 -17.597 QT\n355.189 -19.074 352.986 -19.074 QT\n351.158 -19.074 349.494 -18.379 QT\n347.83 -17.683 346.845 -16.277 QT\n346.939 -16.308 347.01 -16.316 QT\n347.08 -16.324 347.174 -16.324 QT\n348.252 -16.324 348.978 -15.574 QT\n349.705 -14.824 349.705 -13.777 QT\n349.705 -12.746 348.978 -11.996 QT\n348.252 -11.246 347.174 -11.246 QT\n346.127 -11.246 345.377 -11.996 QT\n344.627 -12.746 344.627 -13.777 QT\n344.627 -15.84 345.869 -17.363 QT\n347.111 -18.886 349.064 -19.668 QT\n351.017 -20.449 352.986 -20.449 QT\n354.439 -20.449 356.056 -20.019 QT\n357.674 -19.59 358.986 -18.777 QT\n360.299 -17.965 361.135 -16.699 QT\n361.97 -15.433 361.97 -13.824 QT\n361.97 -11.808 361.064 -10.097 QT\n360.158 -8.386 358.588 -7.144 QT\n357.017 -5.902 355.142 -5.293 QT\n357.236 -4.886 359.111 -3.715 QT\n360.986 -2.543 362.119 -0.715 QT\n363.252 1.114 363.252 3.223 QT\n363.252 5.864 361.799 8.012 QT\n360.345 10.16 357.978 11.371 QT\n355.611 12.582 352.986 12.582 QT\n350.736 12.582 348.478 11.723 QT\n346.22 10.864 344.775 9.153 QT\n343.33 7.442 343.33 5.051 QT\n343.33 3.848 344.127 3.051 QT\n344.924 2.254 346.127 2.254 QT\n346.892 2.254 347.541 2.621 QT\n348.189 2.989 348.549 3.645 QT\n348.908 4.301 348.908 5.051 QT\n348.908 6.223 348.088 7.02 QT\n347.267 7.817 346.127 7.817 QT\n345.892 7.817 L\ncp}def\r\nf704190049\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f400715756{367.705 11.52 M\n367.705 10.223 L\n367.705 10.114 367.799 9.973 QT\n375.252 1.723 L\n376.939 -0.105 377.994 -1.347 QT\n379.049 -2.59 380.08 -4.207 QT\n381.111 -5.824 381.713 -7.504 QT\n382.314 -9.183 382.314 -11.058 QT\n382.314 -13.027 381.588 -14.816 QT\n380.861 -16.605 379.416 -17.683 QT\n377.971 -18.761 375.939 -18.761 QT\n373.846 -18.761 372.182 -17.511 QT\n370.517 -16.261 369.846 -14.261 QT\n370.033 -14.308 370.361 -14.308 QT\n371.439 -14.308 372.197 -13.582 QT\n372.955 -12.855 372.955 -11.715 QT\n372.955 -10.605 372.197 -9.847 QT\n371.439 -9.09 370.361 -9.09 QT\n369.236 -9.09 368.471 -9.871 QT\n367.705 -10.652 367.705 -11.715 QT\n367.705 -13.511 368.385 -15.097 QT\n369.064 -16.683 370.346 -17.91 QT\n371.627 -19.136 373.228 -19.793 QT\n374.83 -20.449 376.642 -20.449 QT\n379.377 -20.449 381.744 -19.293 QT\n384.111 -18.136 385.494 -16.011 QT\n386.877 -13.886 386.877 -11.058 QT\n386.877 -8.965 385.963 -7.09 QT\n385.049 -5.215 383.619 -3.683 QT\n382.189 -2.152 379.963 -0.207 QT\n377.736 1.739 377.033 2.395 QT\n371.596 7.629 L\n376.221 7.629 L\n379.611 7.629 381.9 7.567 QT\n384.189 7.504 384.33 7.395 QT\n384.892 6.785 385.471 2.957 QT\n386.877 2.957 L\n385.517 11.52 L\n367.705 11.52 L\ncp}def\r\nf400715756\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f-420795744{392.439 23.52 M\n392.018 23.52 392.018 23.098 QT\n392.018 22.895 392.111 22.801 QT\n400.314 14.785 400.314 -0.48 QT\n400.314 -15.746 392.205 -23.668 QT\n392.018 -23.777 392.018 -24.058 QT\n392.018 -24.23 392.143 -24.355 QT\n392.268 -24.48 392.439 -24.48 QT\n392.877 -24.48 L\n393.018 -24.48 393.111 -24.386 QT\n396.564 -21.668 398.861 -17.777 QT\n401.158 -13.886 402.221 -9.48 QT\n403.283 -5.074 403.283 -0.48 QT\n403.283 2.91 402.713 6.207 QT\n402.143 9.504 400.885 12.707 QT\n399.627 15.91 397.705 18.614 QT\n395.783 21.317 393.111 23.426 QT\n393.018 23.52 392.877 23.52 QT\n392.439 23.52 L\ncp}def\r\nf-420795744\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n387 585.747 M\n467.003 585.747 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf1636705084\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf-518588683\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf763322885\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf1813278697\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf1730672616\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf1581324804\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf-1655348641\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f-2079540185{173.618 11.52 M\n173.618 9.832 L\n175.259 9.832 176.313 9.575 QT\n177.368 9.317 177.368 8.301 QT\n177.368 -4.793 L\n177.368 -6.652 176.649 -7.074 QT\n175.931 -7.496 173.821 -7.496 QT\n173.821 -9.183 L\n180.743 -9.699 L\n180.743 8.301 L\n180.743 9.317 181.657 9.575 QT\n182.571 9.832 184.087 9.832 QT\n184.087 11.52 L\n173.618 11.52 L\ncp\n175.649 -17.949 M\n175.649 -18.996 176.446 -19.793 QT\n177.243 -20.59 178.274 -20.59 QT\n178.962 -20.59 179.595 -20.238 QT\n180.227 -19.886 180.579 -19.254 QT\n180.931 -18.621 180.931 -17.949 QT\n180.931 -16.918 180.134 -16.121 QT\n179.337 -15.324 178.274 -15.324 QT\n177.243 -15.324 176.446 -16.121 QT\n175.649 -16.918 175.649 -17.949 QT\ncp}def\r\nf-2079540185\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f581539271{186.905 11.52 M\n186.905 9.832 L\n188.545 9.832 189.6 9.575 QT\n190.655 9.317 190.655 8.301 QT\n190.655 -4.793 L\n190.655 -6.09 190.264 -6.66 QT\n189.873 -7.23 189.147 -7.363 QT\n188.42 -7.496 186.905 -7.496 QT\n186.905 -9.183 L\n193.858 -9.699 L\n193.858 -5.011 L\n194.826 -7.074 196.709 -8.386 QT\n198.592 -9.699 200.826 -9.699 QT\n204.155 -9.699 205.826 -8.105 QT\n207.498 -6.511 207.498 -3.23 QT\n207.498 8.301 L\n207.498 9.317 208.553 9.575 QT\n209.608 9.832 211.248 9.832 QT\n211.248 11.52 L\n200.264 11.52 L\n200.264 9.832 L\n201.905 9.832 202.959 9.575 QT\n204.014 9.317 204.014 8.301 QT\n204.014 -3.09 L\n204.014 -5.433 203.334 -6.941 QT\n202.655 -8.449 200.545 -8.449 QT\n197.748 -8.449 195.959 -6.222 QT\n194.17 -3.996 194.17 -1.168 QT\n194.17 8.301 L\n194.17 9.317 195.225 9.575 QT\n196.28 9.832 197.889 9.832 QT\n197.889 11.52 L\n186.905 11.52 L\ncp}def\r\nf581539271\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f-1710606110{213.478 15.27 M\n213.478 13.567 214.72 12.285 QT\n215.962 11.004 217.665 10.457 QT\n216.712 9.739 216.204 8.637 QT\n215.696 7.535 215.696 6.285 QT\n215.696 4.035 217.134 2.301 QT\n214.931 0.145 214.931 -2.636 QT\n214.931 -4.136 215.571 -5.449 QT\n216.212 -6.761 217.36 -7.722 QT\n218.509 -8.683 219.915 -9.191 QT\n221.321 -9.699 222.806 -9.699 QT\n225.665 -9.699 227.931 -8.027 QT\n228.915 -9.09 230.267 -9.66 QT\n231.618 -10.23 233.071 -10.23 QT\n234.103 -10.23 234.759 -9.496 QT\n235.415 -8.761 235.415 -7.73 QT\n235.415 -7.136 234.97 -6.691 QT\n234.524 -6.246 233.931 -6.246 QT\n233.321 -6.246 232.876 -6.691 QT\n232.431 -7.136 232.431 -7.73 QT\n232.431 -8.621 233.024 -8.965 QT\n230.54 -8.965 228.759 -7.261 QT\n229.618 -6.386 230.149 -5.136 QT\n230.681 -3.886 230.681 -2.636 QT\n230.681 -0.605 229.556 1.028 QT\n228.431 2.66 226.587 3.559 QT\n224.743 4.457 222.806 4.457 QT\n220.181 4.457 217.993 3.035 QT\n217.321 3.973 217.321 5.145 QT\n217.321 6.41 218.149 7.356 QT\n218.978 8.301 220.243 8.301 QT\n224.181 8.301 L\n227.04 8.301 229.337 8.817 QT\n231.634 9.332 233.196 10.887 QT\n234.759 12.442 234.759 15.27 QT\n234.759 17.379 232.978 18.778 QT\n231.196 20.176 228.72 20.793 QT\n226.243 21.41 224.134 21.41 QT\n222.009 21.41 219.524 20.793 QT\n217.04 20.176 215.259 18.778 QT\n213.478 17.379 213.478 15.27 QT\ncp\n216.165 15.27 M\n216.165 16.895 217.478 17.981 QT\n218.79 19.067 220.642 19.598 QT\n222.493 20.129 224.134 20.129 QT\n225.759 20.129 227.61 19.598 QT\n229.462 19.067 230.759 17.981 QT\n232.056 16.895 232.056 15.27 QT\n232.056 12.77 229.759 12.028 QT\n227.462 11.285 224.181 11.285 QT\n220.243 11.285 L\n219.149 11.285 218.22 11.817 QT\n217.29 12.348 216.728 13.293 QT\n216.165 14.239 216.165 15.27 QT\ncp\n222.806 3.176 M\n226.884 3.176 226.884 -2.636 QT\n226.884 -5.152 226.017 -6.777 QT\n225.149 -8.402 222.806 -8.402 QT\n220.462 -8.402 219.595 -6.777 QT\n218.728 -5.152 218.728 -2.636 QT\n218.728 -1.043 219.056 0.246 QT\n219.384 1.535 220.274 2.356 QT\n221.165 3.176 222.806 3.176 QT\ncp}def\r\nf-1710606110\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f929488190{267.024 23.426 M\n264.353 21.317 262.415 18.59 QT\n260.478 15.864 259.251 12.762 QT\n258.024 9.66 257.415 6.285 QT\n256.806 2.91 256.806 -0.48 QT\n256.806 -3.933 257.415 -7.308 QT\n258.024 -10.683 259.274 -13.8 QT\n260.524 -16.918 262.47 -19.636 QT\n264.415 -22.355 267.024 -24.386 QT\n267.024 -24.48 267.259 -24.48 QT\n267.696 -24.48 L\n267.837 -24.48 267.954 -24.355 QT\n268.071 -24.23 268.071 -24.058 QT\n268.071 -23.855 267.978 -23.761 QT\n265.634 -21.465 264.079 -18.84 QT\n262.524 -16.215 261.571 -13.246 QT\n260.618 -10.277 260.196 -7.105 QT\n259.774 -3.933 259.774 -0.48 QT\n259.774 14.785 267.931 22.707 QT\n268.071 22.848 268.071 23.098 QT\n268.071 23.223 267.946 23.371 QT\n267.821 23.52 267.696 23.52 QT\n267.259 23.52 L\n267.024 23.52 267.024 23.426 QT\ncp}def\r\nf929488190\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f919804271{275.254 11.52 M\n275.254 9.832 L\n281.254 9.832 281.254 8.301 QT\n281.254 -16.886 L\n278.769 -15.699 274.972 -15.699 QT\n274.972 -17.386 L\n280.863 -17.386 283.863 -20.449 QT\n284.535 -20.449 L\n284.707 -20.449 284.855 -20.324 QT\n285.004 -20.199 285.004 -20.027 QT\n285.004 8.301 L\n285.004 9.832 291.004 9.832 QT\n291.004 11.52 L\n275.254 11.52 L\ncp}def\r\nf919804271\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f1957607420{313.04 18.114 M\n312.634 18.114 312.376 17.809 QT\n312.118 17.504 312.118 17.145 QT\n312.118 16.754 312.376 16.473 QT\n312.634 16.192 313.04 16.192 QT\n340.571 16.192 L\n340.946 16.192 341.196 16.473 QT\n341.446 16.754 341.446 17.145 QT\n341.446 17.504 341.196 17.809 QT\n340.946 18.114 340.571 18.114 QT\n313.04 18.114 L\ncp\n312.587 -4.324 M\n312.118 -4.465 312.118 -5.152 QT\n312.118 -5.761 312.759 -6.011 QT\n340.149 -18.949 L\n340.243 -19.027 340.477 -19.027 QT\n340.884 -19.027 341.165 -18.746 QT\n341.446 -18.465 341.446 -18.058 QT\n341.446 -17.433 340.884 -17.199 QT\n315.337 -5.152 L\n341.024 6.989 L\n341.446 7.223 341.446 7.817 QT\n341.446 8.239 341.165 8.504 QT\n340.884 8.77 340.477 8.77 QT\n340.243 8.77 340.149 8.676 QT\n312.587 -4.324 L\ncp}def\r\nf1957607420\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f127127908{358.159 18.348 M\n358.159 17.176 358.972 16.317 QT\n359.784 15.457 360.956 15.457 QT\n361.738 15.457 362.261 15.942 QT\n362.784 16.426 362.784 17.192 QT\n362.784 18.114 362.214 18.848 QT\n361.644 19.582 360.769 19.817 QT\n361.613 20.129 362.456 20.129 QT\n364.503 20.129 366.003 18.239 QT\n367.503 16.348 368.113 14.004 QT\n372.628 -4.043 L\n372.956 -5.433 372.956 -6.386 QT\n372.956 -8.449 371.534 -8.449 QT\n369.425 -8.449 367.839 -6.543 QT\n366.253 -4.636 365.269 -2.121 QT\n365.175 -1.824 364.894 -1.824 QT\n364.331 -1.824 L\n363.941 -1.824 363.941 -2.261 QT\n363.941 -2.402 L\n365.019 -5.293 367.011 -7.496 QT\n369.003 -9.699 371.628 -9.699 QT\n373.613 -9.699 374.894 -8.457 QT\n376.175 -7.215 376.175 -5.293 QT\n376.175 -4.605 376.034 -3.933 QT\n371.488 14.317 L\n370.988 16.254 369.605 17.871 QT\n368.222 19.489 366.3 20.426 QT\n364.378 21.364 362.363 21.364 QT\n360.753 21.364 359.456 20.59 QT\n358.159 19.817 358.159 18.348 QT\ncp\n373.363 -17.574 M\n373.363 -18.621 374.183 -19.418 QT\n375.003 -20.215 376.034 -20.215 QT\n376.847 -20.215 377.378 -19.715 QT\n377.909 -19.215 377.909 -18.433 QT\n377.909 -17.355 377.05 -16.55 QT\n376.191 -15.746 375.159 -15.746 QT\n374.394 -15.746 373.878 -16.285 QT\n373.363 -16.824 373.363 -17.574 QT\ncp}def\r\nf127127908\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f-1058293493{399.101 0.332 M\n398.632 0.129 398.632 -0.48 QT\n398.632 -1.09 399.272 -1.402 QT\n426.663 -14.308 L\n426.851 -14.402 426.991 -14.402 QT\n427.413 -14.402 427.687 -14.113 QT\n427.96 -13.824 427.96 -13.449 QT\n427.96 -12.855 427.397 -12.527 QT\n401.851 -0.48 L\n427.538 11.66 L\n427.96 11.801 427.96 12.489 QT\n427.96 12.864 427.687 13.153 QT\n427.413 13.442 426.991 13.442 QT\n426.851 13.442 426.663 13.348 QT\n399.101 0.332 L\ncp}def\r\nf-1058293493\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f62083131{449.892 7.817 M\n451.017 9.457 452.915 10.254 QT\n454.814 11.051 456.986 11.051 QT\n459.783 11.051 460.955 8.668 QT\n462.126 6.285 462.126 3.27 QT\n462.126 1.91 461.876 0.551 QT\n461.626 -0.808 461.04 -1.98 QT\n460.455 -3.152 459.439 -3.855 QT\n458.423 -4.558 456.939 -4.558 QT\n453.751 -4.558 L\n453.33 -4.558 453.33 -5.011 QT\n453.33 -5.433 L\n453.33 -5.808 453.751 -5.808 QT\n456.408 -6.011 L\n458.095 -6.011 459.205 -7.277 QT\n460.314 -8.543 460.83 -10.363 QT\n461.345 -12.183 461.345 -13.824 QT\n461.345 -16.121 460.267 -17.597 QT\n459.189 -19.074 456.986 -19.074 QT\n455.158 -19.074 453.494 -18.379 QT\n451.83 -17.683 450.845 -16.277 QT\n450.939 -16.308 451.009 -16.316 QT\n451.08 -16.324 451.173 -16.324 QT\n452.251 -16.324 452.978 -15.574 QT\n453.705 -14.824 453.705 -13.777 QT\n453.705 -12.746 452.978 -11.996 QT\n452.251 -11.246 451.173 -11.246 QT\n450.126 -11.246 449.376 -11.996 QT\n448.626 -12.746 448.626 -13.777 QT\n448.626 -15.84 449.869 -17.363 QT\n451.111 -18.886 453.064 -19.668 QT\n455.017 -20.449 456.986 -20.449 QT\n458.439 -20.449 460.056 -20.019 QT\n461.673 -19.59 462.986 -18.777 QT\n464.298 -17.965 465.134 -16.699 QT\n465.97 -15.433 465.97 -13.824 QT\n465.97 -11.808 465.064 -10.097 QT\n464.158 -8.386 462.587 -7.144 QT\n461.017 -5.902 459.142 -5.293 QT\n461.236 -4.886 463.111 -3.715 QT\n464.986 -2.543 466.119 -0.715 QT\n467.251 1.114 467.251 3.223 QT\n467.251 5.864 465.798 8.012 QT\n464.345 10.16 461.978 11.371 QT\n459.611 12.582 456.986 12.582 QT\n454.736 12.582 452.478 11.723 QT\n450.22 10.864 448.775 9.153 QT\n447.33 7.442 447.33 5.051 QT\n447.33 3.848 448.126 3.051 QT\n448.923 2.254 450.126 2.254 QT\n450.892 2.254 451.54 2.621 QT\n452.189 2.989 452.548 3.645 QT\n452.908 4.301 452.908 5.051 QT\n452.908 6.223 452.087 7.02 QT\n451.267 7.817 450.126 7.817 QT\n449.892 7.817 L\ncp}def\r\nf62083131\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f1509408367{471.705 11.52 M\n471.705 10.223 L\n471.705 10.114 471.798 9.973 QT\n479.251 1.723 L\n480.939 -0.105 481.994 -1.347 QT\n483.048 -2.59 484.08 -4.207 QT\n485.111 -5.824 485.712 -7.504 QT\n486.314 -9.183 486.314 -11.058 QT\n486.314 -13.027 485.587 -14.816 QT\n484.861 -16.605 483.416 -17.683 QT\n481.97 -18.761 479.939 -18.761 QT\n477.845 -18.761 476.181 -17.511 QT\n474.517 -16.261 473.845 -14.261 QT\n474.033 -14.308 474.361 -14.308 QT\n475.439 -14.308 476.197 -13.582 QT\n476.955 -12.855 476.955 -11.715 QT\n476.955 -10.605 476.197 -9.847 QT\n475.439 -9.09 474.361 -9.09 QT\n473.236 -9.09 472.47 -9.871 QT\n471.705 -10.652 471.705 -11.715 QT\n471.705 -13.511 472.384 -15.097 QT\n473.064 -16.683 474.345 -17.91 QT\n475.626 -19.136 477.228 -19.793 QT\n478.83 -20.449 480.642 -20.449 QT\n483.376 -20.449 485.744 -19.293 QT\n488.111 -18.136 489.494 -16.011 QT\n490.876 -13.886 490.876 -11.058 QT\n490.876 -8.965 489.962 -7.09 QT\n489.048 -5.215 487.619 -3.683 QT\n486.189 -2.152 483.962 -0.207 QT\n481.736 1.739 481.033 2.395 QT\n475.595 7.629 L\n480.22 7.629 L\n483.611 7.629 485.9 7.567 QT\n488.189 7.504 488.33 7.395 QT\n488.892 6.785 489.47 2.957 QT\n490.876 2.957 L\n489.517 11.52 L\n471.705 11.52 L\ncp}def\r\nf1509408367\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f511719215{496.439 23.52 M\n496.017 23.52 496.017 23.098 QT\n496.017 22.895 496.111 22.801 QT\n504.314 14.785 504.314 -0.48 QT\n504.314 -15.746 496.205 -23.668 QT\n496.017 -23.777 496.017 -24.058 QT\n496.017 -24.23 496.142 -24.355 QT\n496.267 -24.48 496.439 -24.48 QT\n496.877 -24.48 L\n497.017 -24.48 497.111 -24.386 QT\n500.564 -21.668 502.861 -17.777 QT\n505.158 -13.886 506.22 -9.48 QT\n507.283 -5.074 507.283 -0.48 QT\n507.283 2.91 506.712 6.207 QT\n506.142 9.504 504.884 12.707 QT\n503.627 15.91 501.705 18.614 QT\n499.783 21.317 497.111 23.426 QT\n497.017 23.52 496.877 23.52 QT\n496.439 23.52 L\ncp}def\r\nf511719215\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n387 644.253 M\n467.003 644.253 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n10.0 ML\r\n1.333 LW\r\nN\r\n379 677 M\n379 553 L\n993 553 L\n993 677 L\ncp\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n840 319.2 M\n794.317 257.528 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n791.837 270.98 M\n784 243.6 L\n794.317 257.528 L\n791.837 270.98 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n784 243.6 M\n807.908 259.076 L\n794.317 257.528 L\n784 243.6 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\nN\r\n784 243.6 M\n791.837 270.98 L\n794.317 257.528 L\n807.908 259.076 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n336 336 M\n431.77 371.914 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n426.542 359.273 M\n448 378 L\n431.77 371.914 L\n426.542 359.273 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n448 378 M\n419.52 378 L\n431.77 371.914 L\n448 378 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\nN\r\n448 378 M\n426.542 359.273 L\n431.77 371.914 L\n419.52 378 L\ncp\r\nf\r\nGR\r\n%%Trailer\r\n%%Pages: 1\r\n%%EOF\r\n"
  },
  {
    "path": "matlab/acc2023/closedloop_performance/figures/state-converge-2.eps",
    "content": "%!PS-Adobe-3.0 EPSF-3.0\r\n%%Creator: (MATLAB, The Mathworks, Inc. Version 9.10.0.1649659 \\(R2021a\\) Update 1. Operating System: Windows 10)\r\n%%Title: figures/state-converge-2.eps\r\n%%CreationDate: 2023-01-31T03:12:05\r\n%%Pages: (atend)\r\n%%BoundingBox:     1     6   382   298\r\n%%LanguageLevel: 3\r\n%%EndComments\r\n%%BeginProlog\r\n%%BeginResource: procset (Apache XML Graphics Std ProcSet) 1.2 0\r\n%%Version: 1.2 0\r\n%%Copyright: (Copyright 2001-2003,2010 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/bd{bind def}bind def\r\n/ld{load def}bd\r\n/GR/grestore ld\r\n/GS/gsave ld\r\n/RM/rmoveto ld\r\n/C/curveto ld\r\n/t/show ld\r\n/L/lineto ld\r\n/ML/setmiterlimit ld\r\n/CT/concat ld\r\n/f/fill ld\r\n/N/newpath ld\r\n/S/stroke ld\r\n/CC/setcmykcolor ld\r\n/A/ashow ld\r\n/cp/closepath ld\r\n/RC/setrgbcolor ld\r\n/LJ/setlinejoin ld\r\n/GC/setgray ld\r\n/LW/setlinewidth ld\r\n/M/moveto ld\r\n/re {4 2 roll M\r\n1 index 0 rlineto\r\n0 exch rlineto\r\nneg 0 rlineto\r\ncp } bd\r\n/_ctm matrix def\r\n/_tm matrix def\r\n/BT { _ctm currentmatrix pop matrix _tm copy pop 0 0 moveto } bd\r\n/ET { _ctm setmatrix } bd\r\n/iTm { _ctm setmatrix _tm concat } bd\r\n/Tm { _tm astore pop iTm 0 0 moveto } bd\r\n/ux 0.0 def\r\n/uy 0.0 def\r\n/F {\r\n  /Tp exch def\r\n  /Tf exch def\r\n  Tf findfont Tp scalefont setfont\r\n  /cf Tf def  /cs Tp def\r\n} bd\r\n/ULS {currentpoint /uy exch def /ux exch def} bd\r\n/ULE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add moveto  Tcx uy To add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/OLE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs add moveto Tcx uy To add cs add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/SOE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs 10 mul 26 idiv add moveto Tcx uy To add cs 10 mul 26 idiv add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/QT {\r\n/Y22 exch store\r\n/X22 exch store\r\n/Y21 exch store\r\n/X21 exch store\r\ncurrentpoint\r\n/Y21 load 2 mul add 3 div exch\r\n/X21 load 2 mul add 3 div exch\r\n/X21 load 2 mul /X22 load add 3 div\r\n/Y21 load 2 mul /Y22 load add 3 div\r\n/X22 load /Y22 load curveto\r\n} bd\r\n/SSPD {\r\ndup length /d exch dict def\r\n{\r\n/v exch def\r\n/k exch def\r\ncurrentpagedevice k known {\r\n/cpdv currentpagedevice k get def\r\nv cpdv ne {\r\n/upd false def\r\n/nullv v type /nulltype eq def\r\n/nullcpdv cpdv type /nulltype eq def\r\nnullv nullcpdv or\r\n{\r\n/upd true def\r\n} {\r\n/sametype v type cpdv type eq def\r\nsametype {\r\nv type /arraytype eq {\r\n/vlen v length def\r\n/cpdvlen cpdv length def\r\nvlen cpdvlen eq {\r\n0 1 vlen 1 sub {\r\n/i exch def\r\n/obj v i get def\r\n/cpdobj cpdv i get def\r\nobj cpdobj ne {\r\n/upd true def\r\nexit\r\n} if\r\n} for\r\n} {\r\n/upd true def\r\n} ifelse\r\n} {\r\nv type /dicttype eq {\r\nv {\r\n/dv exch def\r\n/dk exch def\r\n/cpddv cpdv dk get def\r\ndv cpddv ne {\r\n/upd true def\r\nexit\r\n} if\r\n} forall\r\n} {\r\n/upd true def\r\n} ifelse\r\n} ifelse\r\n} if\r\n} ifelse\r\nupd true eq {\r\nd k v put\r\n} if\r\n} if\r\n} if\r\n} forall\r\nd length 0 gt {\r\nd setpagedevice\r\n} if\r\n} bd\r\n/RE { % /NewFontName [NewEncodingArray] /FontName RE -\r\n  findfont dup length dict begin\r\n  {\r\n    1 index /FID ne\r\n    {def} {pop pop} ifelse\r\n  } forall\r\n  /Encoding exch def\r\n  /FontName 1 index def\r\n  currentdict definefont pop\r\n  end\r\n} bind def\r\n%%EndResource\r\n%%BeginResource: procset (Apache XML Graphics EPS ProcSet) 1.0 0\r\n%%Version: 1.0 0\r\n%%Copyright: (Copyright 2002-2003 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/BeginEPSF { %def\r\n/b4_Inc_state save def         % Save state for cleanup\r\n/dict_count countdictstack def % Count objects on dict stack\r\n/op_count count 1 sub def      % Count objects on operand stack\r\nuserdict begin                 % Push userdict on dict stack\r\n/showpage { } def              % Redefine showpage, { } = null proc\r\n0 setgray 0 setlinecap         % Prepare graphics state\r\n1 setlinewidth 0 setlinejoin\r\n10 setmiterlimit [ ] 0 setdash newpath\r\n/languagelevel where           % If level not equal to 1 then\r\n{pop languagelevel             % set strokeadjust and\r\n1 ne                           % overprint to their defaults.\r\n{false setstrokeadjust false setoverprint\r\n} if\r\n} if\r\n} bd\r\n/EndEPSF { %def\r\ncount op_count sub {pop} repeat            % Clean up stacks\r\ncountdictstack dict_count sub {end} repeat\r\nb4_Inc_state restore\r\n} bd\r\n%%EndResource\r\n%FOPBeginFontDict\r\n%%IncludeResource: font Courier-Oblique\r\n%%IncludeResource: font Courier-BoldOblique\r\n%%IncludeResource: font Courier-Bold\r\n%%IncludeResource: font ZapfDingbats\r\n%%IncludeResource: font Symbol\r\n%%IncludeResource: font Helvetica\r\n%%IncludeResource: font Helvetica-Oblique\r\n%%IncludeResource: font Helvetica-Bold\r\n%%IncludeResource: font Helvetica-BoldOblique\r\n%%IncludeResource: font Times-Roman\r\n%%IncludeResource: font Times-Italic\r\n%%IncludeResource: font Times-Bold\r\n%%IncludeResource: font Times-BoldItalic\r\n%%IncludeResource: font Courier\r\n%FOPEndFontDict\r\n%%BeginResource: encoding WinAnsiEncoding\r\n/WinAnsiEncoding [\r\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /space /exclam /quotedbl\n/numbersign /dollar /percent /ampersand /quotesingle\n/parenleft /parenright /asterisk /plus /comma\n/hyphen /period /slash /zero /one\n/two /three /four /five /six\n/seven /eight /nine /colon /semicolon\n/less /equal /greater /question /at\n/A /B /C /D /E\n/F /G /H /I /J\n/K /L /M /N /O\n/P /Q /R /S /T\n/U /V /W /X /Y\n/Z /bracketleft /backslash /bracketright /asciicircum\n/underscore /quoteleft /a /b /c\n/d /e /f /g /h\n/i /j /k /l /m\n/n /o /p /q /r\n/s /t /u /v /w\n/x /y /z /braceleft /bar\n/braceright /asciitilde /bullet /Euro /bullet\n/quotesinglbase /florin /quotedblbase /ellipsis /dagger\n/daggerdbl /circumflex /perthousand /Scaron /guilsinglleft\n/OE /bullet /Zcaron /bullet /bullet\n/quoteleft /quoteright /quotedblleft /quotedblright /bullet\n/endash /emdash /asciitilde /trademark /scaron\n/guilsinglright /oe /bullet /zcaron /Ydieresis\n/space /exclamdown /cent /sterling /currency\n/yen /brokenbar /section /dieresis /copyright\n/ordfeminine /guillemotleft /logicalnot /sfthyphen /registered\n/macron /degree /plusminus /twosuperior /threesuperior\n/acute /mu /paragraph /middot /cedilla\n/onesuperior /ordmasculine /guillemotright /onequarter /onehalf\n/threequarters /questiondown /Agrave /Aacute /Acircumflex\n/Atilde /Adieresis /Aring /AE /Ccedilla\n/Egrave /Eacute /Ecircumflex /Edieresis /Igrave\n/Iacute /Icircumflex /Idieresis /Eth /Ntilde\n/Ograve /Oacute /Ocircumflex /Otilde /Odieresis\n/multiply /Oslash /Ugrave /Uacute /Ucircumflex\n/Udieresis /Yacute /Thorn /germandbls /agrave\n/aacute /acircumflex /atilde /adieresis /aring\n/ae /ccedilla /egrave /eacute /ecircumflex\n/edieresis /igrave /iacute /icircumflex /idieresis\n/eth /ntilde /ograve /oacute /ocircumflex\n/otilde /odieresis /divide /oslash /ugrave\n/uacute /ucircumflex /udieresis /yacute /thorn\n/ydieresis\n] def\r\n%%EndResource\r\n%FOPBeginFontReencode\r\n/Courier-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Oblique exch definefont pop\r\n/Courier-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-BoldOblique exch definefont pop\r\n/Courier-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Bold exch definefont pop\r\n/Helvetica findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica exch definefont pop\r\n/Helvetica-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Oblique exch definefont pop\r\n/Helvetica-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Bold exch definefont pop\r\n/Helvetica-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-BoldOblique exch definefont pop\r\n/Times-Roman findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Roman exch definefont pop\r\n/Times-Italic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Italic exch definefont pop\r\n/Times-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Bold exch definefont pop\r\n/Times-BoldItalic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-BoldItalic exch definefont pop\r\n/Courier findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier exch definefont pop\r\n%FOPEndFontReencode\r\n%%EndProlog\r\n%%Page: 1 1\r\n%%PageBoundingBox: 0 0 420 315\r\n%%BeginPageSetup\r\n[1 0 0 -1 0 315] CT\r\n%%EndPageSetup\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n154 698 M\n1014 698 L\n1014 63 L\n154 63 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n154 698 M\n1014 698 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n154 63 M\n1014 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n154 698 M\n154 689.4 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n333.167 698 M\n333.167 689.4 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n512.333 698 M\n512.333 689.4 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n691.5 698 M\n691.5 689.4 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n870.667 698 M\n870.667 689.4 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n154 63 M\n154 71.6 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n333.167 63 M\n333.167 71.6 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n512.333 63 M\n512.333 71.6 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n691.5 63 M\n691.5 71.6 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n870.667 63 M\n870.667 71.6 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 57.75 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-13.5 49 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 124.9375 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-13.5 49 moveto \r\n1 -1 scale\r\n(5) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 192.12499 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(10) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 259.3125 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(15) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 326.50001 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(20) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 219.00016 291] CT\r\n0.149 GC\r\nN\r\n-11.894 43.847 M\n-11.894 43.534 -11.847 43.378 QT\n-4.16 12.737 L\n-3.957 11.831 -3.91 11.315 QT\n-3.91 10.456 -7.347 10.456 QT\n-7.894 10.456 -7.894 9.753 QT\n-7.863 9.628 -7.769 9.292 QT\n-7.675 8.956 -7.535 8.776 QT\n-7.394 8.597 -7.144 8.597 QT\n-0.003 8.019 L\n0.153 8.019 L\n0.153 8.081 0.34 8.167 QT\n0.528 8.253 0.543 8.284 QT\n0.653 8.55 0.653 8.706 QT\n-4.91 30.847 L\n-3.003 30.05 -0.089 27.034 QT\n2.825 24.019 4.465 22.698 QT\n6.106 21.378 8.59 21.378 QT\n10.075 21.378 11.106 22.386 QT\n12.137 23.394 12.137 24.878 QT\n12.137 25.8 11.754 26.589 QT\n11.372 27.378 10.668 27.87 QT\n9.965 28.362 9.028 28.362 QT\n8.184 28.362 7.598 27.831 QT\n7.012 27.3 7.012 26.456 QT\n7.012 25.19 7.911 24.323 QT\n8.809 23.456 10.075 23.456 QT\n9.559 22.753 8.497 22.753 QT\n6.918 22.753 5.45 23.659 QT\n3.981 24.565 2.293 26.261 QT\n0.606 27.956 -0.793 29.362 QT\n-2.191 30.769 -3.394 31.503 QT\n-0.253 31.862 2.051 33.144 QT\n4.356 34.425 4.356 37.065 QT\n4.356 37.612 4.137 38.44 QT\n3.684 40.425 3.684 41.612 QT\n3.684 44.003 5.309 44.003 QT\n7.231 44.003 8.223 41.901 QT\n9.215 39.8 9.856 37.003 QT\n9.965 36.706 10.309 36.706 QT\n10.918 36.706 L\n11.137 36.706 11.278 36.831 QT\n11.418 36.956 11.418 37.159 QT\n11.418 37.222 11.372 37.315 QT\n9.372 45.394 5.2 45.394 QT\n3.7 45.394 2.551 44.698 QT\n1.403 44.003 0.778 42.8 QT\n0.153 41.597 0.153 40.097 QT\n0.153 39.237 0.387 38.331 QT\n0.543 37.706 0.543 37.159 QT\n0.543 35.128 -1.269 34.065 QT\n-3.082 33.003 -5.41 32.769 QT\n-8.097 43.581 L\n-8.3 44.378 -8.894 44.886 QT\n-9.488 45.394 -10.269 45.394 QT\n-10.941 45.394 -11.418 44.94 QT\n-11.894 44.487 -11.894 43.847 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n154 698 M\n154 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 698 M\n1014 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n154 698 M\n162.6 698 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n154 571 M\n162.6 571 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n154 444 M\n162.6 444 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n154 317 M\n162.6 317 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n154 190 M\n162.6 190 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n154 63 M\n162.6 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 698 M\n1005.4 698 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 571 M\n1005.4 571 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 444 M\n1005.4 444 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 317 M\n1005.4 317 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 190 M\n1005.4 190 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 63 M\n1005.4 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 52.15 261.75] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-67 19 moveto \r\n1 -1 scale\r\n(0.2) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 52.15 214.125] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-67 19 moveto \r\n1 -1 scale\r\n(0.4) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 52.15 166.5] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-67 19 moveto \r\n1 -1 scale\r\n(0.6) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 52.15 118.875] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-67 19 moveto \r\n1 -1 scale\r\n(0.8) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 52.15 71.25] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 19 moveto \r\n1 -1 scale\r\n(1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 52.15 23.62499] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-67 19 moveto \r\n1 -1 scale\r\n(1.2) t \r\nGR\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24 142.68737] CT\r\n0.149 GC\r\nN\r\n-53.732 -11.622 M\n-52.623 -9.7 -49.857 -9.7 QT\n-47.342 -9.7 -45.506 -11.458 QT\n-43.67 -13.216 -42.545 -15.716 QT\n-41.42 -18.216 -40.795 -20.825 QT\n-43.154 -18.606 -45.889 -18.606 QT\n-47.982 -18.606 -49.459 -19.333 QT\n-50.935 -20.06 -51.756 -21.497 QT\n-52.576 -22.935 -52.576 -24.966 QT\n-52.576 -26.7 -52.107 -28.528 QT\n-51.639 -30.356 -50.795 -32.591 QT\n-49.951 -34.825 -49.342 -36.481 QT\n-48.639 -38.435 -48.639 -39.669 QT\n-48.639 -41.247 -49.795 -41.247 QT\n-51.904 -41.247 -53.256 -39.091 QT\n-54.607 -36.935 -55.264 -34.263 QT\n-55.357 -33.919 -55.701 -33.919 QT\n-56.326 -33.919 L\n-56.764 -33.919 -56.764 -34.419 QT\n-56.764 -34.575 L\n-55.904 -37.731 -54.146 -40.177 QT\n-52.389 -42.622 -49.701 -42.622 QT\n-47.81 -42.622 -46.506 -41.38 QT\n-45.201 -40.138 -45.201 -38.216 QT\n-45.201 -37.231 -45.639 -36.153 QT\n-45.873 -35.497 -46.701 -33.325 QT\n-47.529 -31.153 -47.967 -29.731 QT\n-48.404 -28.31 -48.685 -26.935 QT\n-48.967 -25.56 -48.967 -24.2 QT\n-48.967 -22.435 -48.217 -21.216 QT\n-47.467 -19.997 -45.842 -19.997 QT\n-42.56 -19.997 -39.935 -24.013 QT\n-35.935 -40.341 L\n-35.748 -41.044 -35.099 -41.544 QT\n-34.451 -42.044 -33.701 -42.044 QT\n-33.06 -42.044 -32.576 -41.63 QT\n-32.092 -41.216 -32.092 -40.544 QT\n-32.092 -40.247 -32.154 -40.138 QT\n-37.404 -19.044 L\n-38.107 -16.325 -39.967 -13.841 QT\n-41.826 -11.356 -44.451 -9.841 QT\n-47.076 -8.325 -49.935 -8.325 QT\n-51.295 -8.325 -52.646 -8.856 QT\n-53.998 -9.388 -54.826 -10.45 QT\n-55.654 -11.513 -55.654 -12.935 QT\n-55.654 -14.388 -54.795 -15.45 QT\n-53.935 -16.513 -52.514 -16.513 QT\n-51.67 -16.513 -51.084 -15.981 QT\n-50.498 -15.45 -50.498 -14.591 QT\n-50.498 -13.372 -51.404 -12.466 QT\n-52.31 -11.56 -53.529 -11.56 QT\n-53.576 -11.591 -53.631 -11.606 QT\n-53.685 -11.622 -53.732 -11.622 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24 142.68737] CT\r\n0.149 GC\r\nN\r\n-13.686 -6.06 M\n-16.639 -8.388 -18.772 -11.403 QT\n-20.905 -14.419 -22.264 -17.833 QT\n-23.624 -21.247 -24.295 -24.974 QT\n-24.967 -28.7 -24.967 -32.45 QT\n-24.967 -36.247 -24.295 -39.974 QT\n-23.624 -43.7 -22.241 -47.146 QT\n-20.858 -50.591 -18.709 -53.591 QT\n-16.561 -56.591 -13.686 -58.841 QT\n-13.686 -58.95 -13.436 -58.95 QT\n-12.936 -58.95 L\n-12.78 -58.95 -12.655 -58.81 QT\n-12.53 -58.669 -12.53 -58.481 QT\n-12.53 -58.247 -12.624 -58.153 QT\n-15.217 -55.606 -16.936 -52.708 QT\n-18.655 -49.81 -19.702 -46.536 QT\n-20.749 -43.263 -21.217 -39.755 QT\n-21.686 -36.247 -21.686 -32.45 QT\n-21.686 -15.606 -12.686 -6.856 QT\n-12.53 -6.7 -12.53 -6.419 QT\n-12.53 -6.294 -12.67 -6.122 QT\n-12.811 -5.95 -12.936 -5.95 QT\n-13.436 -5.95 L\n-13.686 -5.95 -13.686 -6.06 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24 142.68737] CT\r\n0.149 GC\r\nN\r\n-5.289 -20.106 M\n-5.289 -20.419 -5.242 -20.575 QT\n-1.289 -36.388 L\n-0.898 -37.856 -0.898 -38.966 QT\n-0.898 -41.247 -2.445 -41.247 QT\n-4.101 -41.247 -4.906 -39.271 QT\n-5.711 -37.294 -6.461 -34.263 QT\n-6.461 -34.106 -6.617 -34.013 QT\n-6.773 -33.919 -6.898 -33.919 QT\n-7.523 -33.919 L\n-7.695 -33.919 -7.828 -34.114 QT\n-7.961 -34.31 -7.961 -34.466 QT\n-7.383 -36.778 -6.859 -38.38 QT\n-6.336 -39.981 -5.203 -41.302 QT\n-4.07 -42.622 -2.398 -42.622 QT\n-0.398 -42.622 1.125 -41.364 QT\n2.649 -40.106 2.649 -38.169 QT\n4.227 -40.247 6.352 -41.435 QT\n8.477 -42.622 10.852 -42.622 QT\n13.367 -42.622 15.188 -41.341 QT\n17.008 -40.06 17.008 -37.7 QT\n18.649 -40.013 20.836 -41.317 QT\n23.024 -42.622 25.602 -42.622 QT\n28.352 -42.622 30.016 -41.13 QT\n31.68 -39.638 31.68 -36.903 QT\n31.68 -34.731 30.711 -31.653 QT\n29.742 -28.575 28.305 -24.763 QT\n27.539 -22.935 27.539 -21.575 QT\n27.539 -19.997 28.789 -19.997 QT\n30.852 -19.997 32.227 -22.224 QT\n33.602 -24.45 34.164 -26.997 QT\n34.32 -27.294 34.617 -27.294 QT\n35.227 -27.294 L\n35.445 -27.294 35.586 -27.153 QT\n35.727 -27.013 35.727 -26.841 QT\n35.727 -26.778 35.68 -26.685 QT\n34.945 -23.685 33.149 -21.146 QT\n31.352 -18.606 28.664 -18.606 QT\n26.789 -18.606 25.477 -19.888 QT\n24.164 -21.169 24.164 -22.997 QT\n24.164 -23.935 24.602 -25.075 QT\n26.102 -29.06 27.094 -32.192 QT\n28.086 -35.325 28.086 -37.7 QT\n28.086 -39.185 27.492 -40.216 QT\n26.899 -41.247 25.508 -41.247 QT\n22.602 -41.247 20.484 -39.474 QT\n18.367 -37.7 16.805 -34.778 QT\n16.711 -34.263 16.649 -33.981 QT\n13.242 -20.372 L\n13.055 -19.638 12.422 -19.122 QT\n11.789 -18.606 11.008 -18.606 QT\n10.383 -18.606 9.906 -19.021 QT\n9.43 -19.435 9.43 -20.106 QT\n9.43 -20.419 9.477 -20.575 QT\n12.867 -34.075 L\n13.414 -36.247 13.414 -37.7 QT\n13.414 -39.185 12.805 -40.216 QT\n12.195 -41.247 10.758 -41.247 QT\n8.805 -41.247 7.18 -40.396 QT\n5.555 -39.544 4.336 -38.13 QT\n3.117 -36.716 2.102 -34.778 QT\n-1.492 -20.372 L\n-1.664 -19.638 -2.305 -19.122 QT\n-2.945 -18.606 -3.711 -18.606 QT\n-4.367 -18.606 -4.828 -19.021 QT\n-5.289 -19.435 -5.289 -20.106 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24 142.68737] CT\r\n0.149 GC\r\nN\r\n40.882 -5.95 M\n40.413 -5.95 40.413 -6.419 QT\n40.413 -6.653 40.523 -6.747 QT\n49.585 -15.606 49.585 -32.45 QT\n49.585 -49.294 40.632 -58.044 QT\n40.413 -58.169 40.413 -58.481 QT\n40.413 -58.669 40.562 -58.81 QT\n40.71 -58.95 40.882 -58.95 QT\n41.382 -58.95 L\n41.538 -58.95 41.632 -58.841 QT\n45.445 -55.841 47.976 -51.544 QT\n50.507 -47.247 51.687 -42.388 QT\n52.867 -37.528 52.867 -32.45 QT\n52.867 -28.7 52.234 -25.06 QT\n51.601 -21.419 50.218 -17.888 QT\n48.835 -14.356 46.71 -11.372 QT\n44.585 -8.388 41.632 -6.06 QT\n41.538 -5.95 41.382 -5.95 QT\n40.882 -5.95 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 666.435 M\n189.833 614.964 L\n225.667 572.908 L\n261.5 525.496 L\n297.333 462.287 L\n333.167 383.754 L\n369 303.948 L\n404.833 232.248 L\n440.667 170.246 L\n476.5 125.795 L\n512.333 109.864 L\n548.167 121.16 L\n584 145.694 L\n619.833 175.008 L\n655.667 204.18 L\n691.5 230.526 L\n727.333 252.799 L\n763.167 270.679 L\n799 284.411 L\n834.833 294.556 L\n870.667 301.808 L\n906.5 306.872 L\n942.333 310.386 L\n978.167 312.881 L\n1014 314.783 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 666.434 M\n189.833 614.964 L\n225.667 535.784 L\n261.5 442.74 L\n297.333 353.019 L\n333.167 265.413 L\n369 187.746 L\n404.833 132.376 L\n440.667 105.441 L\n476.5 116.525 L\n512.333 167.956 L\n548.167 240.529 L\n584 306.384 L\n619.833 358.267 L\n655.667 396.899 L\n691.5 425.093 L\n727.333 445.594 L\n763.167 460.515 L\n799 471.35 L\n834.833 479.152 L\n870.667 484.694 L\n906.5 488.577 L\n942.333 491.29 L\n978.167 493.233 L\n1014 494.729 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 666.435 M\n189.833 614.964 L\n225.667 562.691 L\n261.5 495.881 L\n297.333 410.036 L\n333.167 317.222 L\n369 233.962 L\n404.833 172.885 L\n440.667 140.943 L\n476.5 150.495 L\n512.333 186.12 L\n548.167 225.258 L\n584 259.671 L\n619.833 288.545 L\n655.667 313.029 L\n691.5 333.865 L\n727.333 351.292 L\n763.167 365.435 L\n799 376.515 L\n834.833 384.888 L\n870.667 391.006 L\n906.5 395.358 L\n942.333 398.418 L\n978.167 400.609 L\n1014 402.29 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 666.435 M\n189.833 614.964 L\n225.667 548.115 L\n261.5 474.46 L\n297.333 391.874 L\n333.167 302.924 L\n369 223.625 L\n404.833 166.22 L\n440.667 138.3 L\n476.5 152.115 L\n512.333 204.531 L\n548.167 270.912 L\n584 332.127 L\n619.833 380.8 L\n655.667 416.921 L\n691.5 442.943 L\n727.333 461.486 L\n763.167 474.652 L\n799 483.971 L\n834.833 490.527 L\n870.667 495.096 L\n906.5 498.255 L\n942.333 500.448 L\n978.167 502.018 L\n1014 503.237 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 558.206 L\n261.5 489.083 L\n297.333 405.539 L\n333.167 315.641 L\n369 234.484 L\n404.833 174.357 L\n440.667 142.233 L\n476.5 150.495 L\n512.333 187.392 L\n548.167 232.999 L\n584 274.686 L\n619.833 308.892 L\n655.667 336.429 L\n691.5 358.714 L\n727.333 376.697 L\n763.167 390.961 L\n799 401.975 L\n834.833 410.218 L\n870.667 416.201 L\n906.5 420.438 L\n942.333 423.409 L\n978.167 425.536 L\n1014 427.168 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 551.524 L\n261.5 479.736 L\n297.333 396.298 L\n333.167 307.085 L\n369 227.181 L\n404.833 169.056 L\n440.667 139.793 L\n476.5 151.381 L\n512.333 201.166 L\n548.167 264.418 L\n584 322.638 L\n619.833 368.77 L\n655.667 403.002 L\n691.5 427.84 L\n727.333 445.79 L\n763.167 458.763 L\n799 468.109 L\n834.833 474.783 L\n870.667 479.49 L\n906.5 482.773 L\n942.333 485.062 L\n978.167 486.706 L\n1014 487.981 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 556.134 L\n261.5 486.37 L\n297.333 403.213 L\n333.167 313.757 L\n369 233.074 L\n404.833 173.456 L\n440.667 141.904 L\n476.5 150.686 L\n512.333 190.118 L\n548.167 239.759 L\n584 285.496 L\n619.833 322.674 L\n655.667 351.887 L\n691.5 374.849 L\n727.333 392.906 L\n763.167 406.955 L\n799 417.658 L\n834.833 425.599 L\n870.667 431.33 L\n906.5 435.376 L\n942.333 438.21 L\n978.167 440.238 L\n1014 441.797 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 552.964 L\n261.5 481.746 L\n297.333 398.338 L\n333.167 309.046 L\n369 228.92 L\n404.833 170.368 L\n440.667 140.446 L\n476.5 151.181 L\n512.333 198.926 L\n548.167 259.786 L\n584 315.818 L\n619.833 360.242 L\n655.667 393.36 L\n691.5 417.635 L\n727.333 435.429 L\n763.167 448.48 L\n799 458.004 L\n834.833 464.87 L\n870.667 469.744 L\n906.5 473.154 L\n942.333 475.537 L\n978.167 477.247 L\n1014 478.571 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 555.258 L\n261.5 485.233 L\n297.333 402.154 L\n333.167 312.842 L\n369 232.345 L\n404.833 172.961 L\n440.667 141.702 L\n476.5 150.775 L\n512.333 191.918 L\n548.167 244.076 L\n584 292.209 L\n619.833 331.082 L\n655.667 361.207 L\n691.5 384.486 L\n727.333 402.509 L\n763.167 416.362 L\n799 426.826 L\n834.833 434.547 L\n870.667 440.102 L\n906.5 444.016 L\n942.333 446.756 L\n978.167 448.718 L\n1014 450.228 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 553.605 L\n261.5 482.676 L\n297.333 399.339 L\n333.167 310.046 L\n369 229.829 L\n404.833 171.063 L\n440.667 140.791 L\n476.5 151.071 L\n512.333 197.467 L\n548.167 256.671 L\n584 311.209 L\n619.833 354.532 L\n655.667 386.999 L\n691.5 411.005 L\n727.333 428.784 L\n763.167 441.954 L\n799 451.639 L\n834.833 458.661 L\n870.667 463.661 L\n906.5 467.167 L\n942.333 469.618 L\n978.167 471.377 L\n1014 472.737 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.843 L\n261.5 484.652 L\n297.333 401.566 L\n333.167 312.297 L\n369 231.882 L\n404.833 172.627 L\n440.667 141.553 L\n476.5 150.83 L\n512.333 193.069 L\n548.167 246.78 L\n584 296.354 L\n619.833 336.228 L\n655.667 366.876 L\n691.5 390.318 L\n727.333 408.294 L\n763.167 422.006 L\n799 432.308 L\n834.833 439.883 L\n870.667 445.322 L\n906.5 449.15 L\n942.333 451.829 L\n978.167 453.748 L\n1014 455.226 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 553.919 L\n261.5 483.16 L\n297.333 399.879 L\n333.167 310.594 L\n369 230.334 L\n404.833 171.45 L\n440.667 140.984 L\n476.5 151.012 L\n512.333 196.545 L\n548.167 254.659 L\n584 308.214 L\n619.833 350.837 L\n655.667 382.914 L\n691.5 406.78 L\n727.333 424.579 L\n763.167 437.845 L\n799 447.648 L\n834.833 454.778 L\n870.667 459.865 L\n906.5 463.435 L\n942.333 465.932 L\n978.167 467.723 L\n1014 469.106 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.628 L\n261.5 484.326 L\n297.333 401.217 L\n333.167 311.958 L\n369 231.584 L\n404.833 172.407 L\n440.667 141.45 L\n476.5 150.865 L\n512.333 193.796 L\n548.167 248.464 L\n584 298.913 L\n619.833 339.391 L\n655.667 370.349 L\n691.5 393.884 L\n727.333 411.823 L\n763.167 425.44 L\n799 435.638 L\n834.833 443.119 L\n870.667 448.484 L\n906.5 452.257 L\n942.333 454.898 L\n978.167 456.79 L\n1014 458.248 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.087 L\n261.5 483.429 L\n297.333 400.187 L\n333.167 310.91 L\n369 230.625 L\n404.833 171.675 L\n440.667 141.095 L\n476.5 150.978 L\n512.333 195.967 L\n548.167 253.379 L\n584 306.305 L\n619.833 348.486 L\n655.667 380.325 L\n691.5 404.113 L\n727.333 421.933 L\n763.167 435.267 L\n799 445.149 L\n834.833 452.35 L\n870.667 457.494 L\n906.5 461.106 L\n942.333 463.632 L\n978.167 465.443 L\n1014 466.842 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.507 L\n261.5 484.134 L\n297.333 401.003 L\n333.167 311.746 L\n369 231.394 L\n404.833 172.264 L\n440.667 141.383 L\n476.5 150.888 L\n512.333 194.252 L\n548.167 249.51 L\n584 300.496 L\n619.833 341.342 L\n655.667 372.49 L\n691.5 396.078 L\n727.333 413.991 L\n763.167 427.549 L\n799 437.68 L\n834.833 445.102 L\n870.667 450.42 L\n906.5 454.16 L\n942.333 456.776 L\n978.167 458.651 L\n1014 460.096 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.181 L\n261.5 483.586 L\n297.333 400.368 L\n333.167 311.097 L\n369 230.798 L\n404.833 171.808 L\n440.667 141.161 L\n476.5 150.958 L\n512.333 195.606 L\n548.167 252.573 L\n584 305.099 L\n619.833 347.003 L\n655.667 378.695 L\n691.5 402.439 L\n727.333 420.276 L\n763.167 433.655 L\n799 443.587 L\n834.833 450.834 L\n870.667 456.014 L\n906.5 459.652 L\n942.333 462.197 L\n978.167 464.022 L\n1014 465.43 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.436 L\n261.5 484.018 L\n297.333 400.871 L\n333.167 311.613 L\n369 231.273 L\n404.833 172.172 L\n440.667 141.339 L\n476.5 150.902 L\n512.333 194.537 L\n548.167 250.16 L\n584 301.477 L\n619.833 342.549 L\n655.667 373.813 L\n691.5 397.434 L\n727.333 415.331 L\n763.167 428.851 L\n799 438.94 L\n834.833 446.325 L\n870.667 451.613 L\n906.5 455.332 L\n942.333 457.933 L\n978.167 459.797 L\n1014 461.235 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.237 L\n261.5 483.68 L\n297.333 400.478 L\n333.167 311.21 L\n369 230.902 L\n404.833 171.888 L\n440.667 141.2 L\n476.5 150.946 L\n512.333 195.381 L\n548.167 252.068 L\n584 304.342 L\n619.833 346.072 L\n655.667 377.674 L\n691.5 401.391 L\n727.333 419.239 L\n763.167 432.647 L\n799 442.612 L\n834.833 449.888 L\n870.667 455.09 L\n906.5 458.745 L\n942.333 461.302 L\n978.167 463.135 L\n1014 464.55 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.394 L\n261.5 483.947 L\n297.333 400.789 L\n333.167 311.529 L\n369 231.197 L\n404.833 172.114 L\n440.667 141.311 L\n476.5 150.911 L\n512.333 194.715 L\n548.167 250.564 L\n584 302.085 L\n619.833 343.297 L\n655.667 374.633 L\n691.5 398.274 L\n727.333 416.161 L\n763.167 429.657 L\n799 439.719 L\n834.833 447.081 L\n870.667 452.352 L\n906.5 456.057 L\n942.333 458.649 L\n978.167 460.506 L\n1014 461.939 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.271 L\n261.5 483.737 L\n297.333 400.545 L\n333.167 311.279 L\n369 230.966 L\n404.833 171.937 L\n440.667 141.225 L\n476.5 150.939 L\n512.333 195.241 L\n548.167 251.752 L\n584 303.869 L\n619.833 345.49 L\n655.667 377.036 L\n691.5 400.736 L\n727.333 418.593 L\n763.167 432.019 L\n799 442.004 L\n834.833 449.298 L\n870.667 454.514 L\n906.5 458.18 L\n942.333 460.744 L\n978.167 462.582 L\n1014 464.001 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.368 L\n261.5 483.902 L\n297.333 400.738 L\n333.167 311.477 L\n369 231.149 L\n404.833 172.077 L\n440.667 141.293 L\n476.5 150.917 L\n512.333 194.826 L\n548.167 250.815 L\n584 302.463 L\n619.833 343.762 L\n655.667 375.142 L\n691.5 398.796 L\n727.333 416.676 L\n763.167 430.157 L\n799 440.203 L\n834.833 447.551 L\n870.667 452.81 L\n906.5 456.507 L\n942.333 459.093 L\n978.167 460.946 L\n1014 462.376 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.292 L\n261.5 483.773 L\n297.333 400.586 L\n333.167 311.321 L\n369 231.005 L\n404.833 171.967 L\n440.667 141.239 L\n476.5 150.934 L\n512.333 195.153 L\n548.167 251.555 L\n584 303.573 L\n619.833 345.127 L\n655.667 376.637 L\n691.5 400.328 L\n727.333 418.189 L\n763.167 431.627 L\n799 441.625 L\n834.833 448.93 L\n870.667 454.155 L\n906.5 457.828 L\n942.333 460.396 L\n978.167 462.238 L\n1014 463.658 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.352 L\n261.5 483.875 L\n297.333 400.706 L\n333.167 311.445 L\n369 231.119 L\n404.833 172.055 L\n440.667 141.282 L\n476.5 150.921 L\n512.333 194.895 L\n548.167 250.972 L\n584 302.697 L\n619.833 344.051 L\n655.667 375.458 L\n691.5 399.12 L\n727.333 416.996 L\n763.167 430.468 L\n799 440.504 L\n834.833 447.842 L\n870.667 453.095 L\n906.5 456.786 L\n942.333 459.368 L\n978.167 461.219 L\n1014 462.647 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.305 L\n261.5 483.794 L\n297.333 400.612 L\n333.167 311.348 L\n369 231.03 L\n404.833 171.986 L\n440.667 141.249 L\n476.5 150.931 L\n512.333 195.099 L\n548.167 251.432 L\n584 303.389 L\n619.833 344.9 L\n655.667 376.389 L\n691.5 400.073 L\n727.333 417.938 L\n763.167 431.383 L\n799 441.389 L\n834.833 448.701 L\n870.667 453.932 L\n906.5 457.608 L\n942.333 460.179 L\n978.167 462.023 L\n1014 463.445 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.342 L\n261.5 483.858 L\n297.333 400.687 L\n333.167 311.424 L\n369 231.1 L\n404.833 172.04 L\n440.667 141.275 L\n476.5 150.923 L\n512.333 194.938 L\n548.167 251.069 L\n584 302.843 L\n619.833 344.23 L\n655.667 375.655 L\n691.5 399.321 L\n727.333 417.195 L\n763.167 430.661 L\n799 440.691 L\n834.833 448.024 L\n870.667 453.271 L\n906.5 456.96 L\n942.333 459.54 L\n978.167 461.389 L\n1014 462.816 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.313 L\n261.5 483.808 L\n297.333 400.628 L\n333.167 311.364 L\n369 231.045 L\n404.833 171.998 L\n440.667 141.254 L\n476.5 150.929 L\n512.333 195.065 L\n548.167 251.355 L\n584 303.274 L\n619.833 344.759 L\n655.667 376.234 L\n691.5 399.915 L\n727.333 417.781 L\n763.167 431.23 L\n799 441.241 L\n834.833 448.558 L\n870.667 453.792 L\n906.5 457.471 L\n942.333 460.044 L\n978.167 461.889 L\n1014 463.312 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.336 L\n261.5 483.848 L\n297.333 400.674 L\n333.167 311.412 L\n369 231.089 L\n404.833 172.031 L\n440.667 141.271 L\n476.5 150.924 L\n512.333 194.964 L\n548.167 251.129 L\n584 302.934 L\n619.833 344.342 L\n655.667 375.777 L\n691.5 399.446 L\n727.333 417.319 L\n763.167 430.781 L\n799 440.807 L\n834.833 448.136 L\n870.667 453.381 L\n906.5 457.068 L\n942.333 459.646 L\n978.167 461.495 L\n1014 462.921 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.318 L\n261.5 483.817 L\n297.333 400.638 L\n333.167 311.374 L\n369 231.054 L\n404.833 172.005 L\n440.667 141.258 L\n476.5 150.928 L\n512.333 195.043 L\n548.167 251.308 L\n584 303.202 L\n619.833 344.671 L\n655.667 376.138 L\n691.5 399.816 L\n727.333 417.683 L\n763.167 431.135 L\n799 441.15 L\n834.833 448.469 L\n870.667 453.706 L\n906.5 457.386 L\n942.333 459.96 L\n978.167 461.806 L\n1014 463.23 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.332 L\n261.5 483.841 L\n297.333 400.667 L\n333.167 311.404 L\n369 231.082 L\n404.833 172.026 L\n440.667 141.268 L\n476.5 150.925 L\n512.333 194.981 L\n548.167 251.167 L\n584 302.991 L\n619.833 344.411 L\n655.667 375.853 L\n691.5 399.524 L\n727.333 417.395 L\n763.167 430.856 L\n799 440.879 L\n834.833 448.206 L\n870.667 453.45 L\n906.5 457.135 L\n942.333 459.712 L\n978.167 461.56 L\n1014 462.986 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.321 L\n261.5 483.822 L\n297.333 400.644 L\n333.167 311.38 L\n369 231.06 L\n404.833 172.009 L\n440.667 141.26 L\n476.5 150.928 L\n512.333 195.03 L\n548.167 251.278 L\n584 303.157 L\n619.833 344.616 L\n655.667 376.077 L\n691.5 399.754 L\n727.333 417.622 L\n763.167 431.076 L\n799 441.092 L\n834.833 448.413 L\n870.667 453.652 L\n906.5 457.333 L\n942.333 459.908 L\n978.167 461.754 L\n1014 463.178 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.33 L\n261.5 483.837 L\n297.333 400.662 L\n333.167 311.399 L\n369 231.077 L\n404.833 172.023 L\n440.667 141.266 L\n476.5 150.926 L\n512.333 194.991 L\n548.167 251.19 L\n584 303.026 L\n619.833 344.454 L\n655.667 375.9 L\n691.5 399.573 L\n727.333 417.443 L\n763.167 430.902 L\n799 440.924 L\n834.833 448.25 L\n870.667 453.492 L\n906.5 457.176 L\n942.333 459.754 L\n978.167 461.601 L\n1014 463.026 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 666.435 M\n189.833 614.965 L\n225.667 554.323 L\n261.5 483.825 L\n297.333 400.648 L\n333.167 311.384 L\n369 231.064 L\n404.833 172.012 L\n440.667 141.261 L\n476.5 150.927 L\n512.333 195.022 L\n548.167 251.259 L\n584 303.129 L\n619.833 344.582 L\n655.667 376.04 L\n691.5 399.716 L\n727.333 417.585 L\n763.167 431.04 L\n799 441.057 L\n834.833 448.379 L\n870.667 453.618 L\n906.5 457.3 L\n942.333 459.875 L\n978.167 461.721 L\n1014 463.146 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 279.46875 71.25] CT\r\nN\r\n-0.641 18.348 M\n-0.641 17.176 0.172 16.317 QT\n0.984 15.457 2.156 15.457 QT\n2.938 15.457 3.461 15.942 QT\n3.984 16.426 3.984 17.192 QT\n3.984 18.114 3.414 18.848 QT\n2.844 19.582 1.969 19.817 QT\n2.813 20.129 3.656 20.129 QT\n5.703 20.129 7.203 18.239 QT\n8.703 16.348 9.313 14.004 QT\n13.828 -4.043 L\n14.156 -5.433 14.156 -6.386 QT\n14.156 -8.449 12.734 -8.449 QT\n10.625 -8.449 9.039 -6.543 QT\n7.453 -4.636 6.469 -2.121 QT\n6.375 -1.824 6.094 -1.824 QT\n5.531 -1.824 L\n5.141 -1.824 5.141 -2.261 QT\n5.141 -2.402 L\n6.219 -5.293 8.211 -7.496 QT\n10.203 -9.699 12.828 -9.699 QT\n14.813 -9.699 16.094 -8.457 QT\n17.375 -7.215 17.375 -5.293 QT\n17.375 -4.605 17.234 -3.933 QT\n12.688 14.317 L\n12.188 16.254 10.805 17.871 QT\n9.422 19.489 7.5 20.426 QT\n5.578 21.364 3.563 21.364 QT\n1.953 21.364 0.656 20.59 QT\n-0.641 19.817 -0.641 18.348 QT\ncp\n14.563 -17.574 M\n14.563 -18.621 15.383 -19.418 QT\n16.203 -20.215 17.234 -20.215 QT\n18.047 -20.215 18.578 -19.715 QT\n19.109 -19.215 19.109 -18.433 QT\n19.109 -17.355 18.25 -16.55 QT\n17.391 -15.746 16.359 -15.746 QT\n15.594 -15.746 15.078 -16.285 QT\n14.563 -16.824 14.563 -17.574 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 279.46875 71.25] CT\r\nN\r\n39.457 5.145 M\n39.066 5.145 38.808 4.84 QT\n38.55 4.535 38.55 4.176 QT\n38.55 3.785 38.808 3.504 QT\n39.066 3.223 39.457 3.223 QT\n69.597 3.223 L\n69.957 3.223 70.215 3.504 QT\n70.472 3.785 70.472 4.176 QT\n70.472 4.535 70.215 4.84 QT\n69.957 5.145 69.597 5.145 QT\n39.457 5.145 L\ncp\n39.457 -4.183 M\n39.066 -4.183 38.808 -4.465 QT\n38.55 -4.746 38.55 -5.152 QT\n38.55 -5.496 38.808 -5.8 QT\n39.066 -6.105 39.457 -6.105 QT\n69.597 -6.105 L\n69.957 -6.105 70.215 -5.8 QT\n70.472 -5.496 70.472 -5.152 QT\n70.472 -4.746 70.215 -4.465 QT\n69.957 -4.183 69.597 -4.183 QT\n39.457 -4.183 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 279.46875 71.25] CT\r\nN\r\n90.967 11.52 M\n90.967 9.832 L\n96.967 9.832 96.967 8.301 QT\n96.967 -16.886 L\n94.483 -15.699 90.686 -15.699 QT\n90.686 -17.386 L\n96.576 -17.386 99.576 -20.449 QT\n100.248 -20.449 L\n100.42 -20.449 100.569 -20.324 QT\n100.717 -20.199 100.717 -20.027 QT\n100.717 8.301 L\n100.717 9.832 106.717 9.832 QT\n106.717 11.52 L\n90.967 11.52 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 83.28125 95.06251] CT\r\nN\r\n/f946251025{-0.641 18.348 M\n-0.641 17.176 0.172 16.317 QT\n0.984 15.457 2.156 15.457 QT\n2.938 15.457 3.461 15.942 QT\n3.984 16.426 3.984 17.192 QT\n3.984 18.114 3.414 18.848 QT\n2.844 19.582 1.969 19.817 QT\n2.813 20.129 3.656 20.129 QT\n5.703 20.129 7.203 18.239 QT\n8.703 16.348 9.313 14.004 QT\n13.828 -4.043 L\n14.156 -5.433 14.156 -6.386 QT\n14.156 -8.449 12.734 -8.449 QT\n10.625 -8.449 9.039 -6.543 QT\n7.453 -4.636 6.469 -2.121 QT\n6.375 -1.824 6.094 -1.824 QT\n5.531 -1.824 L\n5.141 -1.824 5.141 -2.261 QT\n5.141 -2.402 L\n6.219 -5.293 8.211 -7.496 QT\n10.203 -9.699 12.828 -9.699 QT\n14.813 -9.699 16.094 -8.457 QT\n17.375 -7.215 17.375 -5.293 QT\n17.375 -4.605 17.234 -3.933 QT\n12.688 14.317 L\n12.188 16.254 10.805 17.871 QT\n9.422 19.489 7.5 20.426 QT\n5.578 21.364 3.563 21.364 QT\n1.953 21.364 0.656 20.59 QT\n-0.641 19.817 -0.641 18.348 QT\ncp\n14.563 -17.574 M\n14.563 -18.621 15.383 -19.418 QT\n16.203 -20.215 17.234 -20.215 QT\n18.047 -20.215 18.578 -19.715 QT\n19.109 -19.215 19.109 -18.433 QT\n19.109 -17.355 18.25 -16.55 QT\n17.391 -15.746 16.359 -15.746 QT\n15.594 -15.746 15.078 -16.285 QT\n14.563 -16.824 14.563 -17.574 QT\ncp}def\r\nf946251025\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 83.28125 95.06251] CT\r\nN\r\n/f-1792154824{39.457 5.145 M\n39.066 5.145 38.808 4.84 QT\n38.55 4.535 38.55 4.176 QT\n38.55 3.785 38.808 3.504 QT\n39.066 3.223 39.457 3.223 QT\n69.597 3.223 L\n69.957 3.223 70.215 3.504 QT\n70.472 3.785 70.472 4.176 QT\n70.472 4.535 70.215 4.84 QT\n69.957 5.145 69.597 5.145 QT\n39.457 5.145 L\ncp\n39.457 -4.183 M\n39.066 -4.183 38.808 -4.465 QT\n38.55 -4.746 38.55 -5.152 QT\n38.55 -5.496 38.808 -5.8 QT\n39.066 -6.105 39.457 -6.105 QT\n69.597 -6.105 L\n69.957 -6.105 70.215 -5.8 QT\n70.472 -5.496 70.472 -5.152 QT\n70.472 -4.746 70.215 -4.465 QT\n69.957 -4.183 69.597 -4.183 QT\n39.457 -4.183 L\ncp}def\r\nf-1792154824\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 83.28125 95.06251] CT\r\nN\r\n/f1600933324{88.904 11.52 M\n88.904 10.223 L\n88.904 10.114 88.998 9.973 QT\n96.451 1.723 L\n98.139 -0.105 99.194 -1.347 QT\n100.248 -2.59 101.279 -4.207 QT\n102.311 -5.824 102.912 -7.504 QT\n103.514 -9.183 103.514 -11.058 QT\n103.514 -13.027 102.787 -14.816 QT\n102.061 -16.605 100.615 -17.683 QT\n99.17 -18.761 97.139 -18.761 QT\n95.045 -18.761 93.381 -17.511 QT\n91.717 -16.261 91.045 -14.261 QT\n91.233 -14.308 91.561 -14.308 QT\n92.639 -14.308 93.397 -13.582 QT\n94.154 -12.855 94.154 -11.715 QT\n94.154 -10.605 93.397 -9.847 QT\n92.639 -9.09 91.561 -9.09 QT\n90.436 -9.09 89.67 -9.871 QT\n88.904 -10.652 88.904 -11.715 QT\n88.904 -13.511 89.584 -15.097 QT\n90.264 -16.683 91.545 -17.91 QT\n92.826 -19.136 94.428 -19.793 QT\n96.029 -20.449 97.842 -20.449 QT\n100.576 -20.449 102.944 -19.293 QT\n105.311 -18.136 106.694 -16.011 QT\n108.076 -13.886 108.076 -11.058 QT\n108.076 -8.965 107.162 -7.09 QT\n106.248 -5.215 104.819 -3.683 QT\n103.389 -2.152 101.162 -0.207 QT\n98.936 1.739 98.233 2.395 QT\n92.795 7.629 L\n97.42 7.629 L\n100.811 7.629 103.1 7.567 QT\n105.389 7.504 105.529 7.395 QT\n106.092 6.785 106.67 2.957 QT\n108.076 2.957 L\n106.717 11.52 L\n88.904 11.52 L\ncp}def\r\nf1600933324\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n993 677 M\n993 553 L\n379 553 L\n379 677 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f1636705084{10.953 6.379 M\n12.594 8.473 15.055 9.676 QT\n17.516 10.879 20.156 10.879 QT\n22.391 10.879 24.289 10.004 QT\n26.188 9.129 27.602 7.559 QT\n29.016 5.989 29.781 3.996 QT\n30.547 2.004 30.547 -0.199 QT\n30.547 -0.574 30.969 -0.574 QT\n31.547 -0.574 L\n31.922 -0.574 31.922 -0.105 QT\n31.922 2.395 30.961 4.731 QT\n30 7.067 28.242 8.832 QT\n26.484 10.598 24.203 11.59 QT\n21.922 12.582 19.438 12.582 QT\n15.984 12.582 12.906 11.184 QT\n9.828 9.785 7.539 7.356 QT\n5.25 4.926 3.977 1.739 QT\n2.703 -1.449 2.703 -4.886 QT\n2.703 -8.34 3.977 -11.527 QT\n5.25 -14.715 7.539 -17.152 QT\n9.828 -19.59 12.906 -20.957 QT\n15.984 -22.324 19.438 -22.324 QT\n21.891 -22.324 24.141 -21.261 QT\n26.391 -20.199 28.078 -18.246 QT\n30.875 -22.183 L\n31.156 -22.324 31.203 -22.324 QT\n31.547 -22.324 L\n31.688 -22.324 31.805 -22.207 QT\n31.922 -22.09 31.922 -21.933 QT\n31.922 -8.965 L\n31.922 -8.543 31.547 -8.543 QT\n30.688 -8.543 L\n30.234 -8.543 30.234 -8.965 QT\n30.234 -10.355 29.688 -12.066 QT\n29.141 -13.777 28.281 -15.308 QT\n27.422 -16.84 26.297 -18.011 QT\n23.609 -20.636 20.109 -20.636 QT\n17.469 -20.636 15.039 -19.441 QT\n12.609 -18.246 10.953 -16.136 QT\n9.188 -13.886 8.508 -11.019 QT\n7.828 -8.152 7.828 -4.886 QT\n7.828 -1.636 8.508 1.246 QT\n9.188 4.129 10.953 6.379 QT\ncp}def\r\nf1636705084\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f-518588683{46.667 12.067 M\n43.792 12.067 41.331 10.598 QT\n38.87 9.129 37.44 6.668 QT\n36.01 4.207 36.01 1.301 QT\n36.01 -0.902 36.792 -2.941 QT\n37.573 -4.98 39.042 -6.59 QT\n40.51 -8.199 42.456 -9.097 QT\n44.401 -9.996 46.667 -9.996 QT\n49.62 -9.996 52.05 -8.441 QT\n54.479 -6.886 55.885 -4.269 QT\n57.292 -1.652 57.292 1.301 QT\n57.292 4.176 55.862 6.653 QT\n54.432 9.129 51.979 10.598 QT\n49.526 12.067 46.667 12.067 QT\ncp\n46.667 10.645 M\n50.51 10.645 51.8 7.856 QT\n53.089 5.067 53.089 0.754 QT\n53.089 -1.652 52.831 -3.238 QT\n52.573 -4.824 51.714 -6.105 QT\n51.167 -6.902 50.339 -7.504 QT\n49.51 -8.105 48.581 -8.418 QT\n47.651 -8.73 46.667 -8.73 QT\n45.167 -8.73 43.823 -8.05 QT\n42.479 -7.371 41.589 -6.105 QT\n40.698 -4.746 40.448 -3.121 QT\n40.198 -1.496 40.198 0.754 QT\n40.198 3.457 40.667 5.598 QT\n41.135 7.739 42.557 9.192 QT\n43.979 10.645 46.667 10.645 QT\ncp}def\r\nf-518588683\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f763322885{60.104 11.52 M\n60.104 9.832 L\n61.745 9.832 62.8 9.575 QT\n63.854 9.317 63.854 8.301 QT\n63.854 -4.793 L\n63.854 -6.09 63.464 -6.66 QT\n63.073 -7.23 62.346 -7.363 QT\n61.62 -7.496 60.104 -7.496 QT\n60.104 -9.183 L\n67.057 -9.699 L\n67.057 -5.011 L\n68.026 -7.074 69.909 -8.386 QT\n71.792 -9.699 74.026 -9.699 QT\n77.354 -9.699 79.026 -8.105 QT\n80.698 -6.511 80.698 -3.23 QT\n80.698 8.301 L\n80.698 9.317 81.753 9.575 QT\n82.807 9.832 84.448 9.832 QT\n84.448 11.52 L\n73.464 11.52 L\n73.464 9.832 L\n75.104 9.832 76.159 9.575 QT\n77.214 9.317 77.214 8.301 QT\n77.214 -3.09 L\n77.214 -5.433 76.534 -6.941 QT\n75.854 -8.449 73.745 -8.449 QT\n70.948 -8.449 69.159 -6.222 QT\n67.37 -3.996 67.37 -1.168 QT\n67.37 8.301 L\n67.37 9.317 68.425 9.575 QT\n69.479 9.832 71.089 9.832 QT\n71.089 11.52 L\n60.104 11.52 L\ncp}def\r\nf763322885\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f1813278697{95.719 11.52 M\n88.719 -6.105 L\n88.266 -6.996 87.344 -7.246 QT\n86.422 -7.496 84.922 -7.496 QT\n84.922 -9.183 L\n95 -9.183 L\n95 -7.496 L\n92.297 -7.496 92.297 -6.34 QT\n92.297 -6.152 92.344 -6.058 QT\n97.735 7.489 L\n102.594 -4.746 L\n102.735 -5.121 102.735 -5.527 QT\n102.735 -6.433 102.039 -6.965 QT\n101.344 -7.496 100.406 -7.496 QT\n100.406 -9.183 L\n108.375 -9.183 L\n108.375 -7.496 L\n106.906 -7.496 105.789 -6.816 QT\n104.672 -6.136 104.063 -4.793 QT\n97.594 11.52 L\n97.406 12.067 96.828 12.067 QT\n96.469 12.067 L\n95.891 12.067 95.719 11.52 QT\ncp}def\r\nf1813278697\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f1730672616{119.953 12.067 M\n117.031 12.067 114.578 10.528 QT\n112.125 8.989 110.735 6.418 QT\n109.344 3.848 109.344 0.989 QT\n109.344 -1.824 110.617 -4.355 QT\n111.891 -6.886 114.18 -8.441 QT\n116.469 -9.996 119.281 -9.996 QT\n121.485 -9.996 123.11 -9.261 QT\n124.735 -8.527 125.789 -7.215 QT\n126.844 -5.902 127.383 -4.121 QT\n127.922 -2.34 127.922 -0.199 QT\n127.922 0.426 127.438 0.426 QT\n113.531 0.426 L\n113.531 0.942 L\n113.531 4.926 115.141 7.785 QT\n116.75 10.645 120.375 10.645 QT\n121.86 10.645 123.11 9.989 QT\n124.36 9.332 125.289 8.16 QT\n126.219 6.989 126.547 5.66 QT\n126.594 5.489 126.719 5.364 QT\n126.844 5.239 127.016 5.239 QT\n127.438 5.239 L\n127.922 5.239 127.922 5.848 QT\n127.25 8.567 125 10.317 QT\n122.75 12.067 119.953 12.067 QT\ncp\n113.578 -0.761 M\n124.531 -0.761 L\n124.531 -2.574 124.024 -4.425 QT\n123.516 -6.277 122.344 -7.504 QT\n121.172 -8.73 119.281 -8.73 QT\n116.563 -8.73 115.071 -6.191 QT\n113.578 -3.652 113.578 -0.761 QT\ncp}def\r\nf1730672616\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f1581324804{130.584 11.52 M\n130.584 9.832 L\n132.224 9.832 133.279 9.575 QT\n134.334 9.317 134.334 8.301 QT\n134.334 -4.793 L\n134.334 -6.09 133.943 -6.66 QT\n133.552 -7.23 132.826 -7.363 QT\n132.099 -7.496 130.584 -7.496 QT\n130.584 -9.183 L\n137.443 -9.699 L\n137.443 -5.011 L\n138.224 -7.09 139.654 -8.394 QT\n141.084 -9.699 143.115 -9.699 QT\n144.552 -9.699 145.677 -8.855 QT\n146.802 -8.011 146.802 -6.621 QT\n146.802 -5.761 146.177 -5.113 QT\n145.552 -4.465 144.646 -4.465 QT\n143.755 -4.465 143.123 -5.097 QT\n142.49 -5.73 142.49 -6.621 QT\n142.49 -7.918 143.396 -8.449 QT\n143.115 -8.449 L\n141.177 -8.449 139.943 -7.043 QT\n138.709 -5.636 138.193 -3.55 QT\n137.677 -1.465 137.677 0.426 QT\n137.677 8.301 L\n137.677 9.832 142.349 9.832 QT\n142.349 11.52 L\n130.584 11.52 L\ncp}def\r\nf1581324804\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f-1655348641{149.477 15.27 M\n149.477 13.567 150.72 12.285 QT\n151.962 11.004 153.665 10.457 QT\n152.712 9.739 152.204 8.637 QT\n151.696 7.535 151.696 6.285 QT\n151.696 4.035 153.134 2.301 QT\n150.93 0.145 150.93 -2.636 QT\n150.93 -4.136 151.571 -5.449 QT\n152.212 -6.761 153.36 -7.722 QT\n154.509 -8.683 155.915 -9.191 QT\n157.321 -9.699 158.805 -9.699 QT\n161.665 -9.699 163.93 -8.027 QT\n164.915 -9.09 166.266 -9.66 QT\n167.618 -10.23 169.071 -10.23 QT\n170.102 -10.23 170.759 -9.496 QT\n171.415 -8.761 171.415 -7.73 QT\n171.415 -7.136 170.97 -6.691 QT\n170.524 -6.246 169.93 -6.246 QT\n169.321 -6.246 168.876 -6.691 QT\n168.43 -7.136 168.43 -7.73 QT\n168.43 -8.621 169.024 -8.965 QT\n166.54 -8.965 164.759 -7.261 QT\n165.618 -6.386 166.149 -5.136 QT\n166.68 -3.886 166.68 -2.636 QT\n166.68 -0.605 165.555 1.028 QT\n164.43 2.66 162.587 3.559 QT\n160.743 4.457 158.805 4.457 QT\n156.18 4.457 153.993 3.035 QT\n153.321 3.973 153.321 5.145 QT\n153.321 6.41 154.149 7.356 QT\n154.977 8.301 156.243 8.301 QT\n160.18 8.301 L\n163.04 8.301 165.337 8.817 QT\n167.634 9.332 169.196 10.887 QT\n170.759 12.442 170.759 15.27 QT\n170.759 17.379 168.977 18.778 QT\n167.196 20.176 164.72 20.793 QT\n162.243 21.41 160.134 21.41 QT\n158.009 21.41 155.524 20.793 QT\n153.04 20.176 151.259 18.778 QT\n149.477 17.379 149.477 15.27 QT\ncp\n152.165 15.27 M\n152.165 16.895 153.477 17.981 QT\n154.79 19.067 156.641 19.598 QT\n158.493 20.129 160.134 20.129 QT\n161.759 20.129 163.61 19.598 QT\n165.462 19.067 166.759 17.981 QT\n168.055 16.895 168.055 15.27 QT\n168.055 12.77 165.759 12.028 QT\n163.462 11.285 160.18 11.285 QT\n156.243 11.285 L\n155.149 11.285 154.22 11.817 QT\n153.29 12.348 152.727 13.293 QT\n152.165 14.239 152.165 15.27 QT\ncp\n158.805 3.176 M\n162.884 3.176 162.884 -2.636 QT\n162.884 -5.152 162.016 -6.777 QT\n161.149 -8.402 158.805 -8.402 QT\n156.462 -8.402 155.595 -6.777 QT\n154.727 -5.152 154.727 -2.636 QT\n154.727 -1.043 155.055 0.246 QT\n155.384 1.535 156.274 2.356 QT\n157.165 3.176 158.805 3.176 QT\ncp}def\r\nf-1655348641\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f402514587{184.087 12.067 M\n181.165 12.067 178.712 10.528 QT\n176.259 8.989 174.868 6.418 QT\n173.477 3.848 173.477 0.989 QT\n173.477 -1.824 174.751 -4.355 QT\n176.024 -6.886 178.313 -8.441 QT\n180.602 -9.996 183.415 -9.996 QT\n185.618 -9.996 187.243 -9.261 QT\n188.868 -8.527 189.923 -7.215 QT\n190.977 -5.902 191.516 -4.121 QT\n192.056 -2.34 192.056 -0.199 QT\n192.056 0.426 191.571 0.426 QT\n177.665 0.426 L\n177.665 0.942 L\n177.665 4.926 179.274 7.785 QT\n180.884 10.645 184.509 10.645 QT\n185.993 10.645 187.243 9.989 QT\n188.493 9.332 189.423 8.16 QT\n190.352 6.989 190.681 5.66 QT\n190.727 5.489 190.852 5.364 QT\n190.977 5.239 191.149 5.239 QT\n191.571 5.239 L\n192.056 5.239 192.056 5.848 QT\n191.384 8.567 189.134 10.317 QT\n186.884 12.067 184.087 12.067 QT\ncp\n177.712 -0.761 M\n188.665 -0.761 L\n188.665 -2.574 188.157 -4.425 QT\n187.649 -6.277 186.477 -7.504 QT\n185.306 -8.73 183.415 -8.73 QT\n180.696 -8.73 179.204 -6.191 QT\n177.712 -3.652 177.712 -0.761 QT\ncp}def\r\nf402514587\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f909272395{205.186 12.067 M\n202.358 12.067 200.014 10.528 QT\n197.67 8.989 196.365 6.481 QT\n195.061 3.973 195.061 1.16 QT\n195.061 -1.746 196.483 -4.246 QT\n197.904 -6.746 200.342 -8.222 QT\n202.779 -9.699 205.701 -9.699 QT\n207.467 -9.699 209.037 -8.957 QT\n210.608 -8.215 211.748 -6.902 QT\n211.748 -16.886 L\n211.748 -18.183 211.365 -18.754 QT\n210.983 -19.324 210.264 -19.457 QT\n209.545 -19.59 208.029 -19.59 QT\n208.029 -21.277 L\n215.123 -21.793 L\n215.123 7.16 L\n215.123 8.426 215.514 8.996 QT\n215.904 9.567 216.615 9.7 QT\n217.326 9.832 218.858 9.832 QT\n218.858 11.52 L\n211.608 12.067 L\n211.608 9.035 L\n210.373 10.457 208.662 11.262 QT\n206.951 12.067 205.186 12.067 QT\ncp\n200.295 7.348 M\n201.108 8.91 202.483 9.848 QT\n203.858 10.785 205.467 10.785 QT\n207.467 10.785 209.131 9.637 QT\n210.795 8.489 211.608 6.66 QT\n211.608 -4.84 L\n211.045 -5.902 210.194 -6.73 QT\n209.342 -7.558 208.272 -8.004 QT\n207.201 -8.449 206.014 -8.449 QT\n203.498 -8.449 201.975 -7.035 QT\n200.451 -5.621 199.842 -3.418 QT\n199.233 -1.215 199.233 1.207 QT\n199.233 3.129 199.436 4.559 QT\n199.639 5.989 200.295 7.348 QT\ncp}def\r\nf909272395\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f-583193730{251.024 23.426 M\n248.352 21.317 246.415 18.59 QT\n244.477 15.864 243.251 12.762 QT\n242.024 9.66 241.415 6.285 QT\n240.806 2.91 240.806 -0.48 QT\n240.806 -3.933 241.415 -7.308 QT\n242.024 -10.683 243.274 -13.8 QT\n244.524 -16.918 246.47 -19.636 QT\n248.415 -22.355 251.024 -24.386 QT\n251.024 -24.48 251.259 -24.48 QT\n251.696 -24.48 L\n251.837 -24.48 251.954 -24.355 QT\n252.071 -24.23 252.071 -24.058 QT\n252.071 -23.855 251.977 -23.761 QT\n249.634 -21.465 248.079 -18.84 QT\n246.524 -16.215 245.571 -13.246 QT\n244.618 -10.277 244.196 -7.105 QT\n243.774 -3.933 243.774 -0.48 QT\n243.774 14.785 251.931 22.707 QT\n252.071 22.848 252.071 23.098 QT\n252.071 23.223 251.946 23.371 QT\n251.821 23.52 251.696 23.52 QT\n251.259 23.52 L\n251.024 23.52 251.024 23.426 QT\ncp}def\r\nf-583193730\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f-129920944{254.16 18.348 M\n254.16 17.176 254.972 16.317 QT\n255.785 15.457 256.957 15.457 QT\n257.738 15.457 258.261 15.942 QT\n258.785 16.426 258.785 17.192 QT\n258.785 18.114 258.214 18.848 QT\n257.644 19.582 256.769 19.817 QT\n257.613 20.129 258.457 20.129 QT\n260.504 20.129 262.004 18.239 QT\n263.504 16.348 264.113 14.004 QT\n268.629 -4.043 L\n268.957 -5.433 268.957 -6.386 QT\n268.957 -8.449 267.535 -8.449 QT\n265.425 -8.449 263.839 -6.543 QT\n262.254 -4.636 261.269 -2.121 QT\n261.175 -1.824 260.894 -1.824 QT\n260.332 -1.824 L\n259.941 -1.824 259.941 -2.261 QT\n259.941 -2.402 L\n261.019 -5.293 263.011 -7.496 QT\n265.004 -9.699 267.629 -9.699 QT\n269.613 -9.699 270.894 -8.457 QT\n272.175 -7.215 272.175 -5.293 QT\n272.175 -4.605 272.035 -3.933 QT\n267.488 14.317 L\n266.988 16.254 265.605 17.871 QT\n264.222 19.489 262.3 20.426 QT\n260.379 21.364 258.363 21.364 QT\n256.754 21.364 255.457 20.59 QT\n254.16 19.817 254.16 18.348 QT\ncp\n269.363 -17.574 M\n269.363 -18.621 270.183 -19.418 QT\n271.004 -20.215 272.035 -20.215 QT\n272.847 -20.215 273.379 -19.715 QT\n273.91 -19.215 273.91 -18.433 QT\n273.91 -17.355 273.05 -16.55 QT\n272.191 -15.746 271.16 -15.746 QT\n270.394 -15.746 269.879 -16.285 QT\n269.363 -16.824 269.363 -17.574 QT\ncp}def\r\nf-129920944\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f730600524{294.257 5.145 M\n293.867 5.145 293.609 4.84 QT\n293.351 4.535 293.351 4.176 QT\n293.351 3.785 293.609 3.504 QT\n293.867 3.223 294.257 3.223 QT\n324.398 3.223 L\n324.757 3.223 325.015 3.504 QT\n325.273 3.785 325.273 4.176 QT\n325.273 4.535 325.015 4.84 QT\n324.757 5.145 324.398 5.145 QT\n294.257 5.145 L\ncp\n294.257 -4.183 M\n293.867 -4.183 293.609 -4.465 QT\n293.351 -4.746 293.351 -5.152 QT\n293.351 -5.496 293.609 -5.8 QT\n293.867 -6.105 294.257 -6.105 QT\n324.398 -6.105 L\n324.757 -6.105 325.015 -5.8 QT\n325.273 -5.496 325.273 -5.152 QT\n325.273 -4.746 325.015 -4.465 QT\n324.757 -4.183 324.398 -4.183 QT\n294.257 -4.183 L\ncp}def\r\nf730600524\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f704190049{345.892 7.817 M\n347.017 9.457 348.916 10.254 QT\n350.814 11.051 352.986 11.051 QT\n355.783 11.051 356.955 8.668 QT\n358.127 6.285 358.127 3.27 QT\n358.127 1.91 357.877 0.551 QT\n357.627 -0.808 357.041 -1.98 QT\n356.455 -3.152 355.439 -3.855 QT\n354.424 -4.558 352.939 -4.558 QT\n349.752 -4.558 L\n349.33 -4.558 349.33 -5.011 QT\n349.33 -5.433 L\n349.33 -5.808 349.752 -5.808 QT\n352.408 -6.011 L\n354.095 -6.011 355.205 -7.277 QT\n356.314 -8.543 356.83 -10.363 QT\n357.345 -12.183 357.345 -13.824 QT\n357.345 -16.121 356.267 -17.597 QT\n355.189 -19.074 352.986 -19.074 QT\n351.158 -19.074 349.494 -18.379 QT\n347.83 -17.683 346.845 -16.277 QT\n346.939 -16.308 347.01 -16.316 QT\n347.08 -16.324 347.174 -16.324 QT\n348.252 -16.324 348.978 -15.574 QT\n349.705 -14.824 349.705 -13.777 QT\n349.705 -12.746 348.978 -11.996 QT\n348.252 -11.246 347.174 -11.246 QT\n346.127 -11.246 345.377 -11.996 QT\n344.627 -12.746 344.627 -13.777 QT\n344.627 -15.84 345.869 -17.363 QT\n347.111 -18.886 349.064 -19.668 QT\n351.017 -20.449 352.986 -20.449 QT\n354.439 -20.449 356.056 -20.019 QT\n357.674 -19.59 358.986 -18.777 QT\n360.299 -17.965 361.135 -16.699 QT\n361.97 -15.433 361.97 -13.824 QT\n361.97 -11.808 361.064 -10.097 QT\n360.158 -8.386 358.588 -7.144 QT\n357.017 -5.902 355.142 -5.293 QT\n357.236 -4.886 359.111 -3.715 QT\n360.986 -2.543 362.119 -0.715 QT\n363.252 1.114 363.252 3.223 QT\n363.252 5.864 361.799 8.012 QT\n360.345 10.16 357.978 11.371 QT\n355.611 12.582 352.986 12.582 QT\n350.736 12.582 348.478 11.723 QT\n346.22 10.864 344.775 9.153 QT\n343.33 7.442 343.33 5.051 QT\n343.33 3.848 344.127 3.051 QT\n344.924 2.254 346.127 2.254 QT\n346.892 2.254 347.541 2.621 QT\n348.189 2.989 348.549 3.645 QT\n348.908 4.301 348.908 5.051 QT\n348.908 6.223 348.088 7.02 QT\n347.267 7.817 346.127 7.817 QT\n345.892 7.817 L\ncp}def\r\nf704190049\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f400715756{367.705 11.52 M\n367.705 10.223 L\n367.705 10.114 367.799 9.973 QT\n375.252 1.723 L\n376.939 -0.105 377.994 -1.347 QT\n379.049 -2.59 380.08 -4.207 QT\n381.111 -5.824 381.713 -7.504 QT\n382.314 -9.183 382.314 -11.058 QT\n382.314 -13.027 381.588 -14.816 QT\n380.861 -16.605 379.416 -17.683 QT\n377.971 -18.761 375.939 -18.761 QT\n373.846 -18.761 372.182 -17.511 QT\n370.517 -16.261 369.846 -14.261 QT\n370.033 -14.308 370.361 -14.308 QT\n371.439 -14.308 372.197 -13.582 QT\n372.955 -12.855 372.955 -11.715 QT\n372.955 -10.605 372.197 -9.847 QT\n371.439 -9.09 370.361 -9.09 QT\n369.236 -9.09 368.471 -9.871 QT\n367.705 -10.652 367.705 -11.715 QT\n367.705 -13.511 368.385 -15.097 QT\n369.064 -16.683 370.346 -17.91 QT\n371.627 -19.136 373.228 -19.793 QT\n374.83 -20.449 376.642 -20.449 QT\n379.377 -20.449 381.744 -19.293 QT\n384.111 -18.136 385.494 -16.011 QT\n386.877 -13.886 386.877 -11.058 QT\n386.877 -8.965 385.963 -7.09 QT\n385.049 -5.215 383.619 -3.683 QT\n382.189 -2.152 379.963 -0.207 QT\n377.736 1.739 377.033 2.395 QT\n371.596 7.629 L\n376.221 7.629 L\n379.611 7.629 381.9 7.567 QT\n384.189 7.504 384.33 7.395 QT\n384.892 6.785 385.471 2.957 QT\n386.877 2.957 L\n385.517 11.52 L\n367.705 11.52 L\ncp}def\r\nf400715756\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f-420795744{392.439 23.52 M\n392.018 23.52 392.018 23.098 QT\n392.018 22.895 392.111 22.801 QT\n400.314 14.785 400.314 -0.48 QT\n400.314 -15.746 392.205 -23.668 QT\n392.018 -23.777 392.018 -24.058 QT\n392.018 -24.23 392.143 -24.355 QT\n392.268 -24.48 392.439 -24.48 QT\n392.877 -24.48 L\n393.018 -24.48 393.111 -24.386 QT\n396.564 -21.668 398.861 -17.777 QT\n401.158 -13.886 402.221 -9.48 QT\n403.283 -5.074 403.283 -0.48 QT\n403.283 2.91 402.713 6.207 QT\n402.143 9.504 400.885 12.707 QT\n399.627 15.91 397.705 18.614 QT\n395.783 21.317 393.111 23.426 QT\n393.018 23.52 392.877 23.52 QT\n392.439 23.52 L\ncp}def\r\nf-420795744\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n387 585.747 M\n467.003 585.747 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf1636705084\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf-518588683\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf763322885\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf1813278697\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf1730672616\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf1581324804\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf-1655348641\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f-2079540185{173.618 11.52 M\n173.618 9.832 L\n175.259 9.832 176.313 9.575 QT\n177.368 9.317 177.368 8.301 QT\n177.368 -4.793 L\n177.368 -6.652 176.649 -7.074 QT\n175.931 -7.496 173.821 -7.496 QT\n173.821 -9.183 L\n180.743 -9.699 L\n180.743 8.301 L\n180.743 9.317 181.657 9.575 QT\n182.571 9.832 184.087 9.832 QT\n184.087 11.52 L\n173.618 11.52 L\ncp\n175.649 -17.949 M\n175.649 -18.996 176.446 -19.793 QT\n177.243 -20.59 178.274 -20.59 QT\n178.962 -20.59 179.595 -20.238 QT\n180.227 -19.886 180.579 -19.254 QT\n180.931 -18.621 180.931 -17.949 QT\n180.931 -16.918 180.134 -16.121 QT\n179.337 -15.324 178.274 -15.324 QT\n177.243 -15.324 176.446 -16.121 QT\n175.649 -16.918 175.649 -17.949 QT\ncp}def\r\nf-2079540185\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f581539271{186.905 11.52 M\n186.905 9.832 L\n188.545 9.832 189.6 9.575 QT\n190.655 9.317 190.655 8.301 QT\n190.655 -4.793 L\n190.655 -6.09 190.264 -6.66 QT\n189.873 -7.23 189.147 -7.363 QT\n188.42 -7.496 186.905 -7.496 QT\n186.905 -9.183 L\n193.858 -9.699 L\n193.858 -5.011 L\n194.826 -7.074 196.709 -8.386 QT\n198.592 -9.699 200.826 -9.699 QT\n204.155 -9.699 205.826 -8.105 QT\n207.498 -6.511 207.498 -3.23 QT\n207.498 8.301 L\n207.498 9.317 208.553 9.575 QT\n209.608 9.832 211.248 9.832 QT\n211.248 11.52 L\n200.264 11.52 L\n200.264 9.832 L\n201.905 9.832 202.959 9.575 QT\n204.014 9.317 204.014 8.301 QT\n204.014 -3.09 L\n204.014 -5.433 203.334 -6.941 QT\n202.655 -8.449 200.545 -8.449 QT\n197.748 -8.449 195.959 -6.222 QT\n194.17 -3.996 194.17 -1.168 QT\n194.17 8.301 L\n194.17 9.317 195.225 9.575 QT\n196.28 9.832 197.889 9.832 QT\n197.889 11.52 L\n186.905 11.52 L\ncp}def\r\nf581539271\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f-1710606110{213.478 15.27 M\n213.478 13.567 214.72 12.285 QT\n215.962 11.004 217.665 10.457 QT\n216.712 9.739 216.204 8.637 QT\n215.696 7.535 215.696 6.285 QT\n215.696 4.035 217.134 2.301 QT\n214.931 0.145 214.931 -2.636 QT\n214.931 -4.136 215.571 -5.449 QT\n216.212 -6.761 217.36 -7.722 QT\n218.509 -8.683 219.915 -9.191 QT\n221.321 -9.699 222.806 -9.699 QT\n225.665 -9.699 227.931 -8.027 QT\n228.915 -9.09 230.267 -9.66 QT\n231.618 -10.23 233.071 -10.23 QT\n234.103 -10.23 234.759 -9.496 QT\n235.415 -8.761 235.415 -7.73 QT\n235.415 -7.136 234.97 -6.691 QT\n234.524 -6.246 233.931 -6.246 QT\n233.321 -6.246 232.876 -6.691 QT\n232.431 -7.136 232.431 -7.73 QT\n232.431 -8.621 233.024 -8.965 QT\n230.54 -8.965 228.759 -7.261 QT\n229.618 -6.386 230.149 -5.136 QT\n230.681 -3.886 230.681 -2.636 QT\n230.681 -0.605 229.556 1.028 QT\n228.431 2.66 226.587 3.559 QT\n224.743 4.457 222.806 4.457 QT\n220.181 4.457 217.993 3.035 QT\n217.321 3.973 217.321 5.145 QT\n217.321 6.41 218.149 7.356 QT\n218.978 8.301 220.243 8.301 QT\n224.181 8.301 L\n227.04 8.301 229.337 8.817 QT\n231.634 9.332 233.196 10.887 QT\n234.759 12.442 234.759 15.27 QT\n234.759 17.379 232.978 18.778 QT\n231.196 20.176 228.72 20.793 QT\n226.243 21.41 224.134 21.41 QT\n222.009 21.41 219.524 20.793 QT\n217.04 20.176 215.259 18.778 QT\n213.478 17.379 213.478 15.27 QT\ncp\n216.165 15.27 M\n216.165 16.895 217.478 17.981 QT\n218.79 19.067 220.642 19.598 QT\n222.493 20.129 224.134 20.129 QT\n225.759 20.129 227.61 19.598 QT\n229.462 19.067 230.759 17.981 QT\n232.056 16.895 232.056 15.27 QT\n232.056 12.77 229.759 12.028 QT\n227.462 11.285 224.181 11.285 QT\n220.243 11.285 L\n219.149 11.285 218.22 11.817 QT\n217.29 12.348 216.728 13.293 QT\n216.165 14.239 216.165 15.27 QT\ncp\n222.806 3.176 M\n226.884 3.176 226.884 -2.636 QT\n226.884 -5.152 226.017 -6.777 QT\n225.149 -8.402 222.806 -8.402 QT\n220.462 -8.402 219.595 -6.777 QT\n218.728 -5.152 218.728 -2.636 QT\n218.728 -1.043 219.056 0.246 QT\n219.384 1.535 220.274 2.356 QT\n221.165 3.176 222.806 3.176 QT\ncp}def\r\nf-1710606110\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f929488190{267.024 23.426 M\n264.353 21.317 262.415 18.59 QT\n260.478 15.864 259.251 12.762 QT\n258.024 9.66 257.415 6.285 QT\n256.806 2.91 256.806 -0.48 QT\n256.806 -3.933 257.415 -7.308 QT\n258.024 -10.683 259.274 -13.8 QT\n260.524 -16.918 262.47 -19.636 QT\n264.415 -22.355 267.024 -24.386 QT\n267.024 -24.48 267.259 -24.48 QT\n267.696 -24.48 L\n267.837 -24.48 267.954 -24.355 QT\n268.071 -24.23 268.071 -24.058 QT\n268.071 -23.855 267.978 -23.761 QT\n265.634 -21.465 264.079 -18.84 QT\n262.524 -16.215 261.571 -13.246 QT\n260.618 -10.277 260.196 -7.105 QT\n259.774 -3.933 259.774 -0.48 QT\n259.774 14.785 267.931 22.707 QT\n268.071 22.848 268.071 23.098 QT\n268.071 23.223 267.946 23.371 QT\n267.821 23.52 267.696 23.52 QT\n267.259 23.52 L\n267.024 23.52 267.024 23.426 QT\ncp}def\r\nf929488190\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f919804271{275.254 11.52 M\n275.254 9.832 L\n281.254 9.832 281.254 8.301 QT\n281.254 -16.886 L\n278.769 -15.699 274.972 -15.699 QT\n274.972 -17.386 L\n280.863 -17.386 283.863 -20.449 QT\n284.535 -20.449 L\n284.707 -20.449 284.855 -20.324 QT\n285.004 -20.199 285.004 -20.027 QT\n285.004 8.301 L\n285.004 9.832 291.004 9.832 QT\n291.004 11.52 L\n275.254 11.52 L\ncp}def\r\nf919804271\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f1957607420{313.04 18.114 M\n312.634 18.114 312.376 17.809 QT\n312.118 17.504 312.118 17.145 QT\n312.118 16.754 312.376 16.473 QT\n312.634 16.192 313.04 16.192 QT\n340.571 16.192 L\n340.946 16.192 341.196 16.473 QT\n341.446 16.754 341.446 17.145 QT\n341.446 17.504 341.196 17.809 QT\n340.946 18.114 340.571 18.114 QT\n313.04 18.114 L\ncp\n312.587 -4.324 M\n312.118 -4.465 312.118 -5.152 QT\n312.118 -5.761 312.759 -6.011 QT\n340.149 -18.949 L\n340.243 -19.027 340.477 -19.027 QT\n340.884 -19.027 341.165 -18.746 QT\n341.446 -18.465 341.446 -18.058 QT\n341.446 -17.433 340.884 -17.199 QT\n315.337 -5.152 L\n341.024 6.989 L\n341.446 7.223 341.446 7.817 QT\n341.446 8.239 341.165 8.504 QT\n340.884 8.77 340.477 8.77 QT\n340.243 8.77 340.149 8.676 QT\n312.587 -4.324 L\ncp}def\r\nf1957607420\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f127127908{358.159 18.348 M\n358.159 17.176 358.972 16.317 QT\n359.784 15.457 360.956 15.457 QT\n361.738 15.457 362.261 15.942 QT\n362.784 16.426 362.784 17.192 QT\n362.784 18.114 362.214 18.848 QT\n361.644 19.582 360.769 19.817 QT\n361.613 20.129 362.456 20.129 QT\n364.503 20.129 366.003 18.239 QT\n367.503 16.348 368.113 14.004 QT\n372.628 -4.043 L\n372.956 -5.433 372.956 -6.386 QT\n372.956 -8.449 371.534 -8.449 QT\n369.425 -8.449 367.839 -6.543 QT\n366.253 -4.636 365.269 -2.121 QT\n365.175 -1.824 364.894 -1.824 QT\n364.331 -1.824 L\n363.941 -1.824 363.941 -2.261 QT\n363.941 -2.402 L\n365.019 -5.293 367.011 -7.496 QT\n369.003 -9.699 371.628 -9.699 QT\n373.613 -9.699 374.894 -8.457 QT\n376.175 -7.215 376.175 -5.293 QT\n376.175 -4.605 376.034 -3.933 QT\n371.488 14.317 L\n370.988 16.254 369.605 17.871 QT\n368.222 19.489 366.3 20.426 QT\n364.378 21.364 362.363 21.364 QT\n360.753 21.364 359.456 20.59 QT\n358.159 19.817 358.159 18.348 QT\ncp\n373.363 -17.574 M\n373.363 -18.621 374.183 -19.418 QT\n375.003 -20.215 376.034 -20.215 QT\n376.847 -20.215 377.378 -19.715 QT\n377.909 -19.215 377.909 -18.433 QT\n377.909 -17.355 377.05 -16.55 QT\n376.191 -15.746 375.159 -15.746 QT\n374.394 -15.746 373.878 -16.285 QT\n373.363 -16.824 373.363 -17.574 QT\ncp}def\r\nf127127908\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f-1058293493{399.101 0.332 M\n398.632 0.129 398.632 -0.48 QT\n398.632 -1.09 399.272 -1.402 QT\n426.663 -14.308 L\n426.851 -14.402 426.991 -14.402 QT\n427.413 -14.402 427.687 -14.113 QT\n427.96 -13.824 427.96 -13.449 QT\n427.96 -12.855 427.397 -12.527 QT\n401.851 -0.48 L\n427.538 11.66 L\n427.96 11.801 427.96 12.489 QT\n427.96 12.864 427.687 13.153 QT\n427.413 13.442 426.991 13.442 QT\n426.851 13.442 426.663 13.348 QT\n399.101 0.332 L\ncp}def\r\nf-1058293493\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f62083131{449.892 7.817 M\n451.017 9.457 452.915 10.254 QT\n454.814 11.051 456.986 11.051 QT\n459.783 11.051 460.955 8.668 QT\n462.126 6.285 462.126 3.27 QT\n462.126 1.91 461.876 0.551 QT\n461.626 -0.808 461.04 -1.98 QT\n460.455 -3.152 459.439 -3.855 QT\n458.423 -4.558 456.939 -4.558 QT\n453.751 -4.558 L\n453.33 -4.558 453.33 -5.011 QT\n453.33 -5.433 L\n453.33 -5.808 453.751 -5.808 QT\n456.408 -6.011 L\n458.095 -6.011 459.205 -7.277 QT\n460.314 -8.543 460.83 -10.363 QT\n461.345 -12.183 461.345 -13.824 QT\n461.345 -16.121 460.267 -17.597 QT\n459.189 -19.074 456.986 -19.074 QT\n455.158 -19.074 453.494 -18.379 QT\n451.83 -17.683 450.845 -16.277 QT\n450.939 -16.308 451.009 -16.316 QT\n451.08 -16.324 451.173 -16.324 QT\n452.251 -16.324 452.978 -15.574 QT\n453.705 -14.824 453.705 -13.777 QT\n453.705 -12.746 452.978 -11.996 QT\n452.251 -11.246 451.173 -11.246 QT\n450.126 -11.246 449.376 -11.996 QT\n448.626 -12.746 448.626 -13.777 QT\n448.626 -15.84 449.869 -17.363 QT\n451.111 -18.886 453.064 -19.668 QT\n455.017 -20.449 456.986 -20.449 QT\n458.439 -20.449 460.056 -20.019 QT\n461.673 -19.59 462.986 -18.777 QT\n464.298 -17.965 465.134 -16.699 QT\n465.97 -15.433 465.97 -13.824 QT\n465.97 -11.808 465.064 -10.097 QT\n464.158 -8.386 462.587 -7.144 QT\n461.017 -5.902 459.142 -5.293 QT\n461.236 -4.886 463.111 -3.715 QT\n464.986 -2.543 466.119 -0.715 QT\n467.251 1.114 467.251 3.223 QT\n467.251 5.864 465.798 8.012 QT\n464.345 10.16 461.978 11.371 QT\n459.611 12.582 456.986 12.582 QT\n454.736 12.582 452.478 11.723 QT\n450.22 10.864 448.775 9.153 QT\n447.33 7.442 447.33 5.051 QT\n447.33 3.848 448.126 3.051 QT\n448.923 2.254 450.126 2.254 QT\n450.892 2.254 451.54 2.621 QT\n452.189 2.989 452.548 3.645 QT\n452.908 4.301 452.908 5.051 QT\n452.908 6.223 452.087 7.02 QT\n451.267 7.817 450.126 7.817 QT\n449.892 7.817 L\ncp}def\r\nf62083131\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f1509408367{471.705 11.52 M\n471.705 10.223 L\n471.705 10.114 471.798 9.973 QT\n479.251 1.723 L\n480.939 -0.105 481.994 -1.347 QT\n483.048 -2.59 484.08 -4.207 QT\n485.111 -5.824 485.712 -7.504 QT\n486.314 -9.183 486.314 -11.058 QT\n486.314 -13.027 485.587 -14.816 QT\n484.861 -16.605 483.416 -17.683 QT\n481.97 -18.761 479.939 -18.761 QT\n477.845 -18.761 476.181 -17.511 QT\n474.517 -16.261 473.845 -14.261 QT\n474.033 -14.308 474.361 -14.308 QT\n475.439 -14.308 476.197 -13.582 QT\n476.955 -12.855 476.955 -11.715 QT\n476.955 -10.605 476.197 -9.847 QT\n475.439 -9.09 474.361 -9.09 QT\n473.236 -9.09 472.47 -9.871 QT\n471.705 -10.652 471.705 -11.715 QT\n471.705 -13.511 472.384 -15.097 QT\n473.064 -16.683 474.345 -17.91 QT\n475.626 -19.136 477.228 -19.793 QT\n478.83 -20.449 480.642 -20.449 QT\n483.376 -20.449 485.744 -19.293 QT\n488.111 -18.136 489.494 -16.011 QT\n490.876 -13.886 490.876 -11.058 QT\n490.876 -8.965 489.962 -7.09 QT\n489.048 -5.215 487.619 -3.683 QT\n486.189 -2.152 483.962 -0.207 QT\n481.736 1.739 481.033 2.395 QT\n475.595 7.629 L\n480.22 7.629 L\n483.611 7.629 485.9 7.567 QT\n488.189 7.504 488.33 7.395 QT\n488.892 6.785 489.47 2.957 QT\n490.876 2.957 L\n489.517 11.52 L\n471.705 11.52 L\ncp}def\r\nf1509408367\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f511719215{496.439 23.52 M\n496.017 23.52 496.017 23.098 QT\n496.017 22.895 496.111 22.801 QT\n504.314 14.785 504.314 -0.48 QT\n504.314 -15.746 496.205 -23.668 QT\n496.017 -23.777 496.017 -24.058 QT\n496.017 -24.23 496.142 -24.355 QT\n496.267 -24.48 496.439 -24.48 QT\n496.877 -24.48 L\n497.017 -24.48 497.111 -24.386 QT\n500.564 -21.668 502.861 -17.777 QT\n505.158 -13.886 506.22 -9.48 QT\n507.283 -5.074 507.283 -0.48 QT\n507.283 2.91 506.712 6.207 QT\n506.142 9.504 504.884 12.707 QT\n503.627 15.91 501.705 18.614 QT\n499.783 21.317 497.111 23.426 QT\n497.017 23.52 496.877 23.52 QT\n496.439 23.52 L\ncp}def\r\nf511719215\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n387 644.253 M\n467.003 644.253 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n10.0 ML\r\n1.333 LW\r\nN\r\n379 677 M\n379 553 L\n993 553 L\n993 677 L\ncp\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n784 210 M\n829.683 271.672 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n832.163 258.22 M\n840 285.6 L\n829.683 271.672 L\n832.163 258.22 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n840 285.6 M\n816.092 270.124 L\n829.683 271.672 L\n840 285.6 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\nN\r\n840 285.6 M\n832.163 258.22 L\n829.683 271.672 L\n816.092 270.124 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n224 268.8 M\n289.24 324.72 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n288.661 311.053 M\n302.4 336 L\n289.24 324.72 L\n288.661 311.053 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n302.4 336 M\n275.645 326.238 L\n289.24 324.72 L\n302.4 336 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\nN\r\n302.4 336 M\n288.661 311.053 L\n289.24 324.72 L\n275.645 326.238 L\ncp\r\nf\r\nGR\r\n%%Trailer\r\n%%Pages: 1\r\n%%EOF\r\n"
  },
  {
    "path": "matlab/acc2023/closedloop_performance/figures/state-converge-3.eps",
    "content": "%!PS-Adobe-3.0 EPSF-3.0\r\n%%Creator: (MATLAB, The Mathworks, Inc. Version 9.10.0.1649659 \\(R2021a\\) Update 1. Operating System: Windows 10)\r\n%%Title: figures/state-converge-3.eps\r\n%%CreationDate: 2023-01-31T03:12:07\r\n%%Pages: (atend)\r\n%%BoundingBox:     1     6   382   292\r\n%%LanguageLevel: 3\r\n%%EndComments\r\n%%BeginProlog\r\n%%BeginResource: procset (Apache XML Graphics Std ProcSet) 1.2 0\r\n%%Version: 1.2 0\r\n%%Copyright: (Copyright 2001-2003,2010 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/bd{bind def}bind def\r\n/ld{load def}bd\r\n/GR/grestore ld\r\n/GS/gsave ld\r\n/RM/rmoveto ld\r\n/C/curveto ld\r\n/t/show ld\r\n/L/lineto ld\r\n/ML/setmiterlimit ld\r\n/CT/concat ld\r\n/f/fill ld\r\n/N/newpath ld\r\n/S/stroke ld\r\n/CC/setcmykcolor ld\r\n/A/ashow ld\r\n/cp/closepath ld\r\n/RC/setrgbcolor ld\r\n/LJ/setlinejoin ld\r\n/GC/setgray ld\r\n/LW/setlinewidth ld\r\n/M/moveto ld\r\n/re {4 2 roll M\r\n1 index 0 rlineto\r\n0 exch rlineto\r\nneg 0 rlineto\r\ncp } bd\r\n/_ctm matrix def\r\n/_tm matrix def\r\n/BT { _ctm currentmatrix pop matrix _tm copy pop 0 0 moveto } bd\r\n/ET { _ctm setmatrix } bd\r\n/iTm { _ctm setmatrix _tm concat } bd\r\n/Tm { _tm astore pop iTm 0 0 moveto } bd\r\n/ux 0.0 def\r\n/uy 0.0 def\r\n/F {\r\n  /Tp exch def\r\n  /Tf exch def\r\n  Tf findfont Tp scalefont setfont\r\n  /cf Tf def  /cs Tp def\r\n} bd\r\n/ULS {currentpoint /uy exch def /ux exch def} bd\r\n/ULE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add moveto  Tcx uy To add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/OLE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs add moveto Tcx uy To add cs add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/SOE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs 10 mul 26 idiv add moveto Tcx uy To add cs 10 mul 26 idiv add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/QT {\r\n/Y22 exch store\r\n/X22 exch store\r\n/Y21 exch store\r\n/X21 exch store\r\ncurrentpoint\r\n/Y21 load 2 mul add 3 div exch\r\n/X21 load 2 mul add 3 div exch\r\n/X21 load 2 mul /X22 load add 3 div\r\n/Y21 load 2 mul /Y22 load add 3 div\r\n/X22 load /Y22 load curveto\r\n} bd\r\n/SSPD {\r\ndup length /d exch dict def\r\n{\r\n/v exch def\r\n/k exch def\r\ncurrentpagedevice k known {\r\n/cpdv currentpagedevice k get def\r\nv cpdv ne {\r\n/upd false def\r\n/nullv v type /nulltype eq def\r\n/nullcpdv cpdv type /nulltype eq def\r\nnullv nullcpdv or\r\n{\r\n/upd true def\r\n} {\r\n/sametype v type cpdv type eq def\r\nsametype {\r\nv type /arraytype eq {\r\n/vlen v length def\r\n/cpdvlen cpdv length def\r\nvlen cpdvlen eq {\r\n0 1 vlen 1 sub {\r\n/i exch def\r\n/obj v i get def\r\n/cpdobj cpdv i get def\r\nobj cpdobj ne {\r\n/upd true def\r\nexit\r\n} if\r\n} for\r\n} {\r\n/upd true def\r\n} ifelse\r\n} {\r\nv type /dicttype eq {\r\nv {\r\n/dv exch def\r\n/dk exch def\r\n/cpddv cpdv dk get def\r\ndv cpddv ne {\r\n/upd true def\r\nexit\r\n} if\r\n} forall\r\n} {\r\n/upd true def\r\n} ifelse\r\n} ifelse\r\n} if\r\n} ifelse\r\nupd true eq {\r\nd k v put\r\n} if\r\n} if\r\n} if\r\n} forall\r\nd length 0 gt {\r\nd setpagedevice\r\n} if\r\n} bd\r\n/RE { % /NewFontName [NewEncodingArray] /FontName RE -\r\n  findfont dup length dict begin\r\n  {\r\n    1 index /FID ne\r\n    {def} {pop pop} ifelse\r\n  } forall\r\n  /Encoding exch def\r\n  /FontName 1 index def\r\n  currentdict definefont pop\r\n  end\r\n} bind def\r\n%%EndResource\r\n%%BeginResource: procset (Apache XML Graphics EPS ProcSet) 1.0 0\r\n%%Version: 1.0 0\r\n%%Copyright: (Copyright 2002-2003 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/BeginEPSF { %def\r\n/b4_Inc_state save def         % Save state for cleanup\r\n/dict_count countdictstack def % Count objects on dict stack\r\n/op_count count 1 sub def      % Count objects on operand stack\r\nuserdict begin                 % Push userdict on dict stack\r\n/showpage { } def              % Redefine showpage, { } = null proc\r\n0 setgray 0 setlinecap         % Prepare graphics state\r\n1 setlinewidth 0 setlinejoin\r\n10 setmiterlimit [ ] 0 setdash newpath\r\n/languagelevel where           % If level not equal to 1 then\r\n{pop languagelevel             % set strokeadjust and\r\n1 ne                           % overprint to their defaults.\r\n{false setstrokeadjust false setoverprint\r\n} if\r\n} if\r\n} bd\r\n/EndEPSF { %def\r\ncount op_count sub {pop} repeat            % Clean up stacks\r\ncountdictstack dict_count sub {end} repeat\r\nb4_Inc_state restore\r\n} bd\r\n%%EndResource\r\n%FOPBeginFontDict\r\n%%IncludeResource: font Courier-Oblique\r\n%%IncludeResource: font Courier-BoldOblique\r\n%%IncludeResource: font Courier-Bold\r\n%%IncludeResource: font ZapfDingbats\r\n%%IncludeResource: font Symbol\r\n%%IncludeResource: font Helvetica\r\n%%IncludeResource: font Helvetica-Oblique\r\n%%IncludeResource: font Helvetica-Bold\r\n%%IncludeResource: font Helvetica-BoldOblique\r\n%%IncludeResource: font Times-Roman\r\n%%IncludeResource: font Times-Italic\r\n%%IncludeResource: font Times-Bold\r\n%%IncludeResource: font Times-BoldItalic\r\n%%IncludeResource: font Courier\r\n%FOPEndFontDict\r\n%%BeginResource: encoding WinAnsiEncoding\r\n/WinAnsiEncoding [\r\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /space /exclam /quotedbl\n/numbersign /dollar /percent /ampersand /quotesingle\n/parenleft /parenright /asterisk /plus /comma\n/hyphen /period /slash /zero /one\n/two /three /four /five /six\n/seven /eight /nine /colon /semicolon\n/less /equal /greater /question /at\n/A /B /C /D /E\n/F /G /H /I /J\n/K /L /M /N /O\n/P /Q /R /S /T\n/U /V /W /X /Y\n/Z /bracketleft /backslash /bracketright /asciicircum\n/underscore /quoteleft /a /b /c\n/d /e /f /g /h\n/i /j /k /l /m\n/n /o /p /q /r\n/s /t /u /v /w\n/x /y /z /braceleft /bar\n/braceright /asciitilde /bullet /Euro /bullet\n/quotesinglbase /florin /quotedblbase /ellipsis /dagger\n/daggerdbl /circumflex /perthousand /Scaron /guilsinglleft\n/OE /bullet /Zcaron /bullet /bullet\n/quoteleft /quoteright /quotedblleft /quotedblright /bullet\n/endash /emdash /asciitilde /trademark /scaron\n/guilsinglright /oe /bullet /zcaron /Ydieresis\n/space /exclamdown /cent /sterling /currency\n/yen /brokenbar /section /dieresis /copyright\n/ordfeminine /guillemotleft /logicalnot /sfthyphen /registered\n/macron /degree /plusminus /twosuperior /threesuperior\n/acute /mu /paragraph /middot /cedilla\n/onesuperior /ordmasculine /guillemotright /onequarter /onehalf\n/threequarters /questiondown /Agrave /Aacute /Acircumflex\n/Atilde /Adieresis /Aring /AE /Ccedilla\n/Egrave /Eacute /Ecircumflex /Edieresis /Igrave\n/Iacute /Icircumflex /Idieresis /Eth /Ntilde\n/Ograve /Oacute /Ocircumflex /Otilde /Odieresis\n/multiply /Oslash /Ugrave /Uacute /Ucircumflex\n/Udieresis /Yacute /Thorn /germandbls /agrave\n/aacute /acircumflex /atilde /adieresis /aring\n/ae /ccedilla /egrave /eacute /ecircumflex\n/edieresis /igrave /iacute /icircumflex /idieresis\n/eth /ntilde /ograve /oacute /ocircumflex\n/otilde /odieresis /divide /oslash /ugrave\n/uacute /ucircumflex /udieresis /yacute /thorn\n/ydieresis\n] def\r\n%%EndResource\r\n%FOPBeginFontReencode\r\n/Courier-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Oblique exch definefont pop\r\n/Courier-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-BoldOblique exch definefont pop\r\n/Courier-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Bold exch definefont pop\r\n/Helvetica findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica exch definefont pop\r\n/Helvetica-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Oblique exch definefont pop\r\n/Helvetica-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Bold exch definefont pop\r\n/Helvetica-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-BoldOblique exch definefont pop\r\n/Times-Roman findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Roman exch definefont pop\r\n/Times-Italic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Italic exch definefont pop\r\n/Times-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Bold exch definefont pop\r\n/Times-BoldItalic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-BoldItalic exch definefont pop\r\n/Courier findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier exch definefont pop\r\n%FOPEndFontReencode\r\n%%EndProlog\r\n%%Page: 1 1\r\n%%PageBoundingBox: 0 0 420 315\r\n%%BeginPageSetup\r\n[1 0 0 -1 0 315] CT\r\n%%EndPageSetup\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n170 698 M\n1014 698 L\n1014 63 L\n170 63 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n170 698 M\n1014 698 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n170 63 M\n1014 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n170 698 M\n170 689.56 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n345.833 698 M\n345.833 689.56 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n521.667 698 M\n521.667 689.56 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n697.5 698 M\n697.5 689.56 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n873.333 698 M\n873.333 689.56 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n170 63 M\n170 71.44 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n345.833 63 M\n345.833 71.44 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n521.667 63 M\n521.667 71.44 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n697.5 63 M\n697.5 71.44 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n873.333 63 M\n873.333 71.44 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 63.75 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-13.5 49 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 129.6875 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-13.5 49 moveto \r\n1 -1 scale\r\n(5) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 195.62501 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(10) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 261.5625 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(15) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 327.49999 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(20) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 222.00016 291] CT\r\n0.149 GC\r\nN\r\n-11.894 43.847 M\n-11.894 43.534 -11.847 43.378 QT\n-4.16 12.737 L\n-3.957 11.831 -3.91 11.315 QT\n-3.91 10.456 -7.347 10.456 QT\n-7.894 10.456 -7.894 9.753 QT\n-7.863 9.628 -7.769 9.292 QT\n-7.675 8.956 -7.535 8.776 QT\n-7.394 8.597 -7.144 8.597 QT\n-0.003 8.019 L\n0.153 8.019 L\n0.153 8.081 0.34 8.167 QT\n0.528 8.253 0.543 8.284 QT\n0.653 8.55 0.653 8.706 QT\n-4.91 30.847 L\n-3.003 30.05 -0.089 27.034 QT\n2.825 24.019 4.465 22.698 QT\n6.106 21.378 8.59 21.378 QT\n10.075 21.378 11.106 22.386 QT\n12.137 23.394 12.137 24.878 QT\n12.137 25.8 11.754 26.589 QT\n11.372 27.378 10.668 27.87 QT\n9.965 28.362 9.028 28.362 QT\n8.184 28.362 7.598 27.831 QT\n7.012 27.3 7.012 26.456 QT\n7.012 25.19 7.911 24.323 QT\n8.809 23.456 10.075 23.456 QT\n9.559 22.753 8.497 22.753 QT\n6.918 22.753 5.45 23.659 QT\n3.981 24.565 2.293 26.261 QT\n0.606 27.956 -0.793 29.362 QT\n-2.191 30.769 -3.394 31.503 QT\n-0.253 31.862 2.051 33.144 QT\n4.356 34.425 4.356 37.065 QT\n4.356 37.612 4.137 38.44 QT\n3.684 40.425 3.684 41.612 QT\n3.684 44.003 5.309 44.003 QT\n7.231 44.003 8.223 41.901 QT\n9.215 39.8 9.856 37.003 QT\n9.965 36.706 10.309 36.706 QT\n10.918 36.706 L\n11.137 36.706 11.278 36.831 QT\n11.418 36.956 11.418 37.159 QT\n11.418 37.222 11.372 37.315 QT\n9.372 45.394 5.2 45.394 QT\n3.7 45.394 2.551 44.698 QT\n1.403 44.003 0.778 42.8 QT\n0.153 41.597 0.153 40.097 QT\n0.153 39.237 0.387 38.331 QT\n0.543 37.706 0.543 37.159 QT\n0.543 35.128 -1.269 34.065 QT\n-3.082 33.003 -5.41 32.769 QT\n-8.097 43.581 L\n-8.3 44.378 -8.894 44.886 QT\n-9.488 45.394 -10.269 45.394 QT\n-10.941 45.394 -11.418 44.94 QT\n-11.894 44.487 -11.894 43.847 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n170 698 M\n170 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 698 M\n1014 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n170 645.083 M\n178.44 645.083 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n170 380.5 M\n178.44 380.5 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n170 115.917 M\n178.44 115.917 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 645.083 M\n1005.56 645.083 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 380.5 M\n1005.56 380.5 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 115.917 M\n1005.56 115.917 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 58.15 241.90624] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-83 19 moveto \r\n1 -1 scale\r\n(-0.5) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 58.15 142.6875] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 19 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 58.15 43.46875] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-67 19 moveto \r\n1 -1 scale\r\n(0.5) t \r\nGR\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24 142.68739] CT\r\n0.149 GC\r\nN\r\n-66.2 -18.606 M\n-68.606 -18.606 -70.06 -20.364 QT\n-71.513 -22.122 -72.067 -24.606 QT\n-72.622 -27.091 -72.622 -29.528 QT\n-72.622 -29.575 L\n-72.622 -32.216 -72.122 -35.06 QT\n-71.622 -37.903 -70.661 -40.739 QT\n-69.7 -43.575 -68.591 -45.81 QT\n-67.81 -47.356 -66.583 -49.271 QT\n-65.356 -51.185 -63.841 -52.856 QT\n-62.325 -54.528 -60.575 -55.552 QT\n-58.825 -56.575 -57.044 -56.575 QT\n-56.997 -56.575 L\n-55.075 -56.575 -53.794 -55.513 QT\n-52.513 -54.45 -51.802 -52.794 QT\n-51.091 -51.138 -50.81 -49.247 QT\n-50.528 -47.356 -50.528 -45.653 QT\n-50.528 -41.638 -51.614 -37.458 QT\n-52.7 -33.278 -54.606 -29.372 QT\n-55.341 -27.903 -56.622 -25.903 QT\n-57.903 -23.903 -59.341 -22.325 QT\n-60.778 -20.747 -62.56 -19.677 QT\n-64.341 -18.606 -66.153 -18.606 QT\n-66.2 -18.606 L\ncp\n-66.106 -19.997 M\n-64.341 -19.997 -62.724 -21.88 QT\n-61.106 -23.763 -59.888 -26.435 QT\n-58.669 -29.106 -57.755 -31.919 QT\n-56.841 -34.731 -56.403 -36.7 QT\n-67.216 -36.7 L\n-68.044 -33.356 -68.513 -30.935 QT\n-68.981 -28.513 -68.981 -26.185 QT\n-68.981 -19.997 -66.106 -19.997 QT\ncp\n-66.81 -38.56 M\n-55.935 -38.56 L\n-55.356 -40.888 -55.021 -42.45 QT\n-54.685 -44.013 -54.458 -45.747 QT\n-54.231 -47.481 -54.231 -48.981 QT\n-54.231 -55.2 -57.044 -55.2 QT\n-60.403 -55.2 -62.849 -49.778 QT\n-65.294 -44.356 -66.81 -38.56 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24 142.68739] CT\r\n0.149 GC\r\nN\r\n-31.791 -6.06 M\n-34.744 -8.388 -36.877 -11.403 QT\n-39.01 -14.419 -40.369 -17.833 QT\n-41.729 -21.247 -42.4 -24.974 QT\n-43.072 -28.7 -43.072 -32.45 QT\n-43.072 -36.247 -42.4 -39.974 QT\n-41.729 -43.7 -40.346 -47.146 QT\n-38.963 -50.591 -36.814 -53.591 QT\n-34.666 -56.591 -31.791 -58.841 QT\n-31.791 -58.95 -31.541 -58.95 QT\n-31.041 -58.95 L\n-30.885 -58.95 -30.76 -58.81 QT\n-30.635 -58.669 -30.635 -58.481 QT\n-30.635 -58.247 -30.729 -58.153 QT\n-33.322 -55.606 -35.041 -52.708 QT\n-36.76 -49.81 -37.807 -46.536 QT\n-38.854 -43.263 -39.322 -39.755 QT\n-39.791 -36.247 -39.791 -32.45 QT\n-39.791 -15.606 -30.791 -6.856 QT\n-30.635 -6.7 -30.635 -6.419 QT\n-30.635 -6.294 -30.775 -6.122 QT\n-30.916 -5.95 -31.041 -5.95 QT\n-31.541 -5.95 L\n-31.791 -5.95 -31.791 -6.06 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24 142.68739] CT\r\n0.149 GC\r\nN\r\n-23.394 -20.106 M\n-23.394 -20.419 -23.347 -20.575 QT\n-19.394 -36.388 L\n-19.003 -37.856 -19.003 -38.966 QT\n-19.003 -41.247 -20.55 -41.247 QT\n-22.206 -41.247 -23.011 -39.271 QT\n-23.816 -37.294 -24.566 -34.263 QT\n-24.566 -34.106 -24.722 -34.013 QT\n-24.878 -33.919 -25.003 -33.919 QT\n-25.628 -33.919 L\n-25.8 -33.919 -25.933 -34.114 QT\n-26.066 -34.31 -26.066 -34.466 QT\n-25.488 -36.778 -24.964 -38.38 QT\n-24.441 -39.981 -23.308 -41.302 QT\n-22.175 -42.622 -20.503 -42.622 QT\n-18.66 -42.622 -17.277 -41.56 QT\n-15.894 -40.497 -15.55 -38.763 QT\n-14.206 -40.528 -12.488 -41.575 QT\n-10.769 -42.622 -8.722 -42.622 QT\n-7.05 -42.622 -5.769 -41.638 QT\n-4.488 -40.653 -4.488 -38.966 QT\n-4.488 -37.622 -5.324 -36.63 QT\n-6.16 -35.638 -7.566 -35.638 QT\n-8.41 -35.638 -8.996 -36.169 QT\n-9.581 -36.7 -9.581 -37.544 QT\n-9.581 -38.716 -8.73 -39.63 QT\n-7.878 -40.544 -6.753 -40.544 QT\n-7.613 -41.247 -8.831 -41.247 QT\n-11.113 -41.247 -12.792 -39.63 QT\n-14.472 -38.013 -15.816 -35.528 QT\n-19.597 -20.372 L\n-19.769 -19.638 -20.41 -19.122 QT\n-21.05 -18.606 -21.816 -18.606 QT\n-22.472 -18.606 -22.933 -19.021 QT\n-23.394 -19.435 -23.394 -20.106 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24 142.68739] CT\r\n0.149 GC\r\nN\r\n7.274 -18.606 M\n3.931 -18.606 2.001 -21.13 QT\n0.071 -23.653 0.071 -27.091 QT\n0.071 -30.481 1.829 -34.13 QT\n3.587 -37.778 6.579 -40.2 QT\n9.571 -42.622 13.009 -42.622 QT\n14.587 -42.622 15.829 -41.771 QT\n17.071 -40.919 17.774 -39.435 QT\n18.368 -41.56 20.102 -41.56 QT\n20.774 -41.56 21.227 -41.161 QT\n21.681 -40.763 21.681 -40.091 QT\n21.681 -39.935 21.673 -39.856 QT\n21.665 -39.778 21.634 -39.669 QT\n17.931 -24.872 L\n17.571 -23.294 17.571 -22.278 QT\n17.571 -19.997 19.102 -19.997 QT\n20.759 -19.997 21.626 -22.106 QT\n22.493 -24.216 23.087 -26.997 QT\n23.181 -27.294 23.493 -27.294 QT\n24.149 -27.294 L\n24.352 -27.294 24.477 -27.114 QT\n24.602 -26.935 24.602 -26.778 QT\n23.681 -23.075 22.579 -20.841 QT\n21.477 -18.606 18.993 -18.606 QT\n17.212 -18.606 15.837 -19.653 QT\n14.462 -20.7 14.134 -22.435 QT\n10.712 -18.606 7.274 -18.606 QT\ncp\n7.321 -19.997 M\n9.243 -19.997 11.04 -21.435 QT\n12.837 -22.872 14.134 -24.81 QT\n14.181 -24.872 14.181 -24.966 QT\n17.024 -36.481 L\n17.071 -36.638 L\n16.759 -38.528 15.712 -39.888 QT\n14.665 -41.247 12.884 -41.247 QT\n11.102 -41.247 9.563 -39.786 QT\n8.024 -38.325 6.962 -36.325 QT\n5.931 -34.216 4.985 -30.513 QT\n4.04 -26.81 4.04 -24.763 QT\n4.04 -22.935 4.829 -21.466 QT\n5.618 -19.997 7.321 -19.997 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24 142.68739] CT\r\n0.149 GC\r\nN\r\n35.466 -18.606 M\n32.122 -18.606 30.192 -21.13 QT\n28.263 -23.653 28.263 -27.091 QT\n28.263 -30.481 30.02 -34.13 QT\n31.778 -37.778 34.77 -40.2 QT\n37.763 -42.622 41.2 -42.622 QT\n42.763 -42.622 44.013 -41.755 QT\n45.263 -40.888 45.966 -39.435 QT\n48.95 -51.263 L\n49.153 -52.169 49.2 -52.685 QT\n49.2 -53.544 45.763 -53.544 QT\n45.216 -53.544 45.216 -54.247 QT\n45.247 -54.372 45.333 -54.708 QT\n45.419 -55.044 45.567 -55.224 QT\n45.716 -55.403 45.966 -55.403 QT\n53.106 -55.981 L\n53.763 -55.981 53.763 -55.294 QT\n46.122 -24.81 L\n45.763 -23.935 45.763 -22.278 QT\n45.763 -19.997 47.294 -19.997 QT\n48.95 -19.997 49.817 -22.106 QT\n50.684 -24.216 51.278 -26.997 QT\n51.372 -27.294 51.684 -27.294 QT\n52.341 -27.294 L\n52.544 -27.294 52.669 -27.114 QT\n52.794 -26.935 52.794 -26.778 QT\n51.872 -23.075 50.77 -20.841 QT\n49.669 -18.606 47.184 -18.606 QT\n45.403 -18.606 44.028 -19.653 QT\n42.653 -20.7 42.325 -22.435 QT\n38.903 -18.606 35.466 -18.606 QT\ncp\n35.513 -19.997 M\n37.434 -19.997 39.231 -21.435 QT\n41.028 -22.872 42.325 -24.81 QT\n42.372 -24.872 42.372 -25.028 QT\n45.263 -36.7 L\n44.95 -38.56 43.895 -39.903 QT\n42.841 -41.247 41.075 -41.247 QT\n39.294 -41.247 37.755 -39.786 QT\n36.216 -38.325 35.153 -36.325 QT\n34.122 -34.216 33.177 -30.513 QT\n32.231 -26.81 32.231 -24.763 QT\n32.231 -22.935 33.02 -21.466 QT\n33.809 -19.997 35.513 -19.997 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 24 142.68739] CT\r\n0.149 GC\r\nN\r\n57.444 -5.95 M\n56.975 -5.95 56.975 -6.419 QT\n56.975 -6.653 57.084 -6.747 QT\n66.147 -15.606 66.147 -32.45 QT\n66.147 -49.294 57.194 -58.044 QT\n56.975 -58.169 56.975 -58.481 QT\n56.975 -58.669 57.123 -58.81 QT\n57.272 -58.95 57.444 -58.95 QT\n57.944 -58.95 L\n58.1 -58.95 58.194 -58.841 QT\n62.006 -55.841 64.538 -51.544 QT\n67.069 -47.247 68.248 -42.388 QT\n69.428 -37.528 69.428 -32.45 QT\n69.428 -28.7 68.795 -25.06 QT\n68.163 -21.419 66.78 -17.888 QT\n65.397 -14.356 63.272 -11.372 QT\n61.147 -8.388 58.194 -6.06 QT\n58.1 -5.95 57.944 -5.95 QT\n57.444 -5.95 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n170 193.896 M\n205.167 251.241 L\n240.333 241.234 L\n275.5 181.159 L\n310.667 115.833 L\n345.833 99.908 L\n381 118.829 L\n416.167 126.683 L\n451.333 159.818 L\n486.5 258.776 L\n521.667 380.082 L\n556.833 455.022 L\n592 498.754 L\n627.167 521.059 L\n662.333 528.404 L\n697.5 525.419 L\n732.667 515.61 L\n767.833 501.719 L\n803 485.911 L\n838.167 469.876 L\n873.333 454.894 L\n908.5 441.886 L\n943.667 431.48 L\n978.833 424.108 L\n1014 420.146 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n170 193.896 M\n205.167 139.739 L\n240.333 114.54 L\n275.5 128.164 L\n310.667 137.514 L\n345.833 166.604 L\n381 230.182 L\n416.167 303.273 L\n451.333 401.683 L\n486.5 516.923 L\n521.667 608.931 L\n556.833 622.657 L\n592 605.493 L\n627.167 579.961 L\n662.333 554.999 L\n697.5 532.993 L\n732.667 513.721 L\n767.833 496.338 L\n803 480.215 L\n838.167 465.173 L\n873.333 451.417 L\n908.5 439.383 L\n943.667 429.585 L\n978.833 422.527 L\n1014 418.704 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n170 193.896 M\n205.167 219.763 L\n240.333 180.92 L\n275.5 124.492 L\n310.667 110.069 L\n345.833 141.981 L\n381 209.079 L\n416.167 286.589 L\n451.333 396.913 L\n486.5 459.407 L\n521.667 466.315 L\n556.833 473.575 L\n592 486.782 L\n627.167 500.234 L\n662.333 509.069 L\n697.5 511.366 L\n732.667 507.37 L\n767.833 498.413 L\n803 486.186 L\n838.167 472.363 L\n873.333 458.433 L\n908.5 445.637 L\n943.667 434.961 L\n978.833 427.176 L\n1014 422.932 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n170 193.896 M\n205.167 175.445 L\n240.333 164.393 L\n275.5 139.177 L\n310.667 124.715 L\n345.833 155.222 L\n381 220.387 L\n416.167 298.832 L\n451.333 410.859 L\n486.5 519.16 L\n521.667 570.951 L\n556.833 586.467 L\n592 579.871 L\n627.167 562.445 L\n662.333 541.534 L\n697.5 520.854 L\n732.667 501.751 L\n767.833 484.415 L\n803 468.697 L\n838.167 454.504 L\n873.333 441.919 L\n908.5 431.172 L\n943.667 422.572 L\n978.833 416.449 L\n1014 413.158 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n170 193.896 M\n205.167 205.883 L\n240.333 174.268 L\n275.5 131.888 L\n310.667 117.646 L\n345.833 146.232 L\n381 210.139 L\n416.167 285.042 L\n451.333 392.792 L\n486.5 462.433 L\n521.667 485.025 L\n556.833 496.328 L\n592 505.974 L\n627.167 513.738 L\n662.333 517.489 L\n697.5 516.035 L\n732.667 509.509 L\n767.833 498.938 L\n803 485.744 L\n838.167 471.405 L\n873.333 457.269 L\n908.5 444.464 L\n943.667 433.884 L\n978.833 426.222 L\n1014 422.067 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n170 193.896 M\n205.167 185.767 L\n240.333 168.666 L\n275.5 135.27 L\n310.667 122.749 L\n345.833 152.445 L\n381 217.668 L\n416.167 294.495 L\n451.333 403.694 L\n486.5 508.48 L\n521.667 553.918 L\n556.833 567.452 L\n592 563.281 L\n627.167 550.341 L\n662.333 534.03 L\n697.5 517.098 L\n732.667 500.636 L\n767.833 484.942 L\n803 470.099 L\n838.167 456.26 L\n873.333 443.713 L\n908.5 432.843 L\n943.667 424.066 L\n978.833 417.784 L\n1014 414.396 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n170 193.896 M\n205.167 199.489 L\n240.333 172.773 L\n275.5 133.654 L\n310.667 119.498 L\n345.833 148.005 L\n381 211.85 L\n416.167 286.871 L\n451.333 394.528 L\n486.5 470.696 L\n521.667 498.207 L\n556.833 510.653 L\n592 518.113 L\n627.167 522.063 L\n662.333 521.89 L\n697.5 517.255 L\n732.667 508.557 L\n767.833 496.744 L\n803 483.02 L\n838.167 468.623 L\n873.333 454.695 L\n908.5 442.21 L\n943.667 431.956 L\n978.833 424.558 L\n1014 420.554 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n170 193.896 M\n205.167 190.047 L\n240.333 169.741 L\n275.5 134.656 L\n310.667 121.814 L\n345.833 151.2 L\n381 216.018 L\n416.167 292.315 L\n451.333 400.938 L\n486.5 500.553 L\n521.667 542.444 L\n556.833 555.491 L\n592 553.357 L\n627.167 543.634 L\n662.333 530.534 L\n697.5 516.148 L\n732.667 501.377 L\n767.833 486.609 L\n803 472.128 L\n838.167 458.293 L\n873.333 445.563 L\n908.5 434.441 L\n943.667 425.421 L\n978.833 418.95 L\n1014 415.456 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n170 193.896 M\n205.167 196.796 L\n240.333 172.221 L\n275.5 134.201 L\n310.667 120.23 L\n345.833 148.785 L\n381 212.678 L\n416.167 287.828 L\n451.333 395.502 L\n486.5 476.518 L\n521.667 507.092 L\n556.833 519.867 L\n592 525.557 L\n627.167 526.818 L\n662.333 524.016 L\n697.5 517.336 L\n732.667 507.317 L\n767.833 494.817 L\n803 480.87 L\n838.167 466.539 L\n873.333 452.826 L\n908.5 440.605 L\n943.667 430.598 L\n978.833 423.39 L\n1014 419.492 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n170 193.896 M\n205.167 191.934 L\n240.333 170.3 L\n275.5 134.494 L\n310.667 121.418 L\n345.833 150.593 L\n381 215.156 L\n416.167 291.144 L\n451.333 399.461 L\n486.5 495.45 L\n521.667 535.048 L\n556.833 547.966 L\n592 547.349 L\n627.167 539.828 L\n662.333 528.838 L\n697.5 516.065 L\n732.667 502.318 L\n767.833 488.065 L\n803 473.739 L\n838.167 459.841 L\n873.333 446.939 L\n908.5 435.615 L\n943.667 426.409 L\n978.833 419.798 L\n1014 416.228 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n170 193.896 M\n205.167 195.543 L\n240.333 171.863 L\n275.5 134.379 L\n310.667 120.562 L\n345.833 149.196 L\n381 213.168 L\n416.167 288.44 L\n451.333 396.176 L\n486.5 480.345 L\n521.667 512.839 L\n556.833 525.711 L\n592 530.152 L\n627.167 529.623 L\n662.333 525.125 L\n697.5 517.163 L\n732.667 506.343 L\n767.833 493.453 L\n803 479.405 L\n838.167 465.149 L\n873.333 451.595 L\n908.5 439.556 L\n943.667 429.716 L\n978.833 422.632 L\n1014 418.803 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n170 193.896 M\n205.167 192.85 L\n240.333 170.642 L\n275.5 134.452 L\n310.667 121.221 L\n345.833 150.267 L\n381 214.679 L\n416.167 290.488 L\n451.333 398.64 L\n486.5 492.239 L\n521.667 530.374 L\n556.833 543.261 L\n592 543.668 L\n627.167 537.586 L\n662.333 527.945 L\n697.5 516.183 L\n732.667 503.06 L\n767.833 489.107 L\n803 474.854 L\n838.167 460.894 L\n873.333 447.867 L\n908.5 436.402 L\n943.667 427.07 L\n978.833 420.364 L\n1014 416.742 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n170 193.896 M\n205.167 194.902 L\n240.333 171.624 L\n275.5 134.435 L\n310.667 120.73 L\n345.833 149.431 L\n381 213.472 L\n416.167 288.836 L\n451.333 396.63 L\n486.5 482.794 L\n521.667 516.487 L\n556.833 529.384 L\n592 533.001 L\n627.167 531.321 L\n662.333 525.747 L\n697.5 516.985 L\n732.667 505.674 L\n767.833 492.552 L\n803 478.454 L\n838.167 464.255 L\n873.333 450.809 L\n908.5 438.89 L\n943.667 429.156 L\n978.833 422.152 L\n1014 418.367 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n170 193.896 M\n205.167 193.334 L\n240.333 170.854 L\n275.5 134.445 L\n310.667 121.115 L\n345.833 150.08 L\n381 214.402 L\n416.167 290.107 L\n451.333 398.166 L\n486.5 490.234 L\n521.667 527.445 L\n556.833 540.327 L\n592 541.398 L\n627.167 536.233 L\n662.333 527.443 L\n697.5 516.313 L\n732.667 503.574 L\n767.833 489.801 L\n803 475.585 L\n838.167 461.579 L\n873.333 448.468 L\n908.5 436.911 L\n943.667 427.497 L\n978.833 420.73 L\n1014 417.075 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n170 193.896 M\n205.167 194.548 L\n240.333 171.468 L\n275.5 134.451 L\n310.667 120.822 L\n345.833 149.572 L\n381 213.661 L\n416.167 289.089 L\n451.333 396.928 L\n486.5 484.342 L\n521.667 518.781 L\n556.833 531.682 L\n592 534.771 L\n627.167 532.362 L\n662.333 526.113 L\n697.5 516.851 L\n732.667 505.237 L\n767.833 491.976 L\n803 477.851 L\n838.167 463.691 L\n873.333 450.315 L\n908.5 438.471 L\n943.667 428.805 L\n978.833 421.851 L\n1014 418.093 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n170 193.896 M\n205.167 193.607 L\n240.333 170.985 L\n275.5 134.445 L\n310.667 121.053 L\n345.833 149.97 L\n381 214.237 L\n416.167 289.879 L\n451.333 397.885 L\n486.5 488.985 L\n521.667 525.616 L\n556.833 538.501 L\n592 539.993 L\n627.167 535.405 L\n662.333 527.149 L\n697.5 516.413 L\n732.667 503.912 L\n767.833 490.248 L\n803 476.053 L\n838.167 462.017 L\n873.333 448.85 L\n908.5 437.234 L\n943.667 427.768 L\n978.833 420.962 L\n1014 417.286 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n170 193.896 M\n205.167 194.341 L\n240.333 171.368 L\n275.5 134.454 L\n310.667 120.875 L\n345.833 149.658 L\n381 213.78 L\n416.167 289.249 L\n451.333 397.12 L\n486.5 485.314 L\n521.667 520.216 L\n556.833 533.117 L\n592 535.872 L\n627.167 533.005 L\n662.333 526.334 L\n697.5 516.761 L\n732.667 504.959 L\n767.833 491.613 L\n803 477.472 L\n838.167 463.338 L\n873.333 450.005 L\n908.5 438.21 L\n943.667 428.585 L\n978.833 421.663 L\n1014 417.922 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n170 193.896 M\n205.167 193.767 L\n240.333 171.066 L\n275.5 134.447 L\n310.667 121.017 L\n345.833 149.904 L\n381 214.137 L\n416.167 289.741 L\n451.333 397.716 L\n486.5 488.208 L\n521.667 524.476 L\n556.833 537.363 L\n592 539.121 L\n627.167 534.895 L\n662.333 526.973 L\n697.5 516.481 L\n732.667 504.129 L\n767.833 490.532 L\n803 476.349 L\n838.167 462.292 L\n873.333 449.092 L\n908.5 437.438 L\n943.667 427.939 L\n978.833 421.109 L\n1014 417.419 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n170 193.896 M\n205.167 194.218 L\n240.333 171.305 L\n275.5 134.454 L\n310.667 120.908 L\n345.833 149.711 L\n381 213.854 L\n416.167 289.35 L\n451.333 397.241 L\n486.5 485.921 L\n521.667 521.113 L\n556.833 534.012 L\n592 536.557 L\n627.167 533.404 L\n662.333 526.469 L\n697.5 516.703 L\n732.667 504.785 L\n767.833 491.385 L\n803 477.235 L\n838.167 463.117 L\n873.333 449.812 L\n908.5 438.046 L\n943.667 428.448 L\n978.833 421.545 L\n1014 417.816 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n170 193.896 M\n205.167 193.864 L\n240.333 171.116 L\n275.5 134.448 L\n310.667 120.995 L\n345.833 149.864 L\n381 214.076 L\n416.167 289.656 L\n451.333 397.613 L\n486.5 487.724 L\n521.667 523.766 L\n556.833 536.656 L\n592 538.579 L\n627.167 534.579 L\n662.333 526.865 L\n697.5 516.526 L\n732.667 504.265 L\n767.833 490.711 L\n803 476.535 L\n838.167 462.465 L\n873.333 449.243 L\n908.5 437.566 L\n943.667 428.045 L\n978.833 421.2 L\n1014 417.502 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n170 193.896 M\n205.167 194.142 L\n240.333 171.265 L\n275.5 134.453 L\n310.667 120.928 L\n345.833 149.744 L\n381 213.9 L\n416.167 289.413 L\n451.333 397.317 L\n486.5 486.3 L\n521.667 521.672 L\n556.833 534.569 L\n592 536.984 L\n627.167 533.652 L\n662.333 526.553 L\n697.5 516.666 L\n732.667 504.675 L\n767.833 491.243 L\n803 477.087 L\n838.167 462.979 L\n873.333 449.692 L\n908.5 437.945 L\n943.667 428.363 L\n978.833 421.472 L\n1014 417.75 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n170 193.896 M\n205.167 193.923 L\n240.333 171.147 L\n275.5 134.449 L\n310.667 120.982 L\n345.833 149.839 L\n381 214.038 L\n416.167 289.603 L\n451.333 397.549 L\n486.5 487.423 L\n521.667 523.324 L\n556.833 536.215 L\n592 538.242 L\n627.167 534.383 L\n662.333 526.798 L\n697.5 516.555 L\n732.667 504.351 L\n767.833 490.822 L\n803 476.651 L\n838.167 462.573 L\n873.333 449.337 L\n908.5 437.645 L\n943.667 428.112 L\n978.833 421.257 L\n1014 417.554 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n170 193.897 M\n205.167 194.095 L\n240.333 171.24 L\n275.5 134.452 L\n310.667 120.941 L\n345.833 149.765 L\n381 213.928 L\n416.167 289.452 L\n451.333 397.365 L\n486.5 486.537 L\n521.667 522.02 L\n556.833 534.916 L\n592 537.249 L\n627.167 533.807 L\n662.333 526.605 L\n697.5 516.642 L\n732.667 504.607 L\n767.833 491.154 L\n803 476.995 L\n838.167 462.894 L\n873.333 449.617 L\n908.5 437.882 L\n943.667 428.31 L\n978.833 421.427 L\n1014 417.708 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n170 193.897 M\n205.167 193.959 L\n240.333 171.166 L\n275.5 134.449 L\n310.667 120.975 L\n345.833 149.825 L\n381 214.015 L\n416.167 289.571 L\n451.333 397.509 L\n486.5 487.236 L\n521.667 523.048 L\n556.833 535.941 L\n592 538.032 L\n627.167 534.261 L\n662.333 526.757 L\n697.5 516.573 L\n732.667 504.405 L\n767.833 490.892 L\n803 476.723 L\n838.167 462.641 L\n873.333 449.396 L\n908.5 437.695 L\n943.667 428.154 L\n978.833 421.293 L\n1014 417.587 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n170 193.897 M\n205.167 194.066 L\n240.333 171.223 L\n275.5 134.451 L\n310.667 120.949 L\n345.833 149.779 L\n381 213.946 L\n416.167 289.476 L\n451.333 397.395 L\n486.5 486.684 L\n521.667 522.237 L\n556.833 535.133 L\n592 537.414 L\n627.167 533.903 L\n662.333 526.637 L\n697.5 516.628 L\n732.667 504.564 L\n767.833 491.099 L\n803 476.938 L\n838.167 462.84 L\n873.333 449.57 L\n908.5 437.842 L\n943.667 428.277 L\n978.833 421.399 L\n1014 417.683 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n170 193.897 M\n205.167 193.981 L\n240.333 171.178 L\n275.5 134.449 L\n310.667 120.97 L\n345.833 149.816 L\n381 214 L\n416.167 289.55 L\n451.333 397.485 L\n486.5 487.119 L\n521.667 522.877 L\n556.833 535.77 L\n592 537.902 L\n627.167 534.185 L\n662.333 526.732 L\n697.5 516.585 L\n732.667 504.439 L\n767.833 490.936 L\n803 476.769 L\n838.167 462.683 L\n873.333 449.433 L\n908.5 437.726 L\n943.667 428.18 L\n978.833 421.315 L\n1014 417.607 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n170 193.897 M\n205.167 194.048 L\n240.333 171.213 L\n275.5 134.45 L\n310.667 120.955 L\n345.833 149.787 L\n381 213.957 L\n416.167 289.491 L\n451.333 397.413 L\n486.5 486.776 L\n521.667 522.372 L\n556.833 535.267 L\n592 537.517 L\n627.167 533.962 L\n662.333 526.657 L\n697.5 516.619 L\n732.667 504.538 L\n767.833 491.064 L\n803 476.902 L\n838.167 462.807 L\n873.333 449.541 L\n908.5 437.818 L\n943.667 428.257 L\n978.833 421.381 L\n1014 417.667 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n170 193.897 M\n205.167 193.995 L\n240.333 171.184 L\n275.5 134.449 L\n310.667 120.968 L\n345.833 149.811 L\n381 213.99 L\n416.167 289.537 L\n451.333 397.469 L\n486.5 487.046 L\n521.667 522.77 L\n556.833 535.664 L\n592 537.821 L\n627.167 534.138 L\n662.333 526.716 L\n697.5 516.592 L\n732.667 504.46 L\n767.833 490.963 L\n803 476.797 L\n838.167 462.709 L\n873.333 449.456 L\n908.5 437.745 L\n943.667 428.196 L\n978.833 421.329 L\n1014 417.62 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n170 193.897 M\n205.167 194.036 L\n240.333 171.206 L\n275.5 134.45 L\n310.667 120.959 L\n345.833 149.793 L\n381 213.964 L\n416.167 289.5 L\n451.333 397.425 L\n486.5 486.833 L\n521.667 522.456 L\n556.833 535.351 L\n592 537.581 L\n627.167 533.999 L\n662.333 526.67 L\n697.5 516.613 L\n732.667 504.521 L\n767.833 491.043 L\n803 476.88 L\n838.167 462.786 L\n873.333 449.523 L\n908.5 437.802 L\n943.667 428.244 L\n978.833 421.37 L\n1014 417.657 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n170 193.897 M\n205.167 194.003 L\n240.333 171.188 L\n275.5 134.449 L\n310.667 120.968 L\n345.833 149.808 L\n381 213.984 L\n416.167 289.529 L\n451.333 397.459 L\n486.5 487.001 L\n521.667 522.704 L\n556.833 535.598 L\n592 537.77 L\n627.167 534.109 L\n662.333 526.706 L\n697.5 516.596 L\n732.667 504.473 L\n767.833 490.98 L\n803 476.814 L\n838.167 462.725 L\n873.333 449.47 L\n908.5 437.757 L\n943.667 428.206 L\n978.833 421.338 L\n1014 417.627 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n170 193.897 M\n205.167 194.029 L\n240.333 171.202 L\n275.5 134.449 L\n310.667 120.962 L\n345.833 149.797 L\n381 213.968 L\n416.167 289.506 L\n451.333 397.432 L\n486.5 486.868 L\n521.667 522.508 L\n556.833 535.403 L\n592 537.621 L\n627.167 534.023 L\n662.333 526.677 L\n697.5 516.61 L\n732.667 504.511 L\n767.833 491.03 L\n803 476.866 L\n838.167 462.774 L\n873.333 449.512 L\n908.5 437.793 L\n943.667 428.236 L\n978.833 421.363 L\n1014 417.651 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n170 193.897 M\n205.167 194.009 L\n240.333 171.191 L\n275.5 134.448 L\n310.667 120.968 L\n345.833 149.807 L\n381 213.98 L\n416.167 289.523 L\n451.333 397.453 L\n486.5 486.973 L\n521.667 522.663 L\n556.833 535.557 L\n592 537.739 L\n627.167 534.091 L\n662.333 526.7 L\n697.5 516.599 L\n732.667 504.481 L\n767.833 490.99 L\n803 476.825 L\n838.167 462.736 L\n873.333 449.479 L\n908.5 437.765 L\n943.667 428.213 L\n978.833 421.343 L\n1014 417.632 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 241.78125 142.6875] CT\r\nN\r\n-0.641 18.348 M\n-0.641 17.176 0.172 16.317 QT\n0.984 15.457 2.156 15.457 QT\n2.938 15.457 3.461 15.942 QT\n3.984 16.426 3.984 17.192 QT\n3.984 18.114 3.414 18.848 QT\n2.844 19.582 1.969 19.817 QT\n2.813 20.129 3.656 20.129 QT\n5.703 20.129 7.203 18.239 QT\n8.703 16.348 9.313 14.004 QT\n13.828 -4.043 L\n14.156 -5.433 14.156 -6.386 QT\n14.156 -8.449 12.734 -8.449 QT\n10.625 -8.449 9.039 -6.543 QT\n7.453 -4.636 6.469 -2.121 QT\n6.375 -1.824 6.094 -1.824 QT\n5.531 -1.824 L\n5.141 -1.824 5.141 -2.261 QT\n5.141 -2.402 L\n6.219 -5.293 8.211 -7.496 QT\n10.203 -9.699 12.828 -9.699 QT\n14.813 -9.699 16.094 -8.457 QT\n17.375 -7.215 17.375 -5.293 QT\n17.375 -4.605 17.234 -3.933 QT\n12.688 14.317 L\n12.188 16.254 10.805 17.871 QT\n9.422 19.489 7.5 20.426 QT\n5.578 21.364 3.563 21.364 QT\n1.953 21.364 0.656 20.59 QT\n-0.641 19.817 -0.641 18.348 QT\ncp\n14.563 -17.574 M\n14.563 -18.621 15.383 -19.418 QT\n16.203 -20.215 17.234 -20.215 QT\n18.047 -20.215 18.578 -19.715 QT\n19.109 -19.215 19.109 -18.433 QT\n19.109 -17.355 18.25 -16.55 QT\n17.391 -15.746 16.359 -15.746 QT\n15.594 -15.746 15.078 -16.285 QT\n14.563 -16.824 14.563 -17.574 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 241.78125 142.6875] CT\r\nN\r\n39.457 5.145 M\n39.066 5.145 38.808 4.84 QT\n38.55 4.535 38.55 4.176 QT\n38.55 3.785 38.808 3.504 QT\n39.066 3.223 39.457 3.223 QT\n69.597 3.223 L\n69.957 3.223 70.215 3.504 QT\n70.472 3.785 70.472 4.176 QT\n70.472 4.535 70.215 4.84 QT\n69.957 5.145 69.597 5.145 QT\n39.457 5.145 L\ncp\n39.457 -4.183 M\n39.066 -4.183 38.808 -4.465 QT\n38.55 -4.746 38.55 -5.152 QT\n38.55 -5.496 38.808 -5.8 QT\n39.066 -6.105 39.457 -6.105 QT\n69.597 -6.105 L\n69.957 -6.105 70.215 -5.8 QT\n70.472 -5.496 70.472 -5.152 QT\n70.472 -4.746 70.215 -4.465 QT\n69.957 -4.183 69.597 -4.183 QT\n39.457 -4.183 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 241.78125 142.6875] CT\r\nN\r\n90.967 11.52 M\n90.967 9.832 L\n96.967 9.832 96.967 8.301 QT\n96.967 -16.886 L\n94.483 -15.699 90.686 -15.699 QT\n90.686 -17.386 L\n96.576 -17.386 99.576 -20.449 QT\n100.248 -20.449 L\n100.42 -20.449 100.569 -20.324 QT\n100.717 -20.199 100.717 -20.027 QT\n100.717 8.301 L\n100.717 9.832 106.717 9.832 QT\n106.717 11.52 L\n90.967 11.52 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 134.9625 176.42188] CT\r\nN\r\n/f946251025{-0.641 18.348 M\n-0.641 17.176 0.172 16.317 QT\n0.984 15.457 2.156 15.457 QT\n2.938 15.457 3.461 15.942 QT\n3.984 16.426 3.984 17.192 QT\n3.984 18.114 3.414 18.848 QT\n2.844 19.582 1.969 19.817 QT\n2.813 20.129 3.656 20.129 QT\n5.703 20.129 7.203 18.239 QT\n8.703 16.348 9.313 14.004 QT\n13.828 -4.043 L\n14.156 -5.433 14.156 -6.386 QT\n14.156 -8.449 12.734 -8.449 QT\n10.625 -8.449 9.039 -6.543 QT\n7.453 -4.636 6.469 -2.121 QT\n6.375 -1.824 6.094 -1.824 QT\n5.531 -1.824 L\n5.141 -1.824 5.141 -2.261 QT\n5.141 -2.402 L\n6.219 -5.293 8.211 -7.496 QT\n10.203 -9.699 12.828 -9.699 QT\n14.813 -9.699 16.094 -8.457 QT\n17.375 -7.215 17.375 -5.293 QT\n17.375 -4.605 17.234 -3.933 QT\n12.688 14.317 L\n12.188 16.254 10.805 17.871 QT\n9.422 19.489 7.5 20.426 QT\n5.578 21.364 3.563 21.364 QT\n1.953 21.364 0.656 20.59 QT\n-0.641 19.817 -0.641 18.348 QT\ncp\n14.563 -17.574 M\n14.563 -18.621 15.383 -19.418 QT\n16.203 -20.215 17.234 -20.215 QT\n18.047 -20.215 18.578 -19.715 QT\n19.109 -19.215 19.109 -18.433 QT\n19.109 -17.355 18.25 -16.55 QT\n17.391 -15.746 16.359 -15.746 QT\n15.594 -15.746 15.078 -16.285 QT\n14.563 -16.824 14.563 -17.574 QT\ncp}def\r\nf946251025\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 134.9625 176.42188] CT\r\nN\r\n/f-1792154824{39.457 5.145 M\n39.066 5.145 38.808 4.84 QT\n38.55 4.535 38.55 4.176 QT\n38.55 3.785 38.808 3.504 QT\n39.066 3.223 39.457 3.223 QT\n69.597 3.223 L\n69.957 3.223 70.215 3.504 QT\n70.472 3.785 70.472 4.176 QT\n70.472 4.535 70.215 4.84 QT\n69.957 5.145 69.597 5.145 QT\n39.457 5.145 L\ncp\n39.457 -4.183 M\n39.066 -4.183 38.808 -4.465 QT\n38.55 -4.746 38.55 -5.152 QT\n38.55 -5.496 38.808 -5.8 QT\n39.066 -6.105 39.457 -6.105 QT\n69.597 -6.105 L\n69.957 -6.105 70.215 -5.8 QT\n70.472 -5.496 70.472 -5.152 QT\n70.472 -4.746 70.215 -4.465 QT\n69.957 -4.183 69.597 -4.183 QT\n39.457 -4.183 L\ncp}def\r\nf-1792154824\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 134.9625 176.42188] CT\r\nN\r\n/f1600933324{88.904 11.52 M\n88.904 10.223 L\n88.904 10.114 88.998 9.973 QT\n96.451 1.723 L\n98.139 -0.105 99.194 -1.347 QT\n100.248 -2.59 101.279 -4.207 QT\n102.311 -5.824 102.912 -7.504 QT\n103.514 -9.183 103.514 -11.058 QT\n103.514 -13.027 102.787 -14.816 QT\n102.061 -16.605 100.615 -17.683 QT\n99.17 -18.761 97.139 -18.761 QT\n95.045 -18.761 93.381 -17.511 QT\n91.717 -16.261 91.045 -14.261 QT\n91.233 -14.308 91.561 -14.308 QT\n92.639 -14.308 93.397 -13.582 QT\n94.154 -12.855 94.154 -11.715 QT\n94.154 -10.605 93.397 -9.847 QT\n92.639 -9.09 91.561 -9.09 QT\n90.436 -9.09 89.67 -9.871 QT\n88.904 -10.652 88.904 -11.715 QT\n88.904 -13.511 89.584 -15.097 QT\n90.264 -16.683 91.545 -17.91 QT\n92.826 -19.136 94.428 -19.793 QT\n96.029 -20.449 97.842 -20.449 QT\n100.576 -20.449 102.944 -19.293 QT\n105.311 -18.136 106.694 -16.011 QT\n108.076 -13.886 108.076 -11.058 QT\n108.076 -8.965 107.162 -7.09 QT\n106.248 -5.215 104.819 -3.683 QT\n103.389 -2.152 101.162 -0.207 QT\n98.936 1.739 98.233 2.395 QT\n92.795 7.629 L\n97.42 7.629 L\n100.811 7.629 103.1 7.567 QT\n105.389 7.504 105.529 7.395 QT\n106.092 6.785 106.67 2.957 QT\n108.076 2.957 L\n106.717 11.52 L\n88.904 11.52 L\ncp}def\r\nf1600933324\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n993 677 M\n993 553 L\n379 553 L\n379 677 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f1636705084{10.953 6.379 M\n12.594 8.473 15.055 9.676 QT\n17.516 10.879 20.156 10.879 QT\n22.391 10.879 24.289 10.004 QT\n26.188 9.129 27.602 7.559 QT\n29.016 5.989 29.781 3.996 QT\n30.547 2.004 30.547 -0.199 QT\n30.547 -0.574 30.969 -0.574 QT\n31.547 -0.574 L\n31.922 -0.574 31.922 -0.105 QT\n31.922 2.395 30.961 4.731 QT\n30 7.067 28.242 8.832 QT\n26.484 10.598 24.203 11.59 QT\n21.922 12.582 19.438 12.582 QT\n15.984 12.582 12.906 11.184 QT\n9.828 9.785 7.539 7.356 QT\n5.25 4.926 3.977 1.739 QT\n2.703 -1.449 2.703 -4.886 QT\n2.703 -8.34 3.977 -11.527 QT\n5.25 -14.715 7.539 -17.152 QT\n9.828 -19.59 12.906 -20.957 QT\n15.984 -22.324 19.438 -22.324 QT\n21.891 -22.324 24.141 -21.261 QT\n26.391 -20.199 28.078 -18.246 QT\n30.875 -22.183 L\n31.156 -22.324 31.203 -22.324 QT\n31.547 -22.324 L\n31.688 -22.324 31.805 -22.207 QT\n31.922 -22.09 31.922 -21.933 QT\n31.922 -8.965 L\n31.922 -8.543 31.547 -8.543 QT\n30.688 -8.543 L\n30.234 -8.543 30.234 -8.965 QT\n30.234 -10.355 29.688 -12.066 QT\n29.141 -13.777 28.281 -15.308 QT\n27.422 -16.84 26.297 -18.011 QT\n23.609 -20.636 20.109 -20.636 QT\n17.469 -20.636 15.039 -19.441 QT\n12.609 -18.246 10.953 -16.136 QT\n9.188 -13.886 8.508 -11.019 QT\n7.828 -8.152 7.828 -4.886 QT\n7.828 -1.636 8.508 1.246 QT\n9.188 4.129 10.953 6.379 QT\ncp}def\r\nf1636705084\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f-518588683{46.667 12.067 M\n43.792 12.067 41.331 10.598 QT\n38.87 9.129 37.44 6.668 QT\n36.01 4.207 36.01 1.301 QT\n36.01 -0.902 36.792 -2.941 QT\n37.573 -4.98 39.042 -6.59 QT\n40.51 -8.199 42.456 -9.097 QT\n44.401 -9.996 46.667 -9.996 QT\n49.62 -9.996 52.05 -8.441 QT\n54.479 -6.886 55.885 -4.269 QT\n57.292 -1.652 57.292 1.301 QT\n57.292 4.176 55.862 6.653 QT\n54.432 9.129 51.979 10.598 QT\n49.526 12.067 46.667 12.067 QT\ncp\n46.667 10.645 M\n50.51 10.645 51.8 7.856 QT\n53.089 5.067 53.089 0.754 QT\n53.089 -1.652 52.831 -3.238 QT\n52.573 -4.824 51.714 -6.105 QT\n51.167 -6.902 50.339 -7.504 QT\n49.51 -8.105 48.581 -8.418 QT\n47.651 -8.73 46.667 -8.73 QT\n45.167 -8.73 43.823 -8.05 QT\n42.479 -7.371 41.589 -6.105 QT\n40.698 -4.746 40.448 -3.121 QT\n40.198 -1.496 40.198 0.754 QT\n40.198 3.457 40.667 5.598 QT\n41.135 7.739 42.557 9.192 QT\n43.979 10.645 46.667 10.645 QT\ncp}def\r\nf-518588683\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f763322885{60.104 11.52 M\n60.104 9.832 L\n61.745 9.832 62.8 9.575 QT\n63.854 9.317 63.854 8.301 QT\n63.854 -4.793 L\n63.854 -6.09 63.464 -6.66 QT\n63.073 -7.23 62.346 -7.363 QT\n61.62 -7.496 60.104 -7.496 QT\n60.104 -9.183 L\n67.057 -9.699 L\n67.057 -5.011 L\n68.026 -7.074 69.909 -8.386 QT\n71.792 -9.699 74.026 -9.699 QT\n77.354 -9.699 79.026 -8.105 QT\n80.698 -6.511 80.698 -3.23 QT\n80.698 8.301 L\n80.698 9.317 81.753 9.575 QT\n82.807 9.832 84.448 9.832 QT\n84.448 11.52 L\n73.464 11.52 L\n73.464 9.832 L\n75.104 9.832 76.159 9.575 QT\n77.214 9.317 77.214 8.301 QT\n77.214 -3.09 L\n77.214 -5.433 76.534 -6.941 QT\n75.854 -8.449 73.745 -8.449 QT\n70.948 -8.449 69.159 -6.222 QT\n67.37 -3.996 67.37 -1.168 QT\n67.37 8.301 L\n67.37 9.317 68.425 9.575 QT\n69.479 9.832 71.089 9.832 QT\n71.089 11.52 L\n60.104 11.52 L\ncp}def\r\nf763322885\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f1813278697{95.719 11.52 M\n88.719 -6.105 L\n88.266 -6.996 87.344 -7.246 QT\n86.422 -7.496 84.922 -7.496 QT\n84.922 -9.183 L\n95 -9.183 L\n95 -7.496 L\n92.297 -7.496 92.297 -6.34 QT\n92.297 -6.152 92.344 -6.058 QT\n97.735 7.489 L\n102.594 -4.746 L\n102.735 -5.121 102.735 -5.527 QT\n102.735 -6.433 102.039 -6.965 QT\n101.344 -7.496 100.406 -7.496 QT\n100.406 -9.183 L\n108.375 -9.183 L\n108.375 -7.496 L\n106.906 -7.496 105.789 -6.816 QT\n104.672 -6.136 104.063 -4.793 QT\n97.594 11.52 L\n97.406 12.067 96.828 12.067 QT\n96.469 12.067 L\n95.891 12.067 95.719 11.52 QT\ncp}def\r\nf1813278697\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f1730672616{119.953 12.067 M\n117.031 12.067 114.578 10.528 QT\n112.125 8.989 110.735 6.418 QT\n109.344 3.848 109.344 0.989 QT\n109.344 -1.824 110.617 -4.355 QT\n111.891 -6.886 114.18 -8.441 QT\n116.469 -9.996 119.281 -9.996 QT\n121.485 -9.996 123.11 -9.261 QT\n124.735 -8.527 125.789 -7.215 QT\n126.844 -5.902 127.383 -4.121 QT\n127.922 -2.34 127.922 -0.199 QT\n127.922 0.426 127.438 0.426 QT\n113.531 0.426 L\n113.531 0.942 L\n113.531 4.926 115.141 7.785 QT\n116.75 10.645 120.375 10.645 QT\n121.86 10.645 123.11 9.989 QT\n124.36 9.332 125.289 8.16 QT\n126.219 6.989 126.547 5.66 QT\n126.594 5.489 126.719 5.364 QT\n126.844 5.239 127.016 5.239 QT\n127.438 5.239 L\n127.922 5.239 127.922 5.848 QT\n127.25 8.567 125 10.317 QT\n122.75 12.067 119.953 12.067 QT\ncp\n113.578 -0.761 M\n124.531 -0.761 L\n124.531 -2.574 124.024 -4.425 QT\n123.516 -6.277 122.344 -7.504 QT\n121.172 -8.73 119.281 -8.73 QT\n116.563 -8.73 115.071 -6.191 QT\n113.578 -3.652 113.578 -0.761 QT\ncp}def\r\nf1730672616\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f1581324804{130.584 11.52 M\n130.584 9.832 L\n132.224 9.832 133.279 9.575 QT\n134.334 9.317 134.334 8.301 QT\n134.334 -4.793 L\n134.334 -6.09 133.943 -6.66 QT\n133.552 -7.23 132.826 -7.363 QT\n132.099 -7.496 130.584 -7.496 QT\n130.584 -9.183 L\n137.443 -9.699 L\n137.443 -5.011 L\n138.224 -7.09 139.654 -8.394 QT\n141.084 -9.699 143.115 -9.699 QT\n144.552 -9.699 145.677 -8.855 QT\n146.802 -8.011 146.802 -6.621 QT\n146.802 -5.761 146.177 -5.113 QT\n145.552 -4.465 144.646 -4.465 QT\n143.755 -4.465 143.123 -5.097 QT\n142.49 -5.73 142.49 -6.621 QT\n142.49 -7.918 143.396 -8.449 QT\n143.115 -8.449 L\n141.177 -8.449 139.943 -7.043 QT\n138.709 -5.636 138.193 -3.55 QT\n137.677 -1.465 137.677 0.426 QT\n137.677 8.301 L\n137.677 9.832 142.349 9.832 QT\n142.349 11.52 L\n130.584 11.52 L\ncp}def\r\nf1581324804\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f-1655348641{149.477 15.27 M\n149.477 13.567 150.72 12.285 QT\n151.962 11.004 153.665 10.457 QT\n152.712 9.739 152.204 8.637 QT\n151.696 7.535 151.696 6.285 QT\n151.696 4.035 153.134 2.301 QT\n150.93 0.145 150.93 -2.636 QT\n150.93 -4.136 151.571 -5.449 QT\n152.212 -6.761 153.36 -7.722 QT\n154.509 -8.683 155.915 -9.191 QT\n157.321 -9.699 158.805 -9.699 QT\n161.665 -9.699 163.93 -8.027 QT\n164.915 -9.09 166.266 -9.66 QT\n167.618 -10.23 169.071 -10.23 QT\n170.102 -10.23 170.759 -9.496 QT\n171.415 -8.761 171.415 -7.73 QT\n171.415 -7.136 170.97 -6.691 QT\n170.524 -6.246 169.93 -6.246 QT\n169.321 -6.246 168.876 -6.691 QT\n168.43 -7.136 168.43 -7.73 QT\n168.43 -8.621 169.024 -8.965 QT\n166.54 -8.965 164.759 -7.261 QT\n165.618 -6.386 166.149 -5.136 QT\n166.68 -3.886 166.68 -2.636 QT\n166.68 -0.605 165.555 1.028 QT\n164.43 2.66 162.587 3.559 QT\n160.743 4.457 158.805 4.457 QT\n156.18 4.457 153.993 3.035 QT\n153.321 3.973 153.321 5.145 QT\n153.321 6.41 154.149 7.356 QT\n154.977 8.301 156.243 8.301 QT\n160.18 8.301 L\n163.04 8.301 165.337 8.817 QT\n167.634 9.332 169.196 10.887 QT\n170.759 12.442 170.759 15.27 QT\n170.759 17.379 168.977 18.778 QT\n167.196 20.176 164.72 20.793 QT\n162.243 21.41 160.134 21.41 QT\n158.009 21.41 155.524 20.793 QT\n153.04 20.176 151.259 18.778 QT\n149.477 17.379 149.477 15.27 QT\ncp\n152.165 15.27 M\n152.165 16.895 153.477 17.981 QT\n154.79 19.067 156.641 19.598 QT\n158.493 20.129 160.134 20.129 QT\n161.759 20.129 163.61 19.598 QT\n165.462 19.067 166.759 17.981 QT\n168.055 16.895 168.055 15.27 QT\n168.055 12.77 165.759 12.028 QT\n163.462 11.285 160.18 11.285 QT\n156.243 11.285 L\n155.149 11.285 154.22 11.817 QT\n153.29 12.348 152.727 13.293 QT\n152.165 14.239 152.165 15.27 QT\ncp\n158.805 3.176 M\n162.884 3.176 162.884 -2.636 QT\n162.884 -5.152 162.016 -6.777 QT\n161.149 -8.402 158.805 -8.402 QT\n156.462 -8.402 155.595 -6.777 QT\n154.727 -5.152 154.727 -2.636 QT\n154.727 -1.043 155.055 0.246 QT\n155.384 1.535 156.274 2.356 QT\n157.165 3.176 158.805 3.176 QT\ncp}def\r\nf-1655348641\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f402514587{184.087 12.067 M\n181.165 12.067 178.712 10.528 QT\n176.259 8.989 174.868 6.418 QT\n173.477 3.848 173.477 0.989 QT\n173.477 -1.824 174.751 -4.355 QT\n176.024 -6.886 178.313 -8.441 QT\n180.602 -9.996 183.415 -9.996 QT\n185.618 -9.996 187.243 -9.261 QT\n188.868 -8.527 189.923 -7.215 QT\n190.977 -5.902 191.516 -4.121 QT\n192.056 -2.34 192.056 -0.199 QT\n192.056 0.426 191.571 0.426 QT\n177.665 0.426 L\n177.665 0.942 L\n177.665 4.926 179.274 7.785 QT\n180.884 10.645 184.509 10.645 QT\n185.993 10.645 187.243 9.989 QT\n188.493 9.332 189.423 8.16 QT\n190.352 6.989 190.681 5.66 QT\n190.727 5.489 190.852 5.364 QT\n190.977 5.239 191.149 5.239 QT\n191.571 5.239 L\n192.056 5.239 192.056 5.848 QT\n191.384 8.567 189.134 10.317 QT\n186.884 12.067 184.087 12.067 QT\ncp\n177.712 -0.761 M\n188.665 -0.761 L\n188.665 -2.574 188.157 -4.425 QT\n187.649 -6.277 186.477 -7.504 QT\n185.306 -8.73 183.415 -8.73 QT\n180.696 -8.73 179.204 -6.191 QT\n177.712 -3.652 177.712 -0.761 QT\ncp}def\r\nf402514587\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f909272395{205.186 12.067 M\n202.358 12.067 200.014 10.528 QT\n197.67 8.989 196.365 6.481 QT\n195.061 3.973 195.061 1.16 QT\n195.061 -1.746 196.483 -4.246 QT\n197.904 -6.746 200.342 -8.222 QT\n202.779 -9.699 205.701 -9.699 QT\n207.467 -9.699 209.037 -8.957 QT\n210.608 -8.215 211.748 -6.902 QT\n211.748 -16.886 L\n211.748 -18.183 211.365 -18.754 QT\n210.983 -19.324 210.264 -19.457 QT\n209.545 -19.59 208.029 -19.59 QT\n208.029 -21.277 L\n215.123 -21.793 L\n215.123 7.16 L\n215.123 8.426 215.514 8.996 QT\n215.904 9.567 216.615 9.7 QT\n217.326 9.832 218.858 9.832 QT\n218.858 11.52 L\n211.608 12.067 L\n211.608 9.035 L\n210.373 10.457 208.662 11.262 QT\n206.951 12.067 205.186 12.067 QT\ncp\n200.295 7.348 M\n201.108 8.91 202.483 9.848 QT\n203.858 10.785 205.467 10.785 QT\n207.467 10.785 209.131 9.637 QT\n210.795 8.489 211.608 6.66 QT\n211.608 -4.84 L\n211.045 -5.902 210.194 -6.73 QT\n209.342 -7.558 208.272 -8.004 QT\n207.201 -8.449 206.014 -8.449 QT\n203.498 -8.449 201.975 -7.035 QT\n200.451 -5.621 199.842 -3.418 QT\n199.233 -1.215 199.233 1.207 QT\n199.233 3.129 199.436 4.559 QT\n199.639 5.989 200.295 7.348 QT\ncp}def\r\nf909272395\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f-583193730{251.024 23.426 M\n248.352 21.317 246.415 18.59 QT\n244.477 15.864 243.251 12.762 QT\n242.024 9.66 241.415 6.285 QT\n240.806 2.91 240.806 -0.48 QT\n240.806 -3.933 241.415 -7.308 QT\n242.024 -10.683 243.274 -13.8 QT\n244.524 -16.918 246.47 -19.636 QT\n248.415 -22.355 251.024 -24.386 QT\n251.024 -24.48 251.259 -24.48 QT\n251.696 -24.48 L\n251.837 -24.48 251.954 -24.355 QT\n252.071 -24.23 252.071 -24.058 QT\n252.071 -23.855 251.977 -23.761 QT\n249.634 -21.465 248.079 -18.84 QT\n246.524 -16.215 245.571 -13.246 QT\n244.618 -10.277 244.196 -7.105 QT\n243.774 -3.933 243.774 -0.48 QT\n243.774 14.785 251.931 22.707 QT\n252.071 22.848 252.071 23.098 QT\n252.071 23.223 251.946 23.371 QT\n251.821 23.52 251.696 23.52 QT\n251.259 23.52 L\n251.024 23.52 251.024 23.426 QT\ncp}def\r\nf-583193730\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f-129920944{254.16 18.348 M\n254.16 17.176 254.972 16.317 QT\n255.785 15.457 256.957 15.457 QT\n257.738 15.457 258.261 15.942 QT\n258.785 16.426 258.785 17.192 QT\n258.785 18.114 258.214 18.848 QT\n257.644 19.582 256.769 19.817 QT\n257.613 20.129 258.457 20.129 QT\n260.504 20.129 262.004 18.239 QT\n263.504 16.348 264.113 14.004 QT\n268.629 -4.043 L\n268.957 -5.433 268.957 -6.386 QT\n268.957 -8.449 267.535 -8.449 QT\n265.425 -8.449 263.839 -6.543 QT\n262.254 -4.636 261.269 -2.121 QT\n261.175 -1.824 260.894 -1.824 QT\n260.332 -1.824 L\n259.941 -1.824 259.941 -2.261 QT\n259.941 -2.402 L\n261.019 -5.293 263.011 -7.496 QT\n265.004 -9.699 267.629 -9.699 QT\n269.613 -9.699 270.894 -8.457 QT\n272.175 -7.215 272.175 -5.293 QT\n272.175 -4.605 272.035 -3.933 QT\n267.488 14.317 L\n266.988 16.254 265.605 17.871 QT\n264.222 19.489 262.3 20.426 QT\n260.379 21.364 258.363 21.364 QT\n256.754 21.364 255.457 20.59 QT\n254.16 19.817 254.16 18.348 QT\ncp\n269.363 -17.574 M\n269.363 -18.621 270.183 -19.418 QT\n271.004 -20.215 272.035 -20.215 QT\n272.847 -20.215 273.379 -19.715 QT\n273.91 -19.215 273.91 -18.433 QT\n273.91 -17.355 273.05 -16.55 QT\n272.191 -15.746 271.16 -15.746 QT\n270.394 -15.746 269.879 -16.285 QT\n269.363 -16.824 269.363 -17.574 QT\ncp}def\r\nf-129920944\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f730600524{294.257 5.145 M\n293.867 5.145 293.609 4.84 QT\n293.351 4.535 293.351 4.176 QT\n293.351 3.785 293.609 3.504 QT\n293.867 3.223 294.257 3.223 QT\n324.398 3.223 L\n324.757 3.223 325.015 3.504 QT\n325.273 3.785 325.273 4.176 QT\n325.273 4.535 325.015 4.84 QT\n324.757 5.145 324.398 5.145 QT\n294.257 5.145 L\ncp\n294.257 -4.183 M\n293.867 -4.183 293.609 -4.465 QT\n293.351 -4.746 293.351 -5.152 QT\n293.351 -5.496 293.609 -5.8 QT\n293.867 -6.105 294.257 -6.105 QT\n324.398 -6.105 L\n324.757 -6.105 325.015 -5.8 QT\n325.273 -5.496 325.273 -5.152 QT\n325.273 -4.746 325.015 -4.465 QT\n324.757 -4.183 324.398 -4.183 QT\n294.257 -4.183 L\ncp}def\r\nf730600524\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f704190049{345.892 7.817 M\n347.017 9.457 348.916 10.254 QT\n350.814 11.051 352.986 11.051 QT\n355.783 11.051 356.955 8.668 QT\n358.127 6.285 358.127 3.27 QT\n358.127 1.91 357.877 0.551 QT\n357.627 -0.808 357.041 -1.98 QT\n356.455 -3.152 355.439 -3.855 QT\n354.424 -4.558 352.939 -4.558 QT\n349.752 -4.558 L\n349.33 -4.558 349.33 -5.011 QT\n349.33 -5.433 L\n349.33 -5.808 349.752 -5.808 QT\n352.408 -6.011 L\n354.095 -6.011 355.205 -7.277 QT\n356.314 -8.543 356.83 -10.363 QT\n357.345 -12.183 357.345 -13.824 QT\n357.345 -16.121 356.267 -17.597 QT\n355.189 -19.074 352.986 -19.074 QT\n351.158 -19.074 349.494 -18.379 QT\n347.83 -17.683 346.845 -16.277 QT\n346.939 -16.308 347.01 -16.316 QT\n347.08 -16.324 347.174 -16.324 QT\n348.252 -16.324 348.978 -15.574 QT\n349.705 -14.824 349.705 -13.777 QT\n349.705 -12.746 348.978 -11.996 QT\n348.252 -11.246 347.174 -11.246 QT\n346.127 -11.246 345.377 -11.996 QT\n344.627 -12.746 344.627 -13.777 QT\n344.627 -15.84 345.869 -17.363 QT\n347.111 -18.886 349.064 -19.668 QT\n351.017 -20.449 352.986 -20.449 QT\n354.439 -20.449 356.056 -20.019 QT\n357.674 -19.59 358.986 -18.777 QT\n360.299 -17.965 361.135 -16.699 QT\n361.97 -15.433 361.97 -13.824 QT\n361.97 -11.808 361.064 -10.097 QT\n360.158 -8.386 358.588 -7.144 QT\n357.017 -5.902 355.142 -5.293 QT\n357.236 -4.886 359.111 -3.715 QT\n360.986 -2.543 362.119 -0.715 QT\n363.252 1.114 363.252 3.223 QT\n363.252 5.864 361.799 8.012 QT\n360.345 10.16 357.978 11.371 QT\n355.611 12.582 352.986 12.582 QT\n350.736 12.582 348.478 11.723 QT\n346.22 10.864 344.775 9.153 QT\n343.33 7.442 343.33 5.051 QT\n343.33 3.848 344.127 3.051 QT\n344.924 2.254 346.127 2.254 QT\n346.892 2.254 347.541 2.621 QT\n348.189 2.989 348.549 3.645 QT\n348.908 4.301 348.908 5.051 QT\n348.908 6.223 348.088 7.02 QT\n347.267 7.817 346.127 7.817 QT\n345.892 7.817 L\ncp}def\r\nf704190049\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f400715756{367.705 11.52 M\n367.705 10.223 L\n367.705 10.114 367.799 9.973 QT\n375.252 1.723 L\n376.939 -0.105 377.994 -1.347 QT\n379.049 -2.59 380.08 -4.207 QT\n381.111 -5.824 381.713 -7.504 QT\n382.314 -9.183 382.314 -11.058 QT\n382.314 -13.027 381.588 -14.816 QT\n380.861 -16.605 379.416 -17.683 QT\n377.971 -18.761 375.939 -18.761 QT\n373.846 -18.761 372.182 -17.511 QT\n370.517 -16.261 369.846 -14.261 QT\n370.033 -14.308 370.361 -14.308 QT\n371.439 -14.308 372.197 -13.582 QT\n372.955 -12.855 372.955 -11.715 QT\n372.955 -10.605 372.197 -9.847 QT\n371.439 -9.09 370.361 -9.09 QT\n369.236 -9.09 368.471 -9.871 QT\n367.705 -10.652 367.705 -11.715 QT\n367.705 -13.511 368.385 -15.097 QT\n369.064 -16.683 370.346 -17.91 QT\n371.627 -19.136 373.228 -19.793 QT\n374.83 -20.449 376.642 -20.449 QT\n379.377 -20.449 381.744 -19.293 QT\n384.111 -18.136 385.494 -16.011 QT\n386.877 -13.886 386.877 -11.058 QT\n386.877 -8.965 385.963 -7.09 QT\n385.049 -5.215 383.619 -3.683 QT\n382.189 -2.152 379.963 -0.207 QT\n377.736 1.739 377.033 2.395 QT\n371.596 7.629 L\n376.221 7.629 L\n379.611 7.629 381.9 7.567 QT\n384.189 7.504 384.33 7.395 QT\n384.892 6.785 385.471 2.957 QT\n386.877 2.957 L\n385.517 11.52 L\n367.705 11.52 L\ncp}def\r\nf400715756\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f-420795744{392.439 23.52 M\n392.018 23.52 392.018 23.098 QT\n392.018 22.895 392.111 22.801 QT\n400.314 14.785 400.314 -0.48 QT\n400.314 -15.746 392.205 -23.668 QT\n392.018 -23.777 392.018 -24.058 QT\n392.018 -24.23 392.143 -24.355 QT\n392.268 -24.48 392.439 -24.48 QT\n392.877 -24.48 L\n393.018 -24.48 393.111 -24.386 QT\n396.564 -21.668 398.861 -17.777 QT\n401.158 -13.886 402.221 -9.48 QT\n403.283 -5.074 403.283 -0.48 QT\n403.283 2.91 402.713 6.207 QT\n402.143 9.504 400.885 12.707 QT\n399.627 15.91 397.705 18.614 QT\n395.783 21.317 393.111 23.426 QT\n393.018 23.52 392.877 23.52 QT\n392.439 23.52 L\ncp}def\r\nf-420795744\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n387 585.747 M\n467.003 585.747 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf1636705084\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf-518588683\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf763322885\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf1813278697\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf1730672616\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf1581324804\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf-1655348641\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f-2079540185{173.618 11.52 M\n173.618 9.832 L\n175.259 9.832 176.313 9.575 QT\n177.368 9.317 177.368 8.301 QT\n177.368 -4.793 L\n177.368 -6.652 176.649 -7.074 QT\n175.931 -7.496 173.821 -7.496 QT\n173.821 -9.183 L\n180.743 -9.699 L\n180.743 8.301 L\n180.743 9.317 181.657 9.575 QT\n182.571 9.832 184.087 9.832 QT\n184.087 11.52 L\n173.618 11.52 L\ncp\n175.649 -17.949 M\n175.649 -18.996 176.446 -19.793 QT\n177.243 -20.59 178.274 -20.59 QT\n178.962 -20.59 179.595 -20.238 QT\n180.227 -19.886 180.579 -19.254 QT\n180.931 -18.621 180.931 -17.949 QT\n180.931 -16.918 180.134 -16.121 QT\n179.337 -15.324 178.274 -15.324 QT\n177.243 -15.324 176.446 -16.121 QT\n175.649 -16.918 175.649 -17.949 QT\ncp}def\r\nf-2079540185\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f581539271{186.905 11.52 M\n186.905 9.832 L\n188.545 9.832 189.6 9.575 QT\n190.655 9.317 190.655 8.301 QT\n190.655 -4.793 L\n190.655 -6.09 190.264 -6.66 QT\n189.873 -7.23 189.147 -7.363 QT\n188.42 -7.496 186.905 -7.496 QT\n186.905 -9.183 L\n193.858 -9.699 L\n193.858 -5.011 L\n194.826 -7.074 196.709 -8.386 QT\n198.592 -9.699 200.826 -9.699 QT\n204.155 -9.699 205.826 -8.105 QT\n207.498 -6.511 207.498 -3.23 QT\n207.498 8.301 L\n207.498 9.317 208.553 9.575 QT\n209.608 9.832 211.248 9.832 QT\n211.248 11.52 L\n200.264 11.52 L\n200.264 9.832 L\n201.905 9.832 202.959 9.575 QT\n204.014 9.317 204.014 8.301 QT\n204.014 -3.09 L\n204.014 -5.433 203.334 -6.941 QT\n202.655 -8.449 200.545 -8.449 QT\n197.748 -8.449 195.959 -6.222 QT\n194.17 -3.996 194.17 -1.168 QT\n194.17 8.301 L\n194.17 9.317 195.225 9.575 QT\n196.28 9.832 197.889 9.832 QT\n197.889 11.52 L\n186.905 11.52 L\ncp}def\r\nf581539271\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f-1710606110{213.478 15.27 M\n213.478 13.567 214.72 12.285 QT\n215.962 11.004 217.665 10.457 QT\n216.712 9.739 216.204 8.637 QT\n215.696 7.535 215.696 6.285 QT\n215.696 4.035 217.134 2.301 QT\n214.931 0.145 214.931 -2.636 QT\n214.931 -4.136 215.571 -5.449 QT\n216.212 -6.761 217.36 -7.722 QT\n218.509 -8.683 219.915 -9.191 QT\n221.321 -9.699 222.806 -9.699 QT\n225.665 -9.699 227.931 -8.027 QT\n228.915 -9.09 230.267 -9.66 QT\n231.618 -10.23 233.071 -10.23 QT\n234.103 -10.23 234.759 -9.496 QT\n235.415 -8.761 235.415 -7.73 QT\n235.415 -7.136 234.97 -6.691 QT\n234.524 -6.246 233.931 -6.246 QT\n233.321 -6.246 232.876 -6.691 QT\n232.431 -7.136 232.431 -7.73 QT\n232.431 -8.621 233.024 -8.965 QT\n230.54 -8.965 228.759 -7.261 QT\n229.618 -6.386 230.149 -5.136 QT\n230.681 -3.886 230.681 -2.636 QT\n230.681 -0.605 229.556 1.028 QT\n228.431 2.66 226.587 3.559 QT\n224.743 4.457 222.806 4.457 QT\n220.181 4.457 217.993 3.035 QT\n217.321 3.973 217.321 5.145 QT\n217.321 6.41 218.149 7.356 QT\n218.978 8.301 220.243 8.301 QT\n224.181 8.301 L\n227.04 8.301 229.337 8.817 QT\n231.634 9.332 233.196 10.887 QT\n234.759 12.442 234.759 15.27 QT\n234.759 17.379 232.978 18.778 QT\n231.196 20.176 228.72 20.793 QT\n226.243 21.41 224.134 21.41 QT\n222.009 21.41 219.524 20.793 QT\n217.04 20.176 215.259 18.778 QT\n213.478 17.379 213.478 15.27 QT\ncp\n216.165 15.27 M\n216.165 16.895 217.478 17.981 QT\n218.79 19.067 220.642 19.598 QT\n222.493 20.129 224.134 20.129 QT\n225.759 20.129 227.61 19.598 QT\n229.462 19.067 230.759 17.981 QT\n232.056 16.895 232.056 15.27 QT\n232.056 12.77 229.759 12.028 QT\n227.462 11.285 224.181 11.285 QT\n220.243 11.285 L\n219.149 11.285 218.22 11.817 QT\n217.29 12.348 216.728 13.293 QT\n216.165 14.239 216.165 15.27 QT\ncp\n222.806 3.176 M\n226.884 3.176 226.884 -2.636 QT\n226.884 -5.152 226.017 -6.777 QT\n225.149 -8.402 222.806 -8.402 QT\n220.462 -8.402 219.595 -6.777 QT\n218.728 -5.152 218.728 -2.636 QT\n218.728 -1.043 219.056 0.246 QT\n219.384 1.535 220.274 2.356 QT\n221.165 3.176 222.806 3.176 QT\ncp}def\r\nf-1710606110\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f929488190{267.024 23.426 M\n264.353 21.317 262.415 18.59 QT\n260.478 15.864 259.251 12.762 QT\n258.024 9.66 257.415 6.285 QT\n256.806 2.91 256.806 -0.48 QT\n256.806 -3.933 257.415 -7.308 QT\n258.024 -10.683 259.274 -13.8 QT\n260.524 -16.918 262.47 -19.636 QT\n264.415 -22.355 267.024 -24.386 QT\n267.024 -24.48 267.259 -24.48 QT\n267.696 -24.48 L\n267.837 -24.48 267.954 -24.355 QT\n268.071 -24.23 268.071 -24.058 QT\n268.071 -23.855 267.978 -23.761 QT\n265.634 -21.465 264.079 -18.84 QT\n262.524 -16.215 261.571 -13.246 QT\n260.618 -10.277 260.196 -7.105 QT\n259.774 -3.933 259.774 -0.48 QT\n259.774 14.785 267.931 22.707 QT\n268.071 22.848 268.071 23.098 QT\n268.071 23.223 267.946 23.371 QT\n267.821 23.52 267.696 23.52 QT\n267.259 23.52 L\n267.024 23.52 267.024 23.426 QT\ncp}def\r\nf929488190\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f919804271{275.254 11.52 M\n275.254 9.832 L\n281.254 9.832 281.254 8.301 QT\n281.254 -16.886 L\n278.769 -15.699 274.972 -15.699 QT\n274.972 -17.386 L\n280.863 -17.386 283.863 -20.449 QT\n284.535 -20.449 L\n284.707 -20.449 284.855 -20.324 QT\n285.004 -20.199 285.004 -20.027 QT\n285.004 8.301 L\n285.004 9.832 291.004 9.832 QT\n291.004 11.52 L\n275.254 11.52 L\ncp}def\r\nf919804271\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f1957607420{313.04 18.114 M\n312.634 18.114 312.376 17.809 QT\n312.118 17.504 312.118 17.145 QT\n312.118 16.754 312.376 16.473 QT\n312.634 16.192 313.04 16.192 QT\n340.571 16.192 L\n340.946 16.192 341.196 16.473 QT\n341.446 16.754 341.446 17.145 QT\n341.446 17.504 341.196 17.809 QT\n340.946 18.114 340.571 18.114 QT\n313.04 18.114 L\ncp\n312.587 -4.324 M\n312.118 -4.465 312.118 -5.152 QT\n312.118 -5.761 312.759 -6.011 QT\n340.149 -18.949 L\n340.243 -19.027 340.477 -19.027 QT\n340.884 -19.027 341.165 -18.746 QT\n341.446 -18.465 341.446 -18.058 QT\n341.446 -17.433 340.884 -17.199 QT\n315.337 -5.152 L\n341.024 6.989 L\n341.446 7.223 341.446 7.817 QT\n341.446 8.239 341.165 8.504 QT\n340.884 8.77 340.477 8.77 QT\n340.243 8.77 340.149 8.676 QT\n312.587 -4.324 L\ncp}def\r\nf1957607420\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f127127908{358.159 18.348 M\n358.159 17.176 358.972 16.317 QT\n359.784 15.457 360.956 15.457 QT\n361.738 15.457 362.261 15.942 QT\n362.784 16.426 362.784 17.192 QT\n362.784 18.114 362.214 18.848 QT\n361.644 19.582 360.769 19.817 QT\n361.613 20.129 362.456 20.129 QT\n364.503 20.129 366.003 18.239 QT\n367.503 16.348 368.113 14.004 QT\n372.628 -4.043 L\n372.956 -5.433 372.956 -6.386 QT\n372.956 -8.449 371.534 -8.449 QT\n369.425 -8.449 367.839 -6.543 QT\n366.253 -4.636 365.269 -2.121 QT\n365.175 -1.824 364.894 -1.824 QT\n364.331 -1.824 L\n363.941 -1.824 363.941 -2.261 QT\n363.941 -2.402 L\n365.019 -5.293 367.011 -7.496 QT\n369.003 -9.699 371.628 -9.699 QT\n373.613 -9.699 374.894 -8.457 QT\n376.175 -7.215 376.175 -5.293 QT\n376.175 -4.605 376.034 -3.933 QT\n371.488 14.317 L\n370.988 16.254 369.605 17.871 QT\n368.222 19.489 366.3 20.426 QT\n364.378 21.364 362.363 21.364 QT\n360.753 21.364 359.456 20.59 QT\n358.159 19.817 358.159 18.348 QT\ncp\n373.363 -17.574 M\n373.363 -18.621 374.183 -19.418 QT\n375.003 -20.215 376.034 -20.215 QT\n376.847 -20.215 377.378 -19.715 QT\n377.909 -19.215 377.909 -18.433 QT\n377.909 -17.355 377.05 -16.55 QT\n376.191 -15.746 375.159 -15.746 QT\n374.394 -15.746 373.878 -16.285 QT\n373.363 -16.824 373.363 -17.574 QT\ncp}def\r\nf127127908\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f-1058293493{399.101 0.332 M\n398.632 0.129 398.632 -0.48 QT\n398.632 -1.09 399.272 -1.402 QT\n426.663 -14.308 L\n426.851 -14.402 426.991 -14.402 QT\n427.413 -14.402 427.687 -14.113 QT\n427.96 -13.824 427.96 -13.449 QT\n427.96 -12.855 427.397 -12.527 QT\n401.851 -0.48 L\n427.538 11.66 L\n427.96 11.801 427.96 12.489 QT\n427.96 12.864 427.687 13.153 QT\n427.413 13.442 426.991 13.442 QT\n426.851 13.442 426.663 13.348 QT\n399.101 0.332 L\ncp}def\r\nf-1058293493\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f62083131{449.892 7.817 M\n451.017 9.457 452.915 10.254 QT\n454.814 11.051 456.986 11.051 QT\n459.783 11.051 460.955 8.668 QT\n462.126 6.285 462.126 3.27 QT\n462.126 1.91 461.876 0.551 QT\n461.626 -0.808 461.04 -1.98 QT\n460.455 -3.152 459.439 -3.855 QT\n458.423 -4.558 456.939 -4.558 QT\n453.751 -4.558 L\n453.33 -4.558 453.33 -5.011 QT\n453.33 -5.433 L\n453.33 -5.808 453.751 -5.808 QT\n456.408 -6.011 L\n458.095 -6.011 459.205 -7.277 QT\n460.314 -8.543 460.83 -10.363 QT\n461.345 -12.183 461.345 -13.824 QT\n461.345 -16.121 460.267 -17.597 QT\n459.189 -19.074 456.986 -19.074 QT\n455.158 -19.074 453.494 -18.379 QT\n451.83 -17.683 450.845 -16.277 QT\n450.939 -16.308 451.009 -16.316 QT\n451.08 -16.324 451.173 -16.324 QT\n452.251 -16.324 452.978 -15.574 QT\n453.705 -14.824 453.705 -13.777 QT\n453.705 -12.746 452.978 -11.996 QT\n452.251 -11.246 451.173 -11.246 QT\n450.126 -11.246 449.376 -11.996 QT\n448.626 -12.746 448.626 -13.777 QT\n448.626 -15.84 449.869 -17.363 QT\n451.111 -18.886 453.064 -19.668 QT\n455.017 -20.449 456.986 -20.449 QT\n458.439 -20.449 460.056 -20.019 QT\n461.673 -19.59 462.986 -18.777 QT\n464.298 -17.965 465.134 -16.699 QT\n465.97 -15.433 465.97 -13.824 QT\n465.97 -11.808 465.064 -10.097 QT\n464.158 -8.386 462.587 -7.144 QT\n461.017 -5.902 459.142 -5.293 QT\n461.236 -4.886 463.111 -3.715 QT\n464.986 -2.543 466.119 -0.715 QT\n467.251 1.114 467.251 3.223 QT\n467.251 5.864 465.798 8.012 QT\n464.345 10.16 461.978 11.371 QT\n459.611 12.582 456.986 12.582 QT\n454.736 12.582 452.478 11.723 QT\n450.22 10.864 448.775 9.153 QT\n447.33 7.442 447.33 5.051 QT\n447.33 3.848 448.126 3.051 QT\n448.923 2.254 450.126 2.254 QT\n450.892 2.254 451.54 2.621 QT\n452.189 2.989 452.548 3.645 QT\n452.908 4.301 452.908 5.051 QT\n452.908 6.223 452.087 7.02 QT\n451.267 7.817 450.126 7.817 QT\n449.892 7.817 L\ncp}def\r\nf62083131\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f1509408367{471.705 11.52 M\n471.705 10.223 L\n471.705 10.114 471.798 9.973 QT\n479.251 1.723 L\n480.939 -0.105 481.994 -1.347 QT\n483.048 -2.59 484.08 -4.207 QT\n485.111 -5.824 485.712 -7.504 QT\n486.314 -9.183 486.314 -11.058 QT\n486.314 -13.027 485.587 -14.816 QT\n484.861 -16.605 483.416 -17.683 QT\n481.97 -18.761 479.939 -18.761 QT\n477.845 -18.761 476.181 -17.511 QT\n474.517 -16.261 473.845 -14.261 QT\n474.033 -14.308 474.361 -14.308 QT\n475.439 -14.308 476.197 -13.582 QT\n476.955 -12.855 476.955 -11.715 QT\n476.955 -10.605 476.197 -9.847 QT\n475.439 -9.09 474.361 -9.09 QT\n473.236 -9.09 472.47 -9.871 QT\n471.705 -10.652 471.705 -11.715 QT\n471.705 -13.511 472.384 -15.097 QT\n473.064 -16.683 474.345 -17.91 QT\n475.626 -19.136 477.228 -19.793 QT\n478.83 -20.449 480.642 -20.449 QT\n483.376 -20.449 485.744 -19.293 QT\n488.111 -18.136 489.494 -16.011 QT\n490.876 -13.886 490.876 -11.058 QT\n490.876 -8.965 489.962 -7.09 QT\n489.048 -5.215 487.619 -3.683 QT\n486.189 -2.152 483.962 -0.207 QT\n481.736 1.739 481.033 2.395 QT\n475.595 7.629 L\n480.22 7.629 L\n483.611 7.629 485.9 7.567 QT\n488.189 7.504 488.33 7.395 QT\n488.892 6.785 489.47 2.957 QT\n490.876 2.957 L\n489.517 11.52 L\n471.705 11.52 L\ncp}def\r\nf1509408367\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f511719215{496.439 23.52 M\n496.017 23.52 496.017 23.098 QT\n496.017 22.895 496.111 22.801 QT\n504.314 14.785 504.314 -0.48 QT\n504.314 -15.746 496.205 -23.668 QT\n496.017 -23.777 496.017 -24.058 QT\n496.017 -24.23 496.142 -24.355 QT\n496.267 -24.48 496.439 -24.48 QT\n496.877 -24.48 L\n497.017 -24.48 497.111 -24.386 QT\n500.564 -21.668 502.861 -17.777 QT\n505.158 -13.886 506.22 -9.48 QT\n507.283 -5.074 507.283 -0.48 QT\n507.283 2.91 506.712 6.207 QT\n506.142 9.504 504.884 12.707 QT\n503.627 15.91 501.705 18.614 QT\n499.783 21.317 497.111 23.426 QT\n497.017 23.52 496.877 23.52 QT\n496.439 23.52 L\ncp}def\r\nf511719215\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n387 644.253 M\n467.003 644.253 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n10.0 ML\r\n1.333 LW\r\nN\r\n379 677 M\n379 553 L\n993 553 L\n993 677 L\ncp\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n649.6 378 M\n553.83 413.914 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n566.08 420 M\n537.6 420 L\n553.83 413.914 L\n566.08 420 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n537.6 420 M\n559.058 401.273 L\n553.83 413.914 L\n537.6 420 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\nN\r\n537.6 420 M\n566.08 420 L\n553.83 413.914 L\n559.058 401.273 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n414.4 478.8 M\n479.64 534.72 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n479.061 521.053 M\n492.8 546 L\n479.64 534.72 L\n479.061 521.053 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n492.8 546 M\n466.045 536.238 L\n479.64 534.72 L\n492.8 546 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\nN\r\n492.8 546 M\n479.061 521.053 L\n479.64 534.72 L\n466.045 536.238 L\ncp\r\nf\r\nGR\r\n%%Trailer\r\n%%Pages: 1\r\n%%EOF\r\n"
  },
  {
    "path": "matlab/acc2023/closedloop_performance/figures/state-converge-4.eps",
    "content": "%!PS-Adobe-3.0 EPSF-3.0\r\n%%Creator: (MATLAB, The Mathworks, Inc. Version 9.10.0.1649659 \\(R2021a\\) Update 1. Operating System: Windows 10)\r\n%%Title: figures/state-converge-4.eps\r\n%%CreationDate: 2023-01-31T03:12:11\r\n%%Pages: (atend)\r\n%%BoundingBox:    15     6   382   292\r\n%%LanguageLevel: 3\r\n%%EndComments\r\n%%BeginProlog\r\n%%BeginResource: procset (Apache XML Graphics Std ProcSet) 1.2 0\r\n%%Version: 1.2 0\r\n%%Copyright: (Copyright 2001-2003,2010 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/bd{bind def}bind def\r\n/ld{load def}bd\r\n/GR/grestore ld\r\n/GS/gsave ld\r\n/RM/rmoveto ld\r\n/C/curveto ld\r\n/t/show ld\r\n/L/lineto ld\r\n/ML/setmiterlimit ld\r\n/CT/concat ld\r\n/f/fill ld\r\n/N/newpath ld\r\n/S/stroke ld\r\n/CC/setcmykcolor ld\r\n/A/ashow ld\r\n/cp/closepath ld\r\n/RC/setrgbcolor ld\r\n/LJ/setlinejoin ld\r\n/GC/setgray ld\r\n/LW/setlinewidth ld\r\n/M/moveto ld\r\n/re {4 2 roll M\r\n1 index 0 rlineto\r\n0 exch rlineto\r\nneg 0 rlineto\r\ncp } bd\r\n/_ctm matrix def\r\n/_tm matrix def\r\n/BT { _ctm currentmatrix pop matrix _tm copy pop 0 0 moveto } bd\r\n/ET { _ctm setmatrix } bd\r\n/iTm { _ctm setmatrix _tm concat } bd\r\n/Tm { _tm astore pop iTm 0 0 moveto } bd\r\n/ux 0.0 def\r\n/uy 0.0 def\r\n/F {\r\n  /Tp exch def\r\n  /Tf exch def\r\n  Tf findfont Tp scalefont setfont\r\n  /cf Tf def  /cs Tp def\r\n} bd\r\n/ULS {currentpoint /uy exch def /ux exch def} bd\r\n/ULE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add moveto  Tcx uy To add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/OLE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs add moveto Tcx uy To add cs add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/SOE {\r\n  /Tcx currentpoint pop def\r\n  gsave\r\n  newpath\r\n  cf findfont cs scalefont dup\r\n  /FontMatrix get 0 get /Ts exch def /FontInfo get dup\r\n  /UnderlinePosition get Ts mul /To exch def\r\n  /UnderlineThickness get Ts mul /Tt exch def\r\n  ux uy To add cs 10 mul 26 idiv add moveto Tcx uy To add cs 10 mul 26 idiv add lineto\r\n  Tt setlinewidth stroke\r\n  grestore\r\n} bd\r\n/QT {\r\n/Y22 exch store\r\n/X22 exch store\r\n/Y21 exch store\r\n/X21 exch store\r\ncurrentpoint\r\n/Y21 load 2 mul add 3 div exch\r\n/X21 load 2 mul add 3 div exch\r\n/X21 load 2 mul /X22 load add 3 div\r\n/Y21 load 2 mul /Y22 load add 3 div\r\n/X22 load /Y22 load curveto\r\n} bd\r\n/SSPD {\r\ndup length /d exch dict def\r\n{\r\n/v exch def\r\n/k exch def\r\ncurrentpagedevice k known {\r\n/cpdv currentpagedevice k get def\r\nv cpdv ne {\r\n/upd false def\r\n/nullv v type /nulltype eq def\r\n/nullcpdv cpdv type /nulltype eq def\r\nnullv nullcpdv or\r\n{\r\n/upd true def\r\n} {\r\n/sametype v type cpdv type eq def\r\nsametype {\r\nv type /arraytype eq {\r\n/vlen v length def\r\n/cpdvlen cpdv length def\r\nvlen cpdvlen eq {\r\n0 1 vlen 1 sub {\r\n/i exch def\r\n/obj v i get def\r\n/cpdobj cpdv i get def\r\nobj cpdobj ne {\r\n/upd true def\r\nexit\r\n} if\r\n} for\r\n} {\r\n/upd true def\r\n} ifelse\r\n} {\r\nv type /dicttype eq {\r\nv {\r\n/dv exch def\r\n/dk exch def\r\n/cpddv cpdv dk get def\r\ndv cpddv ne {\r\n/upd true def\r\nexit\r\n} if\r\n} forall\r\n} {\r\n/upd true def\r\n} ifelse\r\n} ifelse\r\n} if\r\n} ifelse\r\nupd true eq {\r\nd k v put\r\n} if\r\n} if\r\n} if\r\n} forall\r\nd length 0 gt {\r\nd setpagedevice\r\n} if\r\n} bd\r\n/RE { % /NewFontName [NewEncodingArray] /FontName RE -\r\n  findfont dup length dict begin\r\n  {\r\n    1 index /FID ne\r\n    {def} {pop pop} ifelse\r\n  } forall\r\n  /Encoding exch def\r\n  /FontName 1 index def\r\n  currentdict definefont pop\r\n  end\r\n} bind def\r\n%%EndResource\r\n%%BeginResource: procset (Apache XML Graphics EPS ProcSet) 1.0 0\r\n%%Version: 1.0 0\r\n%%Copyright: (Copyright 2002-2003 The Apache Software Foundation. License terms: http://www.apache.org/licenses/LICENSE-2.0)\r\n/BeginEPSF { %def\r\n/b4_Inc_state save def         % Save state for cleanup\r\n/dict_count countdictstack def % Count objects on dict stack\r\n/op_count count 1 sub def      % Count objects on operand stack\r\nuserdict begin                 % Push userdict on dict stack\r\n/showpage { } def              % Redefine showpage, { } = null proc\r\n0 setgray 0 setlinecap         % Prepare graphics state\r\n1 setlinewidth 0 setlinejoin\r\n10 setmiterlimit [ ] 0 setdash newpath\r\n/languagelevel where           % If level not equal to 1 then\r\n{pop languagelevel             % set strokeadjust and\r\n1 ne                           % overprint to their defaults.\r\n{false setstrokeadjust false setoverprint\r\n} if\r\n} if\r\n} bd\r\n/EndEPSF { %def\r\ncount op_count sub {pop} repeat            % Clean up stacks\r\ncountdictstack dict_count sub {end} repeat\r\nb4_Inc_state restore\r\n} bd\r\n%%EndResource\r\n%FOPBeginFontDict\r\n%%IncludeResource: font Courier-Oblique\r\n%%IncludeResource: font Courier-BoldOblique\r\n%%IncludeResource: font Courier-Bold\r\n%%IncludeResource: font ZapfDingbats\r\n%%IncludeResource: font Symbol\r\n%%IncludeResource: font Helvetica\r\n%%IncludeResource: font Helvetica-Oblique\r\n%%IncludeResource: font Helvetica-Bold\r\n%%IncludeResource: font Helvetica-BoldOblique\r\n%%IncludeResource: font Times-Roman\r\n%%IncludeResource: font Times-Italic\r\n%%IncludeResource: font Times-Bold\r\n%%IncludeResource: font Times-BoldItalic\r\n%%IncludeResource: font Courier\r\n%FOPEndFontDict\r\n%%BeginResource: encoding WinAnsiEncoding\r\n/WinAnsiEncoding [\r\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /.notdef /.notdef /.notdef\n/.notdef /.notdef /space /exclam /quotedbl\n/numbersign /dollar /percent /ampersand /quotesingle\n/parenleft /parenright /asterisk /plus /comma\n/hyphen /period /slash /zero /one\n/two /three /four /five /six\n/seven /eight /nine /colon /semicolon\n/less /equal /greater /question /at\n/A /B /C /D /E\n/F /G /H /I /J\n/K /L /M /N /O\n/P /Q /R /S /T\n/U /V /W /X /Y\n/Z /bracketleft /backslash /bracketright /asciicircum\n/underscore /quoteleft /a /b /c\n/d /e /f /g /h\n/i /j /k /l /m\n/n /o /p /q /r\n/s /t /u /v /w\n/x /y /z /braceleft /bar\n/braceright /asciitilde /bullet /Euro /bullet\n/quotesinglbase /florin /quotedblbase /ellipsis /dagger\n/daggerdbl /circumflex /perthousand /Scaron /guilsinglleft\n/OE /bullet /Zcaron /bullet /bullet\n/quoteleft /quoteright /quotedblleft /quotedblright /bullet\n/endash /emdash /asciitilde /trademark /scaron\n/guilsinglright /oe /bullet /zcaron /Ydieresis\n/space /exclamdown /cent /sterling /currency\n/yen /brokenbar /section /dieresis /copyright\n/ordfeminine /guillemotleft /logicalnot /sfthyphen /registered\n/macron /degree /plusminus /twosuperior /threesuperior\n/acute /mu /paragraph /middot /cedilla\n/onesuperior /ordmasculine /guillemotright /onequarter /onehalf\n/threequarters /questiondown /Agrave /Aacute /Acircumflex\n/Atilde /Adieresis /Aring /AE /Ccedilla\n/Egrave /Eacute /Ecircumflex /Edieresis /Igrave\n/Iacute /Icircumflex /Idieresis /Eth /Ntilde\n/Ograve /Oacute /Ocircumflex /Otilde /Odieresis\n/multiply /Oslash /Ugrave /Uacute /Ucircumflex\n/Udieresis /Yacute /Thorn /germandbls /agrave\n/aacute /acircumflex /atilde /adieresis /aring\n/ae /ccedilla /egrave /eacute /ecircumflex\n/edieresis /igrave /iacute /icircumflex /idieresis\n/eth /ntilde /ograve /oacute /ocircumflex\n/otilde /odieresis /divide /oslash /ugrave\n/uacute /ucircumflex /udieresis /yacute /thorn\n/ydieresis\n] def\r\n%%EndResource\r\n%FOPBeginFontReencode\r\n/Courier-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Oblique exch definefont pop\r\n/Courier-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-BoldOblique exch definefont pop\r\n/Courier-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier-Bold exch definefont pop\r\n/Helvetica findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica exch definefont pop\r\n/Helvetica-Oblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Oblique exch definefont pop\r\n/Helvetica-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-Bold exch definefont pop\r\n/Helvetica-BoldOblique findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Helvetica-BoldOblique exch definefont pop\r\n/Times-Roman findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Roman exch definefont pop\r\n/Times-Italic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Italic exch definefont pop\r\n/Times-Bold findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-Bold exch definefont pop\r\n/Times-BoldItalic findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Times-BoldItalic exch definefont pop\r\n/Courier findfont\r\ndup length dict begin\r\n  {1 index /FID ne {def} {pop pop} ifelse} forall\r\n  /Encoding WinAnsiEncoding def\r\n  currentdict\r\nend\r\n/Courier exch definefont pop\r\n%FOPEndFontReencode\r\n%%EndProlog\r\n%%Page: 1 1\r\n%%PageBoundingBox: 0 0 420 315\r\n%%BeginPageSetup\r\n[1 0 0 -1 0 315] CT\r\n%%EndPageSetup\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n0 0 1120 840 re\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n154 698 M\n1014 698 L\n1014 63 L\n154 63 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n154 698 M\n1014 698 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n154 63 M\n1014 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n154 698 M\n154 689.4 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n333.167 698 M\n333.167 689.4 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n512.333 698 M\n512.333 689.4 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n691.5 698 M\n691.5 689.4 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n870.667 698 M\n870.667 689.4 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n154 63 M\n154 71.6 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n333.167 63 M\n333.167 71.6 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n512.333 63 M\n512.333 71.6 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n691.5 63 M\n691.5 71.6 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n870.667 63 M\n870.667 71.6 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 57.75 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-13.5 49 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 124.9375 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-13.5 49 moveto \r\n1 -1 scale\r\n(5) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 192.12499 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(10) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 259.3125 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(15) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 326.50001 267.35001] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 49 moveto \r\n1 -1 scale\r\n(20) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 219.00016 291] CT\r\n0.149 GC\r\nN\r\n-11.894 43.847 M\n-11.894 43.534 -11.847 43.378 QT\n-4.16 12.737 L\n-3.957 11.831 -3.91 11.315 QT\n-3.91 10.456 -7.347 10.456 QT\n-7.894 10.456 -7.894 9.753 QT\n-7.863 9.628 -7.769 9.292 QT\n-7.675 8.956 -7.535 8.776 QT\n-7.394 8.597 -7.144 8.597 QT\n-0.003 8.019 L\n0.153 8.019 L\n0.153 8.081 0.34 8.167 QT\n0.528 8.253 0.543 8.284 QT\n0.653 8.55 0.653 8.706 QT\n-4.91 30.847 L\n-3.003 30.05 -0.089 27.034 QT\n2.825 24.019 4.465 22.698 QT\n6.106 21.378 8.59 21.378 QT\n10.075 21.378 11.106 22.386 QT\n12.137 23.394 12.137 24.878 QT\n12.137 25.8 11.754 26.589 QT\n11.372 27.378 10.668 27.87 QT\n9.965 28.362 9.028 28.362 QT\n8.184 28.362 7.598 27.831 QT\n7.012 27.3 7.012 26.456 QT\n7.012 25.19 7.911 24.323 QT\n8.809 23.456 10.075 23.456 QT\n9.559 22.753 8.497 22.753 QT\n6.918 22.753 5.45 23.659 QT\n3.981 24.565 2.293 26.261 QT\n0.606 27.956 -0.793 29.362 QT\n-2.191 30.769 -3.394 31.503 QT\n-0.253 31.862 2.051 33.144 QT\n4.356 34.425 4.356 37.065 QT\n4.356 37.612 4.137 38.44 QT\n3.684 40.425 3.684 41.612 QT\n3.684 44.003 5.309 44.003 QT\n7.231 44.003 8.223 41.901 QT\n9.215 39.8 9.856 37.003 QT\n9.965 36.706 10.309 36.706 QT\n10.918 36.706 L\n11.137 36.706 11.278 36.831 QT\n11.418 36.956 11.418 37.159 QT\n11.418 37.222 11.372 37.315 QT\n9.372 45.394 5.2 45.394 QT\n3.7 45.394 2.551 44.698 QT\n1.403 44.003 0.778 42.8 QT\n0.153 41.597 0.153 40.097 QT\n0.153 39.237 0.387 38.331 QT\n0.543 37.706 0.543 37.159 QT\n0.543 35.128 -1.269 34.065 QT\n-3.082 33.003 -5.41 32.769 QT\n-8.097 43.581 L\n-8.3 44.378 -8.894 44.886 QT\n-9.488 45.394 -10.269 45.394 QT\n-10.941 45.394 -11.418 44.94 QT\n-11.894 44.487 -11.894 43.847 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n154 698 M\n154 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 698 M\n1014 63 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n154 698 M\n162.6 698 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n154 496.093 M\n162.6 496.093 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n154 294.185 M\n162.6 294.185 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n154 92.278 M\n162.6 92.278 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 698 M\n1005.4 698 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 496.093 M\n1005.4 496.093 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 294.185 M\n1005.4 294.185 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n2 setlinecap\r\n1 LJ\r\n1.333 LW\r\nN\r\n1014 92.278 M\n1005.4 92.278 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 52.15 261.75] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 19 moveto \r\n1 -1 scale\r\n(0) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 52.15 186.03474] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 19 moveto \r\n1 -1 scale\r\n(1) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 52.15 110.31948] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 19 moveto \r\n1 -1 scale\r\n(2) t \r\nGR\r\nGR\r\nGS\r\n[0.375 0 0 0.375 52.15 34.60422] CT\r\n0.149 GC\r\n/Helvetica 48 F\r\nGS\r\n[1 0 0 1 0 0] CT\r\n-27 19 moveto \r\n1 -1 scale\r\n(3) t \r\nGR\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 39 142.68739] CT\r\n0.149 GC\r\nN\r\n-109.309 -25.185 M\n-109.309 -26.372 -109.028 -27.794 QT\n-108.747 -29.216 -108.458 -30.138 QT\n-108.169 -31.06 -107.161 -33.724 QT\n-106.153 -36.388 -106.138 -36.481 QT\n-105.434 -38.435 -105.434 -39.669 QT\n-105.434 -41.247 -106.591 -41.247 QT\n-108.7 -41.247 -110.052 -39.091 QT\n-111.403 -36.935 -112.059 -34.263 QT\n-112.153 -33.919 -112.497 -33.919 QT\n-113.122 -33.919 L\n-113.559 -33.919 -113.559 -34.419 QT\n-113.559 -34.575 L\n-112.7 -37.731 -110.942 -40.177 QT\n-109.184 -42.622 -106.497 -42.622 QT\n-104.606 -42.622 -103.302 -41.38 QT\n-101.997 -40.138 -101.997 -38.216 QT\n-101.997 -37.231 -102.434 -36.153 QT\n-103.466 -33.466 -104.059 -31.849 QT\n-104.653 -30.231 -105.161 -28.224 QT\n-105.669 -26.216 -105.669 -24.513 QT\n-105.669 -22.513 -104.747 -21.255 QT\n-103.825 -19.997 -101.888 -19.997 QT\n-98.216 -19.997 -95.263 -25.669 QT\n-94.325 -27.513 -93.497 -29.997 QT\n-92.669 -32.481 -92.669 -34.028 QT\n-92.669 -35.638 -93.192 -36.528 QT\n-93.716 -37.419 -94.544 -38.388 QT\n-95.372 -39.356 -95.372 -39.935 QT\n-95.372 -40.966 -94.513 -41.817 QT\n-93.653 -42.669 -92.622 -42.669 QT\n-91.356 -42.669 -90.802 -41.505 QT\n-90.247 -40.341 -90.247 -38.872 QT\n-90.247 -37.106 -90.747 -34.677 QT\n-91.247 -32.247 -92.138 -29.63 QT\n-93.028 -27.013 -93.794 -25.513 QT\n-97.278 -18.606 -101.934 -18.606 QT\n-105.278 -18.606 -107.294 -20.278 QT\n-109.309 -21.95 -109.309 -25.185 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 39 142.68739] CT\r\n0.149 GC\r\nN\r\n-70.778 -6.06 M\n-73.732 -8.388 -75.864 -11.403 QT\n-77.997 -14.419 -79.357 -17.833 QT\n-80.716 -21.247 -81.388 -24.974 QT\n-82.06 -28.7 -82.06 -32.45 QT\n-82.06 -36.247 -81.388 -39.974 QT\n-80.716 -43.7 -79.333 -47.146 QT\n-77.95 -50.591 -75.802 -53.591 QT\n-73.653 -56.591 -70.778 -58.841 QT\n-70.778 -58.95 -70.528 -58.95 QT\n-70.028 -58.95 L\n-69.872 -58.95 -69.747 -58.81 QT\n-69.622 -58.669 -69.622 -58.481 QT\n-69.622 -58.247 -69.716 -58.153 QT\n-72.31 -55.606 -74.028 -52.708 QT\n-75.747 -49.81 -76.794 -46.536 QT\n-77.841 -43.263 -78.31 -39.755 QT\n-78.778 -36.247 -78.778 -32.45 QT\n-78.778 -15.606 -69.778 -6.856 QT\n-69.622 -6.7 -69.622 -6.419 QT\n-69.622 -6.294 -69.763 -6.122 QT\n-69.903 -5.95 -70.028 -5.95 QT\n-70.528 -5.95 L\n-70.778 -5.95 -70.778 -6.06 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 39 142.68739] CT\r\n0.149 GC\r\nN\r\n-62.381 -20.106 M\n-62.381 -20.419 -62.335 -20.575 QT\n-58.381 -36.388 L\n-57.991 -37.856 -57.991 -38.966 QT\n-57.991 -41.247 -59.538 -41.247 QT\n-61.194 -41.247 -61.999 -39.271 QT\n-62.803 -37.294 -63.553 -34.263 QT\n-63.553 -34.106 -63.71 -34.013 QT\n-63.866 -33.919 -63.991 -33.919 QT\n-64.616 -33.919 L\n-64.788 -33.919 -64.92 -34.114 QT\n-65.053 -34.31 -65.053 -34.466 QT\n-64.475 -36.778 -63.952 -38.38 QT\n-63.428 -39.981 -62.295 -41.302 QT\n-61.163 -42.622 -59.491 -42.622 QT\n-57.491 -42.622 -55.967 -41.364 QT\n-54.444 -40.106 -54.444 -38.169 QT\n-52.866 -40.247 -50.741 -41.435 QT\n-48.616 -42.622 -46.241 -42.622 QT\n-43.725 -42.622 -41.905 -41.341 QT\n-40.085 -40.06 -40.085 -37.7 QT\n-38.444 -40.013 -36.256 -41.317 QT\n-34.069 -42.622 -31.491 -42.622 QT\n-28.741 -42.622 -27.077 -41.13 QT\n-25.413 -39.638 -25.413 -36.903 QT\n-25.413 -34.731 -26.381 -31.653 QT\n-27.35 -28.575 -28.788 -24.763 QT\n-29.553 -22.935 -29.553 -21.575 QT\n-29.553 -19.997 -28.303 -19.997 QT\n-26.241 -19.997 -24.866 -22.224 QT\n-23.491 -24.45 -22.928 -26.997 QT\n-22.772 -27.294 -22.475 -27.294 QT\n-21.866 -27.294 L\n-21.647 -27.294 -21.506 -27.153 QT\n-21.366 -27.013 -21.366 -26.841 QT\n-21.366 -26.778 -21.413 -26.685 QT\n-22.147 -23.685 -23.944 -21.146 QT\n-25.741 -18.606 -28.428 -18.606 QT\n-30.303 -18.606 -31.616 -19.888 QT\n-32.928 -21.169 -32.928 -22.997 QT\n-32.928 -23.935 -32.491 -25.075 QT\n-30.991 -29.06 -29.999 -32.192 QT\n-29.006 -35.325 -29.006 -37.7 QT\n-29.006 -39.185 -29.6 -40.216 QT\n-30.194 -41.247 -31.585 -41.247 QT\n-34.491 -41.247 -36.608 -39.474 QT\n-38.725 -37.7 -40.288 -34.778 QT\n-40.381 -34.263 -40.444 -33.981 QT\n-43.85 -20.372 L\n-44.038 -19.638 -44.67 -19.122 QT\n-45.303 -18.606 -46.085 -18.606 QT\n-46.71 -18.606 -47.186 -19.021 QT\n-47.663 -19.435 -47.663 -20.106 QT\n-47.663 -20.419 -47.616 -20.575 QT\n-44.225 -34.075 L\n-43.678 -36.247 -43.678 -37.7 QT\n-43.678 -39.185 -44.288 -40.216 QT\n-44.897 -41.247 -46.335 -41.247 QT\n-48.288 -41.247 -49.913 -40.396 QT\n-51.538 -39.544 -52.756 -38.13 QT\n-53.975 -36.716 -54.991 -34.778 QT\n-58.585 -20.372 L\n-58.756 -19.638 -59.397 -19.122 QT\n-60.038 -18.606 -60.803 -18.606 QT\n-61.46 -18.606 -61.92 -19.021 QT\n-62.381 -19.435 -62.381 -20.106 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 39 142.68739] CT\r\n0.149 GC\r\nN\r\n-3.343 -32.45 M\n-3.343 -33.2 -2.952 -33.872 QT\n-2.562 -34.544 -1.882 -34.958 QT\n-1.202 -35.372 -0.421 -35.372 QT\n0.329 -35.372 1.016 -34.958 QT\n1.704 -34.544 2.094 -33.872 QT\n2.485 -33.2 2.485 -32.45 QT\n2.485 -31.263 1.641 -30.396 QT\n0.798 -29.528 -0.421 -29.528 QT\n-1.609 -29.528 -2.476 -30.396 QT\n-3.343 -31.263 -3.343 -32.45 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 39 142.68739] CT\r\n0.149 GC\r\nN\r\n23.48 -22.435 M\n24.901 -19.997 29.198 -19.997 QT\n31.058 -19.997 32.737 -20.638 QT\n34.417 -21.278 35.519 -22.544 QT\n36.62 -23.81 36.62 -25.622 QT\n36.62 -26.997 35.636 -27.872 QT\n34.651 -28.747 33.23 -29.06 QT\n30.355 -29.622 L\n28.401 -30.122 27.128 -31.466 QT\n25.855 -32.81 25.855 -34.731 QT\n25.855 -37.075 27.136 -38.888 QT\n28.417 -40.7 30.511 -41.661 QT\n32.605 -42.622 34.87 -42.622 QT\n37.276 -42.622 39.175 -41.474 QT\n41.073 -40.325 41.073 -38.06 QT\n41.073 -36.856 40.386 -35.919 QT\n39.698 -34.981 38.48 -34.981 QT\n37.792 -34.981 37.284 -35.435 QT\n36.776 -35.888 36.776 -36.591 QT\n36.776 -37.216 37.128 -37.794 QT\n37.48 -38.372 38.058 -38.724 QT\n38.636 -39.075 39.261 -39.075 QT\n38.792 -40.216 37.511 -40.731 QT\n36.23 -41.247 34.761 -41.247 QT\n33.417 -41.247 32.073 -40.708 QT\n30.73 -40.169 29.909 -39.114 QT\n29.089 -38.06 29.089 -36.638 QT\n29.089 -35.685 29.761 -34.958 QT\n30.433 -34.231 31.417 -33.919 QT\n34.495 -33.31 L\n35.98 -32.997 37.206 -32.208 QT\n38.433 -31.419 39.144 -30.216 QT\n39.855 -29.013 39.855 -27.45 QT\n39.855 -25.481 38.753 -23.567 QT\n37.651 -21.653 36.058 -20.513 QT\n33.23 -18.606 29.151 -18.606 QT\n26.323 -18.606 23.972 -19.903 QT\n21.62 -21.2 21.62 -23.763 QT\n21.62 -25.2 22.456 -26.278 QT\n23.292 -27.356 24.745 -27.356 QT\n25.605 -27.356 26.183 -26.833 QT\n26.761 -26.31 26.761 -25.466 QT\n26.761 -24.247 25.855 -23.341 QT\n24.948 -22.435 23.73 -22.435 QT\n23.48 -22.435 L\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 39 142.68739] CT\r\n0.149 GC\r\nN\r\n47.651 -47.07 M\n47.339 -47.07 47.144 -47.304 QT\n46.948 -47.539 46.948 -47.804 QT\n46.948 -48.07 47.144 -48.304 QT\n47.339 -48.539 47.651 -48.539 QT\n68.87 -48.539 L\n69.167 -48.539 69.355 -48.304 QT\n69.542 -48.07 69.542 -47.804 QT\n69.542 -47.539 69.355 -47.304 QT\n69.167 -47.07 68.87 -47.07 QT\n47.651 -47.07 L\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 39 142.68739] CT\r\n0.149 GC\r\nN\r\n76.345 -38.554 M\n76.345 -39.851 L\n80.97 -39.851 80.97 -41.023 QT\n80.97 -60.445 L\n79.048 -59.523 76.126 -59.523 QT\n76.126 -60.836 L\n80.657 -60.836 82.97 -63.195 QT\n83.501 -63.195 L\n83.626 -63.195 83.743 -63.094 QT\n83.86 -62.992 83.86 -62.867 QT\n83.86 -41.023 L\n83.86 -39.851 88.485 -39.851 QT\n88.485 -38.554 L\n76.345 -38.554 L\ncp\r\nf\r\nGR\r\nGS\r\n[0 -0.375 0.375 0 39 142.68739] CT\r\n0.149 GC\r\nN\r\n97.678 -5.95 M\n97.209 -5.95 97.209 -6.419 QT\n97.209 -6.653 97.319 -6.747 QT\n106.381 -15.606 106.381 -32.45 QT\n106.381 -49.294 97.428 -58.044 QT\n97.209 -58.169 97.209 -58.481 QT\n97.209 -58.669 97.358 -58.81 QT\n97.506 -58.95 97.678 -58.95 QT\n98.178 -58.95 L\n98.334 -58.95 98.428 -58.841 QT\n102.241 -55.841 104.772 -51.544 QT\n107.303 -47.247 108.483 -42.388 QT\n109.663 -37.528 109.663 -32.45 QT\n109.663 -28.7 109.03 -25.06 QT\n108.397 -21.419 107.014 -17.888 QT\n105.631 -14.356 103.506 -11.372 QT\n101.381 -8.388 98.428 -6.06 QT\n98.334 -5.95 98.178 -5.95 QT\n97.678 -5.95 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 224.145 M\n189.833 170.587 L\n225.667 151.032 L\n261.5 154.58 L\n297.333 169.699 L\n333.167 183.756 L\n369 196.116 L\n404.833 210.659 L\n440.667 226.054 L\n476.5 236.416 L\n512.333 247.485 L\n548.167 268.958 L\n584 297.285 L\n619.833 329.718 L\n655.667 364.243 L\n691.5 399.392 L\n727.333 434.092 L\n763.167 467.549 L\n799 499.15 L\n834.833 528.387 L\n870.667 554.779 L\n906.5 577.8 L\n942.333 596.791 L\n978.167 610.865 L\n1014 618.777 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 224.145 M\n189.833 128.386 L\n225.667 79.354 L\n261.5 63 L\n297.333 69.932 L\n333.167 86.646 L\n369 109.644 L\n404.833 139.632 L\n440.667 175.094 L\n476.5 214.238 L\n512.333 253.648 L\n548.167 291.663 L\n584 329.125 L\n619.833 365.829 L\n655.667 401.383 L\n691.5 435.442 L\n727.333 467.74 L\n763.167 498.059 L\n799 526.19 L\n834.833 551.907 L\n870.667 574.932 L\n906.5 594.896 L\n942.333 611.289 L\n978.167 623.39 L\n1014 630.17 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 224.145 M\n189.833 146.994 L\n225.667 111.335 L\n261.5 98.378 L\n297.333 98.454 L\n333.167 107.935 L\n369 125.267 L\n404.833 149.921 L\n440.667 179.109 L\n476.5 211.943 L\n512.333 247.772 L\n548.167 285.489 L\n584 323.745 L\n619.833 361.615 L\n655.667 398.417 L\n691.5 433.641 L\n727.333 466.921 L\n763.167 497.996 L\n799 526.658 L\n834.833 552.703 L\n870.667 575.887 L\n906.5 595.881 L\n942.333 612.22 L\n978.167 624.228 L\n1014 630.931 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 224.145 M\n189.833 139.259 L\n225.667 98.494 L\n261.5 88.986 L\n297.333 93.976 L\n333.167 106.341 L\n369 125.492 L\n404.833 151.655 L\n440.667 182.768 L\n476.5 217.903 L\n512.333 255.413 L\n548.167 293.657 L\n584 331.555 L\n619.833 368.475 L\n655.667 404.021 L\n691.5 437.918 L\n727.333 469.964 L\n763.167 499.987 L\n799 527.817 L\n834.833 553.251 L\n870.667 576.025 L\n906.5 595.778 L\n942.333 612.003 L\n978.167 623.98 L\n1014 630.689 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 224.145 M\n189.833 145.425 L\n225.667 108.922 L\n261.5 99.173 L\n297.333 102.868 L\n333.167 114.194 L\n369 131.977 L\n404.833 156.193 L\n440.667 184.376 L\n476.5 216.491 L\n512.333 251.99 L\n548.167 289.351 L\n584 327.245 L\n619.833 364.732 L\n655.667 401.143 L\n691.5 435.994 L\n727.333 468.93 L\n763.167 499.688 L\n799 528.059 L\n834.833 553.842 L\n870.667 576.799 L\n906.5 596.608 L\n942.333 612.807 L\n978.167 624.724 L\n1014 631.384 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 224.145 M\n189.833 141.18 L\n225.667 101.803 L\n261.5 92.381 L\n297.333 96.853 L\n333.167 109.04 L\n369 127.944 L\n404.833 153.838 L\n440.667 184.594 L\n476.5 219.217 L\n512.333 256.221 L\n548.167 294.174 L\n584 331.972 L\n619.833 368.893 L\n655.667 404.477 L\n691.5 438.417 L\n727.333 470.496 L\n763.167 500.538 L\n799 528.371 L\n834.833 553.792 L\n870.667 576.538 L\n906.5 596.254 L\n942.333 612.439 L\n978.167 624.383 L\n1014 631.074 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 224.145 M\n189.833 144.482 L\n225.667 107.382 L\n261.5 98.071 L\n297.333 102.175 L\n333.167 113.86 L\n369 131.999 L\n404.833 156.66 L\n440.667 185.449 L\n476.5 218.071 L\n512.333 253.87 L\n548.167 291.353 L\n584 329.228 L\n619.833 366.581 L\n655.667 402.775 L\n691.5 437.367 L\n727.333 470.037 L\n763.167 500.553 L\n799 528.718 L\n834.833 554.336 L\n870.667 577.168 L\n906.5 596.887 L\n942.333 613.026 L\n978.167 624.907 L\n1014 631.549 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 224.145 M\n189.833 142.164 L\n225.667 103.471 L\n261.5 94.045 L\n297.333 98.427 L\n333.167 110.523 L\n369 129.294 L\n404.833 154.967 L\n440.667 185.359 L\n476.5 219.584 L\n512.333 256.322 L\n548.167 294.15 L\n584 331.934 L\n619.833 368.907 L\n655.667 404.569 L\n691.5 438.59 L\n727.333 470.739 L\n763.167 500.832 L\n799 528.692 L\n834.833 554.118 L\n870.667 576.851 L\n906.5 596.54 L\n942.333 612.693 L\n978.167 624.605 L\n1014 631.276 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 224.145 M\n189.833 144.033 L\n225.667 106.633 L\n261.5 97.411 L\n297.333 101.668 L\n333.167 113.504 L\n369 131.819 L\n404.833 156.716 L\n440.667 185.849 L\n476.5 218.791 L\n512.333 254.768 L\n548.167 292.315 L\n584 330.167 L\n619.833 367.429 L\n655.667 403.492 L\n691.5 437.934 L\n727.333 470.461 L\n763.167 500.852 L\n799 528.919 L\n834.833 554.465 L\n870.667 577.248 L\n906.5 596.936 L\n942.333 613.058 L\n978.167 624.932 L\n1014 631.572 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 224.145 M\n189.833 142.655 L\n225.667 104.303 L\n261.5 94.926 L\n297.333 99.292 L\n333.167 111.348 L\n369 130.037 L\n404.833 155.561 L\n440.667 185.702 L\n476.5 219.659 L\n512.333 256.227 L\n548.167 293.985 L\n584 331.771 L\n619.833 368.79 L\n655.667 404.516 L\n691.5 438.605 L\n727.333 470.813 L\n763.167 500.95 L\n799 528.837 L\n834.833 554.274 L\n870.667 577.005 L\n906.5 596.684 L\n942.333 612.82 L\n978.167 624.718 L\n1014 631.378 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 224.145 M\n189.833 143.764 L\n225.667 106.182 L\n261.5 96.966 L\n297.333 101.279 L\n333.167 113.185 L\n369 131.594 L\n404.833 156.632 L\n440.667 185.981 L\n476.5 219.129 L\n512.333 255.223 L\n548.167 292.811 L\n584 330.646 L\n619.833 367.853 L\n655.667 403.836 L\n691.5 438.192 L\n727.333 470.638 L\n763.167 500.963 L\n799 528.979 L\n834.833 554.49 L\n870.667 577.252 L\n906.5 596.929 L\n942.333 613.047 L\n978.167 624.92 L\n1014 631.561 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 224.145 M\n189.833 142.925 L\n225.667 104.76 L\n261.5 95.422 L\n297.333 99.782 L\n333.167 111.813 L\n369 130.449 L\n404.833 155.876 L\n440.667 185.856 L\n476.5 219.642 L\n512.333 256.106 L\n548.167 293.823 L\n584 331.616 L\n619.833 368.668 L\n655.667 404.441 L\n691.5 438.578 L\n727.333 470.828 L\n763.167 500.997 L\n799 528.905 L\n834.833 554.352 L\n870.667 577.085 L\n906.5 596.759 L\n942.333 612.888 L\n978.167 624.778 L\n1014 631.433 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 224.145 M\n189.833 143.597 L\n225.667 105.9 L\n261.5 96.673 L\n297.333 101.007 L\n333.167 112.948 L\n369 131.411 L\n404.833 156.534 L\n440.667 186.017 L\n476.5 219.297 L\n512.333 255.467 L\n548.167 293.08 L\n584 330.905 L\n619.833 368.078 L\n655.667 404.013 L\n691.5 438.318 L\n727.333 470.717 L\n763.167 501.004 L\n799 528.993 L\n834.833 554.486 L\n870.667 577.238 L\n906.5 596.911 L\n942.333 613.028 L\n978.167 624.902 L\n1014 631.546 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 224.145 M\n189.833 143.08 L\n225.667 105.023 L\n261.5 95.711 L\n297.333 100.069 L\n333.167 112.083 L\n369 130.685 L\n404.833 156.05 L\n440.667 185.927 L\n476.5 219.606 L\n512.333 256.006 L\n548.167 293.7 L\n584 331.498 L\n619.833 368.573 L\n655.667 404.378 L\n691.5 438.546 L\n727.333 470.825 L\n763.167 501.016 L\n799 528.939 L\n834.833 554.394 L\n870.667 577.128 L\n906.5 596.8 L\n942.333 612.926 L\n978.167 624.811 L\n1014 631.463 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 224.145 M\n189.833 143.493 L\n225.667 105.723 L\n261.5 96.483 L\n297.333 100.826 L\n333.167 112.786 L\n369 131.28 L\n404.833 156.455 L\n440.667 186.022 L\n476.5 219.386 L\n512.333 255.603 L\n548.167 293.232 L\n584 331.052 L\n619.833 368.203 L\n655.667 404.109 L\n691.5 438.383 L\n727.333 470.755 L\n763.167 501.02 L\n799 528.993 L\n834.833 554.476 L\n870.667 577.223 L\n906.5 596.894 L\n942.333 613.012 L\n978.167 624.888 L\n1014 631.533 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 224.145 M\n189.833 143.172 L\n225.667 105.179 L\n261.5 95.883 L\n297.333 100.239 L\n333.167 112.243 L\n369 130.823 L\n404.833 156.149 L\n440.667 185.961 L\n476.5 219.574 L\n512.333 255.935 L\n548.167 293.614 L\n584 331.416 L\n619.833 368.507 L\n655.667 404.332 L\n691.5 438.521 L\n727.333 470.818 L\n763.167 501.024 L\n799 528.956 L\n834.833 554.416 L\n870.667 577.153 L\n906.5 596.824 L\n942.333 612.947 L\n978.167 624.83 L\n1014 631.48 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 224.145 M\n189.833 143.427 L\n225.667 105.611 L\n261.5 96.362 L\n297.333 100.709 L\n333.167 112.679 L\n369 131.192 L\n404.833 156.4 L\n440.667 186.019 L\n476.5 219.434 L\n512.333 255.681 L\n548.167 293.321 L\n584 331.137 L\n619.833 368.275 L\n655.667 404.163 L\n691.5 438.419 L\n727.333 470.774 L\n763.167 501.025 L\n799 528.989 L\n834.833 554.467 L\n870.667 577.211 L\n906.5 596.882 L\n942.333 613.001 L\n978.167 624.878 L\n1014 631.523 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 224.145 M\n189.833 143.228 L\n225.667 105.274 L\n261.5 95.988 L\n297.333 100.343 L\n333.167 112.34 L\n369 130.906 L\n404.833 156.207 L\n440.667 185.979 L\n476.5 219.55 L\n512.333 255.886 L\n548.167 293.558 L\n584 331.362 L\n619.833 368.462 L\n655.667 404.3 L\n691.5 438.503 L\n727.333 470.812 L\n763.167 501.027 L\n799 528.965 L\n834.833 554.429 L\n870.667 577.167 L\n906.5 596.838 L\n942.333 612.96 L\n978.167 624.841 L\n1014 631.49 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 224.145 M\n189.833 143.386 L\n225.667 105.542 L\n261.5 96.285 L\n297.333 100.635 L\n333.167 112.611 L\n369 131.135 L\n404.833 156.363 L\n440.667 186.014 L\n476.5 219.462 L\n512.333 255.728 L\n548.167 293.374 L\n584 331.187 L\n619.833 368.317 L\n655.667 404.195 L\n691.5 438.439 L\n727.333 470.784 L\n763.167 501.028 L\n799 528.986 L\n834.833 554.46 L\n870.667 577.203 L\n906.5 596.874 L\n942.333 612.993 L\n978.167 624.871 L\n1014 631.517 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n154 224.145 M\n189.833 143.262 L\n225.667 105.332 L\n261.5 96.053 L\n297.333 100.406 L\n333.167 112.399 L\n369 130.956 L\n404.833 156.242 L\n440.667 185.989 L\n476.5 219.533 L\n512.333 255.855 L\n548.167 293.521 L\n584 331.327 L\n619.833 368.434 L\n655.667 404.28 L\n691.5 438.491 L\n727.333 470.807 L\n763.167 501.028 L\n799 528.971 L\n834.833 554.436 L\n870.667 577.175 L\n906.5 596.846 L\n942.333 612.967 L\n978.167 624.848 L\n1014 631.496 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 224.145 M\n189.833 143.36 L\n225.667 105.498 L\n261.5 96.237 L\n297.333 100.587 L\n333.167 112.567 L\n369 131.099 L\n404.833 156.339 L\n440.667 186.01 L\n476.5 219.479 L\n512.333 255.756 L\n548.167 293.406 L\n584 331.218 L\n619.833 368.343 L\n655.667 404.214 L\n691.5 438.451 L\n727.333 470.79 L\n763.167 501.029 L\n799 528.983 L\n834.833 554.456 L\n870.667 577.197 L\n906.5 596.868 L\n942.333 612.988 L\n978.167 624.866 L\n1014 631.513 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 224.145 M\n189.833 143.283 L\n225.667 105.368 L\n261.5 96.092 L\n297.333 100.445 L\n333.167 112.435 L\n369 130.987 L\n404.833 156.263 L\n440.667 185.994 L\n476.5 219.523 L\n512.333 255.835 L\n548.167 293.497 L\n584 331.305 L\n619.833 368.415 L\n655.667 404.266 L\n691.5 438.483 L\n727.333 470.804 L\n763.167 501.029 L\n799 528.974 L\n834.833 554.441 L\n870.667 577.18 L\n906.5 596.851 L\n942.333 612.972 L\n978.167 624.852 L\n1014 631.5 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 224.145 M\n189.833 143.344 L\n225.667 105.471 L\n261.5 96.207 L\n297.333 100.558 L\n333.167 112.539 L\n369 131.075 L\n404.833 156.323 L\n440.667 186.007 L\n476.5 219.488 L\n512.333 255.773 L\n548.167 293.426 L\n584 331.237 L\n619.833 368.359 L\n655.667 404.225 L\n691.5 438.458 L\n727.333 470.793 L\n763.167 501.029 L\n799 528.982 L\n834.833 554.453 L\n870.667 577.194 L\n906.5 596.865 L\n942.333 612.984 L\n978.167 624.863 L\n1014 631.51 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 224.145 M\n189.833 143.297 L\n225.667 105.39 L\n261.5 96.117 L\n297.333 100.469 L\n333.167 112.457 L\n369 131.006 L\n404.833 156.276 L\n440.667 185.997 L\n476.5 219.516 L\n512.333 255.822 L\n548.167 293.483 L\n584 331.291 L\n619.833 368.404 L\n655.667 404.258 L\n691.5 438.478 L\n727.333 470.802 L\n763.167 501.029 L\n799 528.976 L\n834.833 554.444 L\n870.667 577.183 L\n906.5 596.854 L\n942.333 612.974 L\n978.167 624.854 L\n1014 631.502 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 224.145 M\n189.833 143.335 L\n225.667 105.455 L\n261.5 96.189 L\n297.333 100.539 L\n333.167 112.522 L\n369 131.061 L\n404.833 156.313 L\n440.667 186.005 L\n476.5 219.495 L\n512.333 255.784 L\n548.167 293.438 L\n584 331.249 L\n619.833 368.368 L\n655.667 404.232 L\n691.5 438.463 L\n727.333 470.795 L\n763.167 501.029 L\n799 528.98 L\n834.833 554.451 L\n870.667 577.192 L\n906.5 596.862 L\n942.333 612.982 L\n978.167 624.862 L\n1014 631.508 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 224.145 M\n189.833 143.305 L\n225.667 105.404 L\n261.5 96.133 L\n297.333 100.484 L\n333.167 112.471 L\n369 131.018 L\n404.833 156.284 L\n440.667 185.999 L\n476.5 219.512 L\n512.333 255.814 L\n548.167 293.474 L\n584 331.282 L\n619.833 368.396 L\n655.667 404.253 L\n691.5 438.475 L\n727.333 470.801 L\n763.167 501.029 L\n799 528.977 L\n834.833 554.445 L\n870.667 577.185 L\n906.5 596.856 L\n942.333 612.976 L\n978.167 624.856 L\n1014 631.503 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 224.145 M\n189.833 143.329 L\n225.667 105.445 L\n261.5 96.177 L\n297.333 100.528 L\n333.167 112.511 L\n369 131.052 L\n404.833 156.307 L\n440.667 186.004 L\n476.5 219.498 L\n512.333 255.79 L\n548.167 293.446 L\n584 331.256 L\n619.833 368.374 L\n655.667 404.237 L\n691.5 438.465 L\n727.333 470.797 L\n763.167 501.029 L\n799 528.98 L\n834.833 554.45 L\n870.667 577.19 L\n906.5 596.861 L\n942.333 612.981 L\n978.167 624.86 L\n1014 631.507 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 224.145 M\n189.833 143.31 L\n225.667 105.413 L\n261.5 96.142 L\n297.333 100.493 L\n333.167 112.479 L\n369 131.025 L\n404.833 156.289 L\n440.667 186 L\n476.5 219.509 L\n512.333 255.809 L\n548.167 293.468 L\n584 331.277 L\n619.833 368.392 L\n655.667 404.249 L\n691.5 438.473 L\n727.333 470.8 L\n763.167 501.029 L\n799 528.977 L\n834.833 554.446 L\n870.667 577.186 L\n906.5 596.857 L\n942.333 612.977 L\n978.167 624.857 L\n1014 631.504 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 224.145 M\n189.833 143.325 L\n225.667 105.438 L\n261.5 96.17 L\n297.333 100.52 L\n333.167 112.505 L\n369 131.046 L\n404.833 156.303 L\n440.667 186.003 L\n476.5 219.5 L\n512.333 255.794 L\n548.167 293.451 L\n584 331.26 L\n619.833 368.378 L\n655.667 404.24 L\n691.5 438.467 L\n727.333 470.797 L\n763.167 501.029 L\n799 528.979 L\n834.833 554.449 L\n870.667 577.189 L\n906.5 596.86 L\n942.333 612.98 L\n978.167 624.86 L\n1014 631.507 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 224.145 M\n189.833 143.313 L\n225.667 105.419 L\n261.5 96.149 L\n297.333 100.499 L\n333.167 112.485 L\n369 131.029 L\n404.833 156.292 L\n440.667 186.001 L\n476.5 219.507 L\n512.333 255.806 L\n548.167 293.464 L\n584 331.273 L\n619.833 368.389 L\n655.667 404.247 L\n691.5 438.472 L\n727.333 470.8 L\n763.167 501.029 L\n799 528.978 L\n834.833 554.447 L\n870.667 577.187 L\n906.5 596.858 L\n942.333 612.978 L\n978.167 624.857 L\n1014 631.505 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 224.145 M\n189.833 143.323 L\n225.667 105.435 L\n261.5 96.166 L\n297.333 100.516 L\n333.167 112.5 L\n369 131.042 L\n404.833 156.301 L\n440.667 186.003 L\n476.5 219.502 L\n512.333 255.797 L\n548.167 293.453 L\n584 331.263 L\n619.833 368.38 L\n655.667 404.241 L\n691.5 438.468 L\n727.333 470.798 L\n763.167 501.029 L\n799 528.979 L\n834.833 554.449 L\n870.667 577.189 L\n906.5 596.86 L\n942.333 612.98 L\n978.167 624.859 L\n1014 631.506 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n154 224.145 M\n189.833 143.316 L\n225.667 105.423 L\n261.5 96.153 L\n297.333 100.503 L\n333.167 112.488 L\n369 131.032 L\n404.833 156.294 L\n440.667 186.001 L\n476.5 219.506 L\n512.333 255.804 L\n548.167 293.462 L\n584 331.271 L\n619.833 368.387 L\n655.667 404.246 L\n691.5 438.471 L\n727.333 470.799 L\n763.167 501.029 L\n799 528.978 L\n834.833 554.447 L\n870.667 577.187 L\n906.5 596.858 L\n942.333 612.978 L\n978.167 624.858 L\n1014 631.505 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 292.90624 133.03405] CT\r\nN\r\n-0.641 18.348 M\n-0.641 17.176 0.172 16.317 QT\n0.984 15.457 2.156 15.457 QT\n2.938 15.457 3.461 15.942 QT\n3.984 16.426 3.984 17.192 QT\n3.984 18.114 3.414 18.848 QT\n2.844 19.582 1.969 19.817 QT\n2.813 20.129 3.656 20.129 QT\n5.703 20.129 7.203 18.239 QT\n8.703 16.348 9.313 14.004 QT\n13.828 -4.043 L\n14.156 -5.433 14.156 -6.386 QT\n14.156 -8.449 12.734 -8.449 QT\n10.625 -8.449 9.039 -6.543 QT\n7.453 -4.636 6.469 -2.121 QT\n6.375 -1.824 6.094 -1.824 QT\n5.531 -1.824 L\n5.141 -1.824 5.141 -2.261 QT\n5.141 -2.402 L\n6.219 -5.293 8.211 -7.496 QT\n10.203 -9.699 12.828 -9.699 QT\n14.813 -9.699 16.094 -8.457 QT\n17.375 -7.215 17.375 -5.293 QT\n17.375 -4.605 17.234 -3.933 QT\n12.688 14.317 L\n12.188 16.254 10.805 17.871 QT\n9.422 19.489 7.5 20.426 QT\n5.578 21.364 3.563 21.364 QT\n1.953 21.364 0.656 20.59 QT\n-0.641 19.817 -0.641 18.348 QT\ncp\n14.563 -17.574 M\n14.563 -18.621 15.383 -19.418 QT\n16.203 -20.215 17.234 -20.215 QT\n18.047 -20.215 18.578 -19.715 QT\n19.109 -19.215 19.109 -18.433 QT\n19.109 -17.355 18.25 -16.55 QT\n17.391 -15.746 16.359 -15.746 QT\n15.594 -15.746 15.078 -16.285 QT\n14.563 -16.824 14.563 -17.574 QT\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 292.90624 133.03405] CT\r\nN\r\n39.457 5.145 M\n39.066 5.145 38.808 4.84 QT\n38.55 4.535 38.55 4.176 QT\n38.55 3.785 38.808 3.504 QT\n39.066 3.223 39.457 3.223 QT\n69.597 3.223 L\n69.957 3.223 70.215 3.504 QT\n70.472 3.785 70.472 4.176 QT\n70.472 4.535 70.215 4.84 QT\n69.957 5.145 69.597 5.145 QT\n39.457 5.145 L\ncp\n39.457 -4.183 M\n39.066 -4.183 38.808 -4.465 QT\n38.55 -4.746 38.55 -5.152 QT\n38.55 -5.496 38.808 -5.8 QT\n39.066 -6.105 39.457 -6.105 QT\n69.597 -6.105 L\n69.957 -6.105 70.215 -5.8 QT\n70.472 -5.496 70.472 -5.152 QT\n70.472 -4.746 70.215 -4.465 QT\n69.957 -4.183 69.597 -4.183 QT\n39.457 -4.183 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 292.90624 133.03405] CT\r\nN\r\n90.967 11.52 M\n90.967 9.832 L\n96.967 9.832 96.967 8.301 QT\n96.967 -16.886 L\n94.483 -15.699 90.686 -15.699 QT\n90.686 -17.386 L\n96.576 -17.386 99.576 -20.449 QT\n100.248 -20.449 L\n100.42 -20.449 100.569 -20.324 QT\n100.717 -20.199 100.717 -20.027 QT\n100.717 8.301 L\n100.717 9.832 106.717 9.832 QT\n106.717 11.52 L\n90.967 11.52 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 171.96875 57.3188] CT\r\nN\r\n/f946251025{-0.641 18.348 M\n-0.641 17.176 0.172 16.317 QT\n0.984 15.457 2.156 15.457 QT\n2.938 15.457 3.461 15.942 QT\n3.984 16.426 3.984 17.192 QT\n3.984 18.114 3.414 18.848 QT\n2.844 19.582 1.969 19.817 QT\n2.813 20.129 3.656 20.129 QT\n5.703 20.129 7.203 18.239 QT\n8.703 16.348 9.313 14.004 QT\n13.828 -4.043 L\n14.156 -5.433 14.156 -6.386 QT\n14.156 -8.449 12.734 -8.449 QT\n10.625 -8.449 9.039 -6.543 QT\n7.453 -4.636 6.469 -2.121 QT\n6.375 -1.824 6.094 -1.824 QT\n5.531 -1.824 L\n5.141 -1.824 5.141 -2.261 QT\n5.141 -2.402 L\n6.219 -5.293 8.211 -7.496 QT\n10.203 -9.699 12.828 -9.699 QT\n14.813 -9.699 16.094 -8.457 QT\n17.375 -7.215 17.375 -5.293 QT\n17.375 -4.605 17.234 -3.933 QT\n12.688 14.317 L\n12.188 16.254 10.805 17.871 QT\n9.422 19.489 7.5 20.426 QT\n5.578 21.364 3.563 21.364 QT\n1.953 21.364 0.656 20.59 QT\n-0.641 19.817 -0.641 18.348 QT\ncp\n14.563 -17.574 M\n14.563 -18.621 15.383 -19.418 QT\n16.203 -20.215 17.234 -20.215 QT\n18.047 -20.215 18.578 -19.715 QT\n19.109 -19.215 19.109 -18.433 QT\n19.109 -17.355 18.25 -16.55 QT\n17.391 -15.746 16.359 -15.746 QT\n15.594 -15.746 15.078 -16.285 QT\n14.563 -16.824 14.563 -17.574 QT\ncp}def\r\nf946251025\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 171.96875 57.3188] CT\r\nN\r\n/f-1792154824{39.457 5.145 M\n39.066 5.145 38.808 4.84 QT\n38.55 4.535 38.55 4.176 QT\n38.55 3.785 38.808 3.504 QT\n39.066 3.223 39.457 3.223 QT\n69.597 3.223 L\n69.957 3.223 70.215 3.504 QT\n70.472 3.785 70.472 4.176 QT\n70.472 4.535 70.215 4.84 QT\n69.957 5.145 69.597 5.145 QT\n39.457 5.145 L\ncp\n39.457 -4.183 M\n39.066 -4.183 38.808 -4.465 QT\n38.55 -4.746 38.55 -5.152 QT\n38.55 -5.496 38.808 -5.8 QT\n39.066 -6.105 39.457 -6.105 QT\n69.597 -6.105 L\n69.957 -6.105 70.215 -5.8 QT\n70.472 -5.496 70.472 -5.152 QT\n70.472 -4.746 70.215 -4.465 QT\n69.957 -4.183 69.597 -4.183 QT\n39.457 -4.183 L\ncp}def\r\nf-1792154824\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 171.96875 57.3188] CT\r\nN\r\n/f1600933324{88.904 11.52 M\n88.904 10.223 L\n88.904 10.114 88.998 9.973 QT\n96.451 1.723 L\n98.139 -0.105 99.194 -1.347 QT\n100.248 -2.59 101.279 -4.207 QT\n102.311 -5.824 102.912 -7.504 QT\n103.514 -9.183 103.514 -11.058 QT\n103.514 -13.027 102.787 -14.816 QT\n102.061 -16.605 100.615 -17.683 QT\n99.17 -18.761 97.139 -18.761 QT\n95.045 -18.761 93.381 -17.511 QT\n91.717 -16.261 91.045 -14.261 QT\n91.233 -14.308 91.561 -14.308 QT\n92.639 -14.308 93.397 -13.582 QT\n94.154 -12.855 94.154 -11.715 QT\n94.154 -10.605 93.397 -9.847 QT\n92.639 -9.09 91.561 -9.09 QT\n90.436 -9.09 89.67 -9.871 QT\n88.904 -10.652 88.904 -11.715 QT\n88.904 -13.511 89.584 -15.097 QT\n90.264 -16.683 91.545 -17.91 QT\n92.826 -19.136 94.428 -19.793 QT\n96.029 -20.449 97.842 -20.449 QT\n100.576 -20.449 102.944 -19.293 QT\n105.311 -18.136 106.694 -16.011 QT\n108.076 -13.886 108.076 -11.058 QT\n108.076 -8.965 107.162 -7.09 QT\n106.248 -5.215 104.819 -3.683 QT\n103.389 -2.152 101.162 -0.207 QT\n98.936 1.739 98.233 2.395 QT\n92.795 7.629 L\n97.42 7.629 L\n100.811 7.629 103.1 7.567 QT\n105.389 7.504 105.529 7.395 QT\n106.092 6.785 106.67 2.957 QT\n108.076 2.957 L\n106.717 11.52 L\n88.904 11.52 L\ncp}def\r\nf1600933324\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 GC\r\nN\r\n993 677 M\n993 553 L\n379 553 L\n379 677 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f1636705084{10.953 6.379 M\n12.594 8.473 15.055 9.676 QT\n17.516 10.879 20.156 10.879 QT\n22.391 10.879 24.289 10.004 QT\n26.188 9.129 27.602 7.559 QT\n29.016 5.989 29.781 3.996 QT\n30.547 2.004 30.547 -0.199 QT\n30.547 -0.574 30.969 -0.574 QT\n31.547 -0.574 L\n31.922 -0.574 31.922 -0.105 QT\n31.922 2.395 30.961 4.731 QT\n30 7.067 28.242 8.832 QT\n26.484 10.598 24.203 11.59 QT\n21.922 12.582 19.438 12.582 QT\n15.984 12.582 12.906 11.184 QT\n9.828 9.785 7.539 7.356 QT\n5.25 4.926 3.977 1.739 QT\n2.703 -1.449 2.703 -4.886 QT\n2.703 -8.34 3.977 -11.527 QT\n5.25 -14.715 7.539 -17.152 QT\n9.828 -19.59 12.906 -20.957 QT\n15.984 -22.324 19.438 -22.324 QT\n21.891 -22.324 24.141 -21.261 QT\n26.391 -20.199 28.078 -18.246 QT\n30.875 -22.183 L\n31.156 -22.324 31.203 -22.324 QT\n31.547 -22.324 L\n31.688 -22.324 31.805 -22.207 QT\n31.922 -22.09 31.922 -21.933 QT\n31.922 -8.965 L\n31.922 -8.543 31.547 -8.543 QT\n30.688 -8.543 L\n30.234 -8.543 30.234 -8.965 QT\n30.234 -10.355 29.688 -12.066 QT\n29.141 -13.777 28.281 -15.308 QT\n27.422 -16.84 26.297 -18.011 QT\n23.609 -20.636 20.109 -20.636 QT\n17.469 -20.636 15.039 -19.441 QT\n12.609 -18.246 10.953 -16.136 QT\n9.188 -13.886 8.508 -11.019 QT\n7.828 -8.152 7.828 -4.886 QT\n7.828 -1.636 8.508 1.246 QT\n9.188 4.129 10.953 6.379 QT\ncp}def\r\nf1636705084\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f-518588683{46.667 12.067 M\n43.792 12.067 41.331 10.598 QT\n38.87 9.129 37.44 6.668 QT\n36.01 4.207 36.01 1.301 QT\n36.01 -0.902 36.792 -2.941 QT\n37.573 -4.98 39.042 -6.59 QT\n40.51 -8.199 42.456 -9.097 QT\n44.401 -9.996 46.667 -9.996 QT\n49.62 -9.996 52.05 -8.441 QT\n54.479 -6.886 55.885 -4.269 QT\n57.292 -1.652 57.292 1.301 QT\n57.292 4.176 55.862 6.653 QT\n54.432 9.129 51.979 10.598 QT\n49.526 12.067 46.667 12.067 QT\ncp\n46.667 10.645 M\n50.51 10.645 51.8 7.856 QT\n53.089 5.067 53.089 0.754 QT\n53.089 -1.652 52.831 -3.238 QT\n52.573 -4.824 51.714 -6.105 QT\n51.167 -6.902 50.339 -7.504 QT\n49.51 -8.105 48.581 -8.418 QT\n47.651 -8.73 46.667 -8.73 QT\n45.167 -8.73 43.823 -8.05 QT\n42.479 -7.371 41.589 -6.105 QT\n40.698 -4.746 40.448 -3.121 QT\n40.198 -1.496 40.198 0.754 QT\n40.198 3.457 40.667 5.598 QT\n41.135 7.739 42.557 9.192 QT\n43.979 10.645 46.667 10.645 QT\ncp}def\r\nf-518588683\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f763322885{60.104 11.52 M\n60.104 9.832 L\n61.745 9.832 62.8 9.575 QT\n63.854 9.317 63.854 8.301 QT\n63.854 -4.793 L\n63.854 -6.09 63.464 -6.66 QT\n63.073 -7.23 62.346 -7.363 QT\n61.62 -7.496 60.104 -7.496 QT\n60.104 -9.183 L\n67.057 -9.699 L\n67.057 -5.011 L\n68.026 -7.074 69.909 -8.386 QT\n71.792 -9.699 74.026 -9.699 QT\n77.354 -9.699 79.026 -8.105 QT\n80.698 -6.511 80.698 -3.23 QT\n80.698 8.301 L\n80.698 9.317 81.753 9.575 QT\n82.807 9.832 84.448 9.832 QT\n84.448 11.52 L\n73.464 11.52 L\n73.464 9.832 L\n75.104 9.832 76.159 9.575 QT\n77.214 9.317 77.214 8.301 QT\n77.214 -3.09 L\n77.214 -5.433 76.534 -6.941 QT\n75.854 -8.449 73.745 -8.449 QT\n70.948 -8.449 69.159 -6.222 QT\n67.37 -3.996 67.37 -1.168 QT\n67.37 8.301 L\n67.37 9.317 68.425 9.575 QT\n69.479 9.832 71.089 9.832 QT\n71.089 11.52 L\n60.104 11.52 L\ncp}def\r\nf763322885\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f1813278697{95.719 11.52 M\n88.719 -6.105 L\n88.266 -6.996 87.344 -7.246 QT\n86.422 -7.496 84.922 -7.496 QT\n84.922 -9.183 L\n95 -9.183 L\n95 -7.496 L\n92.297 -7.496 92.297 -6.34 QT\n92.297 -6.152 92.344 -6.058 QT\n97.735 7.489 L\n102.594 -4.746 L\n102.735 -5.121 102.735 -5.527 QT\n102.735 -6.433 102.039 -6.965 QT\n101.344 -7.496 100.406 -7.496 QT\n100.406 -9.183 L\n108.375 -9.183 L\n108.375 -7.496 L\n106.906 -7.496 105.789 -6.816 QT\n104.672 -6.136 104.063 -4.793 QT\n97.594 11.52 L\n97.406 12.067 96.828 12.067 QT\n96.469 12.067 L\n95.891 12.067 95.719 11.52 QT\ncp}def\r\nf1813278697\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f1730672616{119.953 12.067 M\n117.031 12.067 114.578 10.528 QT\n112.125 8.989 110.735 6.418 QT\n109.344 3.848 109.344 0.989 QT\n109.344 -1.824 110.617 -4.355 QT\n111.891 -6.886 114.18 -8.441 QT\n116.469 -9.996 119.281 -9.996 QT\n121.485 -9.996 123.11 -9.261 QT\n124.735 -8.527 125.789 -7.215 QT\n126.844 -5.902 127.383 -4.121 QT\n127.922 -2.34 127.922 -0.199 QT\n127.922 0.426 127.438 0.426 QT\n113.531 0.426 L\n113.531 0.942 L\n113.531 4.926 115.141 7.785 QT\n116.75 10.645 120.375 10.645 QT\n121.86 10.645 123.11 9.989 QT\n124.36 9.332 125.289 8.16 QT\n126.219 6.989 126.547 5.66 QT\n126.594 5.489 126.719 5.364 QT\n126.844 5.239 127.016 5.239 QT\n127.438 5.239 L\n127.922 5.239 127.922 5.848 QT\n127.25 8.567 125 10.317 QT\n122.75 12.067 119.953 12.067 QT\ncp\n113.578 -0.761 M\n124.531 -0.761 L\n124.531 -2.574 124.024 -4.425 QT\n123.516 -6.277 122.344 -7.504 QT\n121.172 -8.73 119.281 -8.73 QT\n116.563 -8.73 115.071 -6.191 QT\n113.578 -3.652 113.578 -0.761 QT\ncp}def\r\nf1730672616\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f1581324804{130.584 11.52 M\n130.584 9.832 L\n132.224 9.832 133.279 9.575 QT\n134.334 9.317 134.334 8.301 QT\n134.334 -4.793 L\n134.334 -6.09 133.943 -6.66 QT\n133.552 -7.23 132.826 -7.363 QT\n132.099 -7.496 130.584 -7.496 QT\n130.584 -9.183 L\n137.443 -9.699 L\n137.443 -5.011 L\n138.224 -7.09 139.654 -8.394 QT\n141.084 -9.699 143.115 -9.699 QT\n144.552 -9.699 145.677 -8.855 QT\n146.802 -8.011 146.802 -6.621 QT\n146.802 -5.761 146.177 -5.113 QT\n145.552 -4.465 144.646 -4.465 QT\n143.755 -4.465 143.123 -5.097 QT\n142.49 -5.73 142.49 -6.621 QT\n142.49 -7.918 143.396 -8.449 QT\n143.115 -8.449 L\n141.177 -8.449 139.943 -7.043 QT\n138.709 -5.636 138.193 -3.55 QT\n137.677 -1.465 137.677 0.426 QT\n137.677 8.301 L\n137.677 9.832 142.349 9.832 QT\n142.349 11.52 L\n130.584 11.52 L\ncp}def\r\nf1581324804\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f-1655348641{149.477 15.27 M\n149.477 13.567 150.72 12.285 QT\n151.962 11.004 153.665 10.457 QT\n152.712 9.739 152.204 8.637 QT\n151.696 7.535 151.696 6.285 QT\n151.696 4.035 153.134 2.301 QT\n150.93 0.145 150.93 -2.636 QT\n150.93 -4.136 151.571 -5.449 QT\n152.212 -6.761 153.36 -7.722 QT\n154.509 -8.683 155.915 -9.191 QT\n157.321 -9.699 158.805 -9.699 QT\n161.665 -9.699 163.93 -8.027 QT\n164.915 -9.09 166.266 -9.66 QT\n167.618 -10.23 169.071 -10.23 QT\n170.102 -10.23 170.759 -9.496 QT\n171.415 -8.761 171.415 -7.73 QT\n171.415 -7.136 170.97 -6.691 QT\n170.524 -6.246 169.93 -6.246 QT\n169.321 -6.246 168.876 -6.691 QT\n168.43 -7.136 168.43 -7.73 QT\n168.43 -8.621 169.024 -8.965 QT\n166.54 -8.965 164.759 -7.261 QT\n165.618 -6.386 166.149 -5.136 QT\n166.68 -3.886 166.68 -2.636 QT\n166.68 -0.605 165.555 1.028 QT\n164.43 2.66 162.587 3.559 QT\n160.743 4.457 158.805 4.457 QT\n156.18 4.457 153.993 3.035 QT\n153.321 3.973 153.321 5.145 QT\n153.321 6.41 154.149 7.356 QT\n154.977 8.301 156.243 8.301 QT\n160.18 8.301 L\n163.04 8.301 165.337 8.817 QT\n167.634 9.332 169.196 10.887 QT\n170.759 12.442 170.759 15.27 QT\n170.759 17.379 168.977 18.778 QT\n167.196 20.176 164.72 20.793 QT\n162.243 21.41 160.134 21.41 QT\n158.009 21.41 155.524 20.793 QT\n153.04 20.176 151.259 18.778 QT\n149.477 17.379 149.477 15.27 QT\ncp\n152.165 15.27 M\n152.165 16.895 153.477 17.981 QT\n154.79 19.067 156.641 19.598 QT\n158.493 20.129 160.134 20.129 QT\n161.759 20.129 163.61 19.598 QT\n165.462 19.067 166.759 17.981 QT\n168.055 16.895 168.055 15.27 QT\n168.055 12.77 165.759 12.028 QT\n163.462 11.285 160.18 11.285 QT\n156.243 11.285 L\n155.149 11.285 154.22 11.817 QT\n153.29 12.348 152.727 13.293 QT\n152.165 14.239 152.165 15.27 QT\ncp\n158.805 3.176 M\n162.884 3.176 162.884 -2.636 QT\n162.884 -5.152 162.016 -6.777 QT\n161.149 -8.402 158.805 -8.402 QT\n156.462 -8.402 155.595 -6.777 QT\n154.727 -5.152 154.727 -2.636 QT\n154.727 -1.043 155.055 0.246 QT\n155.384 1.535 156.274 2.356 QT\n157.165 3.176 158.805 3.176 QT\ncp}def\r\nf-1655348641\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f402514587{184.087 12.067 M\n181.165 12.067 178.712 10.528 QT\n176.259 8.989 174.868 6.418 QT\n173.477 3.848 173.477 0.989 QT\n173.477 -1.824 174.751 -4.355 QT\n176.024 -6.886 178.313 -8.441 QT\n180.602 -9.996 183.415 -9.996 QT\n185.618 -9.996 187.243 -9.261 QT\n188.868 -8.527 189.923 -7.215 QT\n190.977 -5.902 191.516 -4.121 QT\n192.056 -2.34 192.056 -0.199 QT\n192.056 0.426 191.571 0.426 QT\n177.665 0.426 L\n177.665 0.942 L\n177.665 4.926 179.274 7.785 QT\n180.884 10.645 184.509 10.645 QT\n185.993 10.645 187.243 9.989 QT\n188.493 9.332 189.423 8.16 QT\n190.352 6.989 190.681 5.66 QT\n190.727 5.489 190.852 5.364 QT\n190.977 5.239 191.149 5.239 QT\n191.571 5.239 L\n192.056 5.239 192.056 5.848 QT\n191.384 8.567 189.134 10.317 QT\n186.884 12.067 184.087 12.067 QT\ncp\n177.712 -0.761 M\n188.665 -0.761 L\n188.665 -2.574 188.157 -4.425 QT\n187.649 -6.277 186.477 -7.504 QT\n185.306 -8.73 183.415 -8.73 QT\n180.696 -8.73 179.204 -6.191 QT\n177.712 -3.652 177.712 -0.761 QT\ncp}def\r\nf402514587\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f909272395{205.186 12.067 M\n202.358 12.067 200.014 10.528 QT\n197.67 8.989 196.365 6.481 QT\n195.061 3.973 195.061 1.16 QT\n195.061 -1.746 196.483 -4.246 QT\n197.904 -6.746 200.342 -8.222 QT\n202.779 -9.699 205.701 -9.699 QT\n207.467 -9.699 209.037 -8.957 QT\n210.608 -8.215 211.748 -6.902 QT\n211.748 -16.886 L\n211.748 -18.183 211.365 -18.754 QT\n210.983 -19.324 210.264 -19.457 QT\n209.545 -19.59 208.029 -19.59 QT\n208.029 -21.277 L\n215.123 -21.793 L\n215.123 7.16 L\n215.123 8.426 215.514 8.996 QT\n215.904 9.567 216.615 9.7 QT\n217.326 9.832 218.858 9.832 QT\n218.858 11.52 L\n211.608 12.067 L\n211.608 9.035 L\n210.373 10.457 208.662 11.262 QT\n206.951 12.067 205.186 12.067 QT\ncp\n200.295 7.348 M\n201.108 8.91 202.483 9.848 QT\n203.858 10.785 205.467 10.785 QT\n207.467 10.785 209.131 9.637 QT\n210.795 8.489 211.608 6.66 QT\n211.608 -4.84 L\n211.045 -5.902 210.194 -6.73 QT\n209.342 -7.558 208.272 -8.004 QT\n207.201 -8.449 206.014 -8.449 QT\n203.498 -8.449 201.975 -7.035 QT\n200.451 -5.621 199.842 -3.418 QT\n199.233 -1.215 199.233 1.207 QT\n199.233 3.129 199.436 4.559 QT\n199.639 5.989 200.295 7.348 QT\ncp}def\r\nf909272395\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f-583193730{251.024 23.426 M\n248.352 21.317 246.415 18.59 QT\n244.477 15.864 243.251 12.762 QT\n242.024 9.66 241.415 6.285 QT\n240.806 2.91 240.806 -0.48 QT\n240.806 -3.933 241.415 -7.308 QT\n242.024 -10.683 243.274 -13.8 QT\n244.524 -16.918 246.47 -19.636 QT\n248.415 -22.355 251.024 -24.386 QT\n251.024 -24.48 251.259 -24.48 QT\n251.696 -24.48 L\n251.837 -24.48 251.954 -24.355 QT\n252.071 -24.23 252.071 -24.058 QT\n252.071 -23.855 251.977 -23.761 QT\n249.634 -21.465 248.079 -18.84 QT\n246.524 -16.215 245.571 -13.246 QT\n244.618 -10.277 244.196 -7.105 QT\n243.774 -3.933 243.774 -0.48 QT\n243.774 14.785 251.931 22.707 QT\n252.071 22.848 252.071 23.098 QT\n252.071 23.223 251.946 23.371 QT\n251.821 23.52 251.696 23.52 QT\n251.259 23.52 L\n251.024 23.52 251.024 23.426 QT\ncp}def\r\nf-583193730\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f-129920944{254.16 18.348 M\n254.16 17.176 254.972 16.317 QT\n255.785 15.457 256.957 15.457 QT\n257.738 15.457 258.261 15.942 QT\n258.785 16.426 258.785 17.192 QT\n258.785 18.114 258.214 18.848 QT\n257.644 19.582 256.769 19.817 QT\n257.613 20.129 258.457 20.129 QT\n260.504 20.129 262.004 18.239 QT\n263.504 16.348 264.113 14.004 QT\n268.629 -4.043 L\n268.957 -5.433 268.957 -6.386 QT\n268.957 -8.449 267.535 -8.449 QT\n265.425 -8.449 263.839 -6.543 QT\n262.254 -4.636 261.269 -2.121 QT\n261.175 -1.824 260.894 -1.824 QT\n260.332 -1.824 L\n259.941 -1.824 259.941 -2.261 QT\n259.941 -2.402 L\n261.019 -5.293 263.011 -7.496 QT\n265.004 -9.699 267.629 -9.699 QT\n269.613 -9.699 270.894 -8.457 QT\n272.175 -7.215 272.175 -5.293 QT\n272.175 -4.605 272.035 -3.933 QT\n267.488 14.317 L\n266.988 16.254 265.605 17.871 QT\n264.222 19.489 262.3 20.426 QT\n260.379 21.364 258.363 21.364 QT\n256.754 21.364 255.457 20.59 QT\n254.16 19.817 254.16 18.348 QT\ncp\n269.363 -17.574 M\n269.363 -18.621 270.183 -19.418 QT\n271.004 -20.215 272.035 -20.215 QT\n272.847 -20.215 273.379 -19.715 QT\n273.91 -19.215 273.91 -18.433 QT\n273.91 -17.355 273.05 -16.55 QT\n272.191 -15.746 271.16 -15.746 QT\n270.394 -15.746 269.879 -16.285 QT\n269.363 -16.824 269.363 -17.574 QT\ncp}def\r\nf-129920944\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f730600524{294.257 5.145 M\n293.867 5.145 293.609 4.84 QT\n293.351 4.535 293.351 4.176 QT\n293.351 3.785 293.609 3.504 QT\n293.867 3.223 294.257 3.223 QT\n324.398 3.223 L\n324.757 3.223 325.015 3.504 QT\n325.273 3.785 325.273 4.176 QT\n325.273 4.535 325.015 4.84 QT\n324.757 5.145 324.398 5.145 QT\n294.257 5.145 L\ncp\n294.257 -4.183 M\n293.867 -4.183 293.609 -4.465 QT\n293.351 -4.746 293.351 -5.152 QT\n293.351 -5.496 293.609 -5.8 QT\n293.867 -6.105 294.257 -6.105 QT\n324.398 -6.105 L\n324.757 -6.105 325.015 -5.8 QT\n325.273 -5.496 325.273 -5.152 QT\n325.273 -4.746 325.015 -4.465 QT\n324.757 -4.183 324.398 -4.183 QT\n294.257 -4.183 L\ncp}def\r\nf730600524\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f704190049{345.892 7.817 M\n347.017 9.457 348.916 10.254 QT\n350.814 11.051 352.986 11.051 QT\n355.783 11.051 356.955 8.668 QT\n358.127 6.285 358.127 3.27 QT\n358.127 1.91 357.877 0.551 QT\n357.627 -0.808 357.041 -1.98 QT\n356.455 -3.152 355.439 -3.855 QT\n354.424 -4.558 352.939 -4.558 QT\n349.752 -4.558 L\n349.33 -4.558 349.33 -5.011 QT\n349.33 -5.433 L\n349.33 -5.808 349.752 -5.808 QT\n352.408 -6.011 L\n354.095 -6.011 355.205 -7.277 QT\n356.314 -8.543 356.83 -10.363 QT\n357.345 -12.183 357.345 -13.824 QT\n357.345 -16.121 356.267 -17.597 QT\n355.189 -19.074 352.986 -19.074 QT\n351.158 -19.074 349.494 -18.379 QT\n347.83 -17.683 346.845 -16.277 QT\n346.939 -16.308 347.01 -16.316 QT\n347.08 -16.324 347.174 -16.324 QT\n348.252 -16.324 348.978 -15.574 QT\n349.705 -14.824 349.705 -13.777 QT\n349.705 -12.746 348.978 -11.996 QT\n348.252 -11.246 347.174 -11.246 QT\n346.127 -11.246 345.377 -11.996 QT\n344.627 -12.746 344.627 -13.777 QT\n344.627 -15.84 345.869 -17.363 QT\n347.111 -18.886 349.064 -19.668 QT\n351.017 -20.449 352.986 -20.449 QT\n354.439 -20.449 356.056 -20.019 QT\n357.674 -19.59 358.986 -18.777 QT\n360.299 -17.965 361.135 -16.699 QT\n361.97 -15.433 361.97 -13.824 QT\n361.97 -11.808 361.064 -10.097 QT\n360.158 -8.386 358.588 -7.144 QT\n357.017 -5.902 355.142 -5.293 QT\n357.236 -4.886 359.111 -3.715 QT\n360.986 -2.543 362.119 -0.715 QT\n363.252 1.114 363.252 3.223 QT\n363.252 5.864 361.799 8.012 QT\n360.345 10.16 357.978 11.371 QT\n355.611 12.582 352.986 12.582 QT\n350.736 12.582 348.478 11.723 QT\n346.22 10.864 344.775 9.153 QT\n343.33 7.442 343.33 5.051 QT\n343.33 3.848 344.127 3.051 QT\n344.924 2.254 346.127 2.254 QT\n346.892 2.254 347.541 2.621 QT\n348.189 2.989 348.549 3.645 QT\n348.908 4.301 348.908 5.051 QT\n348.908 6.223 348.088 7.02 QT\n347.267 7.817 346.127 7.817 QT\n345.892 7.817 L\ncp}def\r\nf704190049\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f400715756{367.705 11.52 M\n367.705 10.223 L\n367.705 10.114 367.799 9.973 QT\n375.252 1.723 L\n376.939 -0.105 377.994 -1.347 QT\n379.049 -2.59 380.08 -4.207 QT\n381.111 -5.824 381.713 -7.504 QT\n382.314 -9.183 382.314 -11.058 QT\n382.314 -13.027 381.588 -14.816 QT\n380.861 -16.605 379.416 -17.683 QT\n377.971 -18.761 375.939 -18.761 QT\n373.846 -18.761 372.182 -17.511 QT\n370.517 -16.261 369.846 -14.261 QT\n370.033 -14.308 370.361 -14.308 QT\n371.439 -14.308 372.197 -13.582 QT\n372.955 -12.855 372.955 -11.715 QT\n372.955 -10.605 372.197 -9.847 QT\n371.439 -9.09 370.361 -9.09 QT\n369.236 -9.09 368.471 -9.871 QT\n367.705 -10.652 367.705 -11.715 QT\n367.705 -13.511 368.385 -15.097 QT\n369.064 -16.683 370.346 -17.91 QT\n371.627 -19.136 373.228 -19.793 QT\n374.83 -20.449 376.642 -20.449 QT\n379.377 -20.449 381.744 -19.293 QT\n384.111 -18.136 385.494 -16.011 QT\n386.877 -13.886 386.877 -11.058 QT\n386.877 -8.965 385.963 -7.09 QT\n385.049 -5.215 383.619 -3.683 QT\n382.189 -2.152 379.963 -0.207 QT\n377.736 1.739 377.033 2.395 QT\n371.596 7.629 L\n376.221 7.629 L\n379.611 7.629 381.9 7.567 QT\n384.189 7.504 384.33 7.395 QT\n384.892 6.785 385.471 2.957 QT\n386.877 2.957 L\n385.517 11.52 L\n367.705 11.52 L\ncp}def\r\nf400715756\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 219.6552] CT\r\nN\r\n/f-420795744{392.439 23.52 M\n392.018 23.52 392.018 23.098 QT\n392.018 22.895 392.111 22.801 QT\n400.314 14.785 400.314 -0.48 QT\n400.314 -15.746 392.205 -23.668 QT\n392.018 -23.777 392.018 -24.058 QT\n392.018 -24.23 392.143 -24.355 QT\n392.268 -24.48 392.439 -24.48 QT\n392.877 -24.48 L\n393.018 -24.48 393.111 -24.386 QT\n396.564 -21.668 398.861 -17.777 QT\n401.158 -13.886 402.221 -9.48 QT\n403.283 -5.074 403.283 -0.48 QT\n403.283 2.91 402.713 6.207 QT\n402.143 9.504 400.885 12.707 QT\n399.627 15.91 397.705 18.614 QT\n395.783 21.317 393.111 23.426 QT\n393.018 23.52 392.877 23.52 QT\n392.439 23.52 L\ncp}def\r\nf-420795744\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0 0 1 RC\r\n1 LJ\r\n5.333 LW\r\nN\r\n387 585.747 M\n467.003 585.747 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf1636705084\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf-518588683\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf763322885\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf1813278697\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf1730672616\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf1581324804\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\nf-1655348641\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f-2079540185{173.618 11.52 M\n173.618 9.832 L\n175.259 9.832 176.313 9.575 QT\n177.368 9.317 177.368 8.301 QT\n177.368 -4.793 L\n177.368 -6.652 176.649 -7.074 QT\n175.931 -7.496 173.821 -7.496 QT\n173.821 -9.183 L\n180.743 -9.699 L\n180.743 8.301 L\n180.743 9.317 181.657 9.575 QT\n182.571 9.832 184.087 9.832 QT\n184.087 11.52 L\n173.618 11.52 L\ncp\n175.649 -17.949 M\n175.649 -18.996 176.446 -19.793 QT\n177.243 -20.59 178.274 -20.59 QT\n178.962 -20.59 179.595 -20.238 QT\n180.227 -19.886 180.579 -19.254 QT\n180.931 -18.621 180.931 -17.949 QT\n180.931 -16.918 180.134 -16.121 QT\n179.337 -15.324 178.274 -15.324 QT\n177.243 -15.324 176.446 -16.121 QT\n175.649 -16.918 175.649 -17.949 QT\ncp}def\r\nf-2079540185\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f581539271{186.905 11.52 M\n186.905 9.832 L\n188.545 9.832 189.6 9.575 QT\n190.655 9.317 190.655 8.301 QT\n190.655 -4.793 L\n190.655 -6.09 190.264 -6.66 QT\n189.873 -7.23 189.147 -7.363 QT\n188.42 -7.496 186.905 -7.496 QT\n186.905 -9.183 L\n193.858 -9.699 L\n193.858 -5.011 L\n194.826 -7.074 196.709 -8.386 QT\n198.592 -9.699 200.826 -9.699 QT\n204.155 -9.699 205.826 -8.105 QT\n207.498 -6.511 207.498 -3.23 QT\n207.498 8.301 L\n207.498 9.317 208.553 9.575 QT\n209.608 9.832 211.248 9.832 QT\n211.248 11.52 L\n200.264 11.52 L\n200.264 9.832 L\n201.905 9.832 202.959 9.575 QT\n204.014 9.317 204.014 8.301 QT\n204.014 -3.09 L\n204.014 -5.433 203.334 -6.941 QT\n202.655 -8.449 200.545 -8.449 QT\n197.748 -8.449 195.959 -6.222 QT\n194.17 -3.996 194.17 -1.168 QT\n194.17 8.301 L\n194.17 9.317 195.225 9.575 QT\n196.28 9.832 197.889 9.832 QT\n197.889 11.52 L\n186.905 11.52 L\ncp}def\r\nf581539271\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f-1710606110{213.478 15.27 M\n213.478 13.567 214.72 12.285 QT\n215.962 11.004 217.665 10.457 QT\n216.712 9.739 216.204 8.637 QT\n215.696 7.535 215.696 6.285 QT\n215.696 4.035 217.134 2.301 QT\n214.931 0.145 214.931 -2.636 QT\n214.931 -4.136 215.571 -5.449 QT\n216.212 -6.761 217.36 -7.722 QT\n218.509 -8.683 219.915 -9.191 QT\n221.321 -9.699 222.806 -9.699 QT\n225.665 -9.699 227.931 -8.027 QT\n228.915 -9.09 230.267 -9.66 QT\n231.618 -10.23 233.071 -10.23 QT\n234.103 -10.23 234.759 -9.496 QT\n235.415 -8.761 235.415 -7.73 QT\n235.415 -7.136 234.97 -6.691 QT\n234.524 -6.246 233.931 -6.246 QT\n233.321 -6.246 232.876 -6.691 QT\n232.431 -7.136 232.431 -7.73 QT\n232.431 -8.621 233.024 -8.965 QT\n230.54 -8.965 228.759 -7.261 QT\n229.618 -6.386 230.149 -5.136 QT\n230.681 -3.886 230.681 -2.636 QT\n230.681 -0.605 229.556 1.028 QT\n228.431 2.66 226.587 3.559 QT\n224.743 4.457 222.806 4.457 QT\n220.181 4.457 217.993 3.035 QT\n217.321 3.973 217.321 5.145 QT\n217.321 6.41 218.149 7.356 QT\n218.978 8.301 220.243 8.301 QT\n224.181 8.301 L\n227.04 8.301 229.337 8.817 QT\n231.634 9.332 233.196 10.887 QT\n234.759 12.442 234.759 15.27 QT\n234.759 17.379 232.978 18.778 QT\n231.196 20.176 228.72 20.793 QT\n226.243 21.41 224.134 21.41 QT\n222.009 21.41 219.524 20.793 QT\n217.04 20.176 215.259 18.778 QT\n213.478 17.379 213.478 15.27 QT\ncp\n216.165 15.27 M\n216.165 16.895 217.478 17.981 QT\n218.79 19.067 220.642 19.598 QT\n222.493 20.129 224.134 20.129 QT\n225.759 20.129 227.61 19.598 QT\n229.462 19.067 230.759 17.981 QT\n232.056 16.895 232.056 15.27 QT\n232.056 12.77 229.759 12.028 QT\n227.462 11.285 224.181 11.285 QT\n220.243 11.285 L\n219.149 11.285 218.22 11.817 QT\n217.29 12.348 216.728 13.293 QT\n216.165 14.239 216.165 15.27 QT\ncp\n222.806 3.176 M\n226.884 3.176 226.884 -2.636 QT\n226.884 -5.152 226.017 -6.777 QT\n225.149 -8.402 222.806 -8.402 QT\n220.462 -8.402 219.595 -6.777 QT\n218.728 -5.152 218.728 -2.636 QT\n218.728 -1.043 219.056 0.246 QT\n219.384 1.535 220.274 2.356 QT\n221.165 3.176 222.806 3.176 QT\ncp}def\r\nf-1710606110\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f929488190{267.024 23.426 M\n264.353 21.317 262.415 18.59 QT\n260.478 15.864 259.251 12.762 QT\n258.024 9.66 257.415 6.285 QT\n256.806 2.91 256.806 -0.48 QT\n256.806 -3.933 257.415 -7.308 QT\n258.024 -10.683 259.274 -13.8 QT\n260.524 -16.918 262.47 -19.636 QT\n264.415 -22.355 267.024 -24.386 QT\n267.024 -24.48 267.259 -24.48 QT\n267.696 -24.48 L\n267.837 -24.48 267.954 -24.355 QT\n268.071 -24.23 268.071 -24.058 QT\n268.071 -23.855 267.978 -23.761 QT\n265.634 -21.465 264.079 -18.84 QT\n262.524 -16.215 261.571 -13.246 QT\n260.618 -10.277 260.196 -7.105 QT\n259.774 -3.933 259.774 -0.48 QT\n259.774 14.785 267.931 22.707 QT\n268.071 22.848 268.071 23.098 QT\n268.071 23.223 267.946 23.371 QT\n267.821 23.52 267.696 23.52 QT\n267.259 23.52 L\n267.024 23.52 267.024 23.426 QT\ncp}def\r\nf929488190\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f919804271{275.254 11.52 M\n275.254 9.832 L\n281.254 9.832 281.254 8.301 QT\n281.254 -16.886 L\n278.769 -15.699 274.972 -15.699 QT\n274.972 -17.386 L\n280.863 -17.386 283.863 -20.449 QT\n284.535 -20.449 L\n284.707 -20.449 284.855 -20.324 QT\n285.004 -20.199 285.004 -20.027 QT\n285.004 8.301 L\n285.004 9.832 291.004 9.832 QT\n291.004 11.52 L\n275.254 11.52 L\ncp}def\r\nf919804271\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f1957607420{313.04 18.114 M\n312.634 18.114 312.376 17.809 QT\n312.118 17.504 312.118 17.145 QT\n312.118 16.754 312.376 16.473 QT\n312.634 16.192 313.04 16.192 QT\n340.571 16.192 L\n340.946 16.192 341.196 16.473 QT\n341.446 16.754 341.446 17.145 QT\n341.446 17.504 341.196 17.809 QT\n340.946 18.114 340.571 18.114 QT\n313.04 18.114 L\ncp\n312.587 -4.324 M\n312.118 -4.465 312.118 -5.152 QT\n312.118 -5.761 312.759 -6.011 QT\n340.149 -18.949 L\n340.243 -19.027 340.477 -19.027 QT\n340.884 -19.027 341.165 -18.746 QT\n341.446 -18.465 341.446 -18.058 QT\n341.446 -17.433 340.884 -17.199 QT\n315.337 -5.152 L\n341.024 6.989 L\n341.446 7.223 341.446 7.817 QT\n341.446 8.239 341.165 8.504 QT\n340.884 8.77 340.477 8.77 QT\n340.243 8.77 340.149 8.676 QT\n312.587 -4.324 L\ncp}def\r\nf1957607420\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f127127908{358.159 18.348 M\n358.159 17.176 358.972 16.317 QT\n359.784 15.457 360.956 15.457 QT\n361.738 15.457 362.261 15.942 QT\n362.784 16.426 362.784 17.192 QT\n362.784 18.114 362.214 18.848 QT\n361.644 19.582 360.769 19.817 QT\n361.613 20.129 362.456 20.129 QT\n364.503 20.129 366.003 18.239 QT\n367.503 16.348 368.113 14.004 QT\n372.628 -4.043 L\n372.956 -5.433 372.956 -6.386 QT\n372.956 -8.449 371.534 -8.449 QT\n369.425 -8.449 367.839 -6.543 QT\n366.253 -4.636 365.269 -2.121 QT\n365.175 -1.824 364.894 -1.824 QT\n364.331 -1.824 L\n363.941 -1.824 363.941 -2.261 QT\n363.941 -2.402 L\n365.019 -5.293 367.011 -7.496 QT\n369.003 -9.699 371.628 -9.699 QT\n373.613 -9.699 374.894 -8.457 QT\n376.175 -7.215 376.175 -5.293 QT\n376.175 -4.605 376.034 -3.933 QT\n371.488 14.317 L\n370.988 16.254 369.605 17.871 QT\n368.222 19.489 366.3 20.426 QT\n364.378 21.364 362.363 21.364 QT\n360.753 21.364 359.456 20.59 QT\n358.159 19.817 358.159 18.348 QT\ncp\n373.363 -17.574 M\n373.363 -18.621 374.183 -19.418 QT\n375.003 -20.215 376.034 -20.215 QT\n376.847 -20.215 377.378 -19.715 QT\n377.909 -19.215 377.909 -18.433 QT\n377.909 -17.355 377.05 -16.55 QT\n376.191 -15.746 375.159 -15.746 QT\n374.394 -15.746 373.878 -16.285 QT\n373.363 -16.824 373.363 -17.574 QT\ncp}def\r\nf127127908\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f-1058293493{399.101 0.332 M\n398.632 0.129 398.632 -0.48 QT\n398.632 -1.09 399.272 -1.402 QT\n426.663 -14.308 L\n426.851 -14.402 426.991 -14.402 QT\n427.413 -14.402 427.687 -14.113 QT\n427.96 -13.824 427.96 -13.449 QT\n427.96 -12.855 427.397 -12.527 QT\n401.851 -0.48 L\n427.538 11.66 L\n427.96 11.801 427.96 12.489 QT\n427.96 12.864 427.687 13.153 QT\n427.413 13.442 426.991 13.442 QT\n426.851 13.442 426.663 13.348 QT\n399.101 0.332 L\ncp}def\r\nf-1058293493\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f62083131{449.892 7.817 M\n451.017 9.457 452.915 10.254 QT\n454.814 11.051 456.986 11.051 QT\n459.783 11.051 460.955 8.668 QT\n462.126 6.285 462.126 3.27 QT\n462.126 1.91 461.876 0.551 QT\n461.626 -0.808 461.04 -1.98 QT\n460.455 -3.152 459.439 -3.855 QT\n458.423 -4.558 456.939 -4.558 QT\n453.751 -4.558 L\n453.33 -4.558 453.33 -5.011 QT\n453.33 -5.433 L\n453.33 -5.808 453.751 -5.808 QT\n456.408 -6.011 L\n458.095 -6.011 459.205 -7.277 QT\n460.314 -8.543 460.83 -10.363 QT\n461.345 -12.183 461.345 -13.824 QT\n461.345 -16.121 460.267 -17.597 QT\n459.189 -19.074 456.986 -19.074 QT\n455.158 -19.074 453.494 -18.379 QT\n451.83 -17.683 450.845 -16.277 QT\n450.939 -16.308 451.009 -16.316 QT\n451.08 -16.324 451.173 -16.324 QT\n452.251 -16.324 452.978 -15.574 QT\n453.705 -14.824 453.705 -13.777 QT\n453.705 -12.746 452.978 -11.996 QT\n452.251 -11.246 451.173 -11.246 QT\n450.126 -11.246 449.376 -11.996 QT\n448.626 -12.746 448.626 -13.777 QT\n448.626 -15.84 449.869 -17.363 QT\n451.111 -18.886 453.064 -19.668 QT\n455.017 -20.449 456.986 -20.449 QT\n458.439 -20.449 460.056 -20.019 QT\n461.673 -19.59 462.986 -18.777 QT\n464.298 -17.965 465.134 -16.699 QT\n465.97 -15.433 465.97 -13.824 QT\n465.97 -11.808 465.064 -10.097 QT\n464.158 -8.386 462.587 -7.144 QT\n461.017 -5.902 459.142 -5.293 QT\n461.236 -4.886 463.111 -3.715 QT\n464.986 -2.543 466.119 -0.715 QT\n467.251 1.114 467.251 3.223 QT\n467.251 5.864 465.798 8.012 QT\n464.345 10.16 461.978 11.371 QT\n459.611 12.582 456.986 12.582 QT\n454.736 12.582 452.478 11.723 QT\n450.22 10.864 448.775 9.153 QT\n447.33 7.442 447.33 5.051 QT\n447.33 3.848 448.126 3.051 QT\n448.923 2.254 450.126 2.254 QT\n450.892 2.254 451.54 2.621 QT\n452.189 2.989 452.548 3.645 QT\n452.908 4.301 452.908 5.051 QT\n452.908 6.223 452.087 7.02 QT\n451.267 7.817 450.126 7.817 QT\n449.892 7.817 L\ncp}def\r\nf62083131\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f1509408367{471.705 11.52 M\n471.705 10.223 L\n471.705 10.114 471.798 9.973 QT\n479.251 1.723 L\n480.939 -0.105 481.994 -1.347 QT\n483.048 -2.59 484.08 -4.207 QT\n485.111 -5.824 485.712 -7.504 QT\n486.314 -9.183 486.314 -11.058 QT\n486.314 -13.027 485.587 -14.816 QT\n484.861 -16.605 483.416 -17.683 QT\n481.97 -18.761 479.939 -18.761 QT\n477.845 -18.761 476.181 -17.511 QT\n474.517 -16.261 473.845 -14.261 QT\n474.033 -14.308 474.361 -14.308 QT\n475.439 -14.308 476.197 -13.582 QT\n476.955 -12.855 476.955 -11.715 QT\n476.955 -10.605 476.197 -9.847 QT\n475.439 -9.09 474.361 -9.09 QT\n473.236 -9.09 472.47 -9.871 QT\n471.705 -10.652 471.705 -11.715 QT\n471.705 -13.511 472.384 -15.097 QT\n473.064 -16.683 474.345 -17.91 QT\n475.626 -19.136 477.228 -19.793 QT\n478.83 -20.449 480.642 -20.449 QT\n483.376 -20.449 485.744 -19.293 QT\n488.111 -18.136 489.494 -16.011 QT\n490.876 -13.886 490.876 -11.058 QT\n490.876 -8.965 489.962 -7.09 QT\n489.048 -5.215 487.619 -3.683 QT\n486.189 -2.152 483.962 -0.207 QT\n481.736 1.739 481.033 2.395 QT\n475.595 7.629 L\n480.22 7.629 L\n483.611 7.629 485.9 7.567 QT\n488.189 7.504 488.33 7.395 QT\n488.892 6.785 489.47 2.957 QT\n490.876 2.957 L\n489.517 11.52 L\n471.705 11.52 L\ncp}def\r\nf1509408367\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 177.3761 241.5948] CT\r\nN\r\n/f511719215{496.439 23.52 M\n496.017 23.52 496.017 23.098 QT\n496.017 22.895 496.111 22.801 QT\n504.314 14.785 504.314 -0.48 QT\n504.314 -15.746 496.205 -23.668 QT\n496.017 -23.777 496.017 -24.058 QT\n496.017 -24.23 496.142 -24.355 QT\n496.267 -24.48 496.439 -24.48 QT\n496.877 -24.48 L\n497.017 -24.48 497.111 -24.386 QT\n500.564 -21.668 502.861 -17.777 QT\n505.158 -13.886 506.22 -9.48 QT\n507.283 -5.074 507.283 -0.48 QT\n507.283 2.91 506.712 6.207 QT\n506.142 9.504 504.884 12.707 QT\n503.627 15.91 501.705 18.614 QT\n499.783 21.317 497.111 23.426 QT\n497.017 23.52 496.877 23.52 QT\n496.439 23.52 L\ncp}def\r\nf511719215\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 0 0 RC\r\n1 LJ\r\n2.667 LW\r\nN\r\n387 644.253 M\n467.003 644.253 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n0.149 GC\r\n10.0 ML\r\n1.333 LW\r\nN\r\n379 677 M\n379 553 L\n993 553 L\n993 677 L\ncp\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n828.8 378 M\n733.03 413.914 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n745.28 420 M\n716.8 420 L\n733.03 413.914 L\n745.28 420 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n716.8 420 M\n738.258 401.273 L\n733.03 413.914 L\n716.8 420 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\nN\r\n716.8 420 M\n745.28 420 L\n733.03 413.914 L\n738.258 401.273 L\ncp\r\nf\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n470.4 142.8 M\n374.63 106.886 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n379.858 119.527 M\n358.4 100.8 L\n374.63 106.886 L\n379.858 119.527 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\n1 LJ\r\n1.333 LW\r\nN\r\n358.4 100.8 M\n386.88 100.8 L\n374.63 106.886 L\n358.4 100.8 L\r\nS\r\nGR\r\nGS\r\n[0.375 0 0 0.375 0 0] CT\r\nN\r\n358.4 100.8 M\n379.858 119.527 L\n374.63 106.886 L\n386.88 100.8 L\ncp\r\nf\r\nGR\r\n%%Trailer\r\n%%Pages: 1\r\n%%EOF\r\n"
  },
  {
    "path": "matlab/cdc2021/.gitignore",
    "content": "*.eps\n"
  },
  {
    "path": "matlab/cdc2021/CBFDT.m",
    "content": "classdef CBFDT < handle\n    properties\n        systemParam\n        optType\n        optParam\n        xcurr\n        timecurr\n        solvertime\n        xdim\n        udim\n        tlog = []\n        xlog = []\n        ulog = []\n        omegalog = []\n    end\n    \n    methods\n        function self = CBFDT(system_param, x0, t0)\n            self.systemParam = system_param;\n            self.xcurr = x0;\n            self.timecurr = t0;\n            self.xdim = size(self.systemParam.A, 1);\n            self.udim = size(self.systemParam.B, 2);\n        end\n        \n        function setOpt(self, opt_type, opt_param)\n            self.optType = opt_type;\n            self.optParam = opt_param;\n        end\n        \n        function sim(self, total_time)\n            xk = self.xcurr;\n            while self.timecurr <= total_time\n                [feas, xopt, uopt, Jopt] = self.solve();\n                if feas ~= 1\n                    return;\n                end\n                uk = uopt(:,1);\n                xk = self.systemParam.A * xk + self.systemParam.B * uk;\n                self.xcurr = xk;\n                self.timecurr = self.timecurr + self.systemParam.timestep;\n                self.tlog = [self.tlog, self.timecurr];\n                self.xlog = [self.xlog, xk];\n                self.ulog = [self.ulog, uk];\n            end\n        end\n        \n        function [feas, xopt, uopt, Jopt] = solve(self)\n            if strcmp(self.optType,'dclfdcbf')\n                [feas, xopt, uopt, Jopt] = solveDCLFDCBF(self);\n            elseif strcmp(self.optType,'nmpcdclfdcbf')\n                [feas, xopt, uopt, Jopt] = solveNMPCDCLFDCBF(self);\n            elseif strcmp(self.optType,'mpcdcbf')\n                [feas, xopt, uopt, Jopt] = solveMPCDCBF(self);\n            elseif strcmp(self.optType,'mpcgcbf')\n                [feas, xopt, uopt, Jopt] = solveMPCGCBF(self);\n            elseif strcmp(self.optType,'nmpcdcbf')\n                [feas, xopt, uopt, Jopt] = solveNMPCDCBF(self);\n            else\n                disp('optimal control policy undefined');\n            end\n        end\n        \n        function [feas, xopt, uopt, Jopt] = solveDCLFDCBF(self)\n            x = sdpvar(self.xdim, 2);\n            u = sdpvar(self.udim, 1);\n            s = sdpvar(1,1);\n            cost = 0;\n            constraints = [];\n            % initial condition\n            constraints = [constraints; x(:,1) == self.xcurr];\n            % dynamics\n            constraints = [constraints; x(:,2) == self.systemParam.A * x(:,1) + self.systemParam.B * u(:,1)];\n            % DCLF constraint\n            v = x(:,1)' * self.optParam.P * x(:,1);\n            vnext = x(:,2)' * self.optParam.P * x(:,2);\n            constraints = [constraints; vnext - v + self.optParam.alpha * v <= s];\n            % DCBF constraint\n            r = 1;\n            b = x(:,1)' * x(:,1) - r^2;\n            bnext = x(:,2)' * x(:,2) - r^2;\n            constraints = [constraints; bnext - b + self.optParam.gamma * b >= 0];\n            % input constraint\n            constraints = [constraints; self.systemParam.ul <= u <= self.systemParam.uu];\n            % cost\n            cost = cost + u' * self.optParam.uWeight * u + s' * self.optParam.sWeight * s;\n            opt_settings = sdpsettings('solver','ipopt','verbose',0);\n            diagnostics = optimize(constraints, cost, opt_settings);\n            if diagnostics.problem == 0\n                feas = true;\n                xopt = value(x);\n                uopt = value(u);\n                Jopt = value(cost);\n            else\n                feas = false;\n                xopt= [];\n                uopt = [];\n                Jopt = value(cost);\n            end\n            self.solvertime = diagnostics.solvertime;\n            fprintf('solver time: %f\\n', diagnostics.solvertime);\n        end\n        \n        function [feas, xopt, uopt, Jopt] = solveNMPCDCLFDCBF(self)\n            x = sdpvar(self.xdim, self.optParam.horizon + 1);\n            u = sdpvar(self.udim, self.optParam.horizon);\n            s = sdpvar(1,self.optParam.horizonCLF);\n            omega = sdpvar(1,self.optParam.horizonCBF);\n            cost = 0;\n            constraints = [];\n            % initial condition\n            constraints = [constraints; x(:,1) == self.xcurr];\n            % MPC cost and constraints\n            for i = 1:self.optParam.horizon\n                constraints = [constraints;\n                    self.systemParam.ul <= u(:,i) <= self.systemParam.uu;\n                    x(:,i+1) == self.systemParam.A * x(:,i) + self.systemParam.B * u(:,i)];\n                cost = cost + x(:,i)'*self.optParam.xWeight*x(:,i);\n                cost = cost + u(:,i)'*self.optParam.uWeight*u(:,i);\n            end\n            cost = cost + x(:,self.optParam.horizon)' * self.optParam.P * x(:,self.optParam.horizon);\n            % CLF constraints\n            for i = 1:self.optParam.horizonCLF\n                v = x(:,1)' * self.optParam.P * x(:,1);\n                vnext = x(:,2)' * self.optParam.P * x(:,2);\n                constraints = [constraints; vnext - v + self.optParam.alpha * v <= s(i)];\n                cost = cost + s(i)' * self.optParam.sWeight * s(i);\n            end\n            % CBF constraints\n            for i = 1:self.optParam.horizonCBF\n                r = 1;\n                b = x(:,1)' * x(:,1) - r^2;\n                bnext = x(:,2)' * x(:,2) - r^2;\n                constraints = [constraints; bnext >= omega(i) * (1 - self.optParam.gamma) * b];\n                constraints = [constraints; omega(i) >= 0];\n                assign(omega(i), 1);\n                cost = cost + self.optParam.omegaWeight * (omega(i) - 1)^2;\n            end\n            opt_settings = sdpsettings('solver','ipopt','verbose',0);\n            diagnostics = optimize(constraints, cost, opt_settings);\n            if diagnostics.problem == 0\n                feas = true;\n                xopt = value(x);\n                uopt = value(u);\n                Jopt = value(cost);\n            else\n                feas = false;\n                xopt= [];\n                uopt = [];\n                Jopt = value(cost);\n            end\n            self.solvertime = diagnostics.solvertime;\n            fprintf('solver time: %f\\n', diagnostics.solvertime);\n        end\n        \n        function [feas, xopt, uopt, Jopt] = solveMPCDCBF(self)\n            x = sdpvar(self.xdim, self.optParam.horizon + 1);\n            u = sdpvar(self.udim, self.optParam.horizon);\n            cost = 0;\n            constraints = [];\n            % initial condition\n            constraints = [constraints; x(:,1) == self.xcurr];\n            % MPC cost and constraints\n            for i = 1:self.optParam.horizon\n                constraints = [constraints;\n                    self.systemParam.ul <= u(:,i) <= self.systemParam.uu;\n                    x(:,i+1) == self.systemParam.A * x(:,i) + self.systemParam.B * u(:,i)];\n                cost = cost + x(:,i)'*self.optParam.xWeight*x(:,i);\n                cost = cost + u(:,i)'*self.optParam.uWeight*u(:,i);\n            end\n            cost = cost + x(:,self.optParam.horizon)' * self.optParam.P * x(:,self.optParam.horizon);\n            % CBF constraints\n            for i = 1:self.optParam.horizon\n                r = 0;\n                b = r - x(1,i);\n                bnext = r - x(1,i+1);\n                constraints = [constraints; bnext - b + self.optParam.gamma * b >= 0];\n            end\n            opt_settings = sdpsettings('solver','ipopt','verbose',0);\n            diagnostics = optimize(constraints, cost, opt_settings);\n            if diagnostics.problem == 0\n                feas = true;\n                xopt = value(x);\n                uopt = value(u);\n                Jopt = value(cost);\n            else\n                feas = false;\n                xopt= [];\n                uopt = [];\n                Jopt = value(cost);\n            end\n            self.solvertime = diagnostics.solvertime;\n            fprintf('solver time: %f\\n', diagnostics.solvertime);\n        end\n        \n        function [feas, xopt, uopt, Jopt] = solveMPCGCBF(self)\n            x = sdpvar(self.xdim, self.optParam.horizon + 1);\n            u = sdpvar(self.udim, self.optParam.horizon);\n            cost = 0;\n            constraints = [];\n            % initial condition\n            constraints = [constraints; x(:,1) == self.xcurr];\n            % MPC cost and constraints\n            for i = 1:self.optParam.horizon\n                constraints = [constraints;\n                    self.systemParam.ul <= u(:,i) <= self.systemParam.uu;\n                    x(:,i+1) == self.systemParam.A * x(:,i) + self.systemParam.B * u(:,i)];\n                cost = cost + x(:,i)'*self.optParam.xWeight*x(:,i);\n                cost = cost + u(:,i)'*self.optParam.uWeight*u(:,i);\n            end\n            cost = cost + x(:,self.optParam.horizon)' * self.optParam.P * x(:,self.optParam.horizon);\n            % GCBF constraints\n            num_HO = 3;\n            r = 0;\n            b = r - x(1,1);\n            bnext = r - x(1,1+num_HO);\n            constraints = [constraints; bnext >= (1 - self.optParam.gamma)^num_HO * b];            \n            opt_settings = sdpsettings('solver','ipopt','verbose',0);\n            diagnostics = optimize(constraints, cost, opt_settings);\n            if diagnostics.problem == 0\n                feas = true;\n                xopt = value(x);\n                uopt = value(u);\n                Jopt = value(cost);\n            else\n                feas = false;\n                xopt= [];\n                uopt = [];\n                Jopt = value(cost);\n            end\n            self.solvertime = diagnostics.solvertime;\n            fprintf('solver time: %f\\n', diagnostics.solvertime);\n        end\n        \n        function [feas, xopt, uopt, Jopt] = solveNMPCDCBF(self)\n            x = sdpvar(self.xdim, self.optParam.horizon + 1);\n            u = sdpvar(self.udim, self.optParam.horizon);\n            omega = sdpvar(1,self.optParam.horizonCBF);\n            cost = 0;\n            constraints = [];\n            % initial condition\n            constraints = [constraints; x(:,1) == self.xcurr];\n            % MPC cost and constraints\n            for i = 1:self.optParam.horizon\n                constraints = [constraints;\n                    self.systemParam.ul <= u(:,i) <= self.systemParam.uu;\n                    x(:,i+1) == self.systemParam.A * x(:,i) + self.systemParam.B * u(:,i)];\n                cost = cost + x(:,i)'*self.optParam.xWeight*x(:,i);\n                cost = cost + u(:,i)'*self.optParam.uWeight*u(:,i);\n            end\n            cost = cost + x(:,self.optParam.horizon)' * self.optParam.P * x(:,self.optParam.horizon);\n            % CBF constraints\n            for i = 1:self.optParam.horizonCBF\n                r = 0;\n                b = r - x(1,i);\n                bnext = r - x(1,i+1);\n                constraints = [constraints; bnext >= omega(i) * (1 - self.optParam.gamma) * b];\n                constraints = [constraints; omega(i) >= 0];\n                assign(omega(i), 1);\n                cost = cost + self.optParam.omegaWeight * (omega(i) - 1)^2;\n            end\n            opt_settings = sdpsettings('solver','ipopt','verbose',0);\n            diagnostics = optimize(constraints, cost, opt_settings);\n            if diagnostics.problem == 0\n                feas = true;\n                xopt = value(x);\n                uopt = value(u);\n                Jopt = value(cost);\n            else\n                feas = false;\n                xopt= [];\n                uopt = [];\n                Jopt = value(cost);\n            end\n            self.solvertime = diagnostics.solvertime;\n            fprintf('solver time: %f\\n', diagnostics.solvertime);\n        end\n    end\nend\n\n"
  },
  {
    "path": "matlab/cdc2021/ParamDCLFDCBF.m",
    "content": "classdef ParamDCLFDCBF < handle\n    properties\n        alpha\n        gamma\n        P % weight for Lyapunov function\n        uWeight\n        sWeight\n    end\n    methods\n        function self = ParamDCLFDCBF(alpha, gamma, P, u_weight, s_weight)\n            self.alpha = alpha;\n            self.gamma = gamma;\n            self.P = P;\n            self.uWeight = u_weight;\n            self.sWeight = s_weight;\n        end\n    end\nend"
  },
  {
    "path": "matlab/cdc2021/ParamMPCDCBF.m",
    "content": "classdef ParamMPCDCBF < handle\n    properties\n        horizon\n        gamma\n        P % weight for terminal cost (CLF)\n        xWeight\n        uWeight\n    end\n    methods\n        function self = ParamMPCDCBF(horizon, gamma, P, x_weight, u_weight)\n            self.horizon = horizon;\n            self.gamma = gamma;\n            self.P = P;\n            self.xWeight = x_weight;\n            self.uWeight = u_weight;\n        end\n    end\nend"
  },
  {
    "path": "matlab/cdc2021/ParamMPCGCBF.m",
    "content": "classdef ParamMPCGCBF < handle\n    properties\n        horizon\n        gamma\n        P % weight for terminal cost (CLF)\n        xWeight\n        uWeight\n    end\n    methods\n        function self = ParamMPCGCBF(horizon, gamma, P, x_weight, u_weight)\n            self.horizon = horizon;\n            self.gamma = gamma;\n            self.P = P;\n            self.xWeight = x_weight;\n            self.uWeight = u_weight;\n        end\n    end\nend"
  },
  {
    "path": "matlab/cdc2021/ParamNMPCDCBF.m",
    "content": "classdef ParamNMPCDCBF < handle\n    properties\n        horizon\n        horizonCBF\n        gamma\n        P % weight for terminal cost (CLF)\n        xWeight\n        uWeight\n        omegaWeight\n    end\n    methods\n        function self = ParamNMPCDCBF(horizon, horizon_cbf, gamma, P, x_weight, u_weight, omega_weight)\n            self.horizon = horizon;\n            self.horizonCBF = horizon_cbf;\n            self.gamma = gamma;\n            self.P = P;\n            self.xWeight = x_weight;\n            self.uWeight = u_weight;\n            self.omegaWeight = omega_weight;\n        end\n    end\nend"
  },
  {
    "path": "matlab/cdc2021/ParamNMPCDCLFDCBF.m",
    "content": "classdef ParamNMPCDCLFDCBF < handle\n    properties\n        horizon\n        horizonCLF\n        horizonCBF\n        alpha\n        gamma\n        P % weight for Lyapunov function\n        xWeight\n        uWeight\n        sWeight\n        omegaWeight\n    end\n    methods\n        function self = ParamNMPCDCLFDCBF(horizon, horizon_clf, horizon_cbf, alpha, gamma, P, x_weight, u_weight, s_weight, omega_weight)\n            self.horizon = horizon;\n            self.horizonCLF = horizon_clf;\n            self.horizonCBF = horizon_cbf;\n            self.alpha = alpha;\n            self.gamma = gamma;\n            self.P = P;\n            self.xWeight = x_weight;\n            self.uWeight = u_weight;\n            self.sWeight = s_weight;\n            self.omegaWeight = omega_weight;\n        end\n    end\nend"
  },
  {
    "path": "matlab/cdc2021/README.md",
    "content": "## NMPC-DCLF-DCBF-CDC2021\nIn this paper, we discuss the feasibility, safety and complexity about existing optimal control laws using control barrier functions. This is the reference implementation of our paper.\n\nIf you find this code useful in your work, please consider citing:\n```\n@inproceedings{zeng2021nmpc-dclf-dcbf,\n  title={Enhancing Feasibility and Safety of Nonlinear Model Predictive Control with Discrete-Time Control Barrier Functions},\n  author={Zeng, Jun and Li, Zhongyu and Sreenath, Koushil},\n  booktitle={2021 IEEE Conference on Decision and Control (CDC)},\n  year={2021}\n}\n```\n\n### Instructions\nSeveral test files are created to reproduce the results in the paper:\n* `testFeasibilityMPCDCBF.m` compares the feasibility performance between MPC-DCBF and NMPC-DCBF with different hyperparameters.\n* `testFeasibilityMPCGCBF.m` compares the feasibility performance between MPC-GCBF and NMPC-DCBF with different hyperparameters.\n* `testFeasibilityDCLFDCBF.m` compares the feasibility performance between DCLF-DCBF and NMPC-DCLF-DCBF.\n* `testSafety.m` compares the safety performance between MPC-CBF, MPC-GCBF and NMPC-DCBF.\n\nNotice that running either `testFeasibilityMPCDCBF.m` or `testFeasibilityMPCGCBF.m` or `testFeasibilityDCLFDCBF.m` will take more than 4 hours due to the weak memory management using matlab together with excessive Yalmip calling. To check results or have a quick visualization, feel free to load data directly from the `/data`."
  },
  {
    "path": "matlab/cdc2021/test.m",
    "content": "close all\nclear\n\n% system setup and initial condition\ntimestep = 0.1;\nsystem_param.A = [[1 ,timestep, 0]; [0, 1, timestep]; [0, 0, 1]];\nsystem_param.B = [0; 0; timestep];\nsystem_param.ul = -1;\nsystem_param.uu = 1;\nsystem_param.timestep = timestep;\nx0 = [-2;0;1];\nt0 = 0.0;\ntotal_time = 1.0;\n\n% problem setup\nsimulator = CBFDT(system_param, x0, t0);\n\nparam_mpcdcbf = ParamMPCDCBF(6, 0.1, 10 * eye(3), 10.0 * eye(3), 1.0);\nsimulator.setOpt('mpcdcbf', param_mpcdcbf);\nsimulator.sim(total_time);\n\nparam_mpcgcbf = ParamMPCGCBF(6, 0.1, 10 * eye(3), 10.0 * eye(3), 1.0);\nsimulator.setOpt('mpcgcbf', param_mpcgcbf);\nsimulator.sim(total_time);\n\nparam_nmpcdcbf = ParamNMPCDCBF(6, 6, 0.1, 10 * eye(3), 10.0 * eye(3), 1.0, 10.0);\nsimulator.setOpt('nmpcdcbf', param_nmpcdcbf);\nsimulator.sim(total_time);\n\nparam_dclfdcbf = ParamDCLFDCBF(0.1, 0.1, 10 * eye(3), 1.0, 10.0);\nsimulator.setOpt('dclfdcbf', param_dclfdcbf);\nsimulator.sim(total_time);\n\nparam_nmpcdclfdcbf = ParamNMPCDCLFDCBF(6, 6, 6, 0.1, 0.1, 10.0 * eye(3), 10.0 * eye(3), 1.0, 10.0, 10.0);\nsimulator.setOpt('nmpcdclfdcbf', param_nmpcdclfdcbf);\nsimulator.sim(total_time);"
  },
  {
    "path": "matlab/cdc2021/testComplexity.m",
    "content": "clc\nclose all\nclear\n% This file tests computational time for various approaches\n\n%% System setup\n\ntimestep = 0.1;\nsystem_param.A = [[1 ,timestep, 0]; [0, 1, timestep]; [0, 0, 1]];\nsystem_param.B = [0; 0; timestep];\nsystem_param.ul = -1;\nsystem_param.uu = 1;\nsystem_param.timestep = timestep;\nx0 = [0;0;0]; % this value will be overrided\nt0 = 0.0;\n\n%% Sampling states\n\nx1list = linspace(-2,0,11);\nx2list = linspace(0,2,11);\nx3list = linspace(0,2,11);\n\n%% MPC-CBF (N=10)\nsolvertime_list1 = [];\nsimulator_dt = CBFDT(system_param, x0, t0);\nparam_mpcdcbf = ParamMPCDCBF(10, 0.2, 10.0*eye(3), 10.0*eye(3), 1.0);\nsimulator_dt.setOpt('mpcdcbf', param_mpcdcbf);\nsolvertime_list1 = [];\nfor k1 = 1:length(x1list)\n    for k2 = 1:length(x2list)\n        for k3 = 1:length(x3list)\n            xfeas = [x1list(k1); x2list(k2); x3list(k3)];\n            % solve the problem with MPC-DCBF\n            simulator_dt.xcurr = xfeas;\n            [feas, ~, ~, ~] = simulator_dt.solve;\n            if feas == 1\n                solvertime_list1 = [solvertime_list1, simulator_dt.solvertime];\n            end\n        end\n    end\nend\n\n%% MPC-GCBF (N=10)\nsolvertime_list2 = [];\nsimulator_dt = CBFDT(system_param, x0, t0);\nparam_mpcgcbf = ParamMPCGCBF(10, 0.2, 10.0*eye(3), 10.0*eye(3), 1.0);\nsimulator_dt.setOpt('mpcgcbf', param_mpcgcbf);\nsolvertime_list2 = [];\nfor k1 = 1:length(x1list)\n    for k2 = 1:length(x2list)\n        for k3 = 1:length(x3list)\n            xfeas = [x1list(k1); x2list(k2); x3list(k3)];\n            % solve the problem with MPC-GCBF\n            simulator_dt.xcurr = xfeas;\n            [feas, ~, ~, ~] = simulator_dt.solve;\n            if feas == 1\n                solvertime_list2 = [solvertime_list2, simulator_dt.solvertime];\n            end\n        end\n    end\nend\n\n%% NMPC-DCBF (N=10, MCBF=10)\nsolvertime_list3 = [];\nsimulator_dt = CBFDT(system_param, x0, t0);\nparam_nmpcdcbf = ParamNMPCDCBF(10, 10, 0.2, 10.0*eye(3), 10.0*eye(3), 1.0, 10.0);\nsimulator_dt.setOpt('nmpcdcbf', param_nmpcdcbf);\nsolvertime_list3 = [];\nfor k1 = 1:length(x1list)\n    for k2 = 1:length(x2list)\n        for k3 = 1:length(x3list)\n            xfeas = [x1list(k1); x2list(k2); x3list(k3)];\n            % solve the problem with NMPC-DCBF\n            simulator_dt.xcurr = xfeas;\n            [feas, ~, ~, ~] = simulator_dt.solve;\n            if feas == 1\n                solvertime_list3 = [solvertime_list3, simulator_dt.solvertime];\n            end\n        end\n    end\nend\n\n%% NMPC-DCBF (N=10, MCBF=8)\nsolvertime_list4 = [];\nsimulator_dt = CBFDT(system_param, x0, t0);\nparam_nmpcdcbf = ParamNMPCDCBF(10, 8, 0.2, 10.0*eye(3), 10.0*eye(3), 1.0, 10.0);\nsimulator_dt.setOpt('nmpcdcbf', param_nmpcdcbf);\nsolvertime_list4 = [];\nfor k1 = 1:length(x1list)\n    for k2 = 1:length(x2list)\n        for k3 = 1:length(x3list)\n            xfeas = [x1list(k1); x2list(k2); x3list(k3)];\n            % solve the problem with NMPC-DCBF\n            simulator_dt.xcurr = xfeas;\n            [feas, ~, ~, ~] = simulator_dt.solve;\n            if feas == 1\n                solvertime_list4 = [solvertime_list4, simulator_dt.solvertime];\n            end\n        end\n    end\nend\n\n%% NMPC-DCBF (N=10, MCBF=5)\nsolvertime_list5 = [];\nsimulator_dt = CBFDT(system_param, x0, t0);\nparam_nmpcdcbf = ParamNMPCDCBF(10, 5, 0.2, 10.0*eye(3), 10.0*eye(3), 1.0, 10.0);\nsimulator_dt.setOpt('nmpcdcbf', param_nmpcdcbf);\nsolvertime_list5 = [];\nfor k1 = 1:length(x1list)\n    for k2 = 1:length(x2list)\n        for k3 = 1:length(x3list)\n            xfeas = [x1list(k1); x2list(k2); x3list(k3)];\n            % solve the problem with NMPC-DCBF\n            simulator_dt.xcurr = xfeas;\n            [feas, ~, ~, ~] = simulator_dt.solve;\n            if feas == 1\n                solvertime_list5 = [solvertime_list5, simulator_dt.solvertime];\n            end\n        end\n    end\nend\n\n%% NMPC-DCBF (N=10, MCBF=3)\nsolvertime_list6 = [];\nsimulator_dt = CBFDT(system_param, x0, t0);\nparam_nmpcdcbf = ParamNMPCDCBF(10, 3, 0.2, 10.0*eye(3), 10.0*eye(3), 1.0, 10.0);\nsimulator_dt.setOpt('nmpcdcbf', param_nmpcdcbf);\nsolvertime_list6 = [];\nfor k1 = 1:length(x1list)\n    for k2 = 1:length(x2list)\n        for k3 = 1:length(x3list)\n            xfeas = [x1list(k1); x2list(k2); x3list(k3)];\n            % solve the problem with NMPC-DCBF\n            simulator_dt.xcurr = xfeas;\n            [feas, ~, ~, ~] = simulator_dt.solve;\n            if feas == 1\n                solvertime_list6 = [solvertime_list6, simulator_dt.solvertime];\n            end\n        end\n    end\nend"
  },
  {
    "path": "matlab/cdc2021/testFeasibilityDCLFDCBF.m",
    "content": "clc\nclose all\nclear\n% This file tests feasibility between DCLF-DCBF and NMPC-DCLF-DCBF.\n\n%% System setup\n\ntimestep = 0.1;\nsystem_param.A = [[1 ,timestep, 0]; [0, 1, timestep]; [0, 0, 1]];\nsystem_param.B = [0; 0; timestep];\nsystem_param.ul = -1;\nsystem_param.uu = 1;\nsystem_param.timestep = timestep;\nx0 = [0;0;0]; % this value will be overrided\nt0 = 0.0;\n\ngammalist = [0.05, 0.1, 0.15, 0.2];\nfor gammaindex = 1:length(gammalist)\n    %% Problem setup with different hyperparameters\n    \n    % MPC-GCBF simulator\n    simulator_dclfdcbf = CBFDT(system_param, x0, t0);\n    param_dclfdcbf = ParamDCLFDCBF(0.1, gammalist(gammaindex), 10 * eye(3), 1.0, 10.0);\n    simulator_dclfdcbf.setOpt('dclfdcbf', param_dclfdcbf);\n    % NMPC-DCBF simulator\n    simulator_nmpcdclfdcbf = CBFDT(system_param, x0, t0);\n    param_nmpcdclfdcbf = ParamNMPCDCLFDCBF(8, 8, 8, 0.1, gammalist(gammaindex), 10.0 * eye(3), 10.0 * eye(3), 1.0, 10.0, 10.0);\n    simulator_nmpcdclfdcbf.setOpt('nmpcdclfdcbf', param_nmpcdclfdcbf);\n    % iterate over states\n    x1list = linspace(-2,0,11);\n    x2list = linspace(0,2,11);\n    x3list = linspace(0,2,11);\n    % data collection\n    feas_points_dclfdcbf = [];\n    feas_points_nmpcdclfdcbf = [];\n    infeas_points_all = [];\n    \n    %% Test feasibility with sampling states among controllers\n    \n    for k1 = 1:length(x1list)\n        for k2 = 1:length(x2list)\n            for k3 = 1:length(x3list)\n                xfeas = [x1list(k1); x2list(k2); x3list(k3)];\n                % exclude the point if it's always unsafe\n                if xfeas' * xfeas <= 1\n                    continue;\n                end\n                % solve the problem with MPC-GCBF\n                simulator_dclfdcbf.xcurr = xfeas;\n                [feas_dclfdcbf, ~, ~, ~] = simulator_dclfdcbf.solve;\n                % solve the problem with NMPC-DCLF-DCBF\n                simulator_nmpcdclfdcbf.xcurr = xfeas;\n                [feas_nmpcdclfdcbf, ~, ~, ~] = simulator_nmpcdclfdcbf.solve;\n                if feas_dclfdcbf == 1\n                    feas_points_dclfdcbf = [feas_points_dclfdcbf, xfeas];\n                end\n                if feas_nmpcdclfdcbf == 1\n                    feas_points_nmpcdclfdcbf = [feas_points_nmpcdclfdcbf, xfeas];\n                end\n                if feas_dclfdcbf == 0 && feas_nmpcdclfdcbf == 0\n                    infeas_points_all = [infeas_points_all, xfeas];\n                end\n            end\n        end\n    end\n    \n    %% Plotting\n    close all\n    outer_color = [0.3010, 0.7450, 0.9330];\n    inner_color = [1, 0, 0];\n    figure('Renderer', 'painters', 'Position', [0 0 400 400]);\n    set(gca,'LooseInset',get(gca,'TightInset'));\n    hold on;\n    scatter3(feas_points_dclfdcbf(1,:),feas_points_dclfdcbf(2,:),feas_points_dclfdcbf(3,:),...\n        5, 'o', 'LineWidth', 1.0, 'MarkerEdgeColor', inner_color, 'MarkerFaceColor', inner_color);\n    scatter3(feas_points_nmpcdclfdcbf(1,:),feas_points_nmpcdclfdcbf(2,:),feas_points_nmpcdclfdcbf(3,:),...\n        20, 'o', 'LineWidth', 1.2, 'MarkerEdgeColor', outer_color);\n    r = 1.0;\n    [x,y,z] = sphere(50);\n    x = x*r; y = y*r; z = z*r;\n    lightGrey = 0.8*[1 1 1]; % It looks better if the lines are lighter\n    ball_surface = surface(x,y,z,  'FaceColor', 'none', 'EdgeColor', [0.75, 0.75, 0], 'facealpha', 0.5);\n    axis equal\n    if gammaindex == 1\n        h=get(gca,'Children');\n        h_legend = legend(h([end, end-1]),...\n            {'DCLF-DCBF', 'NMPC-DCLF-DCBF'}, 'Location', 'NorthEast');\n        set(h_legend, 'Interpreter','latex');\n    end\n    set(gca,'LineWidth', 1.0, 'FontSize', 15);\n    xlabel('$x (m)$','interpreter','latex','FontSize',20);\n    ylabel('$v (m/s)$','interpreter','latex','FontSize',20);\n    zlabel('$a (m/s^2)$','interpreter','latex','FontSize',20);\n    xlim([-2, 0]);\n    ylim([0, 2]);\n    zlim([0, 2]);\n    view(160, 4);\n    grid on;\n    figurename_eps = \"feasibility-dclfdcbf\" + gammaindex + \".eps\";\n    figurename_png = \"feasibility-dclfdcbf\" + gammaindex + \".png\";\n    dataname = \"feasibility-dclfdcbf\" + gammaindex + \".mat\";\n    % save data and generate figures\n    print(gcf,strcat('figures/',figurename_eps), '-depsc');\n    print(gcf,strcat('figures/',figurename_png), '-dpng', '-r800');\n    save(strcat('data/',dataname));\nend"
  },
  {
    "path": "matlab/cdc2021/testFeasibilityMPCDCBF.m",
    "content": "clc\nclose all\nclear\n% This file tests feasibility between MPC-DCBF and NMPC-DCBF.\n\n%% System setup\n\ntimestep = 0.1;\nsystem_param.A = [[1 ,timestep, 0]; [0, 1, timestep]; [0, 0, 1]];\nsystem_param.B = [0; 0; timestep];\nsystem_param.ul = -1;\nsystem_param.uu = 1;\nsystem_param.timestep = timestep;\nx0 = [0;0;0]; % this value will be overrided\nt0 = 0.0;\n\ngammalist = [0.05, 0.1, 0.15, 0.2];\nfor gammaindex = 1:length(gammalist)\n    %% Problem setup with different hyperparameters\n    \n    % MPC-DCBF simulator\n    simulator_mpcdcbf = CBFDT(system_param, x0, t0);\n    param_mpcdcbf = ParamMPCDCBF(8, gammalist(gammaindex), 10.0*eye(3), 10.0*eye(3), 1.0);\n    simulator_mpcdcbf.setOpt('mpcdcbf', param_mpcdcbf);\n    % NMPC-DCBF simulator\n    simulator_nmpcdcbf = CBFDT(system_param, x0, t0);\n    param_nmpcdcbf = ParamNMPCDCBF(8, 8, gammalist(gammaindex), 10.0*eye(3), 10.0*eye(3), 1.0, 10.0);\n    simulator_nmpcdcbf.setOpt('nmpcdcbf', param_nmpcdcbf);\n    % iterate over states\n    x1list = linspace(-2,0,11);\n    x2list = linspace(0,2,11);\n    x3list = linspace(0,2,11);\n    % data collection\n    feas_points_mpcdcbf = [];\n    feas_points_nmpcdcbf = [];\n    infeas_points_all = [];\n    \n    %% Test feasibility with sampling states among controllers\n    \n    for k1 = 1:length(x1list)\n        for k2 = 1:length(x2list)\n            for k3 = 1:length(x3list)\n                xfeas = [x1list(k1); x2list(k2); x3list(k3)];\n                % solve the problem with MPC-DCBF\n                simulator_mpcdcbf.xcurr = xfeas;\n                [feas_mpcdcbf, ~, ~, ~] = simulator_mpcdcbf.solve;\n                % solve the problem with NMPC-DCBF\n                simulator_nmpcdcbf.xcurr = xfeas;\n                [feas_nmpcdcbf, ~, ~, ~] = simulator_nmpcdcbf.solve;\n                if feas_mpcdcbf == 1\n                    feas_points_mpcdcbf = [feas_points_mpcdcbf, xfeas];\n                end\n                if feas_nmpcdcbf == 1\n                    feas_points_nmpcdcbf = [feas_points_nmpcdcbf, xfeas];\n                end\n                if feas_mpcdcbf == 0 && feas_nmpcdcbf == 0\n                    infeas_points_all = [infeas_points_all, xfeas];\n                end\n            end\n        end\n    end\n    \n    %% Plotting\n    close all\n    outer_color = [0.3010, 0.7450, 0.9330];\n    inner_color = [1, 0, 0];\n    figure('Renderer', 'painters', 'Position', [0 0 400 400]);\n    set(gca,'LooseInset',get(gca,'TightInset'));\n    hold on;\n    scatter3(feas_points_mpcdcbf(1,:),feas_points_mpcdcbf(2,:),feas_points_mpcdcbf(3,:), 5, 'o','LineWidth',1.0, 'MarkerEdgeColor',inner_color,'MarkerFaceColor',inner_color);\n    scatter3(feas_points_nmpcdcbf(1,:),feas_points_nmpcdcbf(2,:),feas_points_nmpcdcbf(3,:), 20, 'o','LineWidth',1.2, 'MarkerEdgeColor',outer_color);\n    axis equal\n    if gammaindex == 1\n        h=get(gca,'Children');\n        h_legend = legend(h([end, end-1]),...\n            {'MPC-DCBF', 'NMPC-DCBF'}, 'Location', 'NorthEast');\n        set(h_legend, 'Interpreter','latex');\n    end\n    set(gca,'LineWidth', 1.0, 'FontSize', 15);\n    xlabel('$x (m)$','interpreter','latex','FontSize',20);\n    ylabel('$v (m/s)$','interpreter','latex','FontSize',20);\n    zlabel('$a (m/s^2)$','interpreter','latex','FontSize',20);\n    xlim([-2, 0]);\n    ylim([0, 2]);\n    zlim([0, 2]);\n    view(70, 4);\n    grid on;\n    figurename_eps = \"feasibility-mpcdcbf\" + gammaindex + \".eps\";\n    figurename_png = \"feasibility-mpcdcbf\" + gammaindex + \".png\";\n    dataname = \"feasibility-mpcdcbf\" + gammaindex + \".mat\";\n    % save data and generate figures\n    print(gcf,strcat('figures/',figurename_eps), '-depsc');\n    print(gcf,strcat('figures/',figurename_png), '-dpng', '-r800');\n    save(strcat('data/',dataname));\nend"
  },
  {
    "path": "matlab/cdc2021/testFeasibilityMPCGCBF.m",
    "content": "clc\nclose all\nclear\n% This file tests feasibility between MPC-GCBF and NMPC-DCBF.\n\n%% System setup\n\ntimestep = 0.1;\nsystem_param.A = [[1 ,timestep, 0]; [0, 1, timestep]; [0, 0, 1]];\nsystem_param.B = [0; 0; timestep];\nsystem_param.ul = -1;\nsystem_param.uu = 1;\nsystem_param.timestep = timestep;\nx0 = [0;0;0]; % this value will be overrided\nt0 = 0.0;\n\ngammalist = [0.05, 0.1, 0.15, 0.2];\nfor gammaindex = 1:length(gammalist)\n    %% Problem setup with different hyperparameters\n    \n    % MPC-GCBF simulator\n    simulator_mpcgcbf = CBFDT(system_param, x0, t0);\n    param_mpcgcbf = ParamMPCGCBF(8, gammalist(gammaindex), 10.0*eye(3), 10.0*eye(3), 1.0);\n    simulator_mpcgcbf.setOpt('mpcgcbf', param_mpcgcbf);\n    % NMPC-DCBF simulator\n    simulator_nmpccbf = CBFDT(system_param, x0, t0);\n    param_nmpcdcbf = ParamNMPCDCBF(8, 3, gammalist(gammaindex), 10.0*eye(3), 10.0*eye(3), 1.0, 10.0);\n    simulator_nmpccbf.setOpt('nmpcdcbf', param_nmpcdcbf);\n    % iterate over states\n    x1list = linspace(-2,0,11);\n    x2list = linspace(0,2,11);\n    x3list = linspace(0,2,11);\n    % data collection\n    feas_points_mpcgcbf = [];\n    feas_points_nmpcdcbf = [];\n    infeas_points_all = [];\n    \n    %% Test feasibility with sampling states among controllers\n    \n    for k1 = 1:length(x1list)\n        for k2 = 1:length(x2list)\n            for k3 = 1:length(x3list)\n                xfeas = [x1list(k1); x2list(k2); x3list(k3)];\n                % solve the problem with MPC-GCBF\n                simulator_mpcgcbf.xcurr = xfeas;\n                [feas_mpcgcbf, ~, ~, ~] = simulator_mpcgcbf.solve;\n                % solve the problem with NMPC-DCBF\n                simulator_nmpccbf.xcurr = xfeas;\n                [feas_nmpcdcbf, ~, ~, ~] = simulator_nmpccbf.solve;\n                if feas_mpcgcbf == 1\n                    feas_points_mpcgcbf = [feas_points_mpcgcbf, xfeas];\n                end\n                if feas_nmpcdcbf == 1\n                    feas_points_nmpcdcbf = [feas_points_nmpcdcbf, xfeas];\n                end\n                if feas_mpcgcbf == 0 && feas_nmpcdcbf == 0\n                    infeas_points_all = [infeas_points_all, xfeas];\n                end\n            end\n        end\n    end\n    \n    %% Plotting\n    close all\n    outer_color = [0.3010, 0.7450, 0.9330];\n    inner_color = [1, 0, 0];\n    figure('Renderer', 'painters', 'Position', [0 0 400 400]);\n    set(gca,'LooseInset',get(gca,'TightInset'));\n    hold on;\n    scatter3(feas_points_mpcgcbf(1,:),feas_points_mpcgcbf(2,:),feas_points_mpcgcbf(3,:),...\n        5, 'o', 'LineWidth', 1.0, 'MarkerEdgeColor', inner_color, 'MarkerFaceColor', inner_color);\n    scatter3(feas_points_nmpcdcbf(1,:),feas_points_nmpcdcbf(2,:),feas_points_nmpcdcbf(3,:),...\n        20, 'o', 'LineWidth', 1.2, 'MarkerEdgeColor', outer_color);\n    axis equal\n    if gammaindex == 1\n        h=get(gca,'Children');\n        h_legend = legend(h([end, end-1]),...\n            {'MPC-GCBF', 'NMPC-DCBF'}, 'Location', 'NorthEast');\n        set(h_legend, 'Interpreter','latex');\n    end\n    set(gca,'LineWidth', 1.0, 'FontSize', 15);\n    xlabel('$x (m)$','interpreter','latex','FontSize',20);\n    ylabel('$v (m/s)$','interpreter','latex','FontSize',20);\n    zlabel('$a (m/s^2)$','interpreter','latex','FontSize',20);\n    xlim([-2, 0]);\n    ylim([0, 2]);\n    zlim([0, 2]);\n    view(70, 4);\n    grid on;\n    figurename_eps = \"feasibility-mpcgcbf\" + gammaindex + \".eps\";\n    figurename_png = \"feasibility-mpcgcbf\" + gammaindex + \".png\";\n    dataname = \"feasibility-mpcgcbf\" + gammaindex + \".mat\";\n    % save data and generate figures\n    print(gcf,strcat('figures/',figurename_eps), '-depsc');\n    print(gcf,strcat('figures/',figurename_png), '-dpng', '-r800');\n    save(strcat('data/',dataname));\nend"
  },
  {
    "path": "matlab/cdc2021/testSafety.m",
    "content": "clc\nclose all\nclear\n% This file tests safety performance for various approaches\n\n%% Setup and simulations\ntimestep = 0.1;\nsystem_param.A = [[1 ,timestep, 0]; [0, 1, timestep]; [0, 0, 1]];\nsystem_param.B = [0; 0; timestep];\nsystem_param.ul = -1;\nsystem_param.uu = 1;\nsystem_param.timestep = timestep;\nx0 = [-2.0;0.0;1.0];\nt0 = 0.0;\n\ngammalist = [0.05, 0.10, 0.15, 0.2];\n\n%% MPC-DCBF simulator\nmpcdcbf_simulators = {};\nfor index = 1:length(gammalist)\n    mpcdcbf_simulators{index} = CBFDT(system_param, x0, t0);\n    param_mpcdcbf = ParamMPCDCBF(8, gammalist(index), 10.0*eye(3), 10.0*eye(3), 1.0);\n    mpcdcbf_simulators{index}.setOpt('mpcdcbf', param_mpcdcbf);\n    mpcdcbf_simulators{index}.sim(10.0);\nend\n\n%% MPC-GCBF simulator\nmpcgcbf_simulators = {};\nfor index = 1:length(gammalist)\n    mpcgcbf_simulators{index} = CBFDT(system_param, x0, t0);\n    param_mpcgcbf = ParamMPCGCBF(8, gammalist(index), 10.0*eye(3), 10.0*eye(3), 1.0);\n    mpcgcbf_simulators{index}.setOpt('mpcgcbf', param_mpcgcbf);\n    mpcgcbf_simulators{index}.sim(10.0);\nend\n\n%% NMPC-DCBF simulator\nnmpcdcbf_simulators = {};\nfor index = 1:length(gammalist)\n    nmpcdcbf_simulators{index} = CBFDT(system_param, x0, t0);\n    param_nmpcdcbf = ParamNMPCDCBF(8, 8, gammalist(index), 10.0*eye(3), 10.0*eye(3), 1.0, 10.0);\n    nmpcdcbf_simulators{index}.setOpt('nmpcdcbf', param_nmpcdcbf);\n    nmpcdcbf_simulators{index}.sim(10.0);\nend\n\n%% Plotting\nfigure('Renderer', 'painters', 'Position', [0 0 500 400]);\ncolor1 = '[0, 0.4470, 0.7410]';\ncolor2 = '[0.8500, 0.3250, 0.0980]';\ncolor3 = '[0.9290, 0.6940, 0.1250]';\ncolor4 = '[0.4940, 0.1840, 0.5560]';\nset(gca,'LineWidth', 0.2, 'FontSize', 20);\nhold on;\ngrid on;\nset(gca, 'YScale', 'log');\nplot(mpcdcbf_simulators{2}.tlog, -mpcdcbf_simulators{2}.xlog(1, :), 'Color', color2, 'LineWidth', 1.0);\nplot(mpcdcbf_simulators{3}.tlog, -mpcdcbf_simulators{3}.xlog(1, :), 'Color', color3, 'LineWidth', 1.0);\nplot(mpcdcbf_simulators{4}.tlog, -mpcdcbf_simulators{4}.xlog(1, :), 'Color', color4, 'LineWidth', 1.0);\nh_legend = legend('MPC-DCBF ($\\gamma=0.10$)', 'MPC-DCBF ($\\gamma=0.15$)', 'MPC-DCBF ($\\gamma=0.20$)');\nset(h_legend, 'Interpreter','latex', 'Location', 'SouthWest');\nxlim([0, 10]);\n% save data and generate figures\nprint(gcf, 'figures/safety-mpcdcbf.eps', '-depsc');\nprint(gcf, 'figures/safety-mpcdcbf.png', '-dpng', '-r800');\nsave('data/safety-mpcdcbf.mat');\n\nfigure('Renderer', 'painters', 'Position', [0 0 500 400]);\nset(gca,'LineWidth', 0.2, 'FontSize', 20);\nhold on;\ngrid on;\nset(gca, 'YScale', 'log');\nplot(mpcgcbf_simulators{2}.tlog, -mpcgcbf_simulators{2}.xlog(1, :), 'Color', color2, 'LineWidth', 1.0);\nplot(mpcgcbf_simulators{3}.tlog, -mpcgcbf_simulators{3}.xlog(1, :), 'Color', color3, 'LineWidth', 1.0);\nplot(mpcgcbf_simulators{4}.tlog, -mpcgcbf_simulators{4}.xlog(1, :), 'Color', color4, 'LineWidth', 1.0);\nh_legend = legend('MPC-GCBF ($\\gamma=0.10$)', 'MPC-GCBF ($\\gamma=0.15$)', 'MPC-GCBF ($\\gamma=0.20$)');\nset(h_legend, 'Interpreter','latex', 'Location', 'SouthWest');\nxlim([0, 10]);\nylim([0.01, 2]);\n% save data and generate figures\nprint(gcf, 'figures/safety-mpcgcbf.eps', '-depsc');\nprint(gcf, 'figures/safety-mpcgcbf.png', '-dpng', '-r800');\nsave('data/safety-mpcgcbf.mat');\n\nfigure('Renderer', 'painters', 'Position', [0 0 500 400]);\nset(gca,'LineWidth', 0.2, 'FontSize', 20);\nhold on;\ngrid on;\nset(gca, 'YScale', 'log');\nplot(nmpcdcbf_simulators{1}.tlog, -nmpcdcbf_simulators{1}.xlog(1, :), 'Color', color1, 'LineWidth', 1.0);\nplot(nmpcdcbf_simulators{2}.tlog, -nmpcdcbf_simulators{2}.xlog(1, :), 'Color', color2, 'LineWidth', 1.0);\nplot(nmpcdcbf_simulators{3}.tlog, -nmpcdcbf_simulators{3}.xlog(1, :), 'Color', color3, 'LineWidth', 1.0);\nplot(nmpcdcbf_simulators{4}.tlog, -nmpcdcbf_simulators{4}.xlog(1, :), 'Color', color4, 'LineWidth', 1.0);\nh_legend = legend('NMPC-DCBF ($\\gamma=0.05$)', 'NMPC-DCBF ($\\gamma=0.10$)', 'NMPC-DCBF ($\\gamma=0.15$)', 'NMPC-DCBF ($\\gamma=0.20$)');\nset(h_legend, 'Interpreter','latex', 'Location', 'SouthWest');\nxlim([0, 10]);\n% save data and generate figures\nprint(gcf, 'figures/safety-nmpcdcbf.eps', '-depsc');\nprint(gcf, 'figures/safety-nmpcdcbf.png', '-dpng', '-r800');\nsave('data/safety-nmpccbf.mat');\n"
  }
]