diff --git a/mav_control_rw/.gitignore b/mav_control_rw/.gitignore
new file mode 100644
index 0000000000000000000000000000000000000000..93d8b1c84d31118940c233c016c6001341e93bde
--- /dev/null
+++ b/mav_control_rw/.gitignore
@@ -0,0 +1,33 @@
+# Compiled Object files
+*.slo
+*.lo
+*.o
+*.obj
+
+# Precompiled Headers
+*.gch
+*.pch
+
+# Fortran module files
+*.mod
+*.smod
+
+# Compiled Static libraries
+*.lai
+*.la
+*.a
+*.lib
+
+# Executables
+*.exe
+*.out
+*.app
+
+*.project
+*.cproject
+*.settings*
+*.DS_Store
+*.idea*
+
+# Build
+build/*
diff --git a/mav_control_rw/.travis.yml b/mav_control_rw/.travis.yml
new file mode 100644
index 0000000000000000000000000000000000000000..a0e877177a8d30eeef6ac6f3d787397acc0af8b9
--- /dev/null
+++ b/mav_control_rw/.travis.yml
@@ -0,0 +1,55 @@
+dist: trusty
+sudo: required
+language: generic
+compiler:
+  - gcc
+cache:
+  - apt
+
+env:
+  global:
+    #- ROS_DISTRO=jade
+    - ROS_CI_DESKTOP="$(lsb_release -cs)"
+    - CI_SOURCE_PATH=$(pwd)
+    - ROSINSTALL_FILE=$CI_SOURCE_PATH/dependencies.rosinstall
+    - ROS_PARALLEL_JOBS='-j8 -l6'
+
+  matrix:
+    - ROS_DISTRO=indigo
+    - ROS_DISTRO=jade
+
+before_install:
+  - sudo sh -c "echo \"deb http://packages.ros.org/ros/ubuntu $ROS_CI_DESKTOP main\" > /etc/apt/sources.list.d/ros-latest.list"
+  #- sudo sh -c "echo \"deb http://packages.ros.org/ros-shadow-fixed/ubuntu $ROS_CI_DESKTOP main\" > /etc/apt/sources.list.d/ros-latest.list"
+  - wget http://packages.ros.org/ros.key -O - | sudo apt-key add -
+  - sudo apt-get -qq update
+  - sudo apt-get -qq install -y python-catkin-pkg python-rosdep python-wstool ros-$ROS_DISTRO-catkin python-catkin-tools
+  - sudo apt-get -qq install liblapacke-dev
+  - source /opt/ros/$ROS_DISTRO/setup.bash
+  # Prepare rosdep
+  - sudo rosdep init >> /dev/null
+  - rosdep update >> /dev/null
+
+install:
+  # Create catkin workspace
+  - mkdir -p ~/catkin_ws/src
+  - cd ~/catkin_ws
+  - catkin init >> /dev/null
+  - catkin config --cmake-args -DCMAKE_BUILD_TYPE=Release >> /dev/null
+  - catkin build >> /dev/null
+  - source devel/setup.bash
+  
+before_script:
+  - cd ~/catkin_ws/src
+  - ln -s $CI_SOURCE_PATH .
+  - git clone https://github.com/ethz-asl/mav_comm.git >> /dev/null
+  - git clone https://github.com/ethz-asl/eigen_catkin.git >> /dev/null
+  - git clone https://github.com/catkin/catkin_simple.git >> /dev/null
+  - wstool init >> /dev/null
+  - wstool up >> /dev/null
+  - cd ~/catkin_ws
+  - rosdep install -y --from-paths src --ignore-src --rosdistro $ROS_DISTRO >> /dev/null
+  - cd ~/catkin_ws
+  - source devel/setup.bash
+
+script: travis_wait 40 catkin build --no-status
diff --git a/mav_control_rw/LICENSE b/mav_control_rw/LICENSE
new file mode 100644
index 0000000000000000000000000000000000000000..8dada3edaf50dbc082c9a125058f25def75e625a
--- /dev/null
+++ b/mav_control_rw/LICENSE
@@ -0,0 +1,201 @@
+                                 Apache License
+                           Version 2.0, January 2004
+                        http://www.apache.org/licenses/
+
+   TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
+
+   1. Definitions.
+
+      "License" shall mean the terms and conditions for use, reproduction,
+      and distribution as defined by Sections 1 through 9 of this document.
+
+      "Licensor" shall mean the copyright owner or entity authorized by
+      the copyright owner that is granting the License.
+
+      "Legal Entity" shall mean the union of the acting entity and all
+      other entities that control, are controlled by, or are under common
+      control with that entity. For the purposes of this definition,
+      "control" means (i) the power, direct or indirect, to cause the
+      direction or management of such entity, whether by contract or
+      otherwise, or (ii) ownership of fifty percent (50%) or more of the
+      outstanding shares, or (iii) beneficial ownership of such entity.
+
+      "You" (or "Your") shall mean an individual or Legal Entity
+      exercising permissions granted by this License.
+
+      "Source" form shall mean the preferred form for making modifications,
+      including but not limited to software source code, documentation
+      source, and configuration files.
+
+      "Object" form shall mean any form resulting from mechanical
+      transformation or translation of a Source form, including but
+      not limited to compiled object code, generated documentation,
+      and conversions to other media types.
+
+      "Work" shall mean the work of authorship, whether in Source or
+      Object form, made available under the License, as indicated by a
+      copyright notice that is included in or attached to the work
+      (an example is provided in the Appendix below).
+
+      "Derivative Works" shall mean any work, whether in Source or Object
+      form, that is based on (or derived from) the Work and for which the
+      editorial revisions, annotations, elaborations, or other modifications
+      represent, as a whole, an original work of authorship. For the purposes
+      of this License, Derivative Works shall not include works that remain
+      separable from, or merely link (or bind by name) to the interfaces of,
+      the Work and Derivative Works thereof.
+
+      "Contribution" shall mean any work of authorship, including
+      the original version of the Work and any modifications or additions
+      to that Work or Derivative Works thereof, that is intentionally
+      submitted to Licensor for inclusion in the Work by the copyright owner
+      or by an individual or Legal Entity authorized to submit on behalf of
+      the copyright owner. For the purposes of this definition, "submitted"
+      means any form of electronic, verbal, or written communication sent
+      to the Licensor or its representatives, including but not limited to
+      communication on electronic mailing lists, source code control systems,
+      and issue tracking systems that are managed by, or on behalf of, the
+      Licensor for the purpose of discussing and improving the Work, but
+      excluding communication that is conspicuously marked or otherwise
+      designated in writing by the copyright owner as "Not a Contribution."
+
+      "Contributor" shall mean Licensor and any individual or Legal Entity
+      on behalf of whom a Contribution has been received by Licensor and
+      subsequently incorporated within the Work.
+
+   2. Grant of Copyright License. Subject to the terms and conditions of
+      this License, each Contributor hereby grants to You a perpetual,
+      worldwide, non-exclusive, no-charge, royalty-free, irrevocable
+      copyright license to reproduce, prepare Derivative Works of,
+      publicly display, publicly perform, sublicense, and distribute the
+      Work and such Derivative Works in Source or Object form.
+
+   3. Grant of Patent License. Subject to the terms and conditions of
+      this License, each Contributor hereby grants to You a perpetual,
+      worldwide, non-exclusive, no-charge, royalty-free, irrevocable
+      (except as stated in this section) patent license to make, have made,
+      use, offer to sell, sell, import, and otherwise transfer the Work,
+      where such license applies only to those patent claims licensable
+      by such Contributor that are necessarily infringed by their
+      Contribution(s) alone or by combination of their Contribution(s)
+      with the Work to which such Contribution(s) was submitted. If You
+      institute patent litigation against any entity (including a
+      cross-claim or counterclaim in a lawsuit) alleging that the Work
+      or a Contribution incorporated within the Work constitutes direct
+      or contributory patent infringement, then any patent licenses
+      granted to You under this License for that Work shall terminate
+      as of the date such litigation is filed.
+
+   4. Redistribution. You may reproduce and distribute copies of the
+      Work or Derivative Works thereof in any medium, with or without
+      modifications, and in Source or Object form, provided that You
+      meet the following conditions:
+
+      (a) You must give any other recipients of the Work or
+          Derivative Works a copy of this License; and
+
+      (b) You must cause any modified files to carry prominent notices
+          stating that You changed the files; and
+
+      (c) You must retain, in the Source form of any Derivative Works
+          that You distribute, all copyright, patent, trademark, and
+          attribution notices from the Source form of the Work,
+          excluding those notices that do not pertain to any part of
+          the Derivative Works; and
+
+      (d) If the Work includes a "NOTICE" text file as part of its
+          distribution, then any Derivative Works that You distribute must
+          include a readable copy of the attribution notices contained
+          within such NOTICE file, excluding those notices that do not
+          pertain to any part of the Derivative Works, in at least one
+          of the following places: within a NOTICE text file distributed
+          as part of the Derivative Works; within the Source form or
+          documentation, if provided along with the Derivative Works; or,
+          within a display generated by the Derivative Works, if and
+          wherever such third-party notices normally appear. The contents
+          of the NOTICE file are for informational purposes only and
+          do not modify the License. You may add Your own attribution
+          notices within Derivative Works that You distribute, alongside
+          or as an addendum to the NOTICE text from the Work, provided
+          that such additional attribution notices cannot be construed
+          as modifying the License.
+
+      You may add Your own copyright statement to Your modifications and
+      may provide additional or different license terms and conditions
+      for use, reproduction, or distribution of Your modifications, or
+      for any such Derivative Works as a whole, provided Your use,
+      reproduction, and distribution of the Work otherwise complies with
+      the conditions stated in this License.
+
+   5. Submission of Contributions. Unless You explicitly state otherwise,
+      any Contribution intentionally submitted for inclusion in the Work
+      by You to the Licensor shall be under the terms and conditions of
+      this License, without any additional terms or conditions.
+      Notwithstanding the above, nothing herein shall supersede or modify
+      the terms of any separate license agreement you may have executed
+      with Licensor regarding such Contributions.
+
+   6. Trademarks. This License does not grant permission to use the trade
+      names, trademarks, service marks, or product names of the Licensor,
+      except as required for reasonable and customary use in describing the
+      origin of the Work and reproducing the content of the NOTICE file.
+
+   7. Disclaimer of Warranty. Unless required by applicable law or
+      agreed to in writing, Licensor provides the Work (and each
+      Contributor provides its Contributions) on an "AS IS" BASIS,
+      WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
+      implied, including, without limitation, any warranties or conditions
+      of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
+      PARTICULAR PURPOSE. You are solely responsible for determining the
+      appropriateness of using or redistributing the Work and assume any
+      risks associated with Your exercise of permissions under this License.
+
+   8. Limitation of Liability. In no event and under no legal theory,
+      whether in tort (including negligence), contract, or otherwise,
+      unless required by applicable law (such as deliberate and grossly
+      negligent acts) or agreed to in writing, shall any Contributor be
+      liable to You for damages, including any direct, indirect, special,
+      incidental, or consequential damages of any character arising as a
+      result of this License or out of the use or inability to use the
+      Work (including but not limited to damages for loss of goodwill,
+      work stoppage, computer failure or malfunction, or any and all
+      other commercial damages or losses), even if such Contributor
+      has been advised of the possibility of such damages.
+
+   9. Accepting Warranty or Additional Liability. While redistributing
+      the Work or Derivative Works thereof, You may choose to offer,
+      and charge a fee for, acceptance of support, warranty, indemnity,
+      or other liability obligations and/or rights consistent with this
+      License. However, in accepting such obligations, You may act only
+      on Your own behalf and on Your sole responsibility, not on behalf
+      of any other Contributor, and only if You agree to indemnify,
+      defend, and hold each Contributor harmless for any liability
+      incurred by, or claims asserted against, such Contributor by reason
+      of your accepting any such warranty or additional liability.
+
+   END OF TERMS AND CONDITIONS
+
+   APPENDIX: How to apply the Apache License to your work.
+
+      To apply the Apache License to your work, attach the following
+      boilerplate notice, with the fields enclosed by brackets "{}"
+      replaced with your own identifying information. (Don't include
+      the brackets!)  The text should be enclosed in the appropriate
+      comment syntax for the file format. We also recommend that a
+      file or class name and description of purpose be included on the
+      same "printed page" as the copyright notice for easier
+      identification within third-party archives.
+
+   Copyright {yyyy} {name of copyright owner}
+
+   Licensed under the Apache License, Version 2.0 (the "License");
+   you may not use this file except in compliance with the License.
+   You may obtain a copy of the License at
+
+       http://www.apache.org/licenses/LICENSE-2.0
+
+   Unless required by applicable law or agreed to in writing, software
+   distributed under the License is distributed on an "AS IS" BASIS,
+   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+   See the License for the specific language governing permissions and
+   limitations under the License.
diff --git a/mav_control_rw/README.md b/mav_control_rw/README.md
new file mode 100644
index 0000000000000000000000000000000000000000..b364bf6c258d12c2e5a2fda009ca3bb559a664b2
--- /dev/null
+++ b/mav_control_rw/README.md
@@ -0,0 +1,219 @@
+mav_control_rw [![Build Status](https://travis-ci.org/ethz-asl/mav_control_rw.svg?branch=master)](https://travis-ci.org/ethz-asl/mav_control_rw)
+======
+
+Control strategies for rotary wing Micro Aerial Vehicles (MAVs) using ROS
+
+Overview
+------
+
+This repository contains controllers for rotary wing MAVs. Currently we support the following controllers:
+- *mav_linear_mpc* : Linear MPC for MAV trajectory tracking
+- *mav_nonlinear_mpc* : Nonlinear MPC for MAV trajectory tracking
+- *PID_attitude_control* : low level PID attitude controller 
+
+Moreover, an external disturbance observer based on Kalman Filter is implemented to achieve offset-free tracking. 
+
+If you use any of these controllers within your research, please cite one of the following references
+
+```bibtex
+@incollection{kamelmpc2016,
+                author      = "Mina Kamel and Thomas Stastny and Kostas Alexis and Roland Siegwart",
+                title       = "Model Predictive Control for Trajectory Tracking of Unmanned Aerial Vehicles Using Robot Operating System",
+                editor      = "Anis Koubaa",
+                booktitle   = "Robot Operating System (ROS) The Complete Reference, Volume 2",
+                publisher   = "Springer",
+                year = “2017”,
+}
+```
+
+```bibtex
+@ARTICLE{2016arXiv161109240K,
+          author = {{Kamel}, M. and {Burri}, M. and {Siegwart}, R.},
+          title = "{Linear vs Nonlinear MPC for Trajectory Tracking Applied to Rotary Wing Micro Aerial Vehicles}",
+          journal = {ArXiv e-prints},
+          archivePrefix = "arXiv",
+          eprint = {1611.09240},
+          primaryClass = "cs.RO",
+          keywords = {Computer Science - Robotics},
+          year = 2016,
+          month = nov
+}
+
+```
+
+
+Installation instructions
+------
+
+To run the controller with RotorS simulator (https://github.com/ethz-asl/rotors_simulator), follow these instructions:
+
+* Install and initialize ROS indigo desktop full, additional ROS packages, catkin-tools:
+  
+```sh
+  $ sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu `lsb_release -sc` main" > /etc/apt/sources.list.d/ros-latest.list'
+  $ wget http://packages.ros.org/ros.key -O - | sudo apt-key add -
+  $ sudo apt-get update
+  $ sudo apt-get install ros-indigo-desktop-full ros-indigo-joy ros-indigo-octomap-ros python-wstool python-catkin-tools
+  $ sudo rosdep init
+  $ rosdep update
+  $ source /opt/ros/indigo/setup.bash
+```
+* Initialize catkin workspace:
+```sh
+  $ mkdir -p ~/catkin_ws/src
+  $ cd ~/catkin_ws
+  $ catkin config --cmake-args -DCMAKE_BUILD_TYPE=Release
+  $ catkin init  # initialize your catkin workspace
+```
+* Get the controllers and dependencies
+```sh
+  $ sudo apt-get install liblapacke-dev
+  $ git clone https://github.com/catkin/catkin_simple.git
+  $ git clone https://github.com/ethz-asl/rotors_simulator.git
+  $ git clone https://github.com/ethz-asl/mav_comm.git
+  $ git clone https://github.com/ethz-asl/eigen_catkin.git
+
+  $ git clone https://github.com/ethz-asl/mav_control_rw.git
+```
+* Build the workspace  
+```sh
+  $ catkin build
+```
+
+* Run the simulator and the linear MPC. In seperate terminals run the following commands
+  
+```sh
+  $ roslaunch rotors_gazebo mav.launch mav_name:=firefly
+```
+```sh
+  $ roslaunch mav_linear_mpc mav_linear_mpc_sim.launch mav_name:=firefly
+```
+You can use `rqt` to publish commands to the controller.
+
+
+To run the controller with the multi sensor fusion (MSF) framewok (https://github.com/ethz-asl/ethzasl_msf):
+* Get msf
+```sh
+  $ git clone https://github.com/ethz-asl/ethzasl_msf.git
+```
+
+* Run the simulator, the linear MPC and MSF, in seperate terminals run the following commands
+  
+```sh
+  $ roslaunch rotors_gazebo mav.launch mav_name:=firefly
+```
+```sh
+  $ roslaunch mav_linear_mpc mav_linear_mpc_sim_msf.launch mav_name:=firefly
+```
+
+Don't forget to initialize MSF. 
+
+Supported autopilots
+------
+### Asctec Research Platforms
+This control will work as is with the ros interface to the now discontinued Asctec research platforms (Hummingbird, Pelican, Firefly and Neo). 
+
+### Pixhawk
+This controller requires some small modifications to the PX4 firmware to allow yaw rate inputs. A modified version of the firmware can be found [here](https://github.com/ethz-asl/ethzasl_mav_px4). The firmware is interfaced with through a [modified mavros node](https://github.com/ethz-asl/mavros).
+
+### DJI
+The controller can interface with DJI platforms through our [mav_dji_ros_interface](https://github.com/ethz-asl/mav_dji_ros_interface)
+
+Published and subscribed topics
+------
+
+The linear and nonlinear MPC controllers publish and subscribe to the following topics:
+
+- Published topics:
+  - **`command/roll_pitch_yawrate_thrust`** of type `mav_msgs/RollPitchYawrateThrust`. This is the command to the low level controller. Angles are in `rad` and `thrust` is in `N`.
+  - **`command/current_reference`** of type `trajectory_msgs/MultiDOFJointTrajectory`. This is the current reference.
+  -  **`state_machine/state_info`** of type `std_msgs/String`. This is the current state of the state machine of mav_control_interface.
+  -  **`predicted_state`** of type `visualization_msgs/Marker`. This is the predicted vehicle positions that can be used for visualization in `rviz`.
+  -  **`reference_trajectory`** of type `visualization_msgs/Marker`. This is the reference trajectory that can be used for visualization in `rviz`.
+  - **`KF_observer/observer_state`** of type `mav_disturbance_observer/ObserverState`. This is the disturbance observer state used for debugging purposes. It includes estimated external forces and torques.
+  
+- Subscribed topics:
+  - **`command/pose`** of type `geometry_msgs/PoseStamped`. This is a reference set point.
+  - **`command/trajectory`** of type `trajectory_msgs/MultiDOFJointTrajectory`. This is a desired trajectory reference that includes desired velocities and accelerations.
+  - **`rc`** of type `sensor_msgs/Joy`. This is the remote control commands for teleoperation purposes. It also serves to abort mission anytime.
+  - **`odometry`** of type `nav_msgs/Odometry`. This is the current state of the vehicle. The odometry msg includes pose and twist information.
+  
+  
+The PID attitude controller publishes and subscribes to the following topics:
+- Published topics:
+  - **`command/motor_speed`** of type `mav_msgs/Actuators`. This is the commanded motor speed.
+
+- Subscribed topics:
+  - **`command/roll_pitch_yawrate_thrust`** of type `mav_msgs/RollPitchYawrateThrust`.
+  - **`odometry`** of type `nav_msgs/Odometry`.
+  
+ 
+ 
+Parameters
+------
+A summary of the linear and nonlinear MPC parameters:
+
+| Parameter             | Description                                                                     |
+| --------------------  |:-------------------------------------------------------------------------------:| 
+| `use_rc_teleop`       | enable RC teleoperation. Set to `false` in case of simulation.                  |
+| `reference_frame`     | the name of the reference frame.                                                |
+| `verbose`             | controller prints on screen debugging information and computation time          |
+| `mass`                | vehicle mass                                                                    | 
+| `roll_time_constant`  | time constant of roll first order model                                         |
+| `pitch_time_constant` | time constant of pitch first order model                                        |
+|`roll_gain`            | gain of roll first order model                                                  |
+|`pitch_gain`           | gain of pitch first order model                                                 |
+|`drag_coefficients`    | drag on `x,y,z` axes                                                            |
+|`q_x, q_y, q_z`*       | penalty on position error                                                       |
+|`q_vx, q_vy, q_vz`*    | penalty on velocity error                                                       |
+|`q_roll, q_pitch`*     | penalty on attitude state                                                       |
+|`r_roll, r_pitch, r_thtust`*| penalty on control input                                                    |
+|`r_droll, r_dpitch, r_dthtust`*| penalty on delta control input (only Linear MPC)                        |
+|`roll_max, pitch_max, yaw_rate_max`*| limits of control input                                             |
+|`thrust_min, thrust_max`* | limit on thrust control input in `m/s^2`                                      |
+|`K_yaw`*                  | yaw P loop gain                                                               |
+|`Ki_xy, Ki_z`*            | integrator gains on `xy` and `z` axes respectively                            |
+|`position_error_integration_limit` | limit of position error integration                                 |
+|`antiwindup_ball`        | if the error is larger than this ball, no integral action is applied          |
+|`enable_offset_free`*     | use estimated disturbances to achieve offset free tracking                    |
+|`enable_integrator`*      | use error integration to achieve offset free tracking                         |
+|`sampling_time`          | the controller sampling time (must be equal to the rate of `odometry` message |
+|`prediction_sampling_time`| the prediction sampling time inside the controller                           |
+
+
+\* Through dynamic reconfigure, it is possible to change these parameters.
+
+--------
+
+
+A summary of the PID attitude parameters:
+
+| Parameter             | Description                                                                     |
+| --------------------  |:-------------------------------------------------------------------------------:| 
+| `inertia`             | vehicle inertia  `3x3` matrix                                                   |
+|`allocation_matrix`    | control allocation matrix depending on the configuration of the rotors          |
+|`n_rotors`             | number of rotors                                                                |
+|`rotor_force_constant` | force constant of the rotor in `N/rad^2` such that `F_i =rotor_force_constant*rotor_velocity^2`                                         |
+|`rotor_moment_constant`| rotor moment constant such that `M = rotor_moment_constant*F_i`                 |
+|`arm_length`           | distance between rotor and vehicle center                                       |
+|`roll_gain, pitch_gain`* | error proportional term                                                       |
+|`p_gain, q_gain, r_gain`* | derivative gain                                                              |
+|`roll_int_gain, pitch_int_gain`*| integrator gains                                                       |
+|`max_integrator_error`     | saturation on the integrator                                                |
+
+\* Through dynamic reconfigure, it is possible to change these parameters.
+
+ --------
+
+References
+------
+
+[1] Model Predictive Control for Trajectory Tracking of Unmanned Aerial Vehicles Using Robot Operating System. Mina Kamel, Thomas Stastny, Kostas Alexis and Roland Siegwart. Robot Operating System (ROS) The Complete Reference Volume 2. Springer 2017 (to appear)
+
+[2] Linear vs Nonlinear MPC for Trajectory Tracking Applied to Rotary Wing Micro Aerial Vehicles. Mina Kamel, Michael Burri and Roland Siegwart. arXiv:1611.09240
+
+--------
+
+Contact
+-------
+Mina Kamel fmina(at)ethz.ch
diff --git a/mav_control_rw/mav_nonlinear_mpc/.vscode/settings.json b/mav_control_rw/mav_nonlinear_mpc/.vscode/settings.json
new file mode 100644
index 0000000000000000000000000000000000000000..691a8f68f405ccdc2ba08296bd21c804bbec2ff3
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/.vscode/settings.json
@@ -0,0 +1,3 @@
+{
+    "C_Cpp.errorSquiggles": "Disabled"
+}
\ No newline at end of file
diff --git a/mav_control_rw/mav_nonlinear_mpc/CMakeLists.txt b/mav_control_rw/mav_nonlinear_mpc/CMakeLists.txt
new file mode 100644
index 0000000000000000000000000000000000000000..93bf59cc56f988596683fa1221f65279c730fcc9
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/CMakeLists.txt
@@ -0,0 +1,82 @@
+cmake_minimum_required(VERSION 2.8.3)
+project(mav_nonlinear_mpc)
+
+set(CMAKE_BUILD_TYPE Release)
+
+set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${PROJECT_SOURCE_DIR}/cmake/")
+
+# On os x we need to use openblas for the lapacke library
+find_package(OpenBLAS REQUIRED)
+if (Openblas_FOUND)
+  message("-- Found Openblas library: ${Openblas_LIBRARIES}")
+  message("-- Found Openblas include dirs: ${Openblas_INCLUDE_DIRS}")
+  include_directories(${Openblas_INCLUDE_DIRS})
+  set(lapacke_LIBRARIES ${Openblas_LIBRARIES})
+else (Openblas_FOUND)
+  message("-- Openblas not found, trying to use lapacke")
+  find_package(LAPACK REQUIRED)
+  set(lapacke_LIBRARIES lapacke)
+endif (Openblas_FOUND)
+
+
+find_package(catkin_simple REQUIRED)
+catkin_simple(ALL_DEPS_REQUIRED)
+
+if(APPLE)
+  set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -stdlib=libc++")
+else()
+  set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
+endif()
+
+find_package(Eigen REQUIRED)
+include_directories(${Eigen_INCLUDE_DIRS})
+
+#############
+# LIBRARIES #
+#############
+cs_add_library(mav_nonlinear_mpc_lib
+  src/nonlinear_mpc.cc
+  solver/qpoases/SRC/Bounds.cpp
+  solver/qpoases/SRC/Constraints.cpp
+  solver/qpoases/SRC/CyclingManager.cpp
+  solver/qpoases/SRC/Indexlist.cpp
+  solver/qpoases/SRC/MessageHandling.cpp
+  solver/qpoases/SRC/QProblem.cpp
+  solver/qpoases/SRC/QProblemB.cpp
+  solver/qpoases/SRC/SubjectTo.cpp
+  solver/qpoases/SRC/Utils.cpp
+  solver/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp
+  solver/acado_qpoases_interface.cpp
+  solver/acado_integrator.c
+  solver/acado_solver.c
+  solver/acado_auxiliary_functions.c
+  )
+
+target_include_directories(mav_nonlinear_mpc_lib PUBLIC
+	solver/
+	solver/qpoases
+	solver/qpoases/INCLUDE
+	solver/qpoases/SRC
+	)
+
+############
+# BINARIES #
+############
+cs_add_executable(nonlinear_mpc_node
+  src/nonlinear_mpc_node.cc
+)
+
+#target_link_libraries(mav_nonlinear_mpc_lib ${lapacke_LIBRARIES})
+
+target_link_libraries(nonlinear_mpc_node mav_nonlinear_mpc_lib)
+target_link_libraries(mav_nonlinear_mpc_lib ${catkin_LIBRARIES})
+
+
+add_dependencies(nonlinear_mpc_node ${${PROJECT_NAME}_EXPORTED_TARGETS})
+
+
+##########
+# EXPORT #
+##########
+cs_install()
+cs_export()
diff --git a/mav_control_rw/mav_nonlinear_mpc/cfg/NonLinearMPC.cfg b/mav_control_rw/mav_nonlinear_mpc/cfg/NonLinearMPC.cfg
new file mode 100644
index 0000000000000000000000000000000000000000..c8eaea48a3ccb66c83c2497f71a6d675d311d764
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/cfg/NonLinearMPC.cfg
@@ -0,0 +1,36 @@
+#!/usr/bin/env python
+PACKAGE = "mav_nonlinear_mpc"
+
+from dynamic_reconfigure.parameter_generator_catkin import *
+
+gen = ParameterGenerator()
+
+gen.add("q_x",    double_t,    0, "Penality on x axis pos", 50.0 ,  0.001, 200.0)
+gen.add("q_y",    double_t,    0, "Penality on y axis pos", 50.0 ,  0.001, 200.0)
+gen.add("q_z",    double_t,    0, "Penality on z axis pos", 80.0 ,  0.001, 200.0)
+
+gen.add("q_vx",    double_t,    0, "Penality on x axis vel", 20.0 ,  0.001, 200.0)
+gen.add("q_vy",    double_t,    0, "Penality on y axis vel", 20.0 ,  0.001, 200.0)
+gen.add("q_vz",    double_t,    0, "Penality on z axis vel", 35.0 ,  0.001, 200.0)
+
+gen.add("q_roll",     double_t,    0, "Penality on roll state", 20.0 ,  0.001, 200.0)
+gen.add("q_pitch",    double_t,    0, "Penality on pitch state", 20.0 ,  0.001, 200.0)
+
+gen.add("r_roll",     double_t,    0, "Penality on roll cmd", 30.0 ,  1.0, 200.0)
+gen.add("r_pitch",    double_t,    0, "Penality on pitch cmd", 30.0 , 1.0, 200.0)
+gen.add("r_thrust",   double_t,    0, "Penality on thrust cmd", 5.0 , 1.0, 200.0)
+
+gen.add("roll_max",     double_t,    0, "max roll cmd [rad]", 0.45, 0.1, 1.0)
+gen.add("pitch_max",    double_t,    0, "max pitch cmd [rad]", 0.45, 0.1, 1.0)
+gen.add("yaw_rate_max",     double_t,    0, "max yawrate cmd [rad/s]", 1.5, 0.1, 2.0)
+gen.add("thrust_min",   double_t,    0, "min thrust cmd [m/s2]", 5.0 ,  5.0, 25.0)
+gen.add("thrust_max",   double_t,    0, "max thrust cmd [m/s2]", 15.0 ,  5.0, 25.0)
+
+gen.add("K_yaw",   double_t,    0, "yaw gain", 0.5 ,  0.01, 2.0)
+gen.add("Ki_xy",   double_t,    0, "integrator gain for xy", 0.2 ,  0.01, 3.0)
+gen.add("Ki_altitude",   double_t,    0, "integrator gain for altitude", 0.2 ,  0.01, 3.0)
+
+gen.add("enable_offset_free",   bool_t,   0, "XY offset free MPC",  True)
+gen.add("enable_integrator",   bool_t,   0, "integral action",  False)
+
+exit(gen.generate(PACKAGE, "Config", "NonLinearMPC"))
diff --git a/mav_control_rw/mav_nonlinear_mpc/cmake/FindOpenBLAS.cmake b/mav_control_rw/mav_nonlinear_mpc/cmake/FindOpenBLAS.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..c5bc3f42a396221912f998fd9733929d47ebec2a
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/cmake/FindOpenBLAS.cmake
@@ -0,0 +1,42 @@
+
+# - Finds Openblas and all dependencies
+# Once done this will define
+#  Openblas_FOUND - System has Openblas
+#  Openblas_INCLUDE_DIRS - The Openblas include directories
+#  Openblas_LIBRARIES - The libraries needed to use Openblas
+
+find_library(Openblas_LIBRARY
+  NAMES libopenblas.so libopenblas.lib libopenblas.dylib
+  PATHS ${Openblas_ROOT}/lib
+    /usr/lib/openblas-base
+    /usr/local/lib
+)
+
+# brew installed openblas library on os x is hard to find and depends on the installed version.
+if(Openblas_LIBRARY STREQUAL "Openblas_LIBRARY-NOTFOUND")
+  file(GLOB Openblas_LIBRARY /usr/local/Cellar/openblas/*/lib/libopenblas.dylib)
+endif()
+
+if(NOT OPENBLAS_IGNORE_HEADERS)
+  find_path(Openblas_INCLUDE_DIR
+    NAMES openblas_config.h
+    PATHS ${Openblas_ROOT}/include
+      /usr/include
+      /usr/local/include
+      /usr/local/Cellar
+      /usr/local/opt/openblas/include
+)
+endif()
+
+if((Openblas_LIBRARY STREQUAL "Openblas_LIBRARY-NOTFOUND") OR (Openblas_INCLUDE_DIR STREQUAL "Openblas_INCLUDE_DIR-NOTFOUND"))
+  set(Openblas_ROOT "" CACHE PATH "Path to the root of a Openblas installation")
+  set(Openblas_FOUND 0)
+  message(WARNING "Openblas not found. Please try specifying Openblas_ROOT")
+else()
+  set(Openblas_FOUND 1)
+  set(Openblas_INCLUDE_DIRS ${Openblas_INCLUDE_DIR})
+  set(Openblas_LIBRARIES ${Openblas_LIBRARY})
+  if(CMAKE_COMPILER_IS_GNUCC)
+    set(Openblas_LIBRARIES ${Openblas_LIBRARIES} gfortran pthread)
+  endif()
+endif()
diff --git a/mav_control_rw/mav_nonlinear_mpc/include/mav_nonlinear_mpc/nonlinear_mpc.h b/mav_control_rw/mav_nonlinear_mpc/include/mav_nonlinear_mpc/nonlinear_mpc.h
new file mode 100644
index 0000000000000000000000000000000000000000..8ebc4e043ac9effdccdb58c6e915d933d4d5f383
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/include/mav_nonlinear_mpc/nonlinear_mpc.h
@@ -0,0 +1,75 @@
+#ifndef INCLUDE_MAV_NONLINEAR_MPC_NONLINEAR_MPC_H_
+#define INCLUDE_MAV_NONLINEAR_MPC_NONLINEAR_MPC_H_
+
+#include <ros/ros.h>
+#include <Eigen/Eigen>
+#include <stdio.h>
+#include <algorithm>
+#include "acado_common.h"
+#include "acado_auxiliary_functions.h"
+#include <std_srvs/Empty.h>
+#include <geometry_msgs/Twist.h>
+#include <geometry_msgs/PoseStamped.h>
+#include <gazebo_msgs/GetModelState.h>
+#include <sensor_msgs/LaserScan.h>
+
+ACADOvariables acadoVariables;
+ACADOworkspace acadoWorkspace;
+
+namespace mav_control {
+
+class NonlinearModelPredictiveControl
+{
+ public:
+  NonlinearModelPredictiveControl(ros::NodeHandle& nh, const ros::NodeHandle& private_nh);
+  ~NonlinearModelPredictiveControl();
+
+  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
+ private:
+
+  // constants
+  static constexpr double kGravity = 9.8066;
+  static constexpr int kDisturbanceSize = 3;
+
+  // variables
+  float distToGoal, angleToGoal, originalGoalDist;
+  float husky_x, husky_y, yaw_angle;
+  float target_x = 8.0;
+  float target_y = 0.0;
+  float SCAN_MAX_VALUE = 11;
+
+  // ros node handles
+  ros::NodeHandle nh_, private_nh_;
+
+  // solver matrices
+  Eigen::Matrix<double, ACADO_NY, ACADO_NY> W_;
+  Eigen::Matrix<double, ACADO_NYN, ACADO_NYN> WN_;
+  Eigen::Matrix<double, ACADO_N + 1, ACADO_NX> state_;
+  Eigen::Matrix<double, ACADO_N, ACADO_NU> input_;
+  Eigen::Matrix<double, ACADO_N, ACADO_NY> reference_;
+  Eigen::Matrix<double, 1, ACADO_NYN> referenceN_;
+  Eigen::Matrix<double, ACADO_N + 1, ACADO_NOD> acado_online_data_;
+
+  // commands
+  Eigen::Vector4d command_roll_pitch_yaw_thrust_;
+
+  // initilize solver
+  void initializeAcadoSolver(Eigen::VectorXd x0);
+
+  // solve continuous time Riccati equation
+  Eigen::MatrixXd solveCARE(Eigen::MatrixXd Q, Eigen::MatrixXd R);
+
+  void initializeSolver();
+
+  void updateWeightingMatrices();
+
+  void goalCallback(const geometry_msgs::PoseStamped::ConstPtr& msg);
+
+  void scanCallback(const sensor_msgs::LaserScan::ConstPtr& msg);
+
+  void printInformation();
+};
+
+}
+
+#endif /* INCLUDE_MAV_NONLINEAR_MPC_NONLINEAR_MPC_H_ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/include/mav_nonlinear_mpc/nonlinear_mpc_node.h b/mav_control_rw/mav_nonlinear_mpc/include/mav_nonlinear_mpc/nonlinear_mpc_node.h
new file mode 100644
index 0000000000000000000000000000000000000000..3d8c55bdd09be34c1f155a8239e2d4f0f66954c8
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/include/mav_nonlinear_mpc/nonlinear_mpc_node.h
@@ -0,0 +1,37 @@
+#ifndef INCLUDE_MAV_NONLINEAR_MPC_NONLINEAR_MPC_NODE_H_
+#define INCLUDE_MAV_NONLINEAR_MPC_NONLINEAR_MPC_NODE_H_
+
+#include <boost/bind.hpp>
+#include <Eigen/Eigen>
+#include <stdio.h>
+
+//ros
+#include <ros/ros.h>
+#include <ros/callback_queue.h>
+
+//ros msgs
+
+//dynamic reconfiguration
+#include <dynamic_reconfigure/server.h>
+#include <mav_nonlinear_mpc/NonLinearMPCConfig.h>
+
+#include <mav_nonlinear_mpc/nonlinear_mpc.h>
+
+namespace mav_control {
+
+class NonLinearModelPredictiveControllerNode {
+ public:
+  NonLinearModelPredictiveControllerNode(ros::NodeHandle& nh, const ros::NodeHandle& private_nh);
+  ~NonLinearModelPredictiveControllerNode();
+
+  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
+ private:
+  NonlinearModelPredictiveControl nonlinear_mpc_;
+
+  dynamic_reconfigure::Server<mav_nonlinear_mpc::NonLinearMPCConfig> controller_dyn_config_server_;
+};
+
+}
+
+
+#endif /* INCLUDE_MAV_NONLINEAR_MPC_NONLINEAR_MPC_NODE_H_ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/launch/mav_nonlinear_mpc.launch b/mav_control_rw/mav_nonlinear_mpc/launch/mav_nonlinear_mpc.launch
new file mode 100644
index 0000000000000000000000000000000000000000..b286cac627be368f50d8a6563f039fc5f26fe275
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/launch/mav_nonlinear_mpc.launch
@@ -0,0 +1,14 @@
+<launch>
+  <arg name="mav_name" default="husky" />
+  <arg name="namespace" default="$(arg mav_name)"/>    
+  <group ns="$(arg namespace)">
+    <node name="mav_nonlinear_mpc" pkg="mav_nonlinear_mpc" type="nonlinear_mpc_node" respawn="true" clear_params="true" output="screen">
+      <remap from="odometry" to="ground_truth/odometry" />
+      <rosparam file="$(find mav_nonlinear_mpc)/resources/nonlinear_mpc_$(arg mav_name).yaml" />
+      <param name="use_rc_teleop" value="true"/>
+      <param name="verbose" value="true" />
+      <param name="reference_frame" value="world"/>
+      <param name="use_sim_time" value="true"/>
+    </node>
+  </group>
+</launch>
diff --git a/mav_control_rw/mav_nonlinear_mpc/launch/mav_nonlinear_mpc_sim.launch b/mav_control_rw/mav_nonlinear_mpc/launch/mav_nonlinear_mpc_sim.launch
new file mode 100644
index 0000000000000000000000000000000000000000..3e496cbaa877a14faf1cfb2abbc342549ea189e3
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/launch/mav_nonlinear_mpc_sim.launch
@@ -0,0 +1,13 @@
+<launch>
+  <arg name="mav_name" default="husky" />
+  <arg name="namespace" default="$(arg mav_name)"/>
+  <group ns="$(arg namespace)">
+    <node name="mav_nonlinear_mpc" pkg="mav_nonlinear_mpc" type="nonlinear_mpc_node" respawn="true" clear_params="true" output="screen">
+      <remap from="odometry" to="ground_truth/odometry" />
+      <rosparam file="$(find mav_nonlinear_mpc)/resources/nonlinear_mpc_$(arg mav_name).yaml" />
+      <param name="use_rc_teleop" value="false"/>
+      <param name="verbose" value="true" />
+      <param name="reference_frame" value="world"/>
+    </node>
+  </group>
+</launch>
diff --git a/mav_control_rw/mav_nonlinear_mpc/package.xml b/mav_control_rw/mav_nonlinear_mpc/package.xml
new file mode 100644
index 0000000000000000000000000000000000000000..cd6a522887aeea2ea3cf397581b0133e964f38c2
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/package.xml
@@ -0,0 +1,21 @@
+<?xml version="1.0"?>
+<package format="2">
+  <name>mav_nonlinear_mpc</name>
+  <version>1.0.0</version>
+  <description>
+    Nonlinear model predictive controller for trajectory tracking of multirotor system
+  </description>
+
+  <maintainer email="mina.kamel@mavt.ethz.com">Mina Kamel</maintainer>
+
+  <license>BSD</license>
+
+  <buildtool_depend>catkin</buildtool_depend>
+  <buildtool_depend>catkin_simple</buildtool_depend>
+
+  <depend>std_msgs</depend>
+  <depend>cmake_modules</depend>
+  <depend>roscpp</depend>
+  <depend>dynamic_reconfigure</depend>
+  <depend>tf</depend>
+</package>
diff --git a/mav_control_rw/mav_nonlinear_mpc/resources/nonlinear_mpc_firefly.yaml b/mav_control_rw/mav_nonlinear_mpc/resources/nonlinear_mpc_firefly.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..3c6aa848d8bf6fd0fa992faa0962b159b2cc9e9a
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/resources/nonlinear_mpc_firefly.yaml
@@ -0,0 +1,53 @@
+#==================================================================================================================
+#
+# Project:	Nonlinear MPC for Hexacopter trajectory tracking.
+#
+# function:	NMPC Position controller parameters.
+#
+# Author:	Mina Kamel	mina.kamel@ethz.ch
+#
+# Generated:	20-Dec-2015 02:37:59
+#
+#==================================================================================================================
+
+## Controller Parameters:
+mass: 1.56
+roll_time_constant: 0.257
+roll_gain: 0.75
+pitch_time_constant: 0.259
+pitch_gain: 0.78
+linear_drag_coefficients: [0.01, 0.01, 0]
+
+# dynamic config default values:
+q_x : 80
+q_y : 80
+q_z : 120
+
+q_vx : 80
+q_vy : 80
+q_vz : 100
+
+q_roll : 10
+q_pitch: 10
+
+r_roll  : 50
+r_pitch : 50
+r_thrust : 1
+
+roll_max: deg(25.0)
+pitch_max: deg(25.0)
+thrust_min: 5
+thrust_max: 20
+
+K_yaw: 1.8
+
+Ki_xy: 0.2
+Ki_z: 0.3
+position_error_integration_limit: 2
+antiwindup_ball: 0.4
+
+enable_offset_free : true
+enable_integrator : true
+
+sampling_time: 0.01    #IMPORTANT: set this equal to the rate of odometry msg
+prediction_sampling_time: 0.1
\ No newline at end of file
diff --git a/mav_control_rw/mav_nonlinear_mpc/resources/nonlinear_mpc_hummingbird.yaml b/mav_control_rw/mav_nonlinear_mpc/resources/nonlinear_mpc_hummingbird.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..c1def79f609bb4b6bbaa6b8594e2e266cc7e6f88
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/resources/nonlinear_mpc_hummingbird.yaml
@@ -0,0 +1,53 @@
+#==================================================================================================================
+#
+# Project:	Nonlinear MPC for Hexacopter trajectory tracking.
+#
+# function:	NMPC Position controller parameters.
+#
+# Author:	Mina Kamel	mina.kamel@ethz.ch
+#
+# Generated:	20-Dec-2015 02:37:59
+#
+#==================================================================================================================
+
+## Controller Parameters:
+mass: 0.68
+roll_time_constant: 0.2
+pitch_time_constant: 0.23
+roll_gain: 0.85
+pitch_gain: 0.86
+drag_coefficients: [ 0.010000 , 0.010000, 0.0000]
+
+# dynamic config default values:
+q_x : 80
+q_y : 80
+q_z : 120
+
+q_vx : 80
+q_vy : 80
+q_vz : 100
+
+q_roll : 10
+q_pitch: 10
+
+r_roll  : 50
+r_pitch : 50
+r_thrust : 1
+
+roll_max: deg(25.0)
+pitch_max: deg(25.0)
+thrust_min: 5
+thrust_max: 20
+
+K_yaw: 1.8
+
+Ki_xy: 0.2
+Ki_z: 0.3
+position_error_integration_limit: 2
+antiwindup_ball: 0.4
+
+enable_offset_free : true
+enable_integrator : true
+
+sampling_time: 0.01    #IMPORTANT: set this equal to the rate of odometry msg
+prediction_sampling_time: 0.1
diff --git a/mav_control_rw/mav_nonlinear_mpc/resources/nonlinear_mpc_husky.yaml b/mav_control_rw/mav_nonlinear_mpc/resources/nonlinear_mpc_husky.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..1f29463648a9c8def9ae016e4cd1aaf9d290d572
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/resources/nonlinear_mpc_husky.yaml
@@ -0,0 +1,9 @@
+## Controller Parameters:
+mass: 1.56
+
+# dynamic config default values:
+thrust_min: 5
+thrust_max: 20
+
+sampling_time: 0.01    #IMPORTANT: set this equal to the rate of odometry msg
+prediction_sampling_time: 0.1
\ No newline at end of file
diff --git a/mav_control_rw/mav_nonlinear_mpc/resources/nonlinear_mpc_neo11.yaml b/mav_control_rw/mav_nonlinear_mpc/resources/nonlinear_mpc_neo11.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..1490df4812485b7a1dd2f59ac2cbfad5f19b7794
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/resources/nonlinear_mpc_neo11.yaml
@@ -0,0 +1,53 @@
+#==================================================================================================================
+#
+# Project:	Nonlinear MPC for Hexacopter trajectory tracking.
+#
+# function:	NMPC Position controller parameters.
+#
+# Author:	Mina Kamel	mina.kamel@ethz.ch
+#
+# Generated:	20-Dec-2015 02:37:59
+#
+#==================================================================================================================
+
+## Controller Parameters:
+mass: 3.5
+roll_time_constant: 0.257
+roll_gain: 0.75
+pitch_time_constant: 0.259
+pitch_gain: 0.78
+linear_drag_coefficients: [0.01, 0.01, 0]
+
+# dynamic config default values:
+q_x : 80
+q_y : 80
+q_z : 120
+
+q_vx : 80
+q_vy : 80
+q_vz : 100
+
+q_roll : 10
+q_pitch: 10
+
+r_roll  : 50
+r_pitch : 50
+r_thrust : 1
+
+roll_max: deg(25.0)
+pitch_max: deg(25.0)
+thrust_min: 5
+thrust_max: 20
+
+K_yaw: 1.8
+
+Ki_xy: 0.2
+Ki_z: 0.3
+position_error_integration_limit: 2
+antiwindup_ball: 0.4
+
+enable_offset_free : true
+enable_integrator : true
+
+sampling_time: 0.01    #IMPORTANT: set this equal to the rate of odometry msg
+prediction_sampling_time: 0.1
\ No newline at end of file
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CATKIN_IGNORE b/mav_control_rw/mav_nonlinear_mpc/solver/CATKIN_IGNORE
new file mode 100644
index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeCache.txt b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeCache.txt
new file mode 100644
index 0000000000000000000000000000000000000000..7d2907421d0d9c0216355e1a3c33a88ecba36eb8
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeCache.txt
@@ -0,0 +1,1003 @@
+# This is the CMakeCache file.
+# For build in directory: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+# It was generated by CMake: /usr/bin/cmake
+# You can edit this file to change values found and used by cmake.
+# If you do not want to change any of the values, simply exit the editor.
+# If you do want to change a value, simply edit, save, and exit the editor.
+# The syntax for the file is as follows:
+# KEY:TYPE=VALUE
+# KEY is the name of a variable in the cache.
+# TYPE is a hint to GUIs for the type of VALUE, DO NOT EDIT TYPE!.
+# VALUE is the current value for the KEY.
+
+########################
+# EXTERNAL cache entries
+########################
+
+//Path to a library.
+BLAS_Accelerate_LIBRARY:FILEPATH=BLAS_Accelerate_LIBRARY-NOTFOUND
+
+//Path to a library.
+BLAS_acml_LIBRARY:FILEPATH=BLAS_acml_LIBRARY-NOTFOUND
+
+//Path to a library.
+BLAS_acml_mp_LIBRARY:FILEPATH=BLAS_acml_mp_LIBRARY-NOTFOUND
+
+//Path to a library.
+BLAS_blas_LIBRARY:FILEPATH=/usr/lib/x86_64-linux-gnu/libblas.so
+
+//Path to a library.
+BLAS_blis_LIBRARY:FILEPATH=BLAS_blis_LIBRARY-NOTFOUND
+
+//Path to a library.
+BLAS_complib.sgimath_LIBRARY:FILEPATH=BLAS_complib.sgimath_LIBRARY-NOTFOUND
+
+//Path to a library.
+BLAS_cxml_LIBRARY:FILEPATH=BLAS_cxml_LIBRARY-NOTFOUND
+
+//Path to a library.
+BLAS_dxml_LIBRARY:FILEPATH=BLAS_dxml_LIBRARY-NOTFOUND
+
+//Path to a library.
+BLAS_essl_LIBRARY:FILEPATH=BLAS_essl_LIBRARY-NOTFOUND
+
+//Path to a library.
+BLAS_f77blas_LIBRARY:FILEPATH=BLAS_f77blas_LIBRARY-NOTFOUND
+
+//Path to a library.
+BLAS_goto2_LIBRARY:FILEPATH=BLAS_goto2_LIBRARY-NOTFOUND
+
+//Path to a library.
+BLAS_mkl_LIBRARY:FILEPATH=BLAS_mkl_LIBRARY-NOTFOUND
+
+//Path to a library.
+BLAS_mkl_em64t_LIBRARY:FILEPATH=BLAS_mkl_em64t_LIBRARY-NOTFOUND
+
+//Path to a library.
+BLAS_mkl_ia32_LIBRARY:FILEPATH=BLAS_mkl_ia32_LIBRARY-NOTFOUND
+
+//Path to a library.
+BLAS_mkl_intel_LIBRARY:FILEPATH=BLAS_mkl_intel_LIBRARY-NOTFOUND
+
+//Path to a library.
+BLAS_mkl_intel_lp64_LIBRARY:FILEPATH=BLAS_mkl_intel_lp64_LIBRARY-NOTFOUND
+
+//Path to a library.
+BLAS_openblas_LIBRARY:FILEPATH=BLAS_openblas_LIBRARY-NOTFOUND
+
+//Path to a library.
+BLAS_scsl_LIBRARY:FILEPATH=BLAS_scsl_LIBRARY-NOTFOUND
+
+//Path to a library.
+BLAS_sgemm_LIBRARY:FILEPATH=BLAS_sgemm_LIBRARY-NOTFOUND
+
+//Path to a library.
+BLAS_sunperf_LIBRARY:FILEPATH=BLAS_sunperf_LIBRARY-NOTFOUND
+
+//Path to a library.
+BLAS_vecLib_LIBRARY:FILEPATH=BLAS_vecLib_LIBRARY-NOTFOUND
+
+//Builds the googlemock subproject
+BUILD_GMOCK:BOOL=ON
+
+//Build dynamically-linked binaries
+BUILD_SHARED_LIBS:BOOL=ON
+
+//Catkin enable testing
+CATKIN_ENABLE_TESTING:BOOL=ON
+
+//Prefix to apply to package generated via gendebian
+CATKIN_PACKAGE_PREFIX:STRING=
+
+//Catkin skip testing
+CATKIN_SKIP_TESTING:BOOL=OFF
+
+//Replace the CMake install command with a custom implementation
+// using symlinks instead of copying resources
+CATKIN_SYMLINK_INSTALL:BOOL=OFF
+
+//Path to a program.
+CMAKE_ADDR2LINE:FILEPATH=/usr/bin/addr2line
+
+//Path to a program.
+CMAKE_AR:FILEPATH=/usr/bin/ar
+
+//Choose the type of build, options are: None Debug Release RelWithDebInfo
+// MinSizeRel ...
+CMAKE_BUILD_TYPE:STRING=
+
+//Enable/Disable color output during build.
+CMAKE_COLOR_MAKEFILE:BOOL=ON
+
+//CXX compiler
+CMAKE_CXX_COMPILER:FILEPATH=/usr/bin/c++
+
+//A wrapper around 'ar' adding the appropriate '--plugin' option
+// for the GCC compiler
+CMAKE_CXX_COMPILER_AR:FILEPATH=/usr/bin/gcc-ar-9
+
+//A wrapper around 'ranlib' adding the appropriate '--plugin' option
+// for the GCC compiler
+CMAKE_CXX_COMPILER_RANLIB:FILEPATH=/usr/bin/gcc-ranlib-9
+
+//Flags used by the CXX compiler during all build types.
+CMAKE_CXX_FLAGS:STRING=
+
+//Flags used by the CXX compiler during DEBUG builds.
+CMAKE_CXX_FLAGS_DEBUG:STRING=-g
+
+//Flags used by the CXX compiler during MINSIZEREL builds.
+CMAKE_CXX_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG
+
+//Flags used by the CXX compiler during RELEASE builds.
+CMAKE_CXX_FLAGS_RELEASE:STRING=-O3 -DNDEBUG
+
+//Flags used by the CXX compiler during RELWITHDEBINFO builds.
+CMAKE_CXX_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG
+
+//C compiler
+CMAKE_C_COMPILER:FILEPATH=/usr/bin/cc
+
+//A wrapper around 'ar' adding the appropriate '--plugin' option
+// for the GCC compiler
+CMAKE_C_COMPILER_AR:FILEPATH=/usr/bin/gcc-ar-9
+
+//A wrapper around 'ranlib' adding the appropriate '--plugin' option
+// for the GCC compiler
+CMAKE_C_COMPILER_RANLIB:FILEPATH=/usr/bin/gcc-ranlib-9
+
+//Flags used by the C compiler during all build types.
+CMAKE_C_FLAGS:STRING=
+
+//Flags used by the C compiler during DEBUG builds.
+CMAKE_C_FLAGS_DEBUG:STRING=-g
+
+//Flags used by the C compiler during MINSIZEREL builds.
+CMAKE_C_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG
+
+//Flags used by the C compiler during RELEASE builds.
+CMAKE_C_FLAGS_RELEASE:STRING=-O3 -DNDEBUG
+
+//Flags used by the C compiler during RELWITHDEBINFO builds.
+CMAKE_C_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG
+
+//Path to a program.
+CMAKE_DLLTOOL:FILEPATH=CMAKE_DLLTOOL-NOTFOUND
+
+//Flags used by the linker during all build types.
+CMAKE_EXE_LINKER_FLAGS:STRING=
+
+//Flags used by the linker during DEBUG builds.
+CMAKE_EXE_LINKER_FLAGS_DEBUG:STRING=
+
+//Flags used by the linker during MINSIZEREL builds.
+CMAKE_EXE_LINKER_FLAGS_MINSIZEREL:STRING=
+
+//Flags used by the linker during RELEASE builds.
+CMAKE_EXE_LINKER_FLAGS_RELEASE:STRING=
+
+//Flags used by the linker during RELWITHDEBINFO builds.
+CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO:STRING=
+
+//Enable/Disable output of compile commands during generation.
+CMAKE_EXPORT_COMPILE_COMMANDS:BOOL=OFF
+
+//User executables (bin)
+CMAKE_INSTALL_BINDIR:PATH=bin
+
+//Read-only architecture-independent data (DATAROOTDIR)
+CMAKE_INSTALL_DATADIR:PATH=
+
+//Read-only architecture-independent data root (share)
+CMAKE_INSTALL_DATAROOTDIR:PATH=share
+
+//Documentation root (DATAROOTDIR/doc/PROJECT_NAME)
+CMAKE_INSTALL_DOCDIR:PATH=
+
+//C header files (include)
+CMAKE_INSTALL_INCLUDEDIR:PATH=include
+
+//Info documentation (DATAROOTDIR/info)
+CMAKE_INSTALL_INFODIR:PATH=
+
+//Object code libraries (lib)
+CMAKE_INSTALL_LIBDIR:PATH=lib
+
+//Program executables (libexec)
+CMAKE_INSTALL_LIBEXECDIR:PATH=libexec
+
+//Locale-dependent data (DATAROOTDIR/locale)
+CMAKE_INSTALL_LOCALEDIR:PATH=
+
+//Modifiable single-machine data (var)
+CMAKE_INSTALL_LOCALSTATEDIR:PATH=var
+
+//Man documentation (DATAROOTDIR/man)
+CMAKE_INSTALL_MANDIR:PATH=
+
+//C header files for non-gcc (/usr/include)
+CMAKE_INSTALL_OLDINCLUDEDIR:PATH=/usr/include
+
+//Install path prefix, prepended onto install directories.
+CMAKE_INSTALL_PREFIX:PATH=/usr/local
+
+//Run-time variable data (LOCALSTATEDIR/run)
+CMAKE_INSTALL_RUNSTATEDIR:PATH=
+
+//System admin executables (sbin)
+CMAKE_INSTALL_SBINDIR:PATH=sbin
+
+//Modifiable architecture-independent data (com)
+CMAKE_INSTALL_SHAREDSTATEDIR:PATH=com
+
+//Read-only single-machine data (etc)
+CMAKE_INSTALL_SYSCONFDIR:PATH=etc
+
+//Path to a program.
+CMAKE_LINKER:FILEPATH=/usr/bin/ld
+
+//Path to a program.
+CMAKE_MAKE_PROGRAM:FILEPATH=/usr/bin/make
+
+//Flags used by the linker during the creation of modules during
+// all build types.
+CMAKE_MODULE_LINKER_FLAGS:STRING=
+
+//Flags used by the linker during the creation of modules during
+// DEBUG builds.
+CMAKE_MODULE_LINKER_FLAGS_DEBUG:STRING=
+
+//Flags used by the linker during the creation of modules during
+// MINSIZEREL builds.
+CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL:STRING=
+
+//Flags used by the linker during the creation of modules during
+// RELEASE builds.
+CMAKE_MODULE_LINKER_FLAGS_RELEASE:STRING=
+
+//Flags used by the linker during the creation of modules during
+// RELWITHDEBINFO builds.
+CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO:STRING=
+
+//Path to a program.
+CMAKE_NM:FILEPATH=/usr/bin/nm
+
+//Path to a program.
+CMAKE_OBJCOPY:FILEPATH=/usr/bin/objcopy
+
+//Path to a program.
+CMAKE_OBJDUMP:FILEPATH=/usr/bin/objdump
+
+//Value Computed by CMake
+CMAKE_PROJECT_DESCRIPTION:STATIC=
+
+//Value Computed by CMake
+CMAKE_PROJECT_HOMEPAGE_URL:STATIC=
+
+//Value Computed by CMake
+CMAKE_PROJECT_NAME:STATIC=mav_nonlinear_mpc
+
+//Value Computed by CMake
+CMAKE_PROJECT_VERSION:STATIC=1.10.0
+
+//Value Computed by CMake
+CMAKE_PROJECT_VERSION_MAJOR:STATIC=1
+
+//Value Computed by CMake
+CMAKE_PROJECT_VERSION_MINOR:STATIC=10
+
+//Value Computed by CMake
+CMAKE_PROJECT_VERSION_PATCH:STATIC=0
+
+//Value Computed by CMake
+CMAKE_PROJECT_VERSION_TWEAK:STATIC=
+
+//Path to a program.
+CMAKE_RANLIB:FILEPATH=/usr/bin/ranlib
+
+//Path to a program.
+CMAKE_READELF:FILEPATH=/usr/bin/readelf
+
+//Flags used by the linker during the creation of shared libraries
+// during all build types.
+CMAKE_SHARED_LINKER_FLAGS:STRING=
+
+//Flags used by the linker during the creation of shared libraries
+// during DEBUG builds.
+CMAKE_SHARED_LINKER_FLAGS_DEBUG:STRING=
+
+//Flags used by the linker during the creation of shared libraries
+// during MINSIZEREL builds.
+CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL:STRING=
+
+//Flags used by the linker during the creation of shared libraries
+// during RELEASE builds.
+CMAKE_SHARED_LINKER_FLAGS_RELEASE:STRING=
+
+//Flags used by the linker during the creation of shared libraries
+// during RELWITHDEBINFO builds.
+CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO:STRING=
+
+//If set, runtime paths are not added when installing shared libraries,
+// but are added when building.
+CMAKE_SKIP_INSTALL_RPATH:BOOL=NO
+
+//If set, runtime paths are not added when using shared libraries.
+CMAKE_SKIP_RPATH:BOOL=NO
+
+//Flags used by the linker during the creation of static libraries
+// during all build types.
+CMAKE_STATIC_LINKER_FLAGS:STRING=
+
+//Flags used by the linker during the creation of static libraries
+// during DEBUG builds.
+CMAKE_STATIC_LINKER_FLAGS_DEBUG:STRING=
+
+//Flags used by the linker during the creation of static libraries
+// during MINSIZEREL builds.
+CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL:STRING=
+
+//Flags used by the linker during the creation of static libraries
+// during RELEASE builds.
+CMAKE_STATIC_LINKER_FLAGS_RELEASE:STRING=
+
+//Flags used by the linker during the creation of static libraries
+// during RELWITHDEBINFO builds.
+CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO:STRING=
+
+//Path to a program.
+CMAKE_STRIP:FILEPATH=/usr/bin/strip
+
+//If this value is on, makefiles will be generated without the
+// .SILENT directive, and all commands will be echoed to the console
+// during the make.  This is useful for debugging only. With Visual
+// Studio IDE projects all commands are done without /nologo.
+CMAKE_VERBOSE_MAKEFILE:BOOL=FALSE
+
+//Path to a program.
+DOXYGEN_EXECUTABLE:FILEPATH=/usr/bin/doxygen
+
+//Doxygen found
+DOXYGEN_FOUND:BOOL=TRUE
+
+//Path to a file.
+EIGEN_INCLUDE_DIR:PATH=/usr/include/eigen3
+
+//Path to a program.
+EMPY_EXECUTABLE:FILEPATH=EMPY_EXECUTABLE-NOTFOUND
+
+//Empy script
+EMPY_SCRIPT:STRING=/usr/lib/python3/dist-packages/em.py
+
+//Path to a library.
+GMOCK_LIBRARY:FILEPATH=GMOCK_LIBRARY-NOTFOUND
+
+//Path to a library.
+GMOCK_LIBRARY_DEBUG:FILEPATH=GMOCK_LIBRARY_DEBUG-NOTFOUND
+
+//Path to a library.
+GMOCK_MAIN_LIBRARY:FILEPATH=GMOCK_MAIN_LIBRARY-NOTFOUND
+
+//Path to a library.
+GMOCK_MAIN_LIBRARY_DEBUG:FILEPATH=GMOCK_MAIN_LIBRARY_DEBUG-NOTFOUND
+
+//The directory containing a CMake configuration file for GMock.
+GMock_DIR:PATH=GMock_DIR-NOTFOUND
+
+//Path to a file.
+GTEST_INCLUDE_DIR:PATH=/usr/include
+
+//Path to a library.
+GTEST_LIBRARY:FILEPATH=/usr/lib/x86_64-linux-gnu/libgtest.a
+
+//Path to a library.
+GTEST_LIBRARY_DEBUG:FILEPATH=GTEST_LIBRARY_DEBUG-NOTFOUND
+
+//Path to a library.
+GTEST_MAIN_LIBRARY:FILEPATH=/usr/lib/x86_64-linux-gnu/libgtest_main.a
+
+//Path to a library.
+GTEST_MAIN_LIBRARY_DEBUG:FILEPATH=GTEST_MAIN_LIBRARY_DEBUG-NOTFOUND
+
+//The directory containing a CMake configuration file for GTest.
+GTest_DIR:PATH=GTest_DIR-NOTFOUND
+
+//Enable installation of googletest. (Projects embedding googletest
+// may want to turn this OFF.)
+INSTALL_GTEST:BOOL=OFF
+
+//Path to a library.
+LAPACK_Accelerate_LIBRARY:FILEPATH=LAPACK_Accelerate_LIBRARY-NOTFOUND
+
+//Path to a library.
+LAPACK_flame_LIBRARY:FILEPATH=LAPACK_flame_LIBRARY-NOTFOUND
+
+//Path to a library.
+LAPACK_goto2_LIBRARY:FILEPATH=LAPACK_goto2_LIBRARY-NOTFOUND
+
+//Path to a library.
+LAPACK_lapack_LIBRARY:FILEPATH=/usr/lib/x86_64-linux-gnu/liblapack.so
+
+//Path to a library.
+LAPACK_mkl_lapack_LIBRARY:FILEPATH=LAPACK_mkl_lapack_LIBRARY-NOTFOUND
+
+//Path to a library.
+LAPACK_openblas_LIBRARY:FILEPATH=LAPACK_openblas_LIBRARY-NOTFOUND
+
+//Path to a library.
+LAPACK_vecLib_LIBRARY:FILEPATH=LAPACK_vecLib_LIBRARY-NOTFOUND
+
+//lsb_release executable was found
+LSB_FOUND:BOOL=TRUE
+
+//Path to a program.
+LSB_RELEASE_EXECUTABLE:FILEPATH=/usr/bin/lsb_release
+
+//Path to a program.
+NOSETESTS:FILEPATH=/usr/bin/nosetests3
+
+//Path to a file.
+Openblas_INCLUDE_DIR:PATH=Openblas_INCLUDE_DIR-NOTFOUND
+
+//Path to a library.
+Openblas_LIBRARY:FILEPATH=Openblas_LIBRARY-NOTFOUND
+
+//Path to the root of a Openblas installation
+Openblas_ROOT:PATH=
+
+//pkg-config executable
+PKG_CONFIG_EXECUTABLE:FILEPATH=/usr/bin/pkg-config
+
+//Path to a program.
+PYTHON_EXECUTABLE:FILEPATH=/usr/bin/python3
+
+//Specify specific Python version to use ('major.minor' or 'major')
+PYTHON_VERSION:STRING=3
+
+//Location of Python module em
+PY_EM:STRING=/usr/lib/python3/dist-packages/em.py
+
+//Path to a library.
+RT_LIBRARY:FILEPATH=/usr/lib/x86_64-linux-gnu/librt.so
+
+//Enable debian style python package layout
+SETUPTOOLS_DEB_LAYOUT:BOOL=ON
+
+//Name of the computer/site where compile is being run
+SITE:STRING=olympen1-112
+
+//LSB Distrib tag
+UBUNTU:BOOL=TRUE
+
+//LSB Distrib - codename tag
+UBUNTU_FOCAL:BOOL=TRUE
+
+//Path to a file.
+_gmock_INCLUDES:FILEPATH=/usr/src/googletest/googlemock/include/gmock/gmock.h
+
+//Path to a file.
+_gmock_SOURCES:FILEPATH=/usr/src/gmock/src/gmock.cc
+
+//Path to a file.
+_gtest_INCLUDES:FILEPATH=/usr/include/gtest/gtest.h
+
+//Path to a file.
+_gtest_SOURCES:FILEPATH=/usr/src/gtest/src/gtest.cc
+
+//The directory containing a CMake configuration file for actionlib.
+actionlib_DIR:PATH=/opt/ros/noetic/share/actionlib/cmake
+
+//The directory containing a CMake configuration file for actionlib_msgs.
+actionlib_msgs_DIR:PATH=/home/simhe502/catkin_ws/devel/share/actionlib_msgs/cmake
+
+//The directory containing a CMake configuration file for catkin.
+catkin_DIR:PATH=/opt/ros/noetic/share/catkin/cmake
+
+//The directory containing a CMake configuration file for catkin_simple.
+catkin_simple_DIR:PATH=/home/simhe502/catkin_ws/devel/share/catkin_simple/cmake
+
+//The directory containing a CMake configuration file for cmake_modules.
+cmake_modules_DIR:PATH=/opt/ros/noetic/share/cmake_modules/cmake
+
+//The directory containing a CMake configuration file for cpp_common.
+cpp_common_DIR:PATH=/opt/ros/noetic/share/cpp_common/cmake
+
+//The directory containing a CMake configuration file for dynamic_reconfigure.
+dynamic_reconfigure_DIR:PATH=/opt/ros/noetic/share/dynamic_reconfigure/cmake
+
+//The directory containing a CMake configuration file for gencpp.
+gencpp_DIR:PATH=/opt/ros/noetic/share/gencpp/cmake
+
+//The directory containing a CMake configuration file for geneus.
+geneus_DIR:PATH=/opt/ros/noetic/share/geneus/cmake
+
+//The directory containing a CMake configuration file for genlisp.
+genlisp_DIR:PATH=/opt/ros/noetic/share/genlisp/cmake
+
+//The directory containing a CMake configuration file for genmsg.
+genmsg_DIR:PATH=/opt/ros/noetic/share/genmsg/cmake
+
+//The directory containing a CMake configuration file for gennodejs.
+gennodejs_DIR:PATH=/opt/ros/noetic/share/gennodejs/cmake
+
+//The directory containing a CMake configuration file for genpy.
+genpy_DIR:PATH=/opt/ros/noetic/share/genpy/cmake
+
+//The directory containing a CMake configuration file for geometry_msgs.
+geometry_msgs_DIR:PATH=/home/simhe502/catkin_ws/devel/share/geometry_msgs/cmake
+
+//Value Computed by CMake
+gmock_BINARY_DIR:STATIC=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock
+
+//Dependencies for the target
+gmock_LIB_DEPENDS:STATIC=general;gtest;
+
+//Value Computed by CMake
+gmock_SOURCE_DIR:STATIC=/usr/src/googletest/googlemock
+
+//Build all of Google Mock's own tests.
+gmock_build_tests:BOOL=OFF
+
+//Dependencies for the target
+gmock_main_LIB_DEPENDS:STATIC=general;gmock;
+
+//Value Computed by CMake
+googletest-distribution_BINARY_DIR:STATIC=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest
+
+//Value Computed by CMake
+googletest-distribution_SOURCE_DIR:STATIC=/usr/src/googletest
+
+//Value Computed by CMake
+gtest_BINARY_DIR:STATIC=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest
+
+//Value Computed by CMake
+gtest_SOURCE_DIR:STATIC=/usr/src/googletest/googletest
+
+//Build gtest's sample programs.
+gtest_build_samples:BOOL=OFF
+
+//Build all of gtest's own tests.
+gtest_build_tests:BOOL=OFF
+
+//Disable uses of pthreads in gtest.
+gtest_disable_pthreads:BOOL=OFF
+
+//Use shared (DLL) run-time lib even when Google Test is built
+// as static lib.
+gtest_force_shared_crt:BOOL=OFF
+
+//Build gtest with internal symbols hidden in shared libraries.
+gtest_hide_internal_symbols:BOOL=OFF
+
+//Dependencies for the target
+gtest_main_LIB_DEPENDS:STATIC=general;gtest;
+
+//Path to a library.
+lib:FILEPATH=/opt/ros/noetic/lib/libtf2.so
+
+//Value Computed by CMake
+mav_nonlinear_mpc_BINARY_DIR:STATIC=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+//Value Computed by CMake
+mav_nonlinear_mpc_SOURCE_DIR:STATIC=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+//Dependencies for the target
+mav_nonlinear_mpc_lib_LIB_DEPENDS:STATIC=general;/opt/ros/noetic/lib/libdynamic_reconfigure_config_init_mutex.so;general;/opt/ros/noetic/lib/libtf.so;general;/opt/ros/noetic/lib/libtf2_ros.so;general;/opt/ros/noetic/lib/libactionlib.so;general;/opt/ros/noetic/lib/libmessage_filters.so;general;/opt/ros/noetic/lib/libroscpp.so;general;/usr/lib/x86_64-linux-gnu/libpthread.so;general;/usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.71.0;general;/usr/lib/x86_64-linux-gnu/libboost_filesystem.so.1.71.0;general;/opt/ros/noetic/lib/libxmlrpcpp.so;general;/opt/ros/noetic/lib/libtf2.so;general;/opt/ros/noetic/lib/libroscpp_serialization.so;general;/opt/ros/noetic/lib/librosconsole.so;general;/opt/ros/noetic/lib/librosconsole_log4cxx.so;general;/opt/ros/noetic/lib/librosconsole_backend_interface.so;general;/usr/lib/x86_64-linux-gnu/liblog4cxx.so;general;/usr/lib/x86_64-linux-gnu/libboost_regex.so.1.71.0;general;/opt/ros/noetic/lib/librostime.so;general;/usr/lib/x86_64-linux-gnu/libboost_date_time.so.1.71.0;general;/opt/ros/noetic/lib/libcpp_common.so;general;/usr/lib/x86_64-linux-gnu/libboost_system.so.1.71.0;general;/usr/lib/x86_64-linux-gnu/libboost_thread.so.1.71.0;general;/usr/lib/x86_64-linux-gnu/libconsole_bridge.so.0.4;general;/opt/ros/noetic/lib/libdynamic_reconfigure_config_init_mutex.so;general;/opt/ros/noetic/lib/libtf.so;general;/opt/ros/noetic/lib/libtf2_ros.so;general;/opt/ros/noetic/lib/libactionlib.so;general;/opt/ros/noetic/lib/libmessage_filters.so;general;/opt/ros/noetic/lib/libroscpp.so;general;/usr/lib/x86_64-linux-gnu/libpthread.so;general;/usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.71.0;general;/usr/lib/x86_64-linux-gnu/libboost_filesystem.so.1.71.0;general;/opt/ros/noetic/lib/libxmlrpcpp.so;general;/opt/ros/noetic/lib/libtf2.so;general;/opt/ros/noetic/lib/libroscpp_serialization.so;general;/opt/ros/noetic/lib/librosconsole.so;general;/opt/ros/noetic/lib/librosconsole_log4cxx.so;general;/opt/ros/noetic/lib/librosconsole_backend_interface.so;general;/usr/lib/x86_64-linux-gnu/liblog4cxx.so;general;/usr/lib/x86_64-linux-gnu/libboost_regex.so.1.71.0;general;/opt/ros/noetic/lib/librostime.so;general;/usr/lib/x86_64-linux-gnu/libboost_date_time.so.1.71.0;general;/opt/ros/noetic/lib/libcpp_common.so;general;/usr/lib/x86_64-linux-gnu/libboost_system.so.1.71.0;general;/usr/lib/x86_64-linux-gnu/libboost_thread.so.1.71.0;general;/usr/lib/x86_64-linux-gnu/libconsole_bridge.so.0.4;
+
+//The directory containing a CMake configuration file for message_filters.
+message_filters_DIR:PATH=/opt/ros/noetic/share/message_filters/cmake
+
+//The directory containing a CMake configuration file for message_generation.
+message_generation_DIR:PATH=/opt/ros/noetic/share/message_generation/cmake
+
+//The directory containing a CMake configuration file for message_runtime.
+message_runtime_DIR:PATH=/opt/ros/noetic/share/message_runtime/cmake
+
+//The directory containing a CMake configuration file for rosconsole.
+rosconsole_DIR:PATH=/opt/ros/noetic/share/rosconsole/cmake
+
+//The directory containing a CMake configuration file for roscpp.
+roscpp_DIR:PATH=/opt/ros/noetic/share/roscpp/cmake
+
+//The directory containing a CMake configuration file for roscpp_serialization.
+roscpp_serialization_DIR:PATH=/opt/ros/noetic/share/roscpp_serialization/cmake
+
+//The directory containing a CMake configuration file for roscpp_traits.
+roscpp_traits_DIR:PATH=/opt/ros/noetic/share/roscpp_traits/cmake
+
+//The directory containing a CMake configuration file for rosgraph.
+rosgraph_DIR:PATH=/opt/ros/noetic/share/rosgraph/cmake
+
+//The directory containing a CMake configuration file for rosgraph_msgs.
+rosgraph_msgs_DIR:PATH=/opt/ros/noetic/share/rosgraph_msgs/cmake
+
+//The directory containing a CMake configuration file for rospy.
+rospy_DIR:PATH=/opt/ros/noetic/share/rospy/cmake
+
+//The directory containing a CMake configuration file for rostime.
+rostime_DIR:PATH=/opt/ros/noetic/share/rostime/cmake
+
+//The directory containing a CMake configuration file for sensor_msgs.
+sensor_msgs_DIR:PATH=/home/simhe502/catkin_ws/devel/share/sensor_msgs/cmake
+
+//The directory containing a CMake configuration file for std_msgs.
+std_msgs_DIR:PATH=/opt/ros/noetic/share/std_msgs/cmake
+
+//The directory containing a CMake configuration file for tf2.
+tf2_DIR:PATH=/opt/ros/noetic/share/tf2/cmake
+
+//The directory containing a CMake configuration file for tf2_msgs.
+tf2_msgs_DIR:PATH=/opt/ros/noetic/share/tf2_msgs/cmake
+
+//The directory containing a CMake configuration file for tf2_py.
+tf2_py_DIR:PATH=/opt/ros/noetic/share/tf2_py/cmake
+
+//The directory containing a CMake configuration file for tf2_ros.
+tf2_ros_DIR:PATH=/opt/ros/noetic/share/tf2_ros/cmake
+
+//The directory containing a CMake configuration file for tf.
+tf_DIR:PATH=/opt/ros/noetic/share/tf/cmake
+
+//The directory containing a CMake configuration file for xmlrpcpp.
+xmlrpcpp_DIR:PATH=/opt/ros/noetic/share/xmlrpcpp/cmake
+
+
+########################
+# INTERNAL cache entries
+########################
+
+//ADVANCED property for variable: BLAS_Accelerate_LIBRARY
+BLAS_Accelerate_LIBRARY-ADVANCED:INTERNAL=1
+//Have function sgemm_
+BLAS_WORKS:INTERNAL=
+//ADVANCED property for variable: BLAS_acml_LIBRARY
+BLAS_acml_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: BLAS_acml_mp_LIBRARY
+BLAS_acml_mp_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: BLAS_blas_LIBRARY
+BLAS_blas_LIBRARY-ADVANCED:INTERNAL=1
+//Have function sgemm_
+BLAS_blas_WORKS:INTERNAL=1
+//ADVANCED property for variable: BLAS_blis_LIBRARY
+BLAS_blis_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: BLAS_complib.sgimath_LIBRARY
+BLAS_complib.sgimath_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: BLAS_cxml_LIBRARY
+BLAS_cxml_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: BLAS_dxml_LIBRARY
+BLAS_dxml_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: BLAS_essl_LIBRARY
+BLAS_essl_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: BLAS_f77blas_LIBRARY
+BLAS_f77blas_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: BLAS_goto2_LIBRARY
+BLAS_goto2_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: BLAS_mkl_LIBRARY
+BLAS_mkl_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: BLAS_mkl_em64t_LIBRARY
+BLAS_mkl_em64t_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: BLAS_mkl_ia32_LIBRARY
+BLAS_mkl_ia32_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: BLAS_mkl_intel_LIBRARY
+BLAS_mkl_intel_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: BLAS_mkl_intel_lp64_LIBRARY
+BLAS_mkl_intel_lp64_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: BLAS_openblas_LIBRARY
+BLAS_openblas_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: BLAS_scsl_LIBRARY
+BLAS_scsl_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: BLAS_sgemm_LIBRARY
+BLAS_sgemm_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: BLAS_sunperf_LIBRARY
+BLAS_sunperf_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: BLAS_vecLib_LIBRARY
+BLAS_vecLib_LIBRARY-ADVANCED:INTERNAL=1
+//catkin environment
+CATKIN_ENV:INTERNAL=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/env_cached.sh
+CATKIN_TEST_RESULTS_DIR:INTERNAL=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/test_results
+//ADVANCED property for variable: CMAKE_ADDR2LINE
+CMAKE_ADDR2LINE-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_AR
+CMAKE_AR-ADVANCED:INTERNAL=1
+//This is the directory where this CMakeCache.txt was created
+CMAKE_CACHEFILE_DIR:INTERNAL=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+//Major version of cmake used to create the current loaded cache
+CMAKE_CACHE_MAJOR_VERSION:INTERNAL=3
+//Minor version of cmake used to create the current loaded cache
+CMAKE_CACHE_MINOR_VERSION:INTERNAL=16
+//Patch version of cmake used to create the current loaded cache
+CMAKE_CACHE_PATCH_VERSION:INTERNAL=3
+//ADVANCED property for variable: CMAKE_COLOR_MAKEFILE
+CMAKE_COLOR_MAKEFILE-ADVANCED:INTERNAL=1
+//Path to CMake executable.
+CMAKE_COMMAND:INTERNAL=/usr/bin/cmake
+//Path to cpack program executable.
+CMAKE_CPACK_COMMAND:INTERNAL=/usr/bin/cpack
+//Path to ctest program executable.
+CMAKE_CTEST_COMMAND:INTERNAL=/usr/bin/ctest
+//ADVANCED property for variable: CMAKE_CXX_COMPILER
+CMAKE_CXX_COMPILER-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_CXX_COMPILER_AR
+CMAKE_CXX_COMPILER_AR-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_CXX_COMPILER_RANLIB
+CMAKE_CXX_COMPILER_RANLIB-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_CXX_FLAGS
+CMAKE_CXX_FLAGS-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_CXX_FLAGS_DEBUG
+CMAKE_CXX_FLAGS_DEBUG-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_CXX_FLAGS_MINSIZEREL
+CMAKE_CXX_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELEASE
+CMAKE_CXX_FLAGS_RELEASE-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELWITHDEBINFO
+CMAKE_CXX_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_C_COMPILER
+CMAKE_C_COMPILER-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_C_COMPILER_AR
+CMAKE_C_COMPILER_AR-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_C_COMPILER_RANLIB
+CMAKE_C_COMPILER_RANLIB-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_C_FLAGS
+CMAKE_C_FLAGS-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_C_FLAGS_DEBUG
+CMAKE_C_FLAGS_DEBUG-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_C_FLAGS_MINSIZEREL
+CMAKE_C_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_C_FLAGS_RELEASE
+CMAKE_C_FLAGS_RELEASE-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_C_FLAGS_RELWITHDEBINFO
+CMAKE_C_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_DLLTOOL
+CMAKE_DLLTOOL-ADVANCED:INTERNAL=1
+//Path to cache edit program executable.
+CMAKE_EDIT_COMMAND:INTERNAL=/usr/bin/ccmake
+//Executable file format
+CMAKE_EXECUTABLE_FORMAT:INTERNAL=ELF
+//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS
+CMAKE_EXE_LINKER_FLAGS-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_DEBUG
+CMAKE_EXE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_MINSIZEREL
+CMAKE_EXE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELEASE
+CMAKE_EXE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO
+CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_EXPORT_COMPILE_COMMANDS
+CMAKE_EXPORT_COMPILE_COMMANDS-ADVANCED:INTERNAL=1
+//Name of external makefile project generator.
+CMAKE_EXTRA_GENERATOR:INTERNAL=
+//Name of generator.
+CMAKE_GENERATOR:INTERNAL=Unix Makefiles
+//Generator instance identifier.
+CMAKE_GENERATOR_INSTANCE:INTERNAL=
+//Name of generator platform.
+CMAKE_GENERATOR_PLATFORM:INTERNAL=
+//Name of generator toolset.
+CMAKE_GENERATOR_TOOLSET:INTERNAL=
+//Test CMAKE_HAVE_LIBC_PTHREAD
+CMAKE_HAVE_LIBC_PTHREAD:INTERNAL=
+//Have library pthreads
+CMAKE_HAVE_PTHREADS_CREATE:INTERNAL=
+//Have library pthread
+CMAKE_HAVE_PTHREAD_CREATE:INTERNAL=1
+//Have include pthread.h
+CMAKE_HAVE_PTHREAD_H:INTERNAL=1
+//Source directory with the top level CMakeLists.txt file for this
+// project
+CMAKE_HOME_DIRECTORY:INTERNAL=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+//ADVANCED property for variable: CMAKE_INSTALL_BINDIR
+CMAKE_INSTALL_BINDIR-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_INSTALL_DATADIR
+CMAKE_INSTALL_DATADIR-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_INSTALL_DATAROOTDIR
+CMAKE_INSTALL_DATAROOTDIR-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_INSTALL_DOCDIR
+CMAKE_INSTALL_DOCDIR-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_INSTALL_INCLUDEDIR
+CMAKE_INSTALL_INCLUDEDIR-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_INSTALL_INFODIR
+CMAKE_INSTALL_INFODIR-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_INSTALL_LIBDIR
+CMAKE_INSTALL_LIBDIR-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_INSTALL_LIBEXECDIR
+CMAKE_INSTALL_LIBEXECDIR-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_INSTALL_LOCALEDIR
+CMAKE_INSTALL_LOCALEDIR-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_INSTALL_LOCALSTATEDIR
+CMAKE_INSTALL_LOCALSTATEDIR-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_INSTALL_MANDIR
+CMAKE_INSTALL_MANDIR-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_INSTALL_OLDINCLUDEDIR
+CMAKE_INSTALL_OLDINCLUDEDIR-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_INSTALL_RUNSTATEDIR
+CMAKE_INSTALL_RUNSTATEDIR-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_INSTALL_SBINDIR
+CMAKE_INSTALL_SBINDIR-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_INSTALL_SHAREDSTATEDIR
+CMAKE_INSTALL_SHAREDSTATEDIR-ADVANCED:INTERNAL=1
+//Install .so files without execute permission.
+CMAKE_INSTALL_SO_NO_EXE:INTERNAL=1
+//ADVANCED property for variable: CMAKE_INSTALL_SYSCONFDIR
+CMAKE_INSTALL_SYSCONFDIR-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_LINKER
+CMAKE_LINKER-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_MAKE_PROGRAM
+CMAKE_MAKE_PROGRAM-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS
+CMAKE_MODULE_LINKER_FLAGS-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_DEBUG
+CMAKE_MODULE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL
+CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELEASE
+CMAKE_MODULE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO
+CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_NM
+CMAKE_NM-ADVANCED:INTERNAL=1
+//number of local generators
+CMAKE_NUMBER_OF_MAKEFILES:INTERNAL=4
+//ADVANCED property for variable: CMAKE_OBJCOPY
+CMAKE_OBJCOPY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_OBJDUMP
+CMAKE_OBJDUMP-ADVANCED:INTERNAL=1
+//Platform information initialized
+CMAKE_PLATFORM_INFO_INITIALIZED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_RANLIB
+CMAKE_RANLIB-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_READELF
+CMAKE_READELF-ADVANCED:INTERNAL=1
+//Path to CMake installation.
+CMAKE_ROOT:INTERNAL=/usr/share/cmake-3.16
+//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS
+CMAKE_SHARED_LINKER_FLAGS-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_DEBUG
+CMAKE_SHARED_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL
+CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELEASE
+CMAKE_SHARED_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO
+CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_SKIP_INSTALL_RPATH
+CMAKE_SKIP_INSTALL_RPATH-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_SKIP_RPATH
+CMAKE_SKIP_RPATH-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS
+CMAKE_STATIC_LINKER_FLAGS-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_DEBUG
+CMAKE_STATIC_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL
+CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELEASE
+CMAKE_STATIC_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO
+CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: CMAKE_STRIP
+CMAKE_STRIP-ADVANCED:INTERNAL=1
+//uname command
+CMAKE_UNAME:INTERNAL=/usr/bin/uname
+//ADVANCED property for variable: CMAKE_VERBOSE_MAKEFILE
+CMAKE_VERBOSE_MAKEFILE-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: EIGEN_INCLUDE_DIR
+EIGEN_INCLUDE_DIR-ADVANCED:INTERNAL=1
+//Details about finding BLAS
+FIND_PACKAGE_MESSAGE_DETAILS_BLAS:INTERNAL=[/usr/lib/x86_64-linux-gnu/libblas.so][v()]
+//Details about finding Eigen
+FIND_PACKAGE_MESSAGE_DETAILS_Eigen:INTERNAL=[/usr/include/eigen3][v()]
+//Details about finding PY_em
+FIND_PACKAGE_MESSAGE_DETAILS_PY_em:INTERNAL=[/usr/lib/python3/dist-packages/em.py][v()]
+//Details about finding PkgConfig
+FIND_PACKAGE_MESSAGE_DETAILS_PkgConfig:INTERNAL=[/usr/bin/pkg-config][v0.29.1()]
+//Details about finding PythonInterp
+FIND_PACKAGE_MESSAGE_DETAILS_PythonInterp:INTERNAL=[/usr/bin/python3][v3.8.10()]
+//Details about finding Threads
+FIND_PACKAGE_MESSAGE_DETAILS_Threads:INTERNAL=[TRUE][v()]
+GMOCK_FROM_SOURCE_FOUND:INTERNAL=TRUE
+GMOCK_FROM_SOURCE_INCLUDE_DIRS:INTERNAL=/usr/src/googletest/googlemock/include
+GMOCK_FROM_SOURCE_LIBRARIES:INTERNAL=gmock
+GMOCK_FROM_SOURCE_LIBRARY_DIRS:INTERNAL=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gmock
+GMOCK_FROM_SOURCE_MAIN_LIBRARIES:INTERNAL=gmock_main
+//ADVANCED property for variable: GMOCK_LIBRARY
+GMOCK_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: GMOCK_LIBRARY_DEBUG
+GMOCK_LIBRARY_DEBUG-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: GMOCK_MAIN_LIBRARY
+GMOCK_MAIN_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: GMOCK_MAIN_LIBRARY_DEBUG
+GMOCK_MAIN_LIBRARY_DEBUG-ADVANCED:INTERNAL=1
+GTEST_FROM_SOURCE_FOUND:INTERNAL=TRUE
+GTEST_FROM_SOURCE_INCLUDE_DIRS:INTERNAL=/usr/include
+GTEST_FROM_SOURCE_LIBRARIES:INTERNAL=gtest
+GTEST_FROM_SOURCE_LIBRARY_DIRS:INTERNAL=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest
+GTEST_FROM_SOURCE_MAIN_LIBRARIES:INTERNAL=gtest_main
+//ADVANCED property for variable: GTEST_INCLUDE_DIR
+GTEST_INCLUDE_DIR-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: GTEST_LIBRARY
+GTEST_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: GTEST_LIBRARY_DEBUG
+GTEST_LIBRARY_DEBUG-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: GTEST_MAIN_LIBRARY
+GTEST_MAIN_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: GTEST_MAIN_LIBRARY_DEBUG
+GTEST_MAIN_LIBRARY_DEBUG-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: LAPACK_Accelerate_LIBRARY
+LAPACK_Accelerate_LIBRARY-ADVANCED:INTERNAL=1
+//Have function cheev_
+LAPACK_WORKS:INTERNAL=
+//ADVANCED property for variable: LAPACK_flame_LIBRARY
+LAPACK_flame_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: LAPACK_goto2_LIBRARY
+LAPACK_goto2_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: LAPACK_lapack_LIBRARY
+LAPACK_lapack_LIBRARY-ADVANCED:INTERNAL=1
+//Have function cheev_
+LAPACK_lapack_WORKS:INTERNAL=1
+//ADVANCED property for variable: LAPACK_mkl_lapack_LIBRARY
+LAPACK_mkl_lapack_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: LAPACK_openblas_LIBRARY
+LAPACK_openblas_LIBRARY-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: LAPACK_vecLib_LIBRARY
+LAPACK_vecLib_LIBRARY-ADVANCED:INTERNAL=1
+PC_EIGEN_CFLAGS:INTERNAL=-I/usr/include/eigen3
+PC_EIGEN_CFLAGS_I:INTERNAL=
+PC_EIGEN_CFLAGS_OTHER:INTERNAL=
+PC_EIGEN_FOUND:INTERNAL=1
+PC_EIGEN_INCLUDEDIR:INTERNAL=
+PC_EIGEN_INCLUDE_DIRS:INTERNAL=/usr/include/eigen3
+PC_EIGEN_LDFLAGS:INTERNAL=
+PC_EIGEN_LDFLAGS_OTHER:INTERNAL=
+PC_EIGEN_LIBDIR:INTERNAL=
+PC_EIGEN_LIBRARIES:INTERNAL=
+PC_EIGEN_LIBRARY_DIRS:INTERNAL=
+PC_EIGEN_LIBS:INTERNAL=
+PC_EIGEN_LIBS_L:INTERNAL=
+PC_EIGEN_LIBS_OTHER:INTERNAL=
+PC_EIGEN_LIBS_PATHS:INTERNAL=
+PC_EIGEN_MODULE_NAME:INTERNAL=eigen3
+PC_EIGEN_PREFIX:INTERNAL=/usr
+PC_EIGEN_STATIC_CFLAGS:INTERNAL=-I/usr/include/eigen3
+PC_EIGEN_STATIC_CFLAGS_I:INTERNAL=
+PC_EIGEN_STATIC_CFLAGS_OTHER:INTERNAL=
+PC_EIGEN_STATIC_INCLUDE_DIRS:INTERNAL=/usr/include/eigen3
+PC_EIGEN_STATIC_LDFLAGS:INTERNAL=
+PC_EIGEN_STATIC_LDFLAGS_OTHER:INTERNAL=
+PC_EIGEN_STATIC_LIBDIR:INTERNAL=
+PC_EIGEN_STATIC_LIBRARIES:INTERNAL=
+PC_EIGEN_STATIC_LIBRARY_DIRS:INTERNAL=
+PC_EIGEN_STATIC_LIBS:INTERNAL=
+PC_EIGEN_STATIC_LIBS_L:INTERNAL=
+PC_EIGEN_STATIC_LIBS_OTHER:INTERNAL=
+PC_EIGEN_STATIC_LIBS_PATHS:INTERNAL=
+PC_EIGEN_VERSION:INTERNAL=3.3.7
+PC_EIGEN_eigen3_INCLUDEDIR:INTERNAL=
+PC_EIGEN_eigen3_LIBDIR:INTERNAL=
+PC_EIGEN_eigen3_PREFIX:INTERNAL=
+PC_EIGEN_eigen3_VERSION:INTERNAL=
+//ADVANCED property for variable: PKG_CONFIG_EXECUTABLE
+PKG_CONFIG_EXECUTABLE-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: PYTHON_EXECUTABLE
+PYTHON_EXECUTABLE-ADVANCED:INTERNAL=1
+//This needs to be in PYTHONPATH when 'setup.py install' is called.
+//  And it needs to match.  But setuptools won't tell us where
+// it will install things.
+PYTHON_INSTALL_DIR:INTERNAL=lib/python3/dist-packages
+//CMAKE_INSTALL_PREFIX during last run
+_GNUInstallDirs_LAST_CMAKE_INSTALL_PREFIX:INTERNAL=/usr/local
+__pkg_config_arguments_PC_EIGEN:INTERNAL=eigen3
+__pkg_config_checked_PC_EIGEN:INTERNAL=1
+//ADVANCED property for variable: gmock_build_tests
+gmock_build_tests-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: gtest_build_samples
+gtest_build_samples-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: gtest_build_tests
+gtest_build_tests-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: gtest_disable_pthreads
+gtest_disable_pthreads-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: gtest_force_shared_crt
+gtest_force_shared_crt-ADVANCED:INTERNAL=1
+//ADVANCED property for variable: gtest_hide_internal_symbols
+gtest_hide_internal_symbols-ADVANCED:INTERNAL=1
+prefix_result:INTERNAL=
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CMakeCCompiler.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CMakeCCompiler.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..c5ece7b85213bfcaf19076a9cca07f9be97f8075
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CMakeCCompiler.cmake
@@ -0,0 +1,76 @@
+set(CMAKE_C_COMPILER "/usr/bin/cc")
+set(CMAKE_C_COMPILER_ARG1 "")
+set(CMAKE_C_COMPILER_ID "GNU")
+set(CMAKE_C_COMPILER_VERSION "9.4.0")
+set(CMAKE_C_COMPILER_VERSION_INTERNAL "")
+set(CMAKE_C_COMPILER_WRAPPER "")
+set(CMAKE_C_STANDARD_COMPUTED_DEFAULT "11")
+set(CMAKE_C_COMPILE_FEATURES "c_std_90;c_function_prototypes;c_std_99;c_restrict;c_variadic_macros;c_std_11;c_static_assert")
+set(CMAKE_C90_COMPILE_FEATURES "c_std_90;c_function_prototypes")
+set(CMAKE_C99_COMPILE_FEATURES "c_std_99;c_restrict;c_variadic_macros")
+set(CMAKE_C11_COMPILE_FEATURES "c_std_11;c_static_assert")
+
+set(CMAKE_C_PLATFORM_ID "Linux")
+set(CMAKE_C_SIMULATE_ID "")
+set(CMAKE_C_COMPILER_FRONTEND_VARIANT "")
+set(CMAKE_C_SIMULATE_VERSION "")
+
+
+
+set(CMAKE_AR "/usr/bin/ar")
+set(CMAKE_C_COMPILER_AR "/usr/bin/gcc-ar-9")
+set(CMAKE_RANLIB "/usr/bin/ranlib")
+set(CMAKE_C_COMPILER_RANLIB "/usr/bin/gcc-ranlib-9")
+set(CMAKE_LINKER "/usr/bin/ld")
+set(CMAKE_MT "")
+set(CMAKE_COMPILER_IS_GNUCC 1)
+set(CMAKE_C_COMPILER_LOADED 1)
+set(CMAKE_C_COMPILER_WORKS TRUE)
+set(CMAKE_C_ABI_COMPILED TRUE)
+set(CMAKE_COMPILER_IS_MINGW )
+set(CMAKE_COMPILER_IS_CYGWIN )
+if(CMAKE_COMPILER_IS_CYGWIN)
+  set(CYGWIN 1)
+  set(UNIX 1)
+endif()
+
+set(CMAKE_C_COMPILER_ENV_VAR "CC")
+
+if(CMAKE_COMPILER_IS_MINGW)
+  set(MINGW 1)
+endif()
+set(CMAKE_C_COMPILER_ID_RUN 1)
+set(CMAKE_C_SOURCE_FILE_EXTENSIONS c;m)
+set(CMAKE_C_IGNORE_EXTENSIONS h;H;o;O;obj;OBJ;def;DEF;rc;RC)
+set(CMAKE_C_LINKER_PREFERENCE 10)
+
+# Save compiler ABI information.
+set(CMAKE_C_SIZEOF_DATA_PTR "8")
+set(CMAKE_C_COMPILER_ABI "ELF")
+set(CMAKE_C_LIBRARY_ARCHITECTURE "x86_64-linux-gnu")
+
+if(CMAKE_C_SIZEOF_DATA_PTR)
+  set(CMAKE_SIZEOF_VOID_P "${CMAKE_C_SIZEOF_DATA_PTR}")
+endif()
+
+if(CMAKE_C_COMPILER_ABI)
+  set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_C_COMPILER_ABI}")
+endif()
+
+if(CMAKE_C_LIBRARY_ARCHITECTURE)
+  set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu")
+endif()
+
+set(CMAKE_C_CL_SHOWINCLUDES_PREFIX "")
+if(CMAKE_C_CL_SHOWINCLUDES_PREFIX)
+  set(CMAKE_CL_SHOWINCLUDES_PREFIX "${CMAKE_C_CL_SHOWINCLUDES_PREFIX}")
+endif()
+
+
+
+
+
+set(CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/9/include;/usr/local/include;/usr/include/x86_64-linux-gnu;/usr/include")
+set(CMAKE_C_IMPLICIT_LINK_LIBRARIES "gcc;gcc_s;c;gcc;gcc_s")
+set(CMAKE_C_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/9;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib")
+set(CMAKE_C_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CMakeCXXCompiler.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CMakeCXXCompiler.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..278ef39ee396e9c0d852a7fc8f2647f7da42a20b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CMakeCXXCompiler.cmake
@@ -0,0 +1,88 @@
+set(CMAKE_CXX_COMPILER "/usr/bin/c++")
+set(CMAKE_CXX_COMPILER_ARG1 "")
+set(CMAKE_CXX_COMPILER_ID "GNU")
+set(CMAKE_CXX_COMPILER_VERSION "9.4.0")
+set(CMAKE_CXX_COMPILER_VERSION_INTERNAL "")
+set(CMAKE_CXX_COMPILER_WRAPPER "")
+set(CMAKE_CXX_STANDARD_COMPUTED_DEFAULT "14")
+set(CMAKE_CXX_COMPILE_FEATURES "cxx_std_98;cxx_template_template_parameters;cxx_std_11;cxx_alias_templates;cxx_alignas;cxx_alignof;cxx_attributes;cxx_auto_type;cxx_constexpr;cxx_decltype;cxx_decltype_incomplete_return_types;cxx_default_function_template_args;cxx_defaulted_functions;cxx_defaulted_move_initializers;cxx_delegating_constructors;cxx_deleted_functions;cxx_enum_forward_declarations;cxx_explicit_conversions;cxx_extended_friend_declarations;cxx_extern_templates;cxx_final;cxx_func_identifier;cxx_generalized_initializers;cxx_inheriting_constructors;cxx_inline_namespaces;cxx_lambdas;cxx_local_type_template_args;cxx_long_long_type;cxx_noexcept;cxx_nonstatic_member_init;cxx_nullptr;cxx_override;cxx_range_for;cxx_raw_string_literals;cxx_reference_qualified_functions;cxx_right_angle_brackets;cxx_rvalue_references;cxx_sizeof_member;cxx_static_assert;cxx_strong_enums;cxx_thread_local;cxx_trailing_return_types;cxx_unicode_literals;cxx_uniform_initialization;cxx_unrestricted_unions;cxx_user_literals;cxx_variadic_macros;cxx_variadic_templates;cxx_std_14;cxx_aggregate_default_initializers;cxx_attribute_deprecated;cxx_binary_literals;cxx_contextual_conversions;cxx_decltype_auto;cxx_digit_separators;cxx_generic_lambdas;cxx_lambda_init_captures;cxx_relaxed_constexpr;cxx_return_type_deduction;cxx_variable_templates;cxx_std_17;cxx_std_20")
+set(CMAKE_CXX98_COMPILE_FEATURES "cxx_std_98;cxx_template_template_parameters")
+set(CMAKE_CXX11_COMPILE_FEATURES "cxx_std_11;cxx_alias_templates;cxx_alignas;cxx_alignof;cxx_attributes;cxx_auto_type;cxx_constexpr;cxx_decltype;cxx_decltype_incomplete_return_types;cxx_default_function_template_args;cxx_defaulted_functions;cxx_defaulted_move_initializers;cxx_delegating_constructors;cxx_deleted_functions;cxx_enum_forward_declarations;cxx_explicit_conversions;cxx_extended_friend_declarations;cxx_extern_templates;cxx_final;cxx_func_identifier;cxx_generalized_initializers;cxx_inheriting_constructors;cxx_inline_namespaces;cxx_lambdas;cxx_local_type_template_args;cxx_long_long_type;cxx_noexcept;cxx_nonstatic_member_init;cxx_nullptr;cxx_override;cxx_range_for;cxx_raw_string_literals;cxx_reference_qualified_functions;cxx_right_angle_brackets;cxx_rvalue_references;cxx_sizeof_member;cxx_static_assert;cxx_strong_enums;cxx_thread_local;cxx_trailing_return_types;cxx_unicode_literals;cxx_uniform_initialization;cxx_unrestricted_unions;cxx_user_literals;cxx_variadic_macros;cxx_variadic_templates")
+set(CMAKE_CXX14_COMPILE_FEATURES "cxx_std_14;cxx_aggregate_default_initializers;cxx_attribute_deprecated;cxx_binary_literals;cxx_contextual_conversions;cxx_decltype_auto;cxx_digit_separators;cxx_generic_lambdas;cxx_lambda_init_captures;cxx_relaxed_constexpr;cxx_return_type_deduction;cxx_variable_templates")
+set(CMAKE_CXX17_COMPILE_FEATURES "cxx_std_17")
+set(CMAKE_CXX20_COMPILE_FEATURES "cxx_std_20")
+
+set(CMAKE_CXX_PLATFORM_ID "Linux")
+set(CMAKE_CXX_SIMULATE_ID "")
+set(CMAKE_CXX_COMPILER_FRONTEND_VARIANT "")
+set(CMAKE_CXX_SIMULATE_VERSION "")
+
+
+
+set(CMAKE_AR "/usr/bin/ar")
+set(CMAKE_CXX_COMPILER_AR "/usr/bin/gcc-ar-9")
+set(CMAKE_RANLIB "/usr/bin/ranlib")
+set(CMAKE_CXX_COMPILER_RANLIB "/usr/bin/gcc-ranlib-9")
+set(CMAKE_LINKER "/usr/bin/ld")
+set(CMAKE_MT "")
+set(CMAKE_COMPILER_IS_GNUCXX 1)
+set(CMAKE_CXX_COMPILER_LOADED 1)
+set(CMAKE_CXX_COMPILER_WORKS TRUE)
+set(CMAKE_CXX_ABI_COMPILED TRUE)
+set(CMAKE_COMPILER_IS_MINGW )
+set(CMAKE_COMPILER_IS_CYGWIN )
+if(CMAKE_COMPILER_IS_CYGWIN)
+  set(CYGWIN 1)
+  set(UNIX 1)
+endif()
+
+set(CMAKE_CXX_COMPILER_ENV_VAR "CXX")
+
+if(CMAKE_COMPILER_IS_MINGW)
+  set(MINGW 1)
+endif()
+set(CMAKE_CXX_COMPILER_ID_RUN 1)
+set(CMAKE_CXX_SOURCE_FILE_EXTENSIONS C;M;c++;cc;cpp;cxx;m;mm;CPP)
+set(CMAKE_CXX_IGNORE_EXTENSIONS inl;h;hpp;HPP;H;o;O;obj;OBJ;def;DEF;rc;RC)
+
+foreach (lang C OBJC OBJCXX)
+  if (CMAKE_${lang}_COMPILER_ID_RUN)
+    foreach(extension IN LISTS CMAKE_${lang}_SOURCE_FILE_EXTENSIONS)
+      list(REMOVE_ITEM CMAKE_CXX_SOURCE_FILE_EXTENSIONS ${extension})
+    endforeach()
+  endif()
+endforeach()
+
+set(CMAKE_CXX_LINKER_PREFERENCE 30)
+set(CMAKE_CXX_LINKER_PREFERENCE_PROPAGATES 1)
+
+# Save compiler ABI information.
+set(CMAKE_CXX_SIZEOF_DATA_PTR "8")
+set(CMAKE_CXX_COMPILER_ABI "ELF")
+set(CMAKE_CXX_LIBRARY_ARCHITECTURE "x86_64-linux-gnu")
+
+if(CMAKE_CXX_SIZEOF_DATA_PTR)
+  set(CMAKE_SIZEOF_VOID_P "${CMAKE_CXX_SIZEOF_DATA_PTR}")
+endif()
+
+if(CMAKE_CXX_COMPILER_ABI)
+  set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_CXX_COMPILER_ABI}")
+endif()
+
+if(CMAKE_CXX_LIBRARY_ARCHITECTURE)
+  set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu")
+endif()
+
+set(CMAKE_CXX_CL_SHOWINCLUDES_PREFIX "")
+if(CMAKE_CXX_CL_SHOWINCLUDES_PREFIX)
+  set(CMAKE_CL_SHOWINCLUDES_PREFIX "${CMAKE_CXX_CL_SHOWINCLUDES_PREFIX}")
+endif()
+
+
+
+
+
+set(CMAKE_CXX_IMPLICIT_INCLUDE_DIRECTORIES "/usr/include/c++/9;/usr/include/x86_64-linux-gnu/c++/9;/usr/include/c++/9/backward;/usr/lib/gcc/x86_64-linux-gnu/9/include;/usr/local/include;/usr/include/x86_64-linux-gnu;/usr/include")
+set(CMAKE_CXX_IMPLICIT_LINK_LIBRARIES "stdc++;m;gcc_s;gcc;c;gcc_s;gcc")
+set(CMAKE_CXX_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/9;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib")
+set(CMAKE_CXX_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CMakeDetermineCompilerABI_C.bin b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CMakeDetermineCompilerABI_C.bin
new file mode 100644
index 0000000000000000000000000000000000000000..35de1468eef863e60eec8592df6b83860a5cea2c
Binary files /dev/null and b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CMakeDetermineCompilerABI_C.bin differ
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CMakeDetermineCompilerABI_CXX.bin b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CMakeDetermineCompilerABI_CXX.bin
new file mode 100644
index 0000000000000000000000000000000000000000..9cba7ec766c0da3a854716392dd048bc86eb07ca
Binary files /dev/null and b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CMakeDetermineCompilerABI_CXX.bin differ
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CMakeSystem.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CMakeSystem.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..3d4e5ed08a82fa8f8ca7e90e90eb5e899a630ba2
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CMakeSystem.cmake
@@ -0,0 +1,15 @@
+set(CMAKE_HOST_SYSTEM "Linux-5.4.0-132-generic")
+set(CMAKE_HOST_SYSTEM_NAME "Linux")
+set(CMAKE_HOST_SYSTEM_VERSION "5.4.0-132-generic")
+set(CMAKE_HOST_SYSTEM_PROCESSOR "x86_64")
+
+
+
+set(CMAKE_SYSTEM "Linux-5.4.0-132-generic")
+set(CMAKE_SYSTEM_NAME "Linux")
+set(CMAKE_SYSTEM_VERSION "5.4.0-132-generic")
+set(CMAKE_SYSTEM_PROCESSOR "x86_64")
+
+set(CMAKE_CROSSCOMPILING "FALSE")
+
+set(CMAKE_SYSTEM_LOADED 1)
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CompilerIdC/CMakeCCompilerId.c b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CompilerIdC/CMakeCCompilerId.c
new file mode 100644
index 0000000000000000000000000000000000000000..d884b50908c9852aad6d3b60781f4e529edc4d50
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CompilerIdC/CMakeCCompilerId.c
@@ -0,0 +1,671 @@
+#ifdef __cplusplus
+# error "A C++ compiler has been selected for C."
+#endif
+
+#if defined(__18CXX)
+# define ID_VOID_MAIN
+#endif
+#if defined(__CLASSIC_C__)
+/* cv-qualifiers did not exist in K&R C */
+# define const
+# define volatile
+#endif
+
+
+/* Version number components: V=Version, R=Revision, P=Patch
+   Version date components:   YYYY=Year, MM=Month,   DD=Day  */
+
+#if defined(__INTEL_COMPILER) || defined(__ICC)
+# define COMPILER_ID "Intel"
+# if defined(_MSC_VER)
+#  define SIMULATE_ID "MSVC"
+# endif
+# if defined(__GNUC__)
+#  define SIMULATE_ID "GNU"
+# endif
+  /* __INTEL_COMPILER = VRP */
+# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100)
+# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10)
+# if defined(__INTEL_COMPILER_UPDATE)
+#  define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER_UPDATE)
+# else
+#  define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER   % 10)
+# endif
+# if defined(__INTEL_COMPILER_BUILD_DATE)
+  /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */
+#  define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE)
+# endif
+# if defined(_MSC_VER)
+   /* _MSC_VER = VVRR */
+#  define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)
+#  define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)
+# endif
+# if defined(__GNUC__)
+#  define SIMULATE_VERSION_MAJOR DEC(__GNUC__)
+# elif defined(__GNUG__)
+#  define SIMULATE_VERSION_MAJOR DEC(__GNUG__)
+# endif
+# if defined(__GNUC_MINOR__)
+#  define SIMULATE_VERSION_MINOR DEC(__GNUC_MINOR__)
+# endif
+# if defined(__GNUC_PATCHLEVEL__)
+#  define SIMULATE_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__)
+# endif
+
+#elif defined(__PATHCC__)
+# define COMPILER_ID "PathScale"
+# define COMPILER_VERSION_MAJOR DEC(__PATHCC__)
+# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__)
+# if defined(__PATHCC_PATCHLEVEL__)
+#  define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__)
+# endif
+
+#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__)
+# define COMPILER_ID "Embarcadero"
+# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF)
+# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF)
+# define COMPILER_VERSION_PATCH DEC(__CODEGEARC_VERSION__     & 0xFFFF)
+
+#elif defined(__BORLANDC__)
+# define COMPILER_ID "Borland"
+  /* __BORLANDC__ = 0xVRR */
+# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8)
+# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF)
+
+#elif defined(__WATCOMC__) && __WATCOMC__ < 1200
+# define COMPILER_ID "Watcom"
+   /* __WATCOMC__ = VVRR */
+# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100)
+# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10)
+# if (__WATCOMC__ % 10) > 0
+#  define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10)
+# endif
+
+#elif defined(__WATCOMC__)
+# define COMPILER_ID "OpenWatcom"
+   /* __WATCOMC__ = VVRP + 1100 */
+# define COMPILER_VERSION_MAJOR DEC((__WATCOMC__ - 1100) / 100)
+# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10)
+# if (__WATCOMC__ % 10) > 0
+#  define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10)
+# endif
+
+#elif defined(__SUNPRO_C)
+# define COMPILER_ID "SunPro"
+# if __SUNPRO_C >= 0x5100
+   /* __SUNPRO_C = 0xVRRP */
+#  define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>12)
+#  define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xFF)
+#  define COMPILER_VERSION_PATCH HEX(__SUNPRO_C    & 0xF)
+# else
+   /* __SUNPRO_CC = 0xVRP */
+#  define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>8)
+#  define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xF)
+#  define COMPILER_VERSION_PATCH HEX(__SUNPRO_C    & 0xF)
+# endif
+
+#elif defined(__HP_cc)
+# define COMPILER_ID "HP"
+  /* __HP_cc = VVRRPP */
+# define COMPILER_VERSION_MAJOR DEC(__HP_cc/10000)
+# define COMPILER_VERSION_MINOR DEC(__HP_cc/100 % 100)
+# define COMPILER_VERSION_PATCH DEC(__HP_cc     % 100)
+
+#elif defined(__DECC)
+# define COMPILER_ID "Compaq"
+  /* __DECC_VER = VVRRTPPPP */
+# define COMPILER_VERSION_MAJOR DEC(__DECC_VER/10000000)
+# define COMPILER_VERSION_MINOR DEC(__DECC_VER/100000  % 100)
+# define COMPILER_VERSION_PATCH DEC(__DECC_VER         % 10000)
+
+#elif defined(__IBMC__) && defined(__COMPILER_VER__)
+# define COMPILER_ID "zOS"
+  /* __IBMC__ = VRP */
+# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100)
+# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10)
+# define COMPILER_VERSION_PATCH DEC(__IBMC__    % 10)
+
+#elif defined(__ibmxl__) && defined(__clang__)
+# define COMPILER_ID "XLClang"
+# define COMPILER_VERSION_MAJOR DEC(__ibmxl_version__)
+# define COMPILER_VERSION_MINOR DEC(__ibmxl_release__)
+# define COMPILER_VERSION_PATCH DEC(__ibmxl_modification__)
+# define COMPILER_VERSION_TWEAK DEC(__ibmxl_ptf_fix_level__)
+
+
+#elif defined(__IBMC__) && !defined(__COMPILER_VER__) && __IBMC__ >= 800
+# define COMPILER_ID "XL"
+  /* __IBMC__ = VRP */
+# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100)
+# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10)
+# define COMPILER_VERSION_PATCH DEC(__IBMC__    % 10)
+
+#elif defined(__IBMC__) && !defined(__COMPILER_VER__) && __IBMC__ < 800
+# define COMPILER_ID "VisualAge"
+  /* __IBMC__ = VRP */
+# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100)
+# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10)
+# define COMPILER_VERSION_PATCH DEC(__IBMC__    % 10)
+
+#elif defined(__PGI)
+# define COMPILER_ID "PGI"
+# define COMPILER_VERSION_MAJOR DEC(__PGIC__)
+# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__)
+# if defined(__PGIC_PATCHLEVEL__)
+#  define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__)
+# endif
+
+#elif defined(_CRAYC)
+# define COMPILER_ID "Cray"
+# define COMPILER_VERSION_MAJOR DEC(_RELEASE_MAJOR)
+# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR)
+
+#elif defined(__TI_COMPILER_VERSION__)
+# define COMPILER_ID "TI"
+  /* __TI_COMPILER_VERSION__ = VVVRRRPPP */
+# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000)
+# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000   % 1000)
+# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__        % 1000)
+
+#elif defined(__FUJITSU) || defined(__FCC_VERSION) || defined(__fcc_version)
+# define COMPILER_ID "Fujitsu"
+
+#elif defined(__ghs__)
+# define COMPILER_ID "GHS"
+/* __GHS_VERSION_NUMBER = VVVVRP */
+# ifdef __GHS_VERSION_NUMBER
+# define COMPILER_VERSION_MAJOR DEC(__GHS_VERSION_NUMBER / 100)
+# define COMPILER_VERSION_MINOR DEC(__GHS_VERSION_NUMBER / 10 % 10)
+# define COMPILER_VERSION_PATCH DEC(__GHS_VERSION_NUMBER      % 10)
+# endif
+
+#elif defined(__TINYC__)
+# define COMPILER_ID "TinyCC"
+
+#elif defined(__BCC__)
+# define COMPILER_ID "Bruce"
+
+#elif defined(__SCO_VERSION__)
+# define COMPILER_ID "SCO"
+
+#elif defined(__ARMCC_VERSION) && !defined(__clang__)
+# define COMPILER_ID "ARMCC"
+#if __ARMCC_VERSION >= 1000000
+  /* __ARMCC_VERSION = VRRPPPP */
+  # define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/1000000)
+  # define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 100)
+  # define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION     % 10000)
+#else
+  /* __ARMCC_VERSION = VRPPPP */
+  # define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/100000)
+  # define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 10)
+  # define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION    % 10000)
+#endif
+
+
+#elif defined(__clang__) && defined(__apple_build_version__)
+# define COMPILER_ID "AppleClang"
+# if defined(_MSC_VER)
+#  define SIMULATE_ID "MSVC"
+# endif
+# define COMPILER_VERSION_MAJOR DEC(__clang_major__)
+# define COMPILER_VERSION_MINOR DEC(__clang_minor__)
+# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__)
+# if defined(_MSC_VER)
+   /* _MSC_VER = VVRR */
+#  define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)
+#  define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)
+# endif
+# define COMPILER_VERSION_TWEAK DEC(__apple_build_version__)
+
+#elif defined(__clang__) && defined(__ARMCOMPILER_VERSION)
+# define COMPILER_ID "ARMClang"
+  # define COMPILER_VERSION_MAJOR DEC(__ARMCOMPILER_VERSION/1000000)
+  # define COMPILER_VERSION_MINOR DEC(__ARMCOMPILER_VERSION/10000 % 100)
+  # define COMPILER_VERSION_PATCH DEC(__ARMCOMPILER_VERSION     % 10000)
+# define COMPILER_VERSION_INTERNAL DEC(__ARMCOMPILER_VERSION)
+
+#elif defined(__clang__)
+# define COMPILER_ID "Clang"
+# if defined(_MSC_VER)
+#  define SIMULATE_ID "MSVC"
+# endif
+# define COMPILER_VERSION_MAJOR DEC(__clang_major__)
+# define COMPILER_VERSION_MINOR DEC(__clang_minor__)
+# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__)
+# if defined(_MSC_VER)
+   /* _MSC_VER = VVRR */
+#  define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)
+#  define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)
+# endif
+
+#elif defined(__GNUC__)
+# define COMPILER_ID "GNU"
+# define COMPILER_VERSION_MAJOR DEC(__GNUC__)
+# if defined(__GNUC_MINOR__)
+#  define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__)
+# endif
+# if defined(__GNUC_PATCHLEVEL__)
+#  define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__)
+# endif
+
+#elif defined(_MSC_VER)
+# define COMPILER_ID "MSVC"
+  /* _MSC_VER = VVRR */
+# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100)
+# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100)
+# if defined(_MSC_FULL_VER)
+#  if _MSC_VER >= 1400
+    /* _MSC_FULL_VER = VVRRPPPPP */
+#   define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000)
+#  else
+    /* _MSC_FULL_VER = VVRRPPPP */
+#   define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000)
+#  endif
+# endif
+# if defined(_MSC_BUILD)
+#  define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD)
+# endif
+
+#elif defined(__VISUALDSPVERSION__) || defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__)
+# define COMPILER_ID "ADSP"
+#if defined(__VISUALDSPVERSION__)
+  /* __VISUALDSPVERSION__ = 0xVVRRPP00 */
+# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24)
+# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF)
+# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8  & 0xFF)
+#endif
+
+#elif defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC)
+# define COMPILER_ID "IAR"
+# if defined(__VER__) && defined(__ICCARM__)
+#  define COMPILER_VERSION_MAJOR DEC((__VER__) / 1000000)
+#  define COMPILER_VERSION_MINOR DEC(((__VER__) / 1000) % 1000)
+#  define COMPILER_VERSION_PATCH DEC((__VER__) % 1000)
+#  define COMPILER_VERSION_INTERNAL DEC(__IAR_SYSTEMS_ICC__)
+# elif defined(__VER__) && (defined(__ICCAVR__) || defined(__ICCRX__) || defined(__ICCRH850__) || defined(__ICCRL78__) || defined(__ICC430__) || defined(__ICCRISCV__) || defined(__ICCV850__) || defined(__ICC8051__))
+#  define COMPILER_VERSION_MAJOR DEC((__VER__) / 100)
+#  define COMPILER_VERSION_MINOR DEC((__VER__) - (((__VER__) / 100)*100))
+#  define COMPILER_VERSION_PATCH DEC(__SUBVERSION__)
+#  define COMPILER_VERSION_INTERNAL DEC(__IAR_SYSTEMS_ICC__)
+# endif
+
+#elif defined(__SDCC_VERSION_MAJOR) || defined(SDCC)
+# define COMPILER_ID "SDCC"
+# if defined(__SDCC_VERSION_MAJOR)
+#  define COMPILER_VERSION_MAJOR DEC(__SDCC_VERSION_MAJOR)
+#  define COMPILER_VERSION_MINOR DEC(__SDCC_VERSION_MINOR)
+#  define COMPILER_VERSION_PATCH DEC(__SDCC_VERSION_PATCH)
+# else
+  /* SDCC = VRP */
+#  define COMPILER_VERSION_MAJOR DEC(SDCC/100)
+#  define COMPILER_VERSION_MINOR DEC(SDCC/10 % 10)
+#  define COMPILER_VERSION_PATCH DEC(SDCC    % 10)
+# endif
+
+
+/* These compilers are either not known or too old to define an
+  identification macro.  Try to identify the platform and guess that
+  it is the native compiler.  */
+#elif defined(__hpux) || defined(__hpua)
+# define COMPILER_ID "HP"
+
+#else /* unknown compiler */
+# define COMPILER_ID ""
+#endif
+
+/* Construct the string literal in pieces to prevent the source from
+   getting matched.  Store it in a pointer rather than an array
+   because some compilers will just produce instructions to fill the
+   array rather than assigning a pointer to a static array.  */
+char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]";
+#ifdef SIMULATE_ID
+char const* info_simulate = "INFO" ":" "simulate[" SIMULATE_ID "]";
+#endif
+
+#ifdef __QNXNTO__
+char const* qnxnto = "INFO" ":" "qnxnto[]";
+#endif
+
+#if defined(__CRAYXE) || defined(__CRAYXC)
+char const *info_cray = "INFO" ":" "compiler_wrapper[CrayPrgEnv]";
+#endif
+
+#define STRINGIFY_HELPER(X) #X
+#define STRINGIFY(X) STRINGIFY_HELPER(X)
+
+/* Identify known platforms by name.  */
+#if defined(__linux) || defined(__linux__) || defined(linux)
+# define PLATFORM_ID "Linux"
+
+#elif defined(__CYGWIN__)
+# define PLATFORM_ID "Cygwin"
+
+#elif defined(__MINGW32__)
+# define PLATFORM_ID "MinGW"
+
+#elif defined(__APPLE__)
+# define PLATFORM_ID "Darwin"
+
+#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32)
+# define PLATFORM_ID "Windows"
+
+#elif defined(__FreeBSD__) || defined(__FreeBSD)
+# define PLATFORM_ID "FreeBSD"
+
+#elif defined(__NetBSD__) || defined(__NetBSD)
+# define PLATFORM_ID "NetBSD"
+
+#elif defined(__OpenBSD__) || defined(__OPENBSD)
+# define PLATFORM_ID "OpenBSD"
+
+#elif defined(__sun) || defined(sun)
+# define PLATFORM_ID "SunOS"
+
+#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__)
+# define PLATFORM_ID "AIX"
+
+#elif defined(__hpux) || defined(__hpux__)
+# define PLATFORM_ID "HP-UX"
+
+#elif defined(__HAIKU__)
+# define PLATFORM_ID "Haiku"
+
+#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS)
+# define PLATFORM_ID "BeOS"
+
+#elif defined(__QNX__) || defined(__QNXNTO__)
+# define PLATFORM_ID "QNX"
+
+#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__)
+# define PLATFORM_ID "Tru64"
+
+#elif defined(__riscos) || defined(__riscos__)
+# define PLATFORM_ID "RISCos"
+
+#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__)
+# define PLATFORM_ID "SINIX"
+
+#elif defined(__UNIX_SV__)
+# define PLATFORM_ID "UNIX_SV"
+
+#elif defined(__bsdos__)
+# define PLATFORM_ID "BSDOS"
+
+#elif defined(_MPRAS) || defined(MPRAS)
+# define PLATFORM_ID "MP-RAS"
+
+#elif defined(__osf) || defined(__osf__)
+# define PLATFORM_ID "OSF1"
+
+#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv)
+# define PLATFORM_ID "SCO_SV"
+
+#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX)
+# define PLATFORM_ID "ULTRIX"
+
+#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX)
+# define PLATFORM_ID "Xenix"
+
+#elif defined(__WATCOMC__)
+# if defined(__LINUX__)
+#  define PLATFORM_ID "Linux"
+
+# elif defined(__DOS__)
+#  define PLATFORM_ID "DOS"
+
+# elif defined(__OS2__)
+#  define PLATFORM_ID "OS2"
+
+# elif defined(__WINDOWS__)
+#  define PLATFORM_ID "Windows3x"
+
+# else /* unknown platform */
+#  define PLATFORM_ID
+# endif
+
+#elif defined(__INTEGRITY)
+# if defined(INT_178B)
+#  define PLATFORM_ID "Integrity178"
+
+# else /* regular Integrity */
+#  define PLATFORM_ID "Integrity"
+# endif
+
+#else /* unknown platform */
+# define PLATFORM_ID
+
+#endif
+
+/* For windows compilers MSVC and Intel we can determine
+   the architecture of the compiler being used.  This is because
+   the compilers do not have flags that can change the architecture,
+   but rather depend on which compiler is being used
+*/
+#if defined(_WIN32) && defined(_MSC_VER)
+# if defined(_M_IA64)
+#  define ARCHITECTURE_ID "IA64"
+
+# elif defined(_M_X64) || defined(_M_AMD64)
+#  define ARCHITECTURE_ID "x64"
+
+# elif defined(_M_IX86)
+#  define ARCHITECTURE_ID "X86"
+
+# elif defined(_M_ARM64)
+#  define ARCHITECTURE_ID "ARM64"
+
+# elif defined(_M_ARM)
+#  if _M_ARM == 4
+#   define ARCHITECTURE_ID "ARMV4I"
+#  elif _M_ARM == 5
+#   define ARCHITECTURE_ID "ARMV5I"
+#  else
+#   define ARCHITECTURE_ID "ARMV" STRINGIFY(_M_ARM)
+#  endif
+
+# elif defined(_M_MIPS)
+#  define ARCHITECTURE_ID "MIPS"
+
+# elif defined(_M_SH)
+#  define ARCHITECTURE_ID "SHx"
+
+# else /* unknown architecture */
+#  define ARCHITECTURE_ID ""
+# endif
+
+#elif defined(__WATCOMC__)
+# if defined(_M_I86)
+#  define ARCHITECTURE_ID "I86"
+
+# elif defined(_M_IX86)
+#  define ARCHITECTURE_ID "X86"
+
+# else /* unknown architecture */
+#  define ARCHITECTURE_ID ""
+# endif
+
+#elif defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC)
+# if defined(__ICCARM__)
+#  define ARCHITECTURE_ID "ARM"
+
+# elif defined(__ICCRX__)
+#  define ARCHITECTURE_ID "RX"
+
+# elif defined(__ICCRH850__)
+#  define ARCHITECTURE_ID "RH850"
+
+# elif defined(__ICCRL78__)
+#  define ARCHITECTURE_ID "RL78"
+
+# elif defined(__ICCRISCV__)
+#  define ARCHITECTURE_ID "RISCV"
+
+# elif defined(__ICCAVR__)
+#  define ARCHITECTURE_ID "AVR"
+
+# elif defined(__ICC430__)
+#  define ARCHITECTURE_ID "MSP430"
+
+# elif defined(__ICCV850__)
+#  define ARCHITECTURE_ID "V850"
+
+# elif defined(__ICC8051__)
+#  define ARCHITECTURE_ID "8051"
+
+# else /* unknown architecture */
+#  define ARCHITECTURE_ID ""
+# endif
+
+#elif defined(__ghs__)
+# if defined(__PPC64__)
+#  define ARCHITECTURE_ID "PPC64"
+
+# elif defined(__ppc__)
+#  define ARCHITECTURE_ID "PPC"
+
+# elif defined(__ARM__)
+#  define ARCHITECTURE_ID "ARM"
+
+# elif defined(__x86_64__)
+#  define ARCHITECTURE_ID "x64"
+
+# elif defined(__i386__)
+#  define ARCHITECTURE_ID "X86"
+
+# else /* unknown architecture */
+#  define ARCHITECTURE_ID ""
+# endif
+#else
+#  define ARCHITECTURE_ID
+#endif
+
+/* Convert integer to decimal digit literals.  */
+#define DEC(n)                   \
+  ('0' + (((n) / 10000000)%10)), \
+  ('0' + (((n) / 1000000)%10)),  \
+  ('0' + (((n) / 100000)%10)),   \
+  ('0' + (((n) / 10000)%10)),    \
+  ('0' + (((n) / 1000)%10)),     \
+  ('0' + (((n) / 100)%10)),      \
+  ('0' + (((n) / 10)%10)),       \
+  ('0' +  ((n) % 10))
+
+/* Convert integer to hex digit literals.  */
+#define HEX(n)             \
+  ('0' + ((n)>>28 & 0xF)), \
+  ('0' + ((n)>>24 & 0xF)), \
+  ('0' + ((n)>>20 & 0xF)), \
+  ('0' + ((n)>>16 & 0xF)), \
+  ('0' + ((n)>>12 & 0xF)), \
+  ('0' + ((n)>>8  & 0xF)), \
+  ('0' + ((n)>>4  & 0xF)), \
+  ('0' + ((n)     & 0xF))
+
+/* Construct a string literal encoding the version number components. */
+#ifdef COMPILER_VERSION_MAJOR
+char const info_version[] = {
+  'I', 'N', 'F', 'O', ':',
+  'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[',
+  COMPILER_VERSION_MAJOR,
+# ifdef COMPILER_VERSION_MINOR
+  '.', COMPILER_VERSION_MINOR,
+#  ifdef COMPILER_VERSION_PATCH
+   '.', COMPILER_VERSION_PATCH,
+#   ifdef COMPILER_VERSION_TWEAK
+    '.', COMPILER_VERSION_TWEAK,
+#   endif
+#  endif
+# endif
+  ']','\0'};
+#endif
+
+/* Construct a string literal encoding the internal version number. */
+#ifdef COMPILER_VERSION_INTERNAL
+char const info_version_internal[] = {
+  'I', 'N', 'F', 'O', ':',
+  'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','_',
+  'i','n','t','e','r','n','a','l','[',
+  COMPILER_VERSION_INTERNAL,']','\0'};
+#endif
+
+/* Construct a string literal encoding the version number components. */
+#ifdef SIMULATE_VERSION_MAJOR
+char const info_simulate_version[] = {
+  'I', 'N', 'F', 'O', ':',
+  's','i','m','u','l','a','t','e','_','v','e','r','s','i','o','n','[',
+  SIMULATE_VERSION_MAJOR,
+# ifdef SIMULATE_VERSION_MINOR
+  '.', SIMULATE_VERSION_MINOR,
+#  ifdef SIMULATE_VERSION_PATCH
+   '.', SIMULATE_VERSION_PATCH,
+#   ifdef SIMULATE_VERSION_TWEAK
+    '.', SIMULATE_VERSION_TWEAK,
+#   endif
+#  endif
+# endif
+  ']','\0'};
+#endif
+
+/* Construct the string literal in pieces to prevent the source from
+   getting matched.  Store it in a pointer rather than an array
+   because some compilers will just produce instructions to fill the
+   array rather than assigning a pointer to a static array.  */
+char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]";
+char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]";
+
+
+
+
+#if !defined(__STDC__)
+# if (defined(_MSC_VER) && !defined(__clang__)) \
+  || (defined(__ibmxl__) || defined(__IBMC__))
+#  define C_DIALECT "90"
+# else
+#  define C_DIALECT
+# endif
+#elif __STDC_VERSION__ >= 201000L
+# define C_DIALECT "11"
+#elif __STDC_VERSION__ >= 199901L
+# define C_DIALECT "99"
+#else
+# define C_DIALECT "90"
+#endif
+const char* info_language_dialect_default =
+  "INFO" ":" "dialect_default[" C_DIALECT "]";
+
+/*--------------------------------------------------------------------------*/
+
+#ifdef ID_VOID_MAIN
+void main() {}
+#else
+# if defined(__CLASSIC_C__)
+int main(argc, argv) int argc; char *argv[];
+# else
+int main(int argc, char* argv[])
+# endif
+{
+  int require = 0;
+  require += info_compiler[argc];
+  require += info_platform[argc];
+  require += info_arch[argc];
+#ifdef COMPILER_VERSION_MAJOR
+  require += info_version[argc];
+#endif
+#ifdef COMPILER_VERSION_INTERNAL
+  require += info_version_internal[argc];
+#endif
+#ifdef SIMULATE_ID
+  require += info_simulate[argc];
+#endif
+#ifdef SIMULATE_VERSION_MAJOR
+  require += info_simulate_version[argc];
+#endif
+#if defined(__CRAYXE) || defined(__CRAYXC)
+  require += info_cray[argc];
+#endif
+  require += info_language_dialect_default[argc];
+  (void)argv;
+  return require;
+}
+#endif
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CompilerIdCXX/CMakeCXXCompilerId.cpp b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CompilerIdCXX/CMakeCXXCompilerId.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..69cfdba6bc7bccb09bf234388908de035caa0969
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CompilerIdCXX/CMakeCXXCompilerId.cpp
@@ -0,0 +1,660 @@
+/* This source file must have a .cpp extension so that all C++ compilers
+   recognize the extension without flags.  Borland does not know .cxx for
+   example.  */
+#ifndef __cplusplus
+# error "A C compiler has been selected for C++."
+#endif
+
+
+/* Version number components: V=Version, R=Revision, P=Patch
+   Version date components:   YYYY=Year, MM=Month,   DD=Day  */
+
+#if defined(__COMO__)
+# define COMPILER_ID "Comeau"
+  /* __COMO_VERSION__ = VRR */
+# define COMPILER_VERSION_MAJOR DEC(__COMO_VERSION__ / 100)
+# define COMPILER_VERSION_MINOR DEC(__COMO_VERSION__ % 100)
+
+#elif defined(__INTEL_COMPILER) || defined(__ICC)
+# define COMPILER_ID "Intel"
+# if defined(_MSC_VER)
+#  define SIMULATE_ID "MSVC"
+# endif
+# if defined(__GNUC__)
+#  define SIMULATE_ID "GNU"
+# endif
+  /* __INTEL_COMPILER = VRP */
+# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100)
+# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10)
+# if defined(__INTEL_COMPILER_UPDATE)
+#  define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER_UPDATE)
+# else
+#  define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER   % 10)
+# endif
+# if defined(__INTEL_COMPILER_BUILD_DATE)
+  /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */
+#  define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE)
+# endif
+# if defined(_MSC_VER)
+   /* _MSC_VER = VVRR */
+#  define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)
+#  define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)
+# endif
+# if defined(__GNUC__)
+#  define SIMULATE_VERSION_MAJOR DEC(__GNUC__)
+# elif defined(__GNUG__)
+#  define SIMULATE_VERSION_MAJOR DEC(__GNUG__)
+# endif
+# if defined(__GNUC_MINOR__)
+#  define SIMULATE_VERSION_MINOR DEC(__GNUC_MINOR__)
+# endif
+# if defined(__GNUC_PATCHLEVEL__)
+#  define SIMULATE_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__)
+# endif
+
+#elif defined(__PATHCC__)
+# define COMPILER_ID "PathScale"
+# define COMPILER_VERSION_MAJOR DEC(__PATHCC__)
+# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__)
+# if defined(__PATHCC_PATCHLEVEL__)
+#  define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__)
+# endif
+
+#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__)
+# define COMPILER_ID "Embarcadero"
+# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF)
+# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF)
+# define COMPILER_VERSION_PATCH DEC(__CODEGEARC_VERSION__     & 0xFFFF)
+
+#elif defined(__BORLANDC__)
+# define COMPILER_ID "Borland"
+  /* __BORLANDC__ = 0xVRR */
+# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8)
+# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF)
+
+#elif defined(__WATCOMC__) && __WATCOMC__ < 1200
+# define COMPILER_ID "Watcom"
+   /* __WATCOMC__ = VVRR */
+# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100)
+# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10)
+# if (__WATCOMC__ % 10) > 0
+#  define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10)
+# endif
+
+#elif defined(__WATCOMC__)
+# define COMPILER_ID "OpenWatcom"
+   /* __WATCOMC__ = VVRP + 1100 */
+# define COMPILER_VERSION_MAJOR DEC((__WATCOMC__ - 1100) / 100)
+# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10)
+# if (__WATCOMC__ % 10) > 0
+#  define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10)
+# endif
+
+#elif defined(__SUNPRO_CC)
+# define COMPILER_ID "SunPro"
+# if __SUNPRO_CC >= 0x5100
+   /* __SUNPRO_CC = 0xVRRP */
+#  define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>12)
+#  define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xFF)
+#  define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC    & 0xF)
+# else
+   /* __SUNPRO_CC = 0xVRP */
+#  define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>8)
+#  define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xF)
+#  define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC    & 0xF)
+# endif
+
+#elif defined(__HP_aCC)
+# define COMPILER_ID "HP"
+  /* __HP_aCC = VVRRPP */
+# define COMPILER_VERSION_MAJOR DEC(__HP_aCC/10000)
+# define COMPILER_VERSION_MINOR DEC(__HP_aCC/100 % 100)
+# define COMPILER_VERSION_PATCH DEC(__HP_aCC     % 100)
+
+#elif defined(__DECCXX)
+# define COMPILER_ID "Compaq"
+  /* __DECCXX_VER = VVRRTPPPP */
+# define COMPILER_VERSION_MAJOR DEC(__DECCXX_VER/10000000)
+# define COMPILER_VERSION_MINOR DEC(__DECCXX_VER/100000  % 100)
+# define COMPILER_VERSION_PATCH DEC(__DECCXX_VER         % 10000)
+
+#elif defined(__IBMCPP__) && defined(__COMPILER_VER__)
+# define COMPILER_ID "zOS"
+  /* __IBMCPP__ = VRP */
+# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100)
+# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10)
+# define COMPILER_VERSION_PATCH DEC(__IBMCPP__    % 10)
+
+#elif defined(__ibmxl__) && defined(__clang__)
+# define COMPILER_ID "XLClang"
+# define COMPILER_VERSION_MAJOR DEC(__ibmxl_version__)
+# define COMPILER_VERSION_MINOR DEC(__ibmxl_release__)
+# define COMPILER_VERSION_PATCH DEC(__ibmxl_modification__)
+# define COMPILER_VERSION_TWEAK DEC(__ibmxl_ptf_fix_level__)
+
+
+#elif defined(__IBMCPP__) && !defined(__COMPILER_VER__) && __IBMCPP__ >= 800
+# define COMPILER_ID "XL"
+  /* __IBMCPP__ = VRP */
+# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100)
+# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10)
+# define COMPILER_VERSION_PATCH DEC(__IBMCPP__    % 10)
+
+#elif defined(__IBMCPP__) && !defined(__COMPILER_VER__) && __IBMCPP__ < 800
+# define COMPILER_ID "VisualAge"
+  /* __IBMCPP__ = VRP */
+# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100)
+# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10)
+# define COMPILER_VERSION_PATCH DEC(__IBMCPP__    % 10)
+
+#elif defined(__PGI)
+# define COMPILER_ID "PGI"
+# define COMPILER_VERSION_MAJOR DEC(__PGIC__)
+# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__)
+# if defined(__PGIC_PATCHLEVEL__)
+#  define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__)
+# endif
+
+#elif defined(_CRAYC)
+# define COMPILER_ID "Cray"
+# define COMPILER_VERSION_MAJOR DEC(_RELEASE_MAJOR)
+# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR)
+
+#elif defined(__TI_COMPILER_VERSION__)
+# define COMPILER_ID "TI"
+  /* __TI_COMPILER_VERSION__ = VVVRRRPPP */
+# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000)
+# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000   % 1000)
+# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__        % 1000)
+
+#elif defined(__FUJITSU) || defined(__FCC_VERSION) || defined(__fcc_version)
+# define COMPILER_ID "Fujitsu"
+
+#elif defined(__ghs__)
+# define COMPILER_ID "GHS"
+/* __GHS_VERSION_NUMBER = VVVVRP */
+# ifdef __GHS_VERSION_NUMBER
+# define COMPILER_VERSION_MAJOR DEC(__GHS_VERSION_NUMBER / 100)
+# define COMPILER_VERSION_MINOR DEC(__GHS_VERSION_NUMBER / 10 % 10)
+# define COMPILER_VERSION_PATCH DEC(__GHS_VERSION_NUMBER      % 10)
+# endif
+
+#elif defined(__SCO_VERSION__)
+# define COMPILER_ID "SCO"
+
+#elif defined(__ARMCC_VERSION) && !defined(__clang__)
+# define COMPILER_ID "ARMCC"
+#if __ARMCC_VERSION >= 1000000
+  /* __ARMCC_VERSION = VRRPPPP */
+  # define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/1000000)
+  # define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 100)
+  # define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION     % 10000)
+#else
+  /* __ARMCC_VERSION = VRPPPP */
+  # define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/100000)
+  # define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 10)
+  # define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION    % 10000)
+#endif
+
+
+#elif defined(__clang__) && defined(__apple_build_version__)
+# define COMPILER_ID "AppleClang"
+# if defined(_MSC_VER)
+#  define SIMULATE_ID "MSVC"
+# endif
+# define COMPILER_VERSION_MAJOR DEC(__clang_major__)
+# define COMPILER_VERSION_MINOR DEC(__clang_minor__)
+# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__)
+# if defined(_MSC_VER)
+   /* _MSC_VER = VVRR */
+#  define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)
+#  define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)
+# endif
+# define COMPILER_VERSION_TWEAK DEC(__apple_build_version__)
+
+#elif defined(__clang__) && defined(__ARMCOMPILER_VERSION)
+# define COMPILER_ID "ARMClang"
+  # define COMPILER_VERSION_MAJOR DEC(__ARMCOMPILER_VERSION/1000000)
+  # define COMPILER_VERSION_MINOR DEC(__ARMCOMPILER_VERSION/10000 % 100)
+  # define COMPILER_VERSION_PATCH DEC(__ARMCOMPILER_VERSION     % 10000)
+# define COMPILER_VERSION_INTERNAL DEC(__ARMCOMPILER_VERSION)
+
+#elif defined(__clang__)
+# define COMPILER_ID "Clang"
+# if defined(_MSC_VER)
+#  define SIMULATE_ID "MSVC"
+# endif
+# define COMPILER_VERSION_MAJOR DEC(__clang_major__)
+# define COMPILER_VERSION_MINOR DEC(__clang_minor__)
+# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__)
+# if defined(_MSC_VER)
+   /* _MSC_VER = VVRR */
+#  define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)
+#  define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)
+# endif
+
+#elif defined(__GNUC__) || defined(__GNUG__)
+# define COMPILER_ID "GNU"
+# if defined(__GNUC__)
+#  define COMPILER_VERSION_MAJOR DEC(__GNUC__)
+# else
+#  define COMPILER_VERSION_MAJOR DEC(__GNUG__)
+# endif
+# if defined(__GNUC_MINOR__)
+#  define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__)
+# endif
+# if defined(__GNUC_PATCHLEVEL__)
+#  define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__)
+# endif
+
+#elif defined(_MSC_VER)
+# define COMPILER_ID "MSVC"
+  /* _MSC_VER = VVRR */
+# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100)
+# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100)
+# if defined(_MSC_FULL_VER)
+#  if _MSC_VER >= 1400
+    /* _MSC_FULL_VER = VVRRPPPPP */
+#   define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000)
+#  else
+    /* _MSC_FULL_VER = VVRRPPPP */
+#   define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000)
+#  endif
+# endif
+# if defined(_MSC_BUILD)
+#  define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD)
+# endif
+
+#elif defined(__VISUALDSPVERSION__) || defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__)
+# define COMPILER_ID "ADSP"
+#if defined(__VISUALDSPVERSION__)
+  /* __VISUALDSPVERSION__ = 0xVVRRPP00 */
+# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24)
+# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF)
+# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8  & 0xFF)
+#endif
+
+#elif defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC)
+# define COMPILER_ID "IAR"
+# if defined(__VER__) && defined(__ICCARM__)
+#  define COMPILER_VERSION_MAJOR DEC((__VER__) / 1000000)
+#  define COMPILER_VERSION_MINOR DEC(((__VER__) / 1000) % 1000)
+#  define COMPILER_VERSION_PATCH DEC((__VER__) % 1000)
+#  define COMPILER_VERSION_INTERNAL DEC(__IAR_SYSTEMS_ICC__)
+# elif defined(__VER__) && (defined(__ICCAVR__) || defined(__ICCRX__) || defined(__ICCRH850__) || defined(__ICCRL78__) || defined(__ICC430__) || defined(__ICCRISCV__) || defined(__ICCV850__) || defined(__ICC8051__))
+#  define COMPILER_VERSION_MAJOR DEC((__VER__) / 100)
+#  define COMPILER_VERSION_MINOR DEC((__VER__) - (((__VER__) / 100)*100))
+#  define COMPILER_VERSION_PATCH DEC(__SUBVERSION__)
+#  define COMPILER_VERSION_INTERNAL DEC(__IAR_SYSTEMS_ICC__)
+# endif
+
+
+/* These compilers are either not known or too old to define an
+  identification macro.  Try to identify the platform and guess that
+  it is the native compiler.  */
+#elif defined(__hpux) || defined(__hpua)
+# define COMPILER_ID "HP"
+
+#else /* unknown compiler */
+# define COMPILER_ID ""
+#endif
+
+/* Construct the string literal in pieces to prevent the source from
+   getting matched.  Store it in a pointer rather than an array
+   because some compilers will just produce instructions to fill the
+   array rather than assigning a pointer to a static array.  */
+char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]";
+#ifdef SIMULATE_ID
+char const* info_simulate = "INFO" ":" "simulate[" SIMULATE_ID "]";
+#endif
+
+#ifdef __QNXNTO__
+char const* qnxnto = "INFO" ":" "qnxnto[]";
+#endif
+
+#if defined(__CRAYXE) || defined(__CRAYXC)
+char const *info_cray = "INFO" ":" "compiler_wrapper[CrayPrgEnv]";
+#endif
+
+#define STRINGIFY_HELPER(X) #X
+#define STRINGIFY(X) STRINGIFY_HELPER(X)
+
+/* Identify known platforms by name.  */
+#if defined(__linux) || defined(__linux__) || defined(linux)
+# define PLATFORM_ID "Linux"
+
+#elif defined(__CYGWIN__)
+# define PLATFORM_ID "Cygwin"
+
+#elif defined(__MINGW32__)
+# define PLATFORM_ID "MinGW"
+
+#elif defined(__APPLE__)
+# define PLATFORM_ID "Darwin"
+
+#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32)
+# define PLATFORM_ID "Windows"
+
+#elif defined(__FreeBSD__) || defined(__FreeBSD)
+# define PLATFORM_ID "FreeBSD"
+
+#elif defined(__NetBSD__) || defined(__NetBSD)
+# define PLATFORM_ID "NetBSD"
+
+#elif defined(__OpenBSD__) || defined(__OPENBSD)
+# define PLATFORM_ID "OpenBSD"
+
+#elif defined(__sun) || defined(sun)
+# define PLATFORM_ID "SunOS"
+
+#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__)
+# define PLATFORM_ID "AIX"
+
+#elif defined(__hpux) || defined(__hpux__)
+# define PLATFORM_ID "HP-UX"
+
+#elif defined(__HAIKU__)
+# define PLATFORM_ID "Haiku"
+
+#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS)
+# define PLATFORM_ID "BeOS"
+
+#elif defined(__QNX__) || defined(__QNXNTO__)
+# define PLATFORM_ID "QNX"
+
+#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__)
+# define PLATFORM_ID "Tru64"
+
+#elif defined(__riscos) || defined(__riscos__)
+# define PLATFORM_ID "RISCos"
+
+#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__)
+# define PLATFORM_ID "SINIX"
+
+#elif defined(__UNIX_SV__)
+# define PLATFORM_ID "UNIX_SV"
+
+#elif defined(__bsdos__)
+# define PLATFORM_ID "BSDOS"
+
+#elif defined(_MPRAS) || defined(MPRAS)
+# define PLATFORM_ID "MP-RAS"
+
+#elif defined(__osf) || defined(__osf__)
+# define PLATFORM_ID "OSF1"
+
+#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv)
+# define PLATFORM_ID "SCO_SV"
+
+#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX)
+# define PLATFORM_ID "ULTRIX"
+
+#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX)
+# define PLATFORM_ID "Xenix"
+
+#elif defined(__WATCOMC__)
+# if defined(__LINUX__)
+#  define PLATFORM_ID "Linux"
+
+# elif defined(__DOS__)
+#  define PLATFORM_ID "DOS"
+
+# elif defined(__OS2__)
+#  define PLATFORM_ID "OS2"
+
+# elif defined(__WINDOWS__)
+#  define PLATFORM_ID "Windows3x"
+
+# else /* unknown platform */
+#  define PLATFORM_ID
+# endif
+
+#elif defined(__INTEGRITY)
+# if defined(INT_178B)
+#  define PLATFORM_ID "Integrity178"
+
+# else /* regular Integrity */
+#  define PLATFORM_ID "Integrity"
+# endif
+
+#else /* unknown platform */
+# define PLATFORM_ID
+
+#endif
+
+/* For windows compilers MSVC and Intel we can determine
+   the architecture of the compiler being used.  This is because
+   the compilers do not have flags that can change the architecture,
+   but rather depend on which compiler is being used
+*/
+#if defined(_WIN32) && defined(_MSC_VER)
+# if defined(_M_IA64)
+#  define ARCHITECTURE_ID "IA64"
+
+# elif defined(_M_X64) || defined(_M_AMD64)
+#  define ARCHITECTURE_ID "x64"
+
+# elif defined(_M_IX86)
+#  define ARCHITECTURE_ID "X86"
+
+# elif defined(_M_ARM64)
+#  define ARCHITECTURE_ID "ARM64"
+
+# elif defined(_M_ARM)
+#  if _M_ARM == 4
+#   define ARCHITECTURE_ID "ARMV4I"
+#  elif _M_ARM == 5
+#   define ARCHITECTURE_ID "ARMV5I"
+#  else
+#   define ARCHITECTURE_ID "ARMV" STRINGIFY(_M_ARM)
+#  endif
+
+# elif defined(_M_MIPS)
+#  define ARCHITECTURE_ID "MIPS"
+
+# elif defined(_M_SH)
+#  define ARCHITECTURE_ID "SHx"
+
+# else /* unknown architecture */
+#  define ARCHITECTURE_ID ""
+# endif
+
+#elif defined(__WATCOMC__)
+# if defined(_M_I86)
+#  define ARCHITECTURE_ID "I86"
+
+# elif defined(_M_IX86)
+#  define ARCHITECTURE_ID "X86"
+
+# else /* unknown architecture */
+#  define ARCHITECTURE_ID ""
+# endif
+
+#elif defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC)
+# if defined(__ICCARM__)
+#  define ARCHITECTURE_ID "ARM"
+
+# elif defined(__ICCRX__)
+#  define ARCHITECTURE_ID "RX"
+
+# elif defined(__ICCRH850__)
+#  define ARCHITECTURE_ID "RH850"
+
+# elif defined(__ICCRL78__)
+#  define ARCHITECTURE_ID "RL78"
+
+# elif defined(__ICCRISCV__)
+#  define ARCHITECTURE_ID "RISCV"
+
+# elif defined(__ICCAVR__)
+#  define ARCHITECTURE_ID "AVR"
+
+# elif defined(__ICC430__)
+#  define ARCHITECTURE_ID "MSP430"
+
+# elif defined(__ICCV850__)
+#  define ARCHITECTURE_ID "V850"
+
+# elif defined(__ICC8051__)
+#  define ARCHITECTURE_ID "8051"
+
+# else /* unknown architecture */
+#  define ARCHITECTURE_ID ""
+# endif
+
+#elif defined(__ghs__)
+# if defined(__PPC64__)
+#  define ARCHITECTURE_ID "PPC64"
+
+# elif defined(__ppc__)
+#  define ARCHITECTURE_ID "PPC"
+
+# elif defined(__ARM__)
+#  define ARCHITECTURE_ID "ARM"
+
+# elif defined(__x86_64__)
+#  define ARCHITECTURE_ID "x64"
+
+# elif defined(__i386__)
+#  define ARCHITECTURE_ID "X86"
+
+# else /* unknown architecture */
+#  define ARCHITECTURE_ID ""
+# endif
+#else
+#  define ARCHITECTURE_ID
+#endif
+
+/* Convert integer to decimal digit literals.  */
+#define DEC(n)                   \
+  ('0' + (((n) / 10000000)%10)), \
+  ('0' + (((n) / 1000000)%10)),  \
+  ('0' + (((n) / 100000)%10)),   \
+  ('0' + (((n) / 10000)%10)),    \
+  ('0' + (((n) / 1000)%10)),     \
+  ('0' + (((n) / 100)%10)),      \
+  ('0' + (((n) / 10)%10)),       \
+  ('0' +  ((n) % 10))
+
+/* Convert integer to hex digit literals.  */
+#define HEX(n)             \
+  ('0' + ((n)>>28 & 0xF)), \
+  ('0' + ((n)>>24 & 0xF)), \
+  ('0' + ((n)>>20 & 0xF)), \
+  ('0' + ((n)>>16 & 0xF)), \
+  ('0' + ((n)>>12 & 0xF)), \
+  ('0' + ((n)>>8  & 0xF)), \
+  ('0' + ((n)>>4  & 0xF)), \
+  ('0' + ((n)     & 0xF))
+
+/* Construct a string literal encoding the version number components. */
+#ifdef COMPILER_VERSION_MAJOR
+char const info_version[] = {
+  'I', 'N', 'F', 'O', ':',
+  'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[',
+  COMPILER_VERSION_MAJOR,
+# ifdef COMPILER_VERSION_MINOR
+  '.', COMPILER_VERSION_MINOR,
+#  ifdef COMPILER_VERSION_PATCH
+   '.', COMPILER_VERSION_PATCH,
+#   ifdef COMPILER_VERSION_TWEAK
+    '.', COMPILER_VERSION_TWEAK,
+#   endif
+#  endif
+# endif
+  ']','\0'};
+#endif
+
+/* Construct a string literal encoding the internal version number. */
+#ifdef COMPILER_VERSION_INTERNAL
+char const info_version_internal[] = {
+  'I', 'N', 'F', 'O', ':',
+  'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','_',
+  'i','n','t','e','r','n','a','l','[',
+  COMPILER_VERSION_INTERNAL,']','\0'};
+#endif
+
+/* Construct a string literal encoding the version number components. */
+#ifdef SIMULATE_VERSION_MAJOR
+char const info_simulate_version[] = {
+  'I', 'N', 'F', 'O', ':',
+  's','i','m','u','l','a','t','e','_','v','e','r','s','i','o','n','[',
+  SIMULATE_VERSION_MAJOR,
+# ifdef SIMULATE_VERSION_MINOR
+  '.', SIMULATE_VERSION_MINOR,
+#  ifdef SIMULATE_VERSION_PATCH
+   '.', SIMULATE_VERSION_PATCH,
+#   ifdef SIMULATE_VERSION_TWEAK
+    '.', SIMULATE_VERSION_TWEAK,
+#   endif
+#  endif
+# endif
+  ']','\0'};
+#endif
+
+/* Construct the string literal in pieces to prevent the source from
+   getting matched.  Store it in a pointer rather than an array
+   because some compilers will just produce instructions to fill the
+   array rather than assigning a pointer to a static array.  */
+char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]";
+char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]";
+
+
+
+
+#if defined(__INTEL_COMPILER) && defined(_MSVC_LANG) && _MSVC_LANG < 201403L
+#  if defined(__INTEL_CXX11_MODE__)
+#    if defined(__cpp_aggregate_nsdmi)
+#      define CXX_STD 201402L
+#    else
+#      define CXX_STD 201103L
+#    endif
+#  else
+#    define CXX_STD 199711L
+#  endif
+#elif defined(_MSC_VER) && defined(_MSVC_LANG)
+#  define CXX_STD _MSVC_LANG
+#else
+#  define CXX_STD __cplusplus
+#endif
+
+const char* info_language_dialect_default = "INFO" ":" "dialect_default["
+#if CXX_STD > 201703L
+  "20"
+#elif CXX_STD >= 201703L
+  "17"
+#elif CXX_STD >= 201402L
+  "14"
+#elif CXX_STD >= 201103L
+  "11"
+#else
+  "98"
+#endif
+"]";
+
+/*--------------------------------------------------------------------------*/
+
+int main(int argc, char* argv[])
+{
+  int require = 0;
+  require += info_compiler[argc];
+  require += info_platform[argc];
+#ifdef COMPILER_VERSION_MAJOR
+  require += info_version[argc];
+#endif
+#ifdef COMPILER_VERSION_INTERNAL
+  require += info_version_internal[argc];
+#endif
+#ifdef SIMULATE_ID
+  require += info_simulate[argc];
+#endif
+#ifdef SIMULATE_VERSION_MAJOR
+  require += info_simulate_version[argc];
+#endif
+#if defined(__CRAYXE) || defined(__CRAYXC)
+  require += info_cray[argc];
+#endif
+  require += info_language_dialect_default[argc];
+  (void)argv;
+  return require;
+}
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeDirectoryInformation.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeDirectoryInformation.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..b963b51cee0319bd82851f71d195feffbd7516e3
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeDirectoryInformation.cmake
@@ -0,0 +1,16 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Relative path conversion top directories.
+set(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc")
+set(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver")
+
+# Force unix paths in dependencies.
+set(CMAKE_FORCE_UNIX_PATHS 1)
+
+
+# The C and CXX include file regular expressions for this directory.
+set(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$")
+set(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$")
+set(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN})
+set(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN})
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeError.log b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeError.log
new file mode 100644
index 0000000000000000000000000000000000000000..cd151c86e8a6aee66c320ce1fe15a3abfdd85407
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeError.log
@@ -0,0 +1,96 @@
+Determining if the function sgemm_ exists failed with the following output:
+Change Dir: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp
+
+Run Build Command(s):/usr/bin/make cmTC_5fc07/fast && /usr/bin/make -f CMakeFiles/cmTC_5fc07.dir/build.make CMakeFiles/cmTC_5fc07.dir/build
+make[1]: Entering directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+Building C object CMakeFiles/cmTC_5fc07.dir/CheckFunctionExists.c.o
+/usr/bin/cc   -DCHECK_FUNCTION_EXISTS=sgemm_   -o CMakeFiles/cmTC_5fc07.dir/CheckFunctionExists.c.o   -c /usr/share/cmake-3.16/Modules/CheckFunctionExists.c
+Linking C executable cmTC_5fc07
+/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_5fc07.dir/link.txt --verbose=1
+/usr/bin/cc  -DCHECK_FUNCTION_EXISTS=sgemm_    -rdynamic CMakeFiles/cmTC_5fc07.dir/CheckFunctionExists.c.o  -o cmTC_5fc07 
+/usr/bin/ld: CMakeFiles/cmTC_5fc07.dir/CheckFunctionExists.c.o: in function `main':
+CheckFunctionExists.c:(.text+0x14): undefined reference to `sgemm_'
+collect2: error: ld returned 1 exit status
+make[1]: *** [CMakeFiles/cmTC_5fc07.dir/build.make:87: cmTC_5fc07] Error 1
+make[1]: Leaving directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+make: *** [Makefile:121: cmTC_5fc07/fast] Error 2
+
+
+
+Performing C SOURCE FILE Test CMAKE_HAVE_LIBC_PTHREAD failed with the following output:
+Change Dir: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp
+
+Run Build Command(s):/usr/bin/make cmTC_b5523/fast && /usr/bin/make -f CMakeFiles/cmTC_b5523.dir/build.make CMakeFiles/cmTC_b5523.dir/build
+make[1]: Entering directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+Building C object CMakeFiles/cmTC_b5523.dir/src.c.o
+/usr/bin/cc   -DCMAKE_HAVE_LIBC_PTHREAD   -o CMakeFiles/cmTC_b5523.dir/src.c.o   -c /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp/src.c
+Linking C executable cmTC_b5523
+/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_b5523.dir/link.txt --verbose=1
+/usr/bin/cc  -DCMAKE_HAVE_LIBC_PTHREAD    -rdynamic CMakeFiles/cmTC_b5523.dir/src.c.o  -o cmTC_b5523 
+/usr/bin/ld: CMakeFiles/cmTC_b5523.dir/src.c.o: in function `main':
+src.c:(.text+0x46): undefined reference to `pthread_create'
+/usr/bin/ld: src.c:(.text+0x52): undefined reference to `pthread_detach'
+/usr/bin/ld: src.c:(.text+0x63): undefined reference to `pthread_join'
+collect2: error: ld returned 1 exit status
+make[1]: *** [CMakeFiles/cmTC_b5523.dir/build.make:87: cmTC_b5523] Error 1
+make[1]: Leaving directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+make: *** [Makefile:121: cmTC_b5523/fast] Error 2
+
+
+Source file was:
+#include <pthread.h>
+
+void* test_func(void* data)
+{
+  return data;
+}
+
+int main(void)
+{
+  pthread_t thread;
+  pthread_create(&thread, NULL, test_func, NULL);
+  pthread_detach(thread);
+  pthread_join(thread, NULL);
+  pthread_atfork(NULL, NULL, NULL);
+  pthread_exit(NULL);
+
+  return 0;
+}
+
+Determining if the function pthread_create exists in the pthreads failed with the following output:
+Change Dir: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp
+
+Run Build Command(s):/usr/bin/make cmTC_34996/fast && /usr/bin/make -f CMakeFiles/cmTC_34996.dir/build.make CMakeFiles/cmTC_34996.dir/build
+make[1]: Entering directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+Building C object CMakeFiles/cmTC_34996.dir/CheckFunctionExists.c.o
+/usr/bin/cc   -DCHECK_FUNCTION_EXISTS=pthread_create   -o CMakeFiles/cmTC_34996.dir/CheckFunctionExists.c.o   -c /usr/share/cmake-3.16/Modules/CheckFunctionExists.c
+Linking C executable cmTC_34996
+/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_34996.dir/link.txt --verbose=1
+/usr/bin/cc  -DCHECK_FUNCTION_EXISTS=pthread_create    -rdynamic CMakeFiles/cmTC_34996.dir/CheckFunctionExists.c.o  -o cmTC_34996  -lpthreads 
+/usr/bin/ld: cannot find -lpthreads
+collect2: error: ld returned 1 exit status
+make[1]: *** [CMakeFiles/cmTC_34996.dir/build.make:87: cmTC_34996] Error 1
+make[1]: Leaving directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+make: *** [Makefile:121: cmTC_34996/fast] Error 2
+
+
+
+Determining if the function cheev_ exists failed with the following output:
+Change Dir: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp
+
+Run Build Command(s):/usr/bin/make cmTC_20d4a/fast && /usr/bin/make -f CMakeFiles/cmTC_20d4a.dir/build.make CMakeFiles/cmTC_20d4a.dir/build
+make[1]: Entering directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+Building C object CMakeFiles/cmTC_20d4a.dir/CheckFunctionExists.c.o
+/usr/bin/cc   -DCHECK_FUNCTION_EXISTS=cheev_   -o CMakeFiles/cmTC_20d4a.dir/CheckFunctionExists.c.o   -c /usr/share/cmake-3.16/Modules/CheckFunctionExists.c
+Linking C executable cmTC_20d4a
+/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_20d4a.dir/link.txt --verbose=1
+/usr/bin/cc  -DCHECK_FUNCTION_EXISTS=cheev_    -rdynamic CMakeFiles/cmTC_20d4a.dir/CheckFunctionExists.c.o  -o cmTC_20d4a  /usr/lib/x86_64-linux-gnu/libblas.so 
+/usr/bin/ld: CMakeFiles/cmTC_20d4a.dir/CheckFunctionExists.c.o: in function `main':
+CheckFunctionExists.c:(.text+0x14): undefined reference to `cheev_'
+collect2: error: ld returned 1 exit status
+make[1]: *** [CMakeFiles/cmTC_20d4a.dir/build.make:88: cmTC_20d4a] Error 1
+make[1]: Leaving directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+make: *** [Makefile:121: cmTC_20d4a/fast] Error 2
+
+
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeOutput.log b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeOutput.log
new file mode 100644
index 0000000000000000000000000000000000000000..46fbd30851456935a057c96060d6dd7aeacb870c
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeOutput.log
@@ -0,0 +1,519 @@
+The system is: Linux - 5.4.0-132-generic - x86_64
+Compiling the C compiler identification source file "CMakeCCompilerId.c" succeeded.
+Compiler: /usr/bin/cc 
+Build flags: 
+Id flags:  
+
+The output was:
+0
+
+
+Compilation of the C compiler identification source "CMakeCCompilerId.c" produced "a.out"
+
+The C compiler identification is GNU, found in "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CompilerIdC/a.out"
+
+Compiling the CXX compiler identification source file "CMakeCXXCompilerId.cpp" succeeded.
+Compiler: /usr/bin/c++ 
+Build flags: 
+Id flags:  
+
+The output was:
+0
+
+
+Compilation of the CXX compiler identification source "CMakeCXXCompilerId.cpp" produced "a.out"
+
+The CXX compiler identification is GNU, found in "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/3.16.3/CompilerIdCXX/a.out"
+
+Determining if the C compiler works passed with the following output:
+Change Dir: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp
+
+Run Build Command(s):/usr/bin/make cmTC_b8dd2/fast && /usr/bin/make -f CMakeFiles/cmTC_b8dd2.dir/build.make CMakeFiles/cmTC_b8dd2.dir/build
+make[1]: Entering directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+Building C object CMakeFiles/cmTC_b8dd2.dir/testCCompiler.c.o
+/usr/bin/cc    -o CMakeFiles/cmTC_b8dd2.dir/testCCompiler.c.o   -c /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp/testCCompiler.c
+Linking C executable cmTC_b8dd2
+/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_b8dd2.dir/link.txt --verbose=1
+/usr/bin/cc      -rdynamic CMakeFiles/cmTC_b8dd2.dir/testCCompiler.c.o  -o cmTC_b8dd2 
+make[1]: Leaving directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+
+
+
+Detecting C compiler ABI info compiled with the following output:
+Change Dir: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp
+
+Run Build Command(s):/usr/bin/make cmTC_186e1/fast && /usr/bin/make -f CMakeFiles/cmTC_186e1.dir/build.make CMakeFiles/cmTC_186e1.dir/build
+make[1]: Entering directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+Building C object CMakeFiles/cmTC_186e1.dir/CMakeCCompilerABI.c.o
+/usr/bin/cc   -v -o CMakeFiles/cmTC_186e1.dir/CMakeCCompilerABI.c.o   -c /usr/share/cmake-3.16/Modules/CMakeCCompilerABI.c
+Using built-in specs.
+COLLECT_GCC=/usr/bin/cc
+OFFLOAD_TARGET_NAMES=nvptx-none:hsa
+OFFLOAD_TARGET_DEFAULT=1
+Target: x86_64-linux-gnu
+Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.4.0-1ubuntu1~20.04.1' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c,ada,c++,go,brig,d,fortran,objc,obj-c++,gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-Av3uEd/gcc-9-9.4.0/debian/tmp-nvptx/usr,hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu
+Thread model: posix
+gcc version 9.4.0 (Ubuntu 9.4.0-1ubuntu1~20.04.1) 
+COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_186e1.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64'
+ /usr/lib/gcc/x86_64-linux-gnu/9/cc1 -quiet -v -imultiarch x86_64-linux-gnu /usr/share/cmake-3.16/Modules/CMakeCCompilerABI.c -quiet -dumpbase CMakeCCompilerABI.c -mtune=generic -march=x86-64 -auxbase-strip CMakeFiles/cmTC_186e1.dir/CMakeCCompilerABI.c.o -version -fasynchronous-unwind-tables -fstack-protector-strong -Wformat -Wformat-security -fstack-clash-protection -fcf-protection -o /tmp/ccXqHJTm.s
+GNU C17 (Ubuntu 9.4.0-1ubuntu1~20.04.1) version 9.4.0 (x86_64-linux-gnu)
+	compiled by GNU C version 9.4.0, GMP version 6.2.0, MPFR version 4.0.2, MPC version 1.1.0, isl version isl-0.22.1-GMP
+
+GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072
+ignoring nonexistent directory "/usr/local/include/x86_64-linux-gnu"
+ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/include-fixed"
+ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/../../../../x86_64-linux-gnu/include"
+#include "..." search starts here:
+#include <...> search starts here:
+ /usr/lib/gcc/x86_64-linux-gnu/9/include
+ /usr/local/include
+ /usr/include/x86_64-linux-gnu
+ /usr/include
+End of search list.
+GNU C17 (Ubuntu 9.4.0-1ubuntu1~20.04.1) version 9.4.0 (x86_64-linux-gnu)
+	compiled by GNU C version 9.4.0, GMP version 6.2.0, MPFR version 4.0.2, MPC version 1.1.0, isl version isl-0.22.1-GMP
+
+GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072
+Compiler executable checksum: c0c95c0b4209efec1c1892d5ff24030b
+COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_186e1.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64'
+ as -v --64 -o CMakeFiles/cmTC_186e1.dir/CMakeCCompilerABI.c.o /tmp/ccXqHJTm.s
+GNU assembler version 2.34 (x86_64-linux-gnu) using BFD version (GNU Binutils for Ubuntu) 2.34
+COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/
+LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/
+COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_186e1.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64'
+Linking C executable cmTC_186e1
+/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_186e1.dir/link.txt --verbose=1
+/usr/bin/cc     -v -rdynamic CMakeFiles/cmTC_186e1.dir/CMakeCCompilerABI.c.o  -o cmTC_186e1 
+Using built-in specs.
+COLLECT_GCC=/usr/bin/cc
+COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper
+OFFLOAD_TARGET_NAMES=nvptx-none:hsa
+OFFLOAD_TARGET_DEFAULT=1
+Target: x86_64-linux-gnu
+Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.4.0-1ubuntu1~20.04.1' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c,ada,c++,go,brig,d,fortran,objc,obj-c++,gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-Av3uEd/gcc-9-9.4.0/debian/tmp-nvptx/usr,hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu
+Thread model: posix
+gcc version 9.4.0 (Ubuntu 9.4.0-1ubuntu1~20.04.1) 
+COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/
+LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/
+COLLECT_GCC_OPTIONS='-v' '-rdynamic' '-o' 'cmTC_186e1' '-mtune=generic' '-march=x86-64'
+ /usr/lib/gcc/x86_64-linux-gnu/9/collect2 -plugin /usr/lib/gcc/x86_64-linux-gnu/9/liblto_plugin.so -plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper -plugin-opt=-fresolution=/tmp/ccTA3ooN.res -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -pie -z now -z relro -o cmTC_186e1 /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o -L/usr/lib/gcc/x86_64-linux-gnu/9 -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/9/../../.. CMakeFiles/cmTC_186e1.dir/CMakeCCompilerABI.c.o -lgcc --push-state --as-needed -lgcc_s --pop-state -lc -lgcc --push-state --as-needed -lgcc_s --pop-state /usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o
+COLLECT_GCC_OPTIONS='-v' '-rdynamic' '-o' 'cmTC_186e1' '-mtune=generic' '-march=x86-64'
+make[1]: Leaving directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+
+
+
+Parsed C implicit include dir info from above output: rv=done
+  found start of include info
+  found start of implicit include info
+    add: [/usr/lib/gcc/x86_64-linux-gnu/9/include]
+    add: [/usr/local/include]
+    add: [/usr/include/x86_64-linux-gnu]
+    add: [/usr/include]
+  end of search list found
+  collapse include dir [/usr/lib/gcc/x86_64-linux-gnu/9/include] ==> [/usr/lib/gcc/x86_64-linux-gnu/9/include]
+  collapse include dir [/usr/local/include] ==> [/usr/local/include]
+  collapse include dir [/usr/include/x86_64-linux-gnu] ==> [/usr/include/x86_64-linux-gnu]
+  collapse include dir [/usr/include] ==> [/usr/include]
+  implicit include dirs: [/usr/lib/gcc/x86_64-linux-gnu/9/include;/usr/local/include;/usr/include/x86_64-linux-gnu;/usr/include]
+
+
+Parsed C implicit link information from above output:
+  link line regex: [^( *|.*[/\])(ld|CMAKE_LINK_STARTFILE-NOTFOUND|([^/\]+-)?ld|collect2)[^/\]*( |$)]
+  ignore line: [Change Dir: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp]
+  ignore line: []
+  ignore line: [Run Build Command(s):/usr/bin/make cmTC_186e1/fast && /usr/bin/make -f CMakeFiles/cmTC_186e1.dir/build.make CMakeFiles/cmTC_186e1.dir/build]
+  ignore line: [make[1]: Entering directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp']
+  ignore line: [Building C object CMakeFiles/cmTC_186e1.dir/CMakeCCompilerABI.c.o]
+  ignore line: [/usr/bin/cc   -v -o CMakeFiles/cmTC_186e1.dir/CMakeCCompilerABI.c.o   -c /usr/share/cmake-3.16/Modules/CMakeCCompilerABI.c]
+  ignore line: [Using built-in specs.]
+  ignore line: [COLLECT_GCC=/usr/bin/cc]
+  ignore line: [OFFLOAD_TARGET_NAMES=nvptx-none:hsa]
+  ignore line: [OFFLOAD_TARGET_DEFAULT=1]
+  ignore line: [Target: x86_64-linux-gnu]
+  ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.4.0-1ubuntu1~20.04.1' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c ada c++ go brig d fortran objc obj-c++ gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32 m64 mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-Av3uEd/gcc-9-9.4.0/debian/tmp-nvptx/usr hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu]
+  ignore line: [Thread model: posix]
+  ignore line: [gcc version 9.4.0 (Ubuntu 9.4.0-1ubuntu1~20.04.1) ]
+  ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_186e1.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64']
+  ignore line: [ /usr/lib/gcc/x86_64-linux-gnu/9/cc1 -quiet -v -imultiarch x86_64-linux-gnu /usr/share/cmake-3.16/Modules/CMakeCCompilerABI.c -quiet -dumpbase CMakeCCompilerABI.c -mtune=generic -march=x86-64 -auxbase-strip CMakeFiles/cmTC_186e1.dir/CMakeCCompilerABI.c.o -version -fasynchronous-unwind-tables -fstack-protector-strong -Wformat -Wformat-security -fstack-clash-protection -fcf-protection -o /tmp/ccXqHJTm.s]
+  ignore line: [GNU C17 (Ubuntu 9.4.0-1ubuntu1~20.04.1) version 9.4.0 (x86_64-linux-gnu)]
+  ignore line: [	compiled by GNU C version 9.4.0  GMP version 6.2.0  MPFR version 4.0.2  MPC version 1.1.0  isl version isl-0.22.1-GMP]
+  ignore line: []
+  ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072]
+  ignore line: [ignoring nonexistent directory "/usr/local/include/x86_64-linux-gnu"]
+  ignore line: [ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/include-fixed"]
+  ignore line: [ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/../../../../x86_64-linux-gnu/include"]
+  ignore line: [#include "..." search starts here:]
+  ignore line: [#include <...> search starts here:]
+  ignore line: [ /usr/lib/gcc/x86_64-linux-gnu/9/include]
+  ignore line: [ /usr/local/include]
+  ignore line: [ /usr/include/x86_64-linux-gnu]
+  ignore line: [ /usr/include]
+  ignore line: [End of search list.]
+  ignore line: [GNU C17 (Ubuntu 9.4.0-1ubuntu1~20.04.1) version 9.4.0 (x86_64-linux-gnu)]
+  ignore line: [	compiled by GNU C version 9.4.0  GMP version 6.2.0  MPFR version 4.0.2  MPC version 1.1.0  isl version isl-0.22.1-GMP]
+  ignore line: []
+  ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072]
+  ignore line: [Compiler executable checksum: c0c95c0b4209efec1c1892d5ff24030b]
+  ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_186e1.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64']
+  ignore line: [ as -v --64 -o CMakeFiles/cmTC_186e1.dir/CMakeCCompilerABI.c.o /tmp/ccXqHJTm.s]
+  ignore line: [GNU assembler version 2.34 (x86_64-linux-gnu) using BFD version (GNU Binutils for Ubuntu) 2.34]
+  ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/]
+  ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/]
+  ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_186e1.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64']
+  ignore line: [Linking C executable cmTC_186e1]
+  ignore line: [/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_186e1.dir/link.txt --verbose=1]
+  ignore line: [/usr/bin/cc     -v -rdynamic CMakeFiles/cmTC_186e1.dir/CMakeCCompilerABI.c.o  -o cmTC_186e1 ]
+  ignore line: [Using built-in specs.]
+  ignore line: [COLLECT_GCC=/usr/bin/cc]
+  ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper]
+  ignore line: [OFFLOAD_TARGET_NAMES=nvptx-none:hsa]
+  ignore line: [OFFLOAD_TARGET_DEFAULT=1]
+  ignore line: [Target: x86_64-linux-gnu]
+  ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.4.0-1ubuntu1~20.04.1' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c ada c++ go brig d fortran objc obj-c++ gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32 m64 mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-Av3uEd/gcc-9-9.4.0/debian/tmp-nvptx/usr hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu]
+  ignore line: [Thread model: posix]
+  ignore line: [gcc version 9.4.0 (Ubuntu 9.4.0-1ubuntu1~20.04.1) ]
+  ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/]
+  ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/]
+  ignore line: [COLLECT_GCC_OPTIONS='-v' '-rdynamic' '-o' 'cmTC_186e1' '-mtune=generic' '-march=x86-64']
+  link line: [ /usr/lib/gcc/x86_64-linux-gnu/9/collect2 -plugin /usr/lib/gcc/x86_64-linux-gnu/9/liblto_plugin.so -plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper -plugin-opt=-fresolution=/tmp/ccTA3ooN.res -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -pie -z now -z relro -o cmTC_186e1 /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o -L/usr/lib/gcc/x86_64-linux-gnu/9 -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/9/../../.. CMakeFiles/cmTC_186e1.dir/CMakeCCompilerABI.c.o -lgcc --push-state --as-needed -lgcc_s --pop-state -lc -lgcc --push-state --as-needed -lgcc_s --pop-state /usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o]
+    arg [/usr/lib/gcc/x86_64-linux-gnu/9/collect2] ==> ignore
+    arg [-plugin] ==> ignore
+    arg [/usr/lib/gcc/x86_64-linux-gnu/9/liblto_plugin.so] ==> ignore
+    arg [-plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper] ==> ignore
+    arg [-plugin-opt=-fresolution=/tmp/ccTA3ooN.res] ==> ignore
+    arg [-plugin-opt=-pass-through=-lgcc] ==> ignore
+    arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore
+    arg [-plugin-opt=-pass-through=-lc] ==> ignore
+    arg [-plugin-opt=-pass-through=-lgcc] ==> ignore
+    arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore
+    arg [--build-id] ==> ignore
+    arg [--eh-frame-hdr] ==> ignore
+    arg [-m] ==> ignore
+    arg [elf_x86_64] ==> ignore
+    arg [--hash-style=gnu] ==> ignore
+    arg [--as-needed] ==> ignore
+    arg [-export-dynamic] ==> ignore
+    arg [-dynamic-linker] ==> ignore
+    arg [/lib64/ld-linux-x86-64.so.2] ==> ignore
+    arg [-pie] ==> ignore
+    arg [-znow] ==> ignore
+    arg [-zrelro] ==> ignore
+    arg [-o] ==> ignore
+    arg [cmTC_186e1] ==> ignore
+    arg [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o] ==> ignore
+    arg [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o] ==> ignore
+    arg [/usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o] ==> ignore
+    arg [-L/usr/lib/gcc/x86_64-linux-gnu/9] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9]
+    arg [-L/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu]
+    arg [-L/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib]
+    arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu]
+    arg [-L/lib/../lib] ==> dir [/lib/../lib]
+    arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu]
+    arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib]
+    arg [-L/usr/lib/gcc/x86_64-linux-gnu/9/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../..]
+    arg [CMakeFiles/cmTC_186e1.dir/CMakeCCompilerABI.c.o] ==> ignore
+    arg [-lgcc] ==> lib [gcc]
+    arg [--push-state] ==> ignore
+    arg [--as-needed] ==> ignore
+    arg [-lgcc_s] ==> lib [gcc_s]
+    arg [--pop-state] ==> ignore
+    arg [-lc] ==> lib [c]
+    arg [-lgcc] ==> lib [gcc]
+    arg [--push-state] ==> ignore
+    arg [--as-needed] ==> ignore
+    arg [-lgcc_s] ==> lib [gcc_s]
+    arg [--pop-state] ==> ignore
+    arg [/usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o] ==> ignore
+    arg [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o] ==> ignore
+  collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9] ==> [/usr/lib/gcc/x86_64-linux-gnu/9]
+  collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu]
+  collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib] ==> [/usr/lib]
+  collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu]
+  collapse library dir [/lib/../lib] ==> [/lib]
+  collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu]
+  collapse library dir [/usr/lib/../lib] ==> [/usr/lib]
+  collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../..] ==> [/usr/lib]
+  implicit libs: [gcc;gcc_s;c;gcc;gcc_s]
+  implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/9;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib]
+  implicit fwks: []
+
+
+Determining if the CXX compiler works passed with the following output:
+Change Dir: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp
+
+Run Build Command(s):/usr/bin/make cmTC_b4472/fast && /usr/bin/make -f CMakeFiles/cmTC_b4472.dir/build.make CMakeFiles/cmTC_b4472.dir/build
+make[1]: Entering directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+Building CXX object CMakeFiles/cmTC_b4472.dir/testCXXCompiler.cxx.o
+/usr/bin/c++     -o CMakeFiles/cmTC_b4472.dir/testCXXCompiler.cxx.o -c /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp/testCXXCompiler.cxx
+Linking CXX executable cmTC_b4472
+/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_b4472.dir/link.txt --verbose=1
+/usr/bin/c++       -rdynamic CMakeFiles/cmTC_b4472.dir/testCXXCompiler.cxx.o  -o cmTC_b4472 
+make[1]: Leaving directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+
+
+
+Detecting CXX compiler ABI info compiled with the following output:
+Change Dir: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp
+
+Run Build Command(s):/usr/bin/make cmTC_98b64/fast && /usr/bin/make -f CMakeFiles/cmTC_98b64.dir/build.make CMakeFiles/cmTC_98b64.dir/build
+make[1]: Entering directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+Building CXX object CMakeFiles/cmTC_98b64.dir/CMakeCXXCompilerABI.cpp.o
+/usr/bin/c++    -v -o CMakeFiles/cmTC_98b64.dir/CMakeCXXCompilerABI.cpp.o -c /usr/share/cmake-3.16/Modules/CMakeCXXCompilerABI.cpp
+Using built-in specs.
+COLLECT_GCC=/usr/bin/c++
+OFFLOAD_TARGET_NAMES=nvptx-none:hsa
+OFFLOAD_TARGET_DEFAULT=1
+Target: x86_64-linux-gnu
+Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.4.0-1ubuntu1~20.04.1' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c,ada,c++,go,brig,d,fortran,objc,obj-c++,gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-Av3uEd/gcc-9-9.4.0/debian/tmp-nvptx/usr,hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu
+Thread model: posix
+gcc version 9.4.0 (Ubuntu 9.4.0-1ubuntu1~20.04.1) 
+COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_98b64.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64'
+ /usr/lib/gcc/x86_64-linux-gnu/9/cc1plus -quiet -v -imultiarch x86_64-linux-gnu -D_GNU_SOURCE /usr/share/cmake-3.16/Modules/CMakeCXXCompilerABI.cpp -quiet -dumpbase CMakeCXXCompilerABI.cpp -mtune=generic -march=x86-64 -auxbase-strip CMakeFiles/cmTC_98b64.dir/CMakeCXXCompilerABI.cpp.o -version -fasynchronous-unwind-tables -fstack-protector-strong -Wformat -Wformat-security -fstack-clash-protection -fcf-protection -o /tmp/cc3XPvqk.s
+GNU C++14 (Ubuntu 9.4.0-1ubuntu1~20.04.1) version 9.4.0 (x86_64-linux-gnu)
+	compiled by GNU C version 9.4.0, GMP version 6.2.0, MPFR version 4.0.2, MPC version 1.1.0, isl version isl-0.22.1-GMP
+
+GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072
+ignoring duplicate directory "/usr/include/x86_64-linux-gnu/c++/9"
+ignoring nonexistent directory "/usr/local/include/x86_64-linux-gnu"
+ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/include-fixed"
+ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/../../../../x86_64-linux-gnu/include"
+#include "..." search starts here:
+#include <...> search starts here:
+ /usr/include/c++/9
+ /usr/include/x86_64-linux-gnu/c++/9
+ /usr/include/c++/9/backward
+ /usr/lib/gcc/x86_64-linux-gnu/9/include
+ /usr/local/include
+ /usr/include/x86_64-linux-gnu
+ /usr/include
+End of search list.
+GNU C++14 (Ubuntu 9.4.0-1ubuntu1~20.04.1) version 9.4.0 (x86_64-linux-gnu)
+	compiled by GNU C version 9.4.0, GMP version 6.2.0, MPFR version 4.0.2, MPC version 1.1.0, isl version isl-0.22.1-GMP
+
+GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072
+Compiler executable checksum: 65fe925b83d3956b533de4aaba7dace0
+COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_98b64.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64'
+ as -v --64 -o CMakeFiles/cmTC_98b64.dir/CMakeCXXCompilerABI.cpp.o /tmp/cc3XPvqk.s
+GNU assembler version 2.34 (x86_64-linux-gnu) using BFD version (GNU Binutils for Ubuntu) 2.34
+COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/
+LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/
+COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_98b64.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64'
+Linking CXX executable cmTC_98b64
+/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_98b64.dir/link.txt --verbose=1
+/usr/bin/c++      -v -rdynamic CMakeFiles/cmTC_98b64.dir/CMakeCXXCompilerABI.cpp.o  -o cmTC_98b64 
+Using built-in specs.
+COLLECT_GCC=/usr/bin/c++
+COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper
+OFFLOAD_TARGET_NAMES=nvptx-none:hsa
+OFFLOAD_TARGET_DEFAULT=1
+Target: x86_64-linux-gnu
+Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.4.0-1ubuntu1~20.04.1' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c,ada,c++,go,brig,d,fortran,objc,obj-c++,gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-Av3uEd/gcc-9-9.4.0/debian/tmp-nvptx/usr,hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu
+Thread model: posix
+gcc version 9.4.0 (Ubuntu 9.4.0-1ubuntu1~20.04.1) 
+COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/
+LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/
+COLLECT_GCC_OPTIONS='-v' '-rdynamic' '-o' 'cmTC_98b64' '-shared-libgcc' '-mtune=generic' '-march=x86-64'
+ /usr/lib/gcc/x86_64-linux-gnu/9/collect2 -plugin /usr/lib/gcc/x86_64-linux-gnu/9/liblto_plugin.so -plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper -plugin-opt=-fresolution=/tmp/cca7u5HO.res -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -pie -z now -z relro -o cmTC_98b64 /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o -L/usr/lib/gcc/x86_64-linux-gnu/9 -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/9/../../.. CMakeFiles/cmTC_98b64.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o
+COLLECT_GCC_OPTIONS='-v' '-rdynamic' '-o' 'cmTC_98b64' '-shared-libgcc' '-mtune=generic' '-march=x86-64'
+make[1]: Leaving directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+
+
+
+Parsed CXX implicit include dir info from above output: rv=done
+  found start of include info
+  found start of implicit include info
+    add: [/usr/include/c++/9]
+    add: [/usr/include/x86_64-linux-gnu/c++/9]
+    add: [/usr/include/c++/9/backward]
+    add: [/usr/lib/gcc/x86_64-linux-gnu/9/include]
+    add: [/usr/local/include]
+    add: [/usr/include/x86_64-linux-gnu]
+    add: [/usr/include]
+  end of search list found
+  collapse include dir [/usr/include/c++/9] ==> [/usr/include/c++/9]
+  collapse include dir [/usr/include/x86_64-linux-gnu/c++/9] ==> [/usr/include/x86_64-linux-gnu/c++/9]
+  collapse include dir [/usr/include/c++/9/backward] ==> [/usr/include/c++/9/backward]
+  collapse include dir [/usr/lib/gcc/x86_64-linux-gnu/9/include] ==> [/usr/lib/gcc/x86_64-linux-gnu/9/include]
+  collapse include dir [/usr/local/include] ==> [/usr/local/include]
+  collapse include dir [/usr/include/x86_64-linux-gnu] ==> [/usr/include/x86_64-linux-gnu]
+  collapse include dir [/usr/include] ==> [/usr/include]
+  implicit include dirs: [/usr/include/c++/9;/usr/include/x86_64-linux-gnu/c++/9;/usr/include/c++/9/backward;/usr/lib/gcc/x86_64-linux-gnu/9/include;/usr/local/include;/usr/include/x86_64-linux-gnu;/usr/include]
+
+
+Parsed CXX implicit link information from above output:
+  link line regex: [^( *|.*[/\])(ld|CMAKE_LINK_STARTFILE-NOTFOUND|([^/\]+-)?ld|collect2)[^/\]*( |$)]
+  ignore line: [Change Dir: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp]
+  ignore line: []
+  ignore line: [Run Build Command(s):/usr/bin/make cmTC_98b64/fast && /usr/bin/make -f CMakeFiles/cmTC_98b64.dir/build.make CMakeFiles/cmTC_98b64.dir/build]
+  ignore line: [make[1]: Entering directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp']
+  ignore line: [Building CXX object CMakeFiles/cmTC_98b64.dir/CMakeCXXCompilerABI.cpp.o]
+  ignore line: [/usr/bin/c++    -v -o CMakeFiles/cmTC_98b64.dir/CMakeCXXCompilerABI.cpp.o -c /usr/share/cmake-3.16/Modules/CMakeCXXCompilerABI.cpp]
+  ignore line: [Using built-in specs.]
+  ignore line: [COLLECT_GCC=/usr/bin/c++]
+  ignore line: [OFFLOAD_TARGET_NAMES=nvptx-none:hsa]
+  ignore line: [OFFLOAD_TARGET_DEFAULT=1]
+  ignore line: [Target: x86_64-linux-gnu]
+  ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.4.0-1ubuntu1~20.04.1' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c ada c++ go brig d fortran objc obj-c++ gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32 m64 mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-Av3uEd/gcc-9-9.4.0/debian/tmp-nvptx/usr hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu]
+  ignore line: [Thread model: posix]
+  ignore line: [gcc version 9.4.0 (Ubuntu 9.4.0-1ubuntu1~20.04.1) ]
+  ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_98b64.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64']
+  ignore line: [ /usr/lib/gcc/x86_64-linux-gnu/9/cc1plus -quiet -v -imultiarch x86_64-linux-gnu -D_GNU_SOURCE /usr/share/cmake-3.16/Modules/CMakeCXXCompilerABI.cpp -quiet -dumpbase CMakeCXXCompilerABI.cpp -mtune=generic -march=x86-64 -auxbase-strip CMakeFiles/cmTC_98b64.dir/CMakeCXXCompilerABI.cpp.o -version -fasynchronous-unwind-tables -fstack-protector-strong -Wformat -Wformat-security -fstack-clash-protection -fcf-protection -o /tmp/cc3XPvqk.s]
+  ignore line: [GNU C++14 (Ubuntu 9.4.0-1ubuntu1~20.04.1) version 9.4.0 (x86_64-linux-gnu)]
+  ignore line: [	compiled by GNU C version 9.4.0  GMP version 6.2.0  MPFR version 4.0.2  MPC version 1.1.0  isl version isl-0.22.1-GMP]
+  ignore line: []
+  ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072]
+  ignore line: [ignoring duplicate directory "/usr/include/x86_64-linux-gnu/c++/9"]
+  ignore line: [ignoring nonexistent directory "/usr/local/include/x86_64-linux-gnu"]
+  ignore line: [ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/include-fixed"]
+  ignore line: [ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/../../../../x86_64-linux-gnu/include"]
+  ignore line: [#include "..." search starts here:]
+  ignore line: [#include <...> search starts here:]
+  ignore line: [ /usr/include/c++/9]
+  ignore line: [ /usr/include/x86_64-linux-gnu/c++/9]
+  ignore line: [ /usr/include/c++/9/backward]
+  ignore line: [ /usr/lib/gcc/x86_64-linux-gnu/9/include]
+  ignore line: [ /usr/local/include]
+  ignore line: [ /usr/include/x86_64-linux-gnu]
+  ignore line: [ /usr/include]
+  ignore line: [End of search list.]
+  ignore line: [GNU C++14 (Ubuntu 9.4.0-1ubuntu1~20.04.1) version 9.4.0 (x86_64-linux-gnu)]
+  ignore line: [	compiled by GNU C version 9.4.0  GMP version 6.2.0  MPFR version 4.0.2  MPC version 1.1.0  isl version isl-0.22.1-GMP]
+  ignore line: []
+  ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072]
+  ignore line: [Compiler executable checksum: 65fe925b83d3956b533de4aaba7dace0]
+  ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_98b64.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64']
+  ignore line: [ as -v --64 -o CMakeFiles/cmTC_98b64.dir/CMakeCXXCompilerABI.cpp.o /tmp/cc3XPvqk.s]
+  ignore line: [GNU assembler version 2.34 (x86_64-linux-gnu) using BFD version (GNU Binutils for Ubuntu) 2.34]
+  ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/]
+  ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/]
+  ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_98b64.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64']
+  ignore line: [Linking CXX executable cmTC_98b64]
+  ignore line: [/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_98b64.dir/link.txt --verbose=1]
+  ignore line: [/usr/bin/c++      -v -rdynamic CMakeFiles/cmTC_98b64.dir/CMakeCXXCompilerABI.cpp.o  -o cmTC_98b64 ]
+  ignore line: [Using built-in specs.]
+  ignore line: [COLLECT_GCC=/usr/bin/c++]
+  ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper]
+  ignore line: [OFFLOAD_TARGET_NAMES=nvptx-none:hsa]
+  ignore line: [OFFLOAD_TARGET_DEFAULT=1]
+  ignore line: [Target: x86_64-linux-gnu]
+  ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.4.0-1ubuntu1~20.04.1' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c ada c++ go brig d fortran objc obj-c++ gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32 m64 mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-Av3uEd/gcc-9-9.4.0/debian/tmp-nvptx/usr hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu]
+  ignore line: [Thread model: posix]
+  ignore line: [gcc version 9.4.0 (Ubuntu 9.4.0-1ubuntu1~20.04.1) ]
+  ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/]
+  ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/]
+  ignore line: [COLLECT_GCC_OPTIONS='-v' '-rdynamic' '-o' 'cmTC_98b64' '-shared-libgcc' '-mtune=generic' '-march=x86-64']
+  link line: [ /usr/lib/gcc/x86_64-linux-gnu/9/collect2 -plugin /usr/lib/gcc/x86_64-linux-gnu/9/liblto_plugin.so -plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper -plugin-opt=-fresolution=/tmp/cca7u5HO.res -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -pie -z now -z relro -o cmTC_98b64 /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o -L/usr/lib/gcc/x86_64-linux-gnu/9 -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/9/../../.. CMakeFiles/cmTC_98b64.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o]
+    arg [/usr/lib/gcc/x86_64-linux-gnu/9/collect2] ==> ignore
+    arg [-plugin] ==> ignore
+    arg [/usr/lib/gcc/x86_64-linux-gnu/9/liblto_plugin.so] ==> ignore
+    arg [-plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper] ==> ignore
+    arg [-plugin-opt=-fresolution=/tmp/cca7u5HO.res] ==> ignore
+    arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore
+    arg [-plugin-opt=-pass-through=-lgcc] ==> ignore
+    arg [-plugin-opt=-pass-through=-lc] ==> ignore
+    arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore
+    arg [-plugin-opt=-pass-through=-lgcc] ==> ignore
+    arg [--build-id] ==> ignore
+    arg [--eh-frame-hdr] ==> ignore
+    arg [-m] ==> ignore
+    arg [elf_x86_64] ==> ignore
+    arg [--hash-style=gnu] ==> ignore
+    arg [--as-needed] ==> ignore
+    arg [-export-dynamic] ==> ignore
+    arg [-dynamic-linker] ==> ignore
+    arg [/lib64/ld-linux-x86-64.so.2] ==> ignore
+    arg [-pie] ==> ignore
+    arg [-znow] ==> ignore
+    arg [-zrelro] ==> ignore
+    arg [-o] ==> ignore
+    arg [cmTC_98b64] ==> ignore
+    arg [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o] ==> ignore
+    arg [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o] ==> ignore
+    arg [/usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o] ==> ignore
+    arg [-L/usr/lib/gcc/x86_64-linux-gnu/9] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9]
+    arg [-L/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu]
+    arg [-L/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib]
+    arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu]
+    arg [-L/lib/../lib] ==> dir [/lib/../lib]
+    arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu]
+    arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib]
+    arg [-L/usr/lib/gcc/x86_64-linux-gnu/9/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../..]
+    arg [CMakeFiles/cmTC_98b64.dir/CMakeCXXCompilerABI.cpp.o] ==> ignore
+    arg [-lstdc++] ==> lib [stdc++]
+    arg [-lm] ==> lib [m]
+    arg [-lgcc_s] ==> lib [gcc_s]
+    arg [-lgcc] ==> lib [gcc]
+    arg [-lc] ==> lib [c]
+    arg [-lgcc_s] ==> lib [gcc_s]
+    arg [-lgcc] ==> lib [gcc]
+    arg [/usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o] ==> ignore
+    arg [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o] ==> ignore
+  collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9] ==> [/usr/lib/gcc/x86_64-linux-gnu/9]
+  collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu]
+  collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib] ==> [/usr/lib]
+  collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu]
+  collapse library dir [/lib/../lib] ==> [/lib]
+  collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu]
+  collapse library dir [/usr/lib/../lib] ==> [/usr/lib]
+  collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../..] ==> [/usr/lib]
+  implicit libs: [stdc++;m;gcc_s;gcc;c;gcc_s;gcc]
+  implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/9;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib]
+  implicit fwks: []
+
+
+Determining if the include file pthread.h exists passed with the following output:
+Change Dir: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp
+
+Run Build Command(s):/usr/bin/make cmTC_78f5d/fast && /usr/bin/make -f CMakeFiles/cmTC_78f5d.dir/build.make CMakeFiles/cmTC_78f5d.dir/build
+make[1]: Entering directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+Building C object CMakeFiles/cmTC_78f5d.dir/CheckIncludeFile.c.o
+/usr/bin/cc    -o CMakeFiles/cmTC_78f5d.dir/CheckIncludeFile.c.o   -c /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp/CheckIncludeFile.c
+Linking C executable cmTC_78f5d
+/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_78f5d.dir/link.txt --verbose=1
+/usr/bin/cc      -rdynamic CMakeFiles/cmTC_78f5d.dir/CheckIncludeFile.c.o  -o cmTC_78f5d 
+make[1]: Leaving directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+
+
+
+Determining if the function pthread_create exists in the pthread passed with the following output:
+Change Dir: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp
+
+Run Build Command(s):/usr/bin/make cmTC_0afaa/fast && /usr/bin/make -f CMakeFiles/cmTC_0afaa.dir/build.make CMakeFiles/cmTC_0afaa.dir/build
+make[1]: Entering directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+Building C object CMakeFiles/cmTC_0afaa.dir/CheckFunctionExists.c.o
+/usr/bin/cc   -DCHECK_FUNCTION_EXISTS=pthread_create   -o CMakeFiles/cmTC_0afaa.dir/CheckFunctionExists.c.o   -c /usr/share/cmake-3.16/Modules/CheckFunctionExists.c
+Linking C executable cmTC_0afaa
+/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_0afaa.dir/link.txt --verbose=1
+/usr/bin/cc  -DCHECK_FUNCTION_EXISTS=pthread_create    -rdynamic CMakeFiles/cmTC_0afaa.dir/CheckFunctionExists.c.o  -o cmTC_0afaa  -lpthread 
+make[1]: Leaving directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+
+
+
+Determining if the function sgemm_ exists passed with the following output:
+Change Dir: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp
+
+Run Build Command(s):/usr/bin/make cmTC_13bb0/fast && /usr/bin/make -f CMakeFiles/cmTC_13bb0.dir/build.make CMakeFiles/cmTC_13bb0.dir/build
+make[1]: Entering directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+Building C object CMakeFiles/cmTC_13bb0.dir/CheckFunctionExists.c.o
+/usr/bin/cc   -DCHECK_FUNCTION_EXISTS=sgemm_   -o CMakeFiles/cmTC_13bb0.dir/CheckFunctionExists.c.o   -c /usr/share/cmake-3.16/Modules/CheckFunctionExists.c
+Linking C executable cmTC_13bb0
+/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_13bb0.dir/link.txt --verbose=1
+/usr/bin/cc  -DCHECK_FUNCTION_EXISTS=sgemm_    -rdynamic CMakeFiles/cmTC_13bb0.dir/CheckFunctionExists.c.o  -o cmTC_13bb0  /usr/lib/x86_64-linux-gnu/libblas.so 
+make[1]: Leaving directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+
+
+
+Determining if the function cheev_ exists passed with the following output:
+Change Dir: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp
+
+Run Build Command(s):/usr/bin/make cmTC_092c0/fast && /usr/bin/make -f CMakeFiles/cmTC_092c0.dir/build.make CMakeFiles/cmTC_092c0.dir/build
+make[1]: Entering directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+Building C object CMakeFiles/cmTC_092c0.dir/CheckFunctionExists.c.o
+/usr/bin/cc   -DCHECK_FUNCTION_EXISTS=cheev_   -o CMakeFiles/cmTC_092c0.dir/CheckFunctionExists.c.o   -c /usr/share/cmake-3.16/Modules/CheckFunctionExists.c
+Linking C executable cmTC_092c0
+/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_092c0.dir/link.txt --verbose=1
+/usr/bin/cc  -DCHECK_FUNCTION_EXISTS=cheev_    -rdynamic CMakeFiles/cmTC_092c0.dir/CheckFunctionExists.c.o  -o cmTC_092c0  /usr/lib/x86_64-linux-gnu/liblapack.so /usr/lib/x86_64-linux-gnu/libblas.so 
+make[1]: Leaving directory '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeTmp'
+
+
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeRuleHashes.txt b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeRuleHashes.txt
new file mode 100644
index 0000000000000000000000000000000000000000..b113470f593f1b568822d0cf269a2125f5448c9b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/CMakeRuleHashes.txt
@@ -0,0 +1,4 @@
+# Hashes of file build rules.
+2bda9e7c7d8ef3cc51a03f8cdf09928a CMakeFiles/clean_test_results
+5bb97a6b8b5fbcc1245e1b642028c294 CMakeFiles/mav_nonlinear_mpc_gencfg
+da5141821d5e3d306243845553ae4759 devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/Makefile.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/Makefile.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..375a1464595a5c40f68cd2f427aee4ed618d3bd5
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/Makefile.cmake
@@ -0,0 +1,324 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# The generator used is:
+set(CMAKE_DEPENDS_GENERATOR "Unix Makefiles")
+
+# The top level Makefile was generated from the following files:
+set(CMAKE_MAKEFILE_DEPENDS
+  "CMakeCache.txt"
+  "/home/simhe502/catkin_ws/devel/share/actionlib_msgs/cmake/actionlib_msgs-extras.cmake"
+  "/home/simhe502/catkin_ws/devel/share/actionlib_msgs/cmake/actionlib_msgs-msg-extras.cmake"
+  "/home/simhe502/catkin_ws/devel/share/actionlib_msgs/cmake/actionlib_msgsConfig-version.cmake"
+  "/home/simhe502/catkin_ws/devel/share/actionlib_msgs/cmake/actionlib_msgsConfig.cmake"
+  "/home/simhe502/catkin_ws/devel/share/catkin_simple/cmake/catkin_simple-extras.cmake"
+  "/home/simhe502/catkin_ws/devel/share/catkin_simple/cmake/catkin_simpleConfig-version.cmake"
+  "/home/simhe502/catkin_ws/devel/share/catkin_simple/cmake/catkin_simpleConfig.cmake"
+  "/home/simhe502/catkin_ws/devel/share/geometry_msgs/cmake/geometry_msgs-msg-extras.cmake"
+  "/home/simhe502/catkin_ws/devel/share/geometry_msgs/cmake/geometry_msgsConfig-version.cmake"
+  "/home/simhe502/catkin_ws/devel/share/geometry_msgs/cmake/geometry_msgsConfig.cmake"
+  "/home/simhe502/catkin_ws/devel/share/sensor_msgs/cmake/sensor_msgs-msg-extras.cmake"
+  "/home/simhe502/catkin_ws/devel/share/sensor_msgs/cmake/sensor_msgsConfig-version.cmake"
+  "/home/simhe502/catkin_ws/devel/share/sensor_msgs/cmake/sensor_msgsConfig.cmake"
+  "../CMakeLists.txt"
+  "../cmake/FindOpenBLAS.cmake"
+  "../package.xml"
+  "CMakeFiles/3.16.3/CMakeCCompiler.cmake"
+  "CMakeFiles/3.16.3/CMakeCXXCompiler.cmake"
+  "CMakeFiles/3.16.3/CMakeSystem.cmake"
+  "catkin/catkin_generated/version/package.cmake"
+  "catkin_generated/installspace/_setup_util.py"
+  "catkin_generated/ordered_paths.cmake"
+  "catkin_generated/package.cmake"
+  "/opt/ros/noetic/share/actionlib/cmake/actionlib-msg-extras.cmake"
+  "/opt/ros/noetic/share/actionlib/cmake/actionlibConfig-version.cmake"
+  "/opt/ros/noetic/share/actionlib/cmake/actionlibConfig.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/all.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/assert.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/atomic_configure_file.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/catkinConfig-version.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/catkinConfig.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/catkin_add_env_hooks.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/catkin_destinations.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/catkin_download.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/catkin_generate_environment.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/catkin_install_python.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/catkin_libraries.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/catkin_metapackage.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/catkin_package.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/catkin_package_xml.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/catkin_python_setup.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/catkin_symlink_install.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/catkin_workspace.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/custom_install.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/debug_message.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/em/pkg.pc.em"
+  "/opt/ros/noetic/share/catkin/cmake/em_expand.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/empy.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/find_program_required.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/interrogate_setup_dot_py.py"
+  "/opt/ros/noetic/share/catkin/cmake/legacy.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/list_append_deduplicate.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/list_append_unique.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/list_insert_in_workspace_order.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/platform/lsb.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/platform/ubuntu.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/platform/windows.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/python.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/safe_execute_process.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/stamp.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/string_starts_with.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/templates/_setup_util.py.in"
+  "/opt/ros/noetic/share/catkin/cmake/templates/env.sh.in"
+  "/opt/ros/noetic/share/catkin/cmake/templates/generate_cached_setup.py.in"
+  "/opt/ros/noetic/share/catkin/cmake/templates/local_setup.bash.in"
+  "/opt/ros/noetic/share/catkin/cmake/templates/local_setup.sh.in"
+  "/opt/ros/noetic/share/catkin/cmake/templates/local_setup.zsh.in"
+  "/opt/ros/noetic/share/catkin/cmake/templates/pkg.context.pc.in"
+  "/opt/ros/noetic/share/catkin/cmake/templates/pkgConfig-version.cmake.in"
+  "/opt/ros/noetic/share/catkin/cmake/templates/pkgConfig.cmake.in"
+  "/opt/ros/noetic/share/catkin/cmake/templates/rosinstall.in"
+  "/opt/ros/noetic/share/catkin/cmake/templates/setup.bash.in"
+  "/opt/ros/noetic/share/catkin/cmake/templates/setup.sh.in"
+  "/opt/ros/noetic/share/catkin/cmake/templates/setup.zsh.in"
+  "/opt/ros/noetic/share/catkin/cmake/test/catkin_download_test_data.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/test/gtest.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/test/nosetests.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/test/tests.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/tools/doxygen.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/tools/libraries.cmake"
+  "/opt/ros/noetic/share/catkin/cmake/tools/rt.cmake"
+  "/opt/ros/noetic/share/catkin/package.xml"
+  "/opt/ros/noetic/share/cmake_modules/cmake/Modules/FindEigen.cmake"
+  "/opt/ros/noetic/share/cmake_modules/cmake/cmake_modules-extras.cmake"
+  "/opt/ros/noetic/share/cmake_modules/cmake/cmake_modulesConfig-version.cmake"
+  "/opt/ros/noetic/share/cmake_modules/cmake/cmake_modulesConfig.cmake"
+  "/opt/ros/noetic/share/cpp_common/cmake/cpp_commonConfig-version.cmake"
+  "/opt/ros/noetic/share/cpp_common/cmake/cpp_commonConfig.cmake"
+  "/opt/ros/noetic/share/dynamic_reconfigure/cmake/dynamic_reconfigure-extras.cmake"
+  "/opt/ros/noetic/share/dynamic_reconfigure/cmake/dynamic_reconfigure-macros.cmake"
+  "/opt/ros/noetic/share/dynamic_reconfigure/cmake/dynamic_reconfigure-msg-extras.cmake"
+  "/opt/ros/noetic/share/dynamic_reconfigure/cmake/dynamic_reconfigureConfig-version.cmake"
+  "/opt/ros/noetic/share/dynamic_reconfigure/cmake/dynamic_reconfigureConfig.cmake"
+  "/opt/ros/noetic/share/dynamic_reconfigure/cmake/setup_custom_pythonpath.sh.in"
+  "/opt/ros/noetic/share/gencpp/cmake/gencpp-extras.cmake"
+  "/opt/ros/noetic/share/gencpp/cmake/gencppConfig-version.cmake"
+  "/opt/ros/noetic/share/gencpp/cmake/gencppConfig.cmake"
+  "/opt/ros/noetic/share/geneus/cmake/geneus-extras.cmake"
+  "/opt/ros/noetic/share/geneus/cmake/geneusConfig-version.cmake"
+  "/opt/ros/noetic/share/geneus/cmake/geneusConfig.cmake"
+  "/opt/ros/noetic/share/genlisp/cmake/genlisp-extras.cmake"
+  "/opt/ros/noetic/share/genlisp/cmake/genlispConfig-version.cmake"
+  "/opt/ros/noetic/share/genlisp/cmake/genlispConfig.cmake"
+  "/opt/ros/noetic/share/genmsg/cmake/genmsg-extras.cmake"
+  "/opt/ros/noetic/share/genmsg/cmake/genmsgConfig-version.cmake"
+  "/opt/ros/noetic/share/genmsg/cmake/genmsgConfig.cmake"
+  "/opt/ros/noetic/share/gennodejs/cmake/gennodejs-extras.cmake"
+  "/opt/ros/noetic/share/gennodejs/cmake/gennodejsConfig-version.cmake"
+  "/opt/ros/noetic/share/gennodejs/cmake/gennodejsConfig.cmake"
+  "/opt/ros/noetic/share/genpy/cmake/genpy-extras.cmake"
+  "/opt/ros/noetic/share/genpy/cmake/genpyConfig-version.cmake"
+  "/opt/ros/noetic/share/genpy/cmake/genpyConfig.cmake"
+  "/opt/ros/noetic/share/message_filters/cmake/message_filtersConfig-version.cmake"
+  "/opt/ros/noetic/share/message_filters/cmake/message_filtersConfig.cmake"
+  "/opt/ros/noetic/share/message_generation/cmake/message_generationConfig-version.cmake"
+  "/opt/ros/noetic/share/message_generation/cmake/message_generationConfig.cmake"
+  "/opt/ros/noetic/share/message_runtime/cmake/message_runtimeConfig-version.cmake"
+  "/opt/ros/noetic/share/message_runtime/cmake/message_runtimeConfig.cmake"
+  "/opt/ros/noetic/share/rosconsole/cmake/rosconsole-extras.cmake"
+  "/opt/ros/noetic/share/rosconsole/cmake/rosconsoleConfig-version.cmake"
+  "/opt/ros/noetic/share/rosconsole/cmake/rosconsoleConfig.cmake"
+  "/opt/ros/noetic/share/roscpp/cmake/roscpp-msg-extras.cmake"
+  "/opt/ros/noetic/share/roscpp/cmake/roscppConfig-version.cmake"
+  "/opt/ros/noetic/share/roscpp/cmake/roscppConfig.cmake"
+  "/opt/ros/noetic/share/roscpp_serialization/cmake/roscpp_serializationConfig-version.cmake"
+  "/opt/ros/noetic/share/roscpp_serialization/cmake/roscpp_serializationConfig.cmake"
+  "/opt/ros/noetic/share/roscpp_traits/cmake/roscpp_traitsConfig-version.cmake"
+  "/opt/ros/noetic/share/roscpp_traits/cmake/roscpp_traitsConfig.cmake"
+  "/opt/ros/noetic/share/rosgraph/cmake/rosgraphConfig-version.cmake"
+  "/opt/ros/noetic/share/rosgraph/cmake/rosgraphConfig.cmake"
+  "/opt/ros/noetic/share/rosgraph_msgs/cmake/rosgraph_msgs-msg-extras.cmake"
+  "/opt/ros/noetic/share/rosgraph_msgs/cmake/rosgraph_msgsConfig-version.cmake"
+  "/opt/ros/noetic/share/rosgraph_msgs/cmake/rosgraph_msgsConfig.cmake"
+  "/opt/ros/noetic/share/rospy/cmake/rospyConfig-version.cmake"
+  "/opt/ros/noetic/share/rospy/cmake/rospyConfig.cmake"
+  "/opt/ros/noetic/share/rostime/cmake/rostimeConfig-version.cmake"
+  "/opt/ros/noetic/share/rostime/cmake/rostimeConfig.cmake"
+  "/opt/ros/noetic/share/std_msgs/cmake/std_msgs-msg-extras.cmake"
+  "/opt/ros/noetic/share/std_msgs/cmake/std_msgsConfig-version.cmake"
+  "/opt/ros/noetic/share/std_msgs/cmake/std_msgsConfig.cmake"
+  "/opt/ros/noetic/share/tf/cmake/tf-msg-extras.cmake"
+  "/opt/ros/noetic/share/tf/cmake/tfConfig-version.cmake"
+  "/opt/ros/noetic/share/tf/cmake/tfConfig.cmake"
+  "/opt/ros/noetic/share/tf2/cmake/tf2Config-version.cmake"
+  "/opt/ros/noetic/share/tf2/cmake/tf2Config.cmake"
+  "/opt/ros/noetic/share/tf2_msgs/cmake/tf2_msgs-msg-extras.cmake"
+  "/opt/ros/noetic/share/tf2_msgs/cmake/tf2_msgsConfig-version.cmake"
+  "/opt/ros/noetic/share/tf2_msgs/cmake/tf2_msgsConfig.cmake"
+  "/opt/ros/noetic/share/tf2_py/cmake/tf2_pyConfig-version.cmake"
+  "/opt/ros/noetic/share/tf2_py/cmake/tf2_pyConfig.cmake"
+  "/opt/ros/noetic/share/tf2_ros/cmake/tf2_rosConfig-version.cmake"
+  "/opt/ros/noetic/share/tf2_ros/cmake/tf2_rosConfig.cmake"
+  "/opt/ros/noetic/share/xmlrpcpp/cmake/xmlrpcpp-extras.cmake"
+  "/opt/ros/noetic/share/xmlrpcpp/cmake/xmlrpcppConfig-version.cmake"
+  "/opt/ros/noetic/share/xmlrpcpp/cmake/xmlrpcppConfig.cmake"
+  "/usr/share/cmake-3.16/Modules/CMakeCInformation.cmake"
+  "/usr/share/cmake-3.16/Modules/CMakeCXXInformation.cmake"
+  "/usr/share/cmake-3.16/Modules/CMakeCheckCompilerFlagCommonPatterns.cmake"
+  "/usr/share/cmake-3.16/Modules/CMakeCommonLanguageInclude.cmake"
+  "/usr/share/cmake-3.16/Modules/CMakeDependentOption.cmake"
+  "/usr/share/cmake-3.16/Modules/CMakeGenericSystem.cmake"
+  "/usr/share/cmake-3.16/Modules/CMakeInitializeConfigs.cmake"
+  "/usr/share/cmake-3.16/Modules/CMakeLanguageInformation.cmake"
+  "/usr/share/cmake-3.16/Modules/CMakeParseArguments.cmake"
+  "/usr/share/cmake-3.16/Modules/CMakePushCheckState.cmake"
+  "/usr/share/cmake-3.16/Modules/CMakeSystemSpecificInformation.cmake"
+  "/usr/share/cmake-3.16/Modules/CMakeSystemSpecificInitialize.cmake"
+  "/usr/share/cmake-3.16/Modules/CheckCSourceCompiles.cmake"
+  "/usr/share/cmake-3.16/Modules/CheckFortranFunctionExists.cmake"
+  "/usr/share/cmake-3.16/Modules/CheckFunctionExists.cmake"
+  "/usr/share/cmake-3.16/Modules/CheckIncludeFile.cmake"
+  "/usr/share/cmake-3.16/Modules/CheckLibraryExists.cmake"
+  "/usr/share/cmake-3.16/Modules/Compiler/CMakeCommonCompilerMacros.cmake"
+  "/usr/share/cmake-3.16/Modules/Compiler/GNU-C.cmake"
+  "/usr/share/cmake-3.16/Modules/Compiler/GNU-CXX.cmake"
+  "/usr/share/cmake-3.16/Modules/Compiler/GNU.cmake"
+  "/usr/share/cmake-3.16/Modules/DartConfiguration.tcl.in"
+  "/usr/share/cmake-3.16/Modules/FindBLAS.cmake"
+  "/usr/share/cmake-3.16/Modules/FindGTest.cmake"
+  "/usr/share/cmake-3.16/Modules/FindLAPACK.cmake"
+  "/usr/share/cmake-3.16/Modules/FindPackageHandleStandardArgs.cmake"
+  "/usr/share/cmake-3.16/Modules/FindPackageMessage.cmake"
+  "/usr/share/cmake-3.16/Modules/FindPkgConfig.cmake"
+  "/usr/share/cmake-3.16/Modules/FindPythonInterp.cmake"
+  "/usr/share/cmake-3.16/Modules/FindThreads.cmake"
+  "/usr/share/cmake-3.16/Modules/GNUInstallDirs.cmake"
+  "/usr/share/cmake-3.16/Modules/GoogleTest.cmake"
+  "/usr/share/cmake-3.16/Modules/Internal/CMakeCheckCompilerFlag.cmake"
+  "/usr/share/cmake-3.16/Modules/Platform/Linux-GNU-C.cmake"
+  "/usr/share/cmake-3.16/Modules/Platform/Linux-GNU-CXX.cmake"
+  "/usr/share/cmake-3.16/Modules/Platform/Linux-GNU.cmake"
+  "/usr/share/cmake-3.16/Modules/Platform/Linux.cmake"
+  "/usr/share/cmake-3.16/Modules/Platform/UnixPaths.cmake"
+  "/usr/src/googletest/CMakeLists.txt"
+  "/usr/src/googletest/googlemock/CMakeLists.txt"
+  "/usr/src/googletest/googletest/CMakeLists.txt"
+  "/usr/src/googletest/googletest/cmake/internal_utils.cmake"
+  )
+
+# The corresponding makefile is:
+set(CMAKE_MAKEFILE_OUTPUTS
+  "Makefile"
+  "CMakeFiles/cmake.check_cache"
+  )
+
+# Byproducts of CMake generate step:
+set(CMAKE_MAKEFILE_PRODUCTS
+  "CTestConfiguration.ini"
+  "catkin_generated/stamps/mav_nonlinear_mpc/package.xml.stamp"
+  "atomic_configure/_setup_util.py"
+  "atomic_configure/env.sh"
+  "atomic_configure/setup.bash"
+  "atomic_configure/local_setup.bash"
+  "atomic_configure/setup.sh"
+  "atomic_configure/local_setup.sh"
+  "atomic_configure/setup.zsh"
+  "atomic_configure/local_setup.zsh"
+  "atomic_configure/.rosinstall"
+  "catkin_generated/installspace/_setup_util.py"
+  "catkin_generated/stamps/mav_nonlinear_mpc/_setup_util.py.stamp"
+  "catkin_generated/installspace/env.sh"
+  "catkin_generated/installspace/setup.bash"
+  "catkin_generated/installspace/local_setup.bash"
+  "catkin_generated/installspace/setup.sh"
+  "catkin_generated/installspace/local_setup.sh"
+  "catkin_generated/installspace/setup.zsh"
+  "catkin_generated/installspace/local_setup.zsh"
+  "catkin_generated/installspace/.rosinstall"
+  "catkin_generated/generate_cached_setup.py"
+  "catkin_generated/env_cached.sh"
+  "catkin_generated/stamps/mav_nonlinear_mpc/interrogate_setup_dot_py.py.stamp"
+  "catkin_generated/stamps/mav_nonlinear_mpc/package.xml.stamp"
+  "setup_custom_pythonpath.sh"
+  "catkin_generated/pkg.develspace.context.pc.py"
+  "catkin_generated/stamps/mav_nonlinear_mpc/pkg.pc.em.stamp"
+  "devel/share/mav_nonlinear_mpc/cmake/mav_nonlinear_mpcConfig.cmake"
+  "devel/share/mav_nonlinear_mpc/cmake/mav_nonlinear_mpcConfig-version.cmake"
+  "catkin_generated/pkg.installspace.context.pc.py"
+  "catkin_generated/stamps/mav_nonlinear_mpc/pkg.pc.em.stamp"
+  "catkin_generated/installspace/mav_nonlinear_mpcConfig.cmake"
+  "catkin_generated/installspace/mav_nonlinear_mpcConfig-version.cmake"
+  "CMakeFiles/CMakeDirectoryInformation.cmake"
+  "gtest/CMakeFiles/CMakeDirectoryInformation.cmake"
+  "gtest/googlemock/CMakeFiles/CMakeDirectoryInformation.cmake"
+  "gtest/googletest/CMakeFiles/CMakeDirectoryInformation.cmake"
+  )
+
+# Dependency information for all targets:
+set(CMAKE_DEPEND_INFO_FILES
+  "CMakeFiles/nonlinear_mpc_node.dir/DependInfo.cmake"
+  "CMakeFiles/mav_nonlinear_mpc_lib.dir/DependInfo.cmake"
+  "CMakeFiles/dynamic_reconfigure_gencfg.dir/DependInfo.cmake"
+  "CMakeFiles/std_msgs_generate_messages_lisp.dir/DependInfo.cmake"
+  "CMakeFiles/sensor_msgs_generate_messages_cpp.dir/DependInfo.cmake"
+  "CMakeFiles/mav_nonlinear_mpc_gencfg.dir/DependInfo.cmake"
+  "CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/DependInfo.cmake"
+  "CMakeFiles/actionlib_generate_messages_cpp.dir/DependInfo.cmake"
+  "CMakeFiles/actionlib_msgs_generate_messages_py.dir/DependInfo.cmake"
+  "CMakeFiles/tf_generate_messages_cpp.dir/DependInfo.cmake"
+  "CMakeFiles/geometry_msgs_generate_messages_lisp.dir/DependInfo.cmake"
+  "CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/DependInfo.cmake"
+  "CMakeFiles/actionlib_msgs_generate_messages_eus.dir/DependInfo.cmake"
+  "CMakeFiles/roscpp_generate_messages_py.dir/DependInfo.cmake"
+  "CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/DependInfo.cmake"
+  "CMakeFiles/tf_generate_messages_lisp.dir/DependInfo.cmake"
+  "CMakeFiles/rosgraph_msgs_generate_messages_py.dir/DependInfo.cmake"
+  "CMakeFiles/download_extra_data.dir/DependInfo.cmake"
+  "CMakeFiles/doxygen.dir/DependInfo.cmake"
+  "CMakeFiles/roscpp_generate_messages_lisp.dir/DependInfo.cmake"
+  "CMakeFiles/_catkin_empty_exported_target.dir/DependInfo.cmake"
+  "CMakeFiles/clean_test_results.dir/DependInfo.cmake"
+  "CMakeFiles/actionlib_generate_messages_lisp.dir/DependInfo.cmake"
+  "CMakeFiles/roscpp_generate_messages_eus.dir/DependInfo.cmake"
+  "CMakeFiles/tests.dir/DependInfo.cmake"
+  "CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/DependInfo.cmake"
+  "CMakeFiles/roscpp_generate_messages_cpp.dir/DependInfo.cmake"
+  "CMakeFiles/std_msgs_generate_messages_cpp.dir/DependInfo.cmake"
+  "CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/DependInfo.cmake"
+  "CMakeFiles/tf_generate_messages_eus.dir/DependInfo.cmake"
+  "CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/DependInfo.cmake"
+  "CMakeFiles/tf2_msgs_generate_messages_cpp.dir/DependInfo.cmake"
+  "CMakeFiles/roscpp_generate_messages_nodejs.dir/DependInfo.cmake"
+  "CMakeFiles/mav_nonlinear_mpc_package.dir/DependInfo.cmake"
+  "CMakeFiles/run_tests.dir/DependInfo.cmake"
+  "CMakeFiles/std_msgs_generate_messages_nodejs.dir/DependInfo.cmake"
+  "CMakeFiles/geometry_msgs_generate_messages_eus.dir/DependInfo.cmake"
+  "CMakeFiles/std_msgs_generate_messages_py.dir/DependInfo.cmake"
+  "CMakeFiles/tf_generate_messages_nodejs.dir/DependInfo.cmake"
+  "CMakeFiles/geometry_msgs_generate_messages_cpp.dir/DependInfo.cmake"
+  "CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/DependInfo.cmake"
+  "CMakeFiles/tf2_msgs_generate_messages_py.dir/DependInfo.cmake"
+  "CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/DependInfo.cmake"
+  "CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/DependInfo.cmake"
+  "CMakeFiles/geometry_msgs_generate_messages_py.dir/DependInfo.cmake"
+  "CMakeFiles/tf2_msgs_generate_messages_eus.dir/DependInfo.cmake"
+  "CMakeFiles/sensor_msgs_generate_messages_py.dir/DependInfo.cmake"
+  "CMakeFiles/sensor_msgs_generate_messages_eus.dir/DependInfo.cmake"
+  "CMakeFiles/sensor_msgs_generate_messages_lisp.dir/DependInfo.cmake"
+  "CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/DependInfo.cmake"
+  "CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/DependInfo.cmake"
+  "CMakeFiles/actionlib_generate_messages_eus.dir/DependInfo.cmake"
+  "CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/DependInfo.cmake"
+  "CMakeFiles/actionlib_generate_messages_nodejs.dir/DependInfo.cmake"
+  "CMakeFiles/actionlib_generate_messages_py.dir/DependInfo.cmake"
+  "CMakeFiles/tf_generate_messages_py.dir/DependInfo.cmake"
+  "CMakeFiles/std_msgs_generate_messages_eus.dir/DependInfo.cmake"
+  "CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/DependInfo.cmake"
+  "CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/DependInfo.cmake"
+  "CMakeFiles/tf2_msgs_generate_messages_lisp.dir/DependInfo.cmake"
+  "CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/DependInfo.cmake"
+  "gtest/googlemock/CMakeFiles/gmock_main.dir/DependInfo.cmake"
+  "gtest/googlemock/CMakeFiles/gmock.dir/DependInfo.cmake"
+  "gtest/googletest/CMakeFiles/gtest_main.dir/DependInfo.cmake"
+  "gtest/googletest/CMakeFiles/gtest.dir/DependInfo.cmake"
+  )
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/Makefile2 b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/Makefile2
new file mode 100644
index 0000000000000000000000000000000000000000..fe0483ed22588df86642e5a7dcef3ba74b0e1c3e
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/Makefile2
@@ -0,0 +1,2060 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Default target executed when no arguments are given to make.
+default_target: all
+
+.PHONY : default_target
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+#=============================================================================
+# Directory level rules for the build root directory
+
+# The main recursive "all" target.
+all: CMakeFiles/nonlinear_mpc_node.dir/all
+all: CMakeFiles/mav_nonlinear_mpc_lib.dir/all
+all: CMakeFiles/mav_nonlinear_mpc_gencfg.dir/all
+all: gtest/all
+
+.PHONY : all
+
+# The main recursive "preinstall" target.
+preinstall: gtest/preinstall
+
+.PHONY : preinstall
+
+# The main recursive "clean" target.
+clean: CMakeFiles/nonlinear_mpc_node.dir/clean
+clean: CMakeFiles/mav_nonlinear_mpc_lib.dir/clean
+clean: CMakeFiles/dynamic_reconfigure_gencfg.dir/clean
+clean: CMakeFiles/std_msgs_generate_messages_lisp.dir/clean
+clean: CMakeFiles/sensor_msgs_generate_messages_cpp.dir/clean
+clean: CMakeFiles/mav_nonlinear_mpc_gencfg.dir/clean
+clean: CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/clean
+clean: CMakeFiles/actionlib_generate_messages_cpp.dir/clean
+clean: CMakeFiles/actionlib_msgs_generate_messages_py.dir/clean
+clean: CMakeFiles/tf_generate_messages_cpp.dir/clean
+clean: CMakeFiles/geometry_msgs_generate_messages_lisp.dir/clean
+clean: CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/clean
+clean: CMakeFiles/actionlib_msgs_generate_messages_eus.dir/clean
+clean: CMakeFiles/roscpp_generate_messages_py.dir/clean
+clean: CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/clean
+clean: CMakeFiles/tf_generate_messages_lisp.dir/clean
+clean: CMakeFiles/rosgraph_msgs_generate_messages_py.dir/clean
+clean: CMakeFiles/download_extra_data.dir/clean
+clean: CMakeFiles/doxygen.dir/clean
+clean: CMakeFiles/roscpp_generate_messages_lisp.dir/clean
+clean: CMakeFiles/_catkin_empty_exported_target.dir/clean
+clean: CMakeFiles/clean_test_results.dir/clean
+clean: CMakeFiles/actionlib_generate_messages_lisp.dir/clean
+clean: CMakeFiles/roscpp_generate_messages_eus.dir/clean
+clean: CMakeFiles/tests.dir/clean
+clean: CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/clean
+clean: CMakeFiles/roscpp_generate_messages_cpp.dir/clean
+clean: CMakeFiles/std_msgs_generate_messages_cpp.dir/clean
+clean: CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/clean
+clean: CMakeFiles/tf_generate_messages_eus.dir/clean
+clean: CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/clean
+clean: CMakeFiles/tf2_msgs_generate_messages_cpp.dir/clean
+clean: CMakeFiles/roscpp_generate_messages_nodejs.dir/clean
+clean: CMakeFiles/mav_nonlinear_mpc_package.dir/clean
+clean: CMakeFiles/run_tests.dir/clean
+clean: CMakeFiles/std_msgs_generate_messages_nodejs.dir/clean
+clean: CMakeFiles/geometry_msgs_generate_messages_eus.dir/clean
+clean: CMakeFiles/std_msgs_generate_messages_py.dir/clean
+clean: CMakeFiles/tf_generate_messages_nodejs.dir/clean
+clean: CMakeFiles/geometry_msgs_generate_messages_cpp.dir/clean
+clean: CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/clean
+clean: CMakeFiles/tf2_msgs_generate_messages_py.dir/clean
+clean: CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/clean
+clean: CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/clean
+clean: CMakeFiles/geometry_msgs_generate_messages_py.dir/clean
+clean: CMakeFiles/tf2_msgs_generate_messages_eus.dir/clean
+clean: CMakeFiles/sensor_msgs_generate_messages_py.dir/clean
+clean: CMakeFiles/sensor_msgs_generate_messages_eus.dir/clean
+clean: CMakeFiles/sensor_msgs_generate_messages_lisp.dir/clean
+clean: CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/clean
+clean: CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/clean
+clean: CMakeFiles/actionlib_generate_messages_eus.dir/clean
+clean: CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/clean
+clean: CMakeFiles/actionlib_generate_messages_nodejs.dir/clean
+clean: CMakeFiles/actionlib_generate_messages_py.dir/clean
+clean: CMakeFiles/tf_generate_messages_py.dir/clean
+clean: CMakeFiles/std_msgs_generate_messages_eus.dir/clean
+clean: CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/clean
+clean: CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/clean
+clean: CMakeFiles/tf2_msgs_generate_messages_lisp.dir/clean
+clean: CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/clean
+clean: gtest/clean
+
+.PHONY : clean
+
+#=============================================================================
+# Directory level rules for directory gtest
+
+# Recursive "all" directory target.
+gtest/all: gtest/googlemock/all
+
+.PHONY : gtest/all
+
+# Recursive "preinstall" directory target.
+gtest/preinstall: gtest/googlemock/preinstall
+
+.PHONY : gtest/preinstall
+
+# Recursive "clean" directory target.
+gtest/clean: gtest/googlemock/clean
+
+.PHONY : gtest/clean
+
+#=============================================================================
+# Directory level rules for directory gtest/googlemock
+
+# Recursive "all" directory target.
+gtest/googlemock/all: gtest/googletest/all
+
+.PHONY : gtest/googlemock/all
+
+# Recursive "preinstall" directory target.
+gtest/googlemock/preinstall: gtest/googletest/preinstall
+
+.PHONY : gtest/googlemock/preinstall
+
+# Recursive "clean" directory target.
+gtest/googlemock/clean: gtest/googlemock/CMakeFiles/gmock_main.dir/clean
+gtest/googlemock/clean: gtest/googlemock/CMakeFiles/gmock.dir/clean
+gtest/googlemock/clean: gtest/googletest/clean
+
+.PHONY : gtest/googlemock/clean
+
+#=============================================================================
+# Directory level rules for directory gtest/googletest
+
+# Recursive "all" directory target.
+gtest/googletest/all:
+
+.PHONY : gtest/googletest/all
+
+# Recursive "preinstall" directory target.
+gtest/googletest/preinstall:
+
+.PHONY : gtest/googletest/preinstall
+
+# Recursive "clean" directory target.
+gtest/googletest/clean: gtest/googletest/CMakeFiles/gtest_main.dir/clean
+gtest/googletest/clean: gtest/googletest/CMakeFiles/gtest.dir/clean
+
+.PHONY : gtest/googletest/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/nonlinear_mpc_node.dir
+
+# All Build rule for target.
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/mav_nonlinear_mpc_lib.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/dynamic_reconfigure_gencfg.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/std_msgs_generate_messages_lisp.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/sensor_msgs_generate_messages_cpp.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/mav_nonlinear_mpc_gencfg.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/actionlib_generate_messages_cpp.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/actionlib_msgs_generate_messages_py.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/tf_generate_messages_cpp.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/geometry_msgs_generate_messages_lisp.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/actionlib_msgs_generate_messages_eus.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/roscpp_generate_messages_py.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/tf_generate_messages_lisp.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/rosgraph_msgs_generate_messages_py.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/roscpp_generate_messages_lisp.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/actionlib_generate_messages_lisp.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/roscpp_generate_messages_eus.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/roscpp_generate_messages_cpp.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/std_msgs_generate_messages_cpp.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/tf_generate_messages_eus.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/tf2_msgs_generate_messages_cpp.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/roscpp_generate_messages_nodejs.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/std_msgs_generate_messages_nodejs.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/geometry_msgs_generate_messages_eus.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/std_msgs_generate_messages_py.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/tf_generate_messages_nodejs.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/geometry_msgs_generate_messages_cpp.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/tf2_msgs_generate_messages_py.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/geometry_msgs_generate_messages_py.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/tf2_msgs_generate_messages_eus.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/sensor_msgs_generate_messages_py.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/sensor_msgs_generate_messages_eus.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/sensor_msgs_generate_messages_lisp.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/actionlib_generate_messages_eus.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/actionlib_generate_messages_nodejs.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/actionlib_generate_messages_py.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/tf_generate_messages_py.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/std_msgs_generate_messages_eus.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/tf2_msgs_generate_messages_lisp.dir/all
+CMakeFiles/nonlinear_mpc_node.dir/all: CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/all
+	$(MAKE) -f CMakeFiles/nonlinear_mpc_node.dir/build.make CMakeFiles/nonlinear_mpc_node.dir/depend
+	$(MAKE) -f CMakeFiles/nonlinear_mpc_node.dir/build.make CMakeFiles/nonlinear_mpc_node.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=26,27 "Built target nonlinear_mpc_node"
+.PHONY : CMakeFiles/nonlinear_mpc_node.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/nonlinear_mpc_node.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 19
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/nonlinear_mpc_node.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/nonlinear_mpc_node.dir/rule
+
+# Convenience name for target.
+nonlinear_mpc_node: CMakeFiles/nonlinear_mpc_node.dir/rule
+
+.PHONY : nonlinear_mpc_node
+
+# clean rule for target.
+CMakeFiles/nonlinear_mpc_node.dir/clean:
+	$(MAKE) -f CMakeFiles/nonlinear_mpc_node.dir/build.make CMakeFiles/nonlinear_mpc_node.dir/clean
+.PHONY : CMakeFiles/nonlinear_mpc_node.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/mav_nonlinear_mpc_lib.dir
+
+# All Build rule for target.
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/dynamic_reconfigure_gencfg.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/std_msgs_generate_messages_lisp.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/sensor_msgs_generate_messages_cpp.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/mav_nonlinear_mpc_gencfg.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/actionlib_generate_messages_cpp.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/actionlib_msgs_generate_messages_py.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/tf_generate_messages_cpp.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/geometry_msgs_generate_messages_lisp.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/actionlib_msgs_generate_messages_eus.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/roscpp_generate_messages_py.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/tf_generate_messages_lisp.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/rosgraph_msgs_generate_messages_py.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/roscpp_generate_messages_lisp.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/actionlib_generate_messages_lisp.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/roscpp_generate_messages_eus.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/roscpp_generate_messages_cpp.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/std_msgs_generate_messages_cpp.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/tf_generate_messages_eus.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/tf2_msgs_generate_messages_cpp.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/roscpp_generate_messages_nodejs.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/std_msgs_generate_messages_nodejs.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/geometry_msgs_generate_messages_eus.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/std_msgs_generate_messages_py.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/tf_generate_messages_nodejs.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/geometry_msgs_generate_messages_cpp.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/tf2_msgs_generate_messages_py.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/geometry_msgs_generate_messages_py.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/tf2_msgs_generate_messages_eus.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/sensor_msgs_generate_messages_py.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/sensor_msgs_generate_messages_eus.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/sensor_msgs_generate_messages_lisp.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/actionlib_generate_messages_eus.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/actionlib_generate_messages_nodejs.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/actionlib_generate_messages_py.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/tf_generate_messages_py.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/std_msgs_generate_messages_eus.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/tf2_msgs_generate_messages_lisp.dir/all
+CMakeFiles/mav_nonlinear_mpc_lib.dir/all: CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/all
+	$(MAKE) -f CMakeFiles/mav_nonlinear_mpc_lib.dir/build.make CMakeFiles/mav_nonlinear_mpc_lib.dir/depend
+	$(MAKE) -f CMakeFiles/mav_nonlinear_mpc_lib.dir/build.make CMakeFiles/mav_nonlinear_mpc_lib.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25 "Built target mav_nonlinear_mpc_lib"
+.PHONY : CMakeFiles/mav_nonlinear_mpc_lib.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/mav_nonlinear_mpc_lib.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 17
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/mav_nonlinear_mpc_lib.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/mav_nonlinear_mpc_lib.dir/rule
+
+# Convenience name for target.
+mav_nonlinear_mpc_lib: CMakeFiles/mav_nonlinear_mpc_lib.dir/rule
+
+.PHONY : mav_nonlinear_mpc_lib
+
+# clean rule for target.
+CMakeFiles/mav_nonlinear_mpc_lib.dir/clean:
+	$(MAKE) -f CMakeFiles/mav_nonlinear_mpc_lib.dir/build.make CMakeFiles/mav_nonlinear_mpc_lib.dir/clean
+.PHONY : CMakeFiles/mav_nonlinear_mpc_lib.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/dynamic_reconfigure_gencfg.dir
+
+# All Build rule for target.
+CMakeFiles/dynamic_reconfigure_gencfg.dir/all:
+	$(MAKE) -f CMakeFiles/dynamic_reconfigure_gencfg.dir/build.make CMakeFiles/dynamic_reconfigure_gencfg.dir/depend
+	$(MAKE) -f CMakeFiles/dynamic_reconfigure_gencfg.dir/build.make CMakeFiles/dynamic_reconfigure_gencfg.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target dynamic_reconfigure_gencfg"
+.PHONY : CMakeFiles/dynamic_reconfigure_gencfg.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/dynamic_reconfigure_gencfg.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/dynamic_reconfigure_gencfg.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/dynamic_reconfigure_gencfg.dir/rule
+
+# Convenience name for target.
+dynamic_reconfigure_gencfg: CMakeFiles/dynamic_reconfigure_gencfg.dir/rule
+
+.PHONY : dynamic_reconfigure_gencfg
+
+# clean rule for target.
+CMakeFiles/dynamic_reconfigure_gencfg.dir/clean:
+	$(MAKE) -f CMakeFiles/dynamic_reconfigure_gencfg.dir/build.make CMakeFiles/dynamic_reconfigure_gencfg.dir/clean
+.PHONY : CMakeFiles/dynamic_reconfigure_gencfg.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/std_msgs_generate_messages_lisp.dir
+
+# All Build rule for target.
+CMakeFiles/std_msgs_generate_messages_lisp.dir/all:
+	$(MAKE) -f CMakeFiles/std_msgs_generate_messages_lisp.dir/build.make CMakeFiles/std_msgs_generate_messages_lisp.dir/depend
+	$(MAKE) -f CMakeFiles/std_msgs_generate_messages_lisp.dir/build.make CMakeFiles/std_msgs_generate_messages_lisp.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target std_msgs_generate_messages_lisp"
+.PHONY : CMakeFiles/std_msgs_generate_messages_lisp.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/std_msgs_generate_messages_lisp.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/std_msgs_generate_messages_lisp.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/std_msgs_generate_messages_lisp.dir/rule
+
+# Convenience name for target.
+std_msgs_generate_messages_lisp: CMakeFiles/std_msgs_generate_messages_lisp.dir/rule
+
+.PHONY : std_msgs_generate_messages_lisp
+
+# clean rule for target.
+CMakeFiles/std_msgs_generate_messages_lisp.dir/clean:
+	$(MAKE) -f CMakeFiles/std_msgs_generate_messages_lisp.dir/build.make CMakeFiles/std_msgs_generate_messages_lisp.dir/clean
+.PHONY : CMakeFiles/std_msgs_generate_messages_lisp.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/sensor_msgs_generate_messages_cpp.dir
+
+# All Build rule for target.
+CMakeFiles/sensor_msgs_generate_messages_cpp.dir/all:
+	$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_cpp.dir/depend
+	$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target sensor_msgs_generate_messages_cpp"
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_cpp.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/sensor_msgs_generate_messages_cpp.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/sensor_msgs_generate_messages_cpp.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_cpp.dir/rule
+
+# Convenience name for target.
+sensor_msgs_generate_messages_cpp: CMakeFiles/sensor_msgs_generate_messages_cpp.dir/rule
+
+.PHONY : sensor_msgs_generate_messages_cpp
+
+# clean rule for target.
+CMakeFiles/sensor_msgs_generate_messages_cpp.dir/clean:
+	$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_cpp.dir/clean
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_cpp.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/mav_nonlinear_mpc_gencfg.dir
+
+# All Build rule for target.
+CMakeFiles/mav_nonlinear_mpc_gencfg.dir/all:
+	$(MAKE) -f CMakeFiles/mav_nonlinear_mpc_gencfg.dir/build.make CMakeFiles/mav_nonlinear_mpc_gencfg.dir/depend
+	$(MAKE) -f CMakeFiles/mav_nonlinear_mpc_gencfg.dir/build.make CMakeFiles/mav_nonlinear_mpc_gencfg.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=9 "Built target mav_nonlinear_mpc_gencfg"
+.PHONY : CMakeFiles/mav_nonlinear_mpc_gencfg.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/mav_nonlinear_mpc_gencfg.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 1
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/mav_nonlinear_mpc_gencfg.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/mav_nonlinear_mpc_gencfg.dir/rule
+
+# Convenience name for target.
+mav_nonlinear_mpc_gencfg: CMakeFiles/mav_nonlinear_mpc_gencfg.dir/rule
+
+.PHONY : mav_nonlinear_mpc_gencfg
+
+# clean rule for target.
+CMakeFiles/mav_nonlinear_mpc_gencfg.dir/clean:
+	$(MAKE) -f CMakeFiles/mav_nonlinear_mpc_gencfg.dir/build.make CMakeFiles/mav_nonlinear_mpc_gencfg.dir/clean
+.PHONY : CMakeFiles/mav_nonlinear_mpc_gencfg.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir
+
+# All Build rule for target.
+CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/all:
+	$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/depend
+	$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target rosgraph_msgs_generate_messages_nodejs"
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/rule
+
+# Convenience name for target.
+rosgraph_msgs_generate_messages_nodejs: CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/rule
+
+.PHONY : rosgraph_msgs_generate_messages_nodejs
+
+# clean rule for target.
+CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/clean:
+	$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/clean
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/actionlib_generate_messages_cpp.dir
+
+# All Build rule for target.
+CMakeFiles/actionlib_generate_messages_cpp.dir/all:
+	$(MAKE) -f CMakeFiles/actionlib_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_generate_messages_cpp.dir/depend
+	$(MAKE) -f CMakeFiles/actionlib_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_generate_messages_cpp.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target actionlib_generate_messages_cpp"
+.PHONY : CMakeFiles/actionlib_generate_messages_cpp.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/actionlib_generate_messages_cpp.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_generate_messages_cpp.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/actionlib_generate_messages_cpp.dir/rule
+
+# Convenience name for target.
+actionlib_generate_messages_cpp: CMakeFiles/actionlib_generate_messages_cpp.dir/rule
+
+.PHONY : actionlib_generate_messages_cpp
+
+# clean rule for target.
+CMakeFiles/actionlib_generate_messages_cpp.dir/clean:
+	$(MAKE) -f CMakeFiles/actionlib_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_generate_messages_cpp.dir/clean
+.PHONY : CMakeFiles/actionlib_generate_messages_cpp.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/actionlib_msgs_generate_messages_py.dir
+
+# All Build rule for target.
+CMakeFiles/actionlib_msgs_generate_messages_py.dir/all:
+	$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_py.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_py.dir/depend
+	$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_py.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_py.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target actionlib_msgs_generate_messages_py"
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_py.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/actionlib_msgs_generate_messages_py.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_msgs_generate_messages_py.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_py.dir/rule
+
+# Convenience name for target.
+actionlib_msgs_generate_messages_py: CMakeFiles/actionlib_msgs_generate_messages_py.dir/rule
+
+.PHONY : actionlib_msgs_generate_messages_py
+
+# clean rule for target.
+CMakeFiles/actionlib_msgs_generate_messages_py.dir/clean:
+	$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_py.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_py.dir/clean
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_py.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/tf_generate_messages_cpp.dir
+
+# All Build rule for target.
+CMakeFiles/tf_generate_messages_cpp.dir/all:
+	$(MAKE) -f CMakeFiles/tf_generate_messages_cpp.dir/build.make CMakeFiles/tf_generate_messages_cpp.dir/depend
+	$(MAKE) -f CMakeFiles/tf_generate_messages_cpp.dir/build.make CMakeFiles/tf_generate_messages_cpp.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target tf_generate_messages_cpp"
+.PHONY : CMakeFiles/tf_generate_messages_cpp.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/tf_generate_messages_cpp.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf_generate_messages_cpp.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/tf_generate_messages_cpp.dir/rule
+
+# Convenience name for target.
+tf_generate_messages_cpp: CMakeFiles/tf_generate_messages_cpp.dir/rule
+
+.PHONY : tf_generate_messages_cpp
+
+# clean rule for target.
+CMakeFiles/tf_generate_messages_cpp.dir/clean:
+	$(MAKE) -f CMakeFiles/tf_generate_messages_cpp.dir/build.make CMakeFiles/tf_generate_messages_cpp.dir/clean
+.PHONY : CMakeFiles/tf_generate_messages_cpp.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/geometry_msgs_generate_messages_lisp.dir
+
+# All Build rule for target.
+CMakeFiles/geometry_msgs_generate_messages_lisp.dir/all:
+	$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_lisp.dir/depend
+	$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target geometry_msgs_generate_messages_lisp"
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_lisp.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/geometry_msgs_generate_messages_lisp.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/geometry_msgs_generate_messages_lisp.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_lisp.dir/rule
+
+# Convenience name for target.
+geometry_msgs_generate_messages_lisp: CMakeFiles/geometry_msgs_generate_messages_lisp.dir/rule
+
+.PHONY : geometry_msgs_generate_messages_lisp
+
+# clean rule for target.
+CMakeFiles/geometry_msgs_generate_messages_lisp.dir/clean:
+	$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_lisp.dir/clean
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_lisp.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/dynamic_reconfigure_generate_messages_py.dir
+
+# All Build rule for target.
+CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/all:
+	$(MAKE) -f CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/build.make CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/depend
+	$(MAKE) -f CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/build.make CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target dynamic_reconfigure_generate_messages_py"
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/rule
+
+# Convenience name for target.
+dynamic_reconfigure_generate_messages_py: CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/rule
+
+.PHONY : dynamic_reconfigure_generate_messages_py
+
+# clean rule for target.
+CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/clean:
+	$(MAKE) -f CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/build.make CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/clean
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/actionlib_msgs_generate_messages_eus.dir
+
+# All Build rule for target.
+CMakeFiles/actionlib_msgs_generate_messages_eus.dir/all:
+	$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_eus.dir/depend
+	$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target actionlib_msgs_generate_messages_eus"
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_eus.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/actionlib_msgs_generate_messages_eus.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_msgs_generate_messages_eus.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_eus.dir/rule
+
+# Convenience name for target.
+actionlib_msgs_generate_messages_eus: CMakeFiles/actionlib_msgs_generate_messages_eus.dir/rule
+
+.PHONY : actionlib_msgs_generate_messages_eus
+
+# clean rule for target.
+CMakeFiles/actionlib_msgs_generate_messages_eus.dir/clean:
+	$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_eus.dir/clean
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_eus.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/roscpp_generate_messages_py.dir
+
+# All Build rule for target.
+CMakeFiles/roscpp_generate_messages_py.dir/all:
+	$(MAKE) -f CMakeFiles/roscpp_generate_messages_py.dir/build.make CMakeFiles/roscpp_generate_messages_py.dir/depend
+	$(MAKE) -f CMakeFiles/roscpp_generate_messages_py.dir/build.make CMakeFiles/roscpp_generate_messages_py.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target roscpp_generate_messages_py"
+.PHONY : CMakeFiles/roscpp_generate_messages_py.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/roscpp_generate_messages_py.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/roscpp_generate_messages_py.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/roscpp_generate_messages_py.dir/rule
+
+# Convenience name for target.
+roscpp_generate_messages_py: CMakeFiles/roscpp_generate_messages_py.dir/rule
+
+.PHONY : roscpp_generate_messages_py
+
+# clean rule for target.
+CMakeFiles/roscpp_generate_messages_py.dir/clean:
+	$(MAKE) -f CMakeFiles/roscpp_generate_messages_py.dir/build.make CMakeFiles/roscpp_generate_messages_py.dir/clean
+.PHONY : CMakeFiles/roscpp_generate_messages_py.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir
+
+# All Build rule for target.
+CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/all:
+	$(MAKE) -f CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/build.make CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/depend
+	$(MAKE) -f CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/build.make CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target dynamic_reconfigure_generate_messages_cpp"
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/rule
+
+# Convenience name for target.
+dynamic_reconfigure_generate_messages_cpp: CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/rule
+
+.PHONY : dynamic_reconfigure_generate_messages_cpp
+
+# clean rule for target.
+CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/clean:
+	$(MAKE) -f CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/build.make CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/clean
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/tf_generate_messages_lisp.dir
+
+# All Build rule for target.
+CMakeFiles/tf_generate_messages_lisp.dir/all:
+	$(MAKE) -f CMakeFiles/tf_generate_messages_lisp.dir/build.make CMakeFiles/tf_generate_messages_lisp.dir/depend
+	$(MAKE) -f CMakeFiles/tf_generate_messages_lisp.dir/build.make CMakeFiles/tf_generate_messages_lisp.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target tf_generate_messages_lisp"
+.PHONY : CMakeFiles/tf_generate_messages_lisp.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/tf_generate_messages_lisp.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf_generate_messages_lisp.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/tf_generate_messages_lisp.dir/rule
+
+# Convenience name for target.
+tf_generate_messages_lisp: CMakeFiles/tf_generate_messages_lisp.dir/rule
+
+.PHONY : tf_generate_messages_lisp
+
+# clean rule for target.
+CMakeFiles/tf_generate_messages_lisp.dir/clean:
+	$(MAKE) -f CMakeFiles/tf_generate_messages_lisp.dir/build.make CMakeFiles/tf_generate_messages_lisp.dir/clean
+.PHONY : CMakeFiles/tf_generate_messages_lisp.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/rosgraph_msgs_generate_messages_py.dir
+
+# All Build rule for target.
+CMakeFiles/rosgraph_msgs_generate_messages_py.dir/all:
+	$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_py.dir/depend
+	$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target rosgraph_msgs_generate_messages_py"
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_py.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/rosgraph_msgs_generate_messages_py.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/rosgraph_msgs_generate_messages_py.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_py.dir/rule
+
+# Convenience name for target.
+rosgraph_msgs_generate_messages_py: CMakeFiles/rosgraph_msgs_generate_messages_py.dir/rule
+
+.PHONY : rosgraph_msgs_generate_messages_py
+
+# clean rule for target.
+CMakeFiles/rosgraph_msgs_generate_messages_py.dir/clean:
+	$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_py.dir/clean
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_py.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/download_extra_data.dir
+
+# All Build rule for target.
+CMakeFiles/download_extra_data.dir/all:
+	$(MAKE) -f CMakeFiles/download_extra_data.dir/build.make CMakeFiles/download_extra_data.dir/depend
+	$(MAKE) -f CMakeFiles/download_extra_data.dir/build.make CMakeFiles/download_extra_data.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target download_extra_data"
+.PHONY : CMakeFiles/download_extra_data.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/download_extra_data.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/download_extra_data.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/download_extra_data.dir/rule
+
+# Convenience name for target.
+download_extra_data: CMakeFiles/download_extra_data.dir/rule
+
+.PHONY : download_extra_data
+
+# clean rule for target.
+CMakeFiles/download_extra_data.dir/clean:
+	$(MAKE) -f CMakeFiles/download_extra_data.dir/build.make CMakeFiles/download_extra_data.dir/clean
+.PHONY : CMakeFiles/download_extra_data.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/doxygen.dir
+
+# All Build rule for target.
+CMakeFiles/doxygen.dir/all:
+	$(MAKE) -f CMakeFiles/doxygen.dir/build.make CMakeFiles/doxygen.dir/depend
+	$(MAKE) -f CMakeFiles/doxygen.dir/build.make CMakeFiles/doxygen.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target doxygen"
+.PHONY : CMakeFiles/doxygen.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/doxygen.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/doxygen.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/doxygen.dir/rule
+
+# Convenience name for target.
+doxygen: CMakeFiles/doxygen.dir/rule
+
+.PHONY : doxygen
+
+# clean rule for target.
+CMakeFiles/doxygen.dir/clean:
+	$(MAKE) -f CMakeFiles/doxygen.dir/build.make CMakeFiles/doxygen.dir/clean
+.PHONY : CMakeFiles/doxygen.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/roscpp_generate_messages_lisp.dir
+
+# All Build rule for target.
+CMakeFiles/roscpp_generate_messages_lisp.dir/all:
+	$(MAKE) -f CMakeFiles/roscpp_generate_messages_lisp.dir/build.make CMakeFiles/roscpp_generate_messages_lisp.dir/depend
+	$(MAKE) -f CMakeFiles/roscpp_generate_messages_lisp.dir/build.make CMakeFiles/roscpp_generate_messages_lisp.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target roscpp_generate_messages_lisp"
+.PHONY : CMakeFiles/roscpp_generate_messages_lisp.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/roscpp_generate_messages_lisp.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/roscpp_generate_messages_lisp.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/roscpp_generate_messages_lisp.dir/rule
+
+# Convenience name for target.
+roscpp_generate_messages_lisp: CMakeFiles/roscpp_generate_messages_lisp.dir/rule
+
+.PHONY : roscpp_generate_messages_lisp
+
+# clean rule for target.
+CMakeFiles/roscpp_generate_messages_lisp.dir/clean:
+	$(MAKE) -f CMakeFiles/roscpp_generate_messages_lisp.dir/build.make CMakeFiles/roscpp_generate_messages_lisp.dir/clean
+.PHONY : CMakeFiles/roscpp_generate_messages_lisp.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/_catkin_empty_exported_target.dir
+
+# All Build rule for target.
+CMakeFiles/_catkin_empty_exported_target.dir/all:
+	$(MAKE) -f CMakeFiles/_catkin_empty_exported_target.dir/build.make CMakeFiles/_catkin_empty_exported_target.dir/depend
+	$(MAKE) -f CMakeFiles/_catkin_empty_exported_target.dir/build.make CMakeFiles/_catkin_empty_exported_target.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target _catkin_empty_exported_target"
+.PHONY : CMakeFiles/_catkin_empty_exported_target.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/_catkin_empty_exported_target.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/_catkin_empty_exported_target.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/_catkin_empty_exported_target.dir/rule
+
+# Convenience name for target.
+_catkin_empty_exported_target: CMakeFiles/_catkin_empty_exported_target.dir/rule
+
+.PHONY : _catkin_empty_exported_target
+
+# clean rule for target.
+CMakeFiles/_catkin_empty_exported_target.dir/clean:
+	$(MAKE) -f CMakeFiles/_catkin_empty_exported_target.dir/build.make CMakeFiles/_catkin_empty_exported_target.dir/clean
+.PHONY : CMakeFiles/_catkin_empty_exported_target.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/clean_test_results.dir
+
+# All Build rule for target.
+CMakeFiles/clean_test_results.dir/all:
+	$(MAKE) -f CMakeFiles/clean_test_results.dir/build.make CMakeFiles/clean_test_results.dir/depend
+	$(MAKE) -f CMakeFiles/clean_test_results.dir/build.make CMakeFiles/clean_test_results.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target clean_test_results"
+.PHONY : CMakeFiles/clean_test_results.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/clean_test_results.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/clean_test_results.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/clean_test_results.dir/rule
+
+# Convenience name for target.
+clean_test_results: CMakeFiles/clean_test_results.dir/rule
+
+.PHONY : clean_test_results
+
+# clean rule for target.
+CMakeFiles/clean_test_results.dir/clean:
+	$(MAKE) -f CMakeFiles/clean_test_results.dir/build.make CMakeFiles/clean_test_results.dir/clean
+.PHONY : CMakeFiles/clean_test_results.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/actionlib_generate_messages_lisp.dir
+
+# All Build rule for target.
+CMakeFiles/actionlib_generate_messages_lisp.dir/all:
+	$(MAKE) -f CMakeFiles/actionlib_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_generate_messages_lisp.dir/depend
+	$(MAKE) -f CMakeFiles/actionlib_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_generate_messages_lisp.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target actionlib_generate_messages_lisp"
+.PHONY : CMakeFiles/actionlib_generate_messages_lisp.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/actionlib_generate_messages_lisp.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_generate_messages_lisp.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/actionlib_generate_messages_lisp.dir/rule
+
+# Convenience name for target.
+actionlib_generate_messages_lisp: CMakeFiles/actionlib_generate_messages_lisp.dir/rule
+
+.PHONY : actionlib_generate_messages_lisp
+
+# clean rule for target.
+CMakeFiles/actionlib_generate_messages_lisp.dir/clean:
+	$(MAKE) -f CMakeFiles/actionlib_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_generate_messages_lisp.dir/clean
+.PHONY : CMakeFiles/actionlib_generate_messages_lisp.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/roscpp_generate_messages_eus.dir
+
+# All Build rule for target.
+CMakeFiles/roscpp_generate_messages_eus.dir/all:
+	$(MAKE) -f CMakeFiles/roscpp_generate_messages_eus.dir/build.make CMakeFiles/roscpp_generate_messages_eus.dir/depend
+	$(MAKE) -f CMakeFiles/roscpp_generate_messages_eus.dir/build.make CMakeFiles/roscpp_generate_messages_eus.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target roscpp_generate_messages_eus"
+.PHONY : CMakeFiles/roscpp_generate_messages_eus.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/roscpp_generate_messages_eus.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/roscpp_generate_messages_eus.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/roscpp_generate_messages_eus.dir/rule
+
+# Convenience name for target.
+roscpp_generate_messages_eus: CMakeFiles/roscpp_generate_messages_eus.dir/rule
+
+.PHONY : roscpp_generate_messages_eus
+
+# clean rule for target.
+CMakeFiles/roscpp_generate_messages_eus.dir/clean:
+	$(MAKE) -f CMakeFiles/roscpp_generate_messages_eus.dir/build.make CMakeFiles/roscpp_generate_messages_eus.dir/clean
+.PHONY : CMakeFiles/roscpp_generate_messages_eus.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/tests.dir
+
+# All Build rule for target.
+CMakeFiles/tests.dir/all:
+	$(MAKE) -f CMakeFiles/tests.dir/build.make CMakeFiles/tests.dir/depend
+	$(MAKE) -f CMakeFiles/tests.dir/build.make CMakeFiles/tests.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target tests"
+.PHONY : CMakeFiles/tests.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/tests.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tests.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/tests.dir/rule
+
+# Convenience name for target.
+tests: CMakeFiles/tests.dir/rule
+
+.PHONY : tests
+
+# clean rule for target.
+CMakeFiles/tests.dir/clean:
+	$(MAKE) -f CMakeFiles/tests.dir/build.make CMakeFiles/tests.dir/clean
+.PHONY : CMakeFiles/tests.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/rosgraph_msgs_generate_messages_eus.dir
+
+# All Build rule for target.
+CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/all:
+	$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/depend
+	$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target rosgraph_msgs_generate_messages_eus"
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/rule
+
+# Convenience name for target.
+rosgraph_msgs_generate_messages_eus: CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/rule
+
+.PHONY : rosgraph_msgs_generate_messages_eus
+
+# clean rule for target.
+CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/clean:
+	$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/clean
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/roscpp_generate_messages_cpp.dir
+
+# All Build rule for target.
+CMakeFiles/roscpp_generate_messages_cpp.dir/all:
+	$(MAKE) -f CMakeFiles/roscpp_generate_messages_cpp.dir/build.make CMakeFiles/roscpp_generate_messages_cpp.dir/depend
+	$(MAKE) -f CMakeFiles/roscpp_generate_messages_cpp.dir/build.make CMakeFiles/roscpp_generate_messages_cpp.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target roscpp_generate_messages_cpp"
+.PHONY : CMakeFiles/roscpp_generate_messages_cpp.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/roscpp_generate_messages_cpp.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/roscpp_generate_messages_cpp.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/roscpp_generate_messages_cpp.dir/rule
+
+# Convenience name for target.
+roscpp_generate_messages_cpp: CMakeFiles/roscpp_generate_messages_cpp.dir/rule
+
+.PHONY : roscpp_generate_messages_cpp
+
+# clean rule for target.
+CMakeFiles/roscpp_generate_messages_cpp.dir/clean:
+	$(MAKE) -f CMakeFiles/roscpp_generate_messages_cpp.dir/build.make CMakeFiles/roscpp_generate_messages_cpp.dir/clean
+.PHONY : CMakeFiles/roscpp_generate_messages_cpp.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/std_msgs_generate_messages_cpp.dir
+
+# All Build rule for target.
+CMakeFiles/std_msgs_generate_messages_cpp.dir/all:
+	$(MAKE) -f CMakeFiles/std_msgs_generate_messages_cpp.dir/build.make CMakeFiles/std_msgs_generate_messages_cpp.dir/depend
+	$(MAKE) -f CMakeFiles/std_msgs_generate_messages_cpp.dir/build.make CMakeFiles/std_msgs_generate_messages_cpp.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target std_msgs_generate_messages_cpp"
+.PHONY : CMakeFiles/std_msgs_generate_messages_cpp.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/std_msgs_generate_messages_cpp.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/std_msgs_generate_messages_cpp.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/std_msgs_generate_messages_cpp.dir/rule
+
+# Convenience name for target.
+std_msgs_generate_messages_cpp: CMakeFiles/std_msgs_generate_messages_cpp.dir/rule
+
+.PHONY : std_msgs_generate_messages_cpp
+
+# clean rule for target.
+CMakeFiles/std_msgs_generate_messages_cpp.dir/clean:
+	$(MAKE) -f CMakeFiles/std_msgs_generate_messages_cpp.dir/build.make CMakeFiles/std_msgs_generate_messages_cpp.dir/clean
+.PHONY : CMakeFiles/std_msgs_generate_messages_cpp.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir
+
+# All Build rule for target.
+CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/all:
+	$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/depend
+	$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target rosgraph_msgs_generate_messages_lisp"
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/rule
+
+# Convenience name for target.
+rosgraph_msgs_generate_messages_lisp: CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/rule
+
+.PHONY : rosgraph_msgs_generate_messages_lisp
+
+# clean rule for target.
+CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/clean:
+	$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/clean
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/tf_generate_messages_eus.dir
+
+# All Build rule for target.
+CMakeFiles/tf_generate_messages_eus.dir/all:
+	$(MAKE) -f CMakeFiles/tf_generate_messages_eus.dir/build.make CMakeFiles/tf_generate_messages_eus.dir/depend
+	$(MAKE) -f CMakeFiles/tf_generate_messages_eus.dir/build.make CMakeFiles/tf_generate_messages_eus.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target tf_generate_messages_eus"
+.PHONY : CMakeFiles/tf_generate_messages_eus.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/tf_generate_messages_eus.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf_generate_messages_eus.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/tf_generate_messages_eus.dir/rule
+
+# Convenience name for target.
+tf_generate_messages_eus: CMakeFiles/tf_generate_messages_eus.dir/rule
+
+.PHONY : tf_generate_messages_eus
+
+# clean rule for target.
+CMakeFiles/tf_generate_messages_eus.dir/clean:
+	$(MAKE) -f CMakeFiles/tf_generate_messages_eus.dir/build.make CMakeFiles/tf_generate_messages_eus.dir/clean
+.PHONY : CMakeFiles/tf_generate_messages_eus.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir
+
+# All Build rule for target.
+CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/all:
+	$(MAKE) -f CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/build.make CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/depend
+	$(MAKE) -f CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/build.make CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target dynamic_reconfigure_generate_messages_lisp"
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/rule
+
+# Convenience name for target.
+dynamic_reconfigure_generate_messages_lisp: CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/rule
+
+.PHONY : dynamic_reconfigure_generate_messages_lisp
+
+# clean rule for target.
+CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/clean:
+	$(MAKE) -f CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/build.make CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/clean
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/tf2_msgs_generate_messages_cpp.dir
+
+# All Build rule for target.
+CMakeFiles/tf2_msgs_generate_messages_cpp.dir/all:
+	$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_cpp.dir/depend
+	$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target tf2_msgs_generate_messages_cpp"
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_cpp.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/tf2_msgs_generate_messages_cpp.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf2_msgs_generate_messages_cpp.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_cpp.dir/rule
+
+# Convenience name for target.
+tf2_msgs_generate_messages_cpp: CMakeFiles/tf2_msgs_generate_messages_cpp.dir/rule
+
+.PHONY : tf2_msgs_generate_messages_cpp
+
+# clean rule for target.
+CMakeFiles/tf2_msgs_generate_messages_cpp.dir/clean:
+	$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_cpp.dir/clean
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_cpp.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/roscpp_generate_messages_nodejs.dir
+
+# All Build rule for target.
+CMakeFiles/roscpp_generate_messages_nodejs.dir/all:
+	$(MAKE) -f CMakeFiles/roscpp_generate_messages_nodejs.dir/build.make CMakeFiles/roscpp_generate_messages_nodejs.dir/depend
+	$(MAKE) -f CMakeFiles/roscpp_generate_messages_nodejs.dir/build.make CMakeFiles/roscpp_generate_messages_nodejs.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target roscpp_generate_messages_nodejs"
+.PHONY : CMakeFiles/roscpp_generate_messages_nodejs.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/roscpp_generate_messages_nodejs.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/roscpp_generate_messages_nodejs.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/roscpp_generate_messages_nodejs.dir/rule
+
+# Convenience name for target.
+roscpp_generate_messages_nodejs: CMakeFiles/roscpp_generate_messages_nodejs.dir/rule
+
+.PHONY : roscpp_generate_messages_nodejs
+
+# clean rule for target.
+CMakeFiles/roscpp_generate_messages_nodejs.dir/clean:
+	$(MAKE) -f CMakeFiles/roscpp_generate_messages_nodejs.dir/build.make CMakeFiles/roscpp_generate_messages_nodejs.dir/clean
+.PHONY : CMakeFiles/roscpp_generate_messages_nodejs.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/mav_nonlinear_mpc_package.dir
+
+# All Build rule for target.
+CMakeFiles/mav_nonlinear_mpc_package.dir/all: CMakeFiles/nonlinear_mpc_node.dir/all
+CMakeFiles/mav_nonlinear_mpc_package.dir/all: CMakeFiles/mav_nonlinear_mpc_lib.dir/all
+	$(MAKE) -f CMakeFiles/mav_nonlinear_mpc_package.dir/build.make CMakeFiles/mav_nonlinear_mpc_package.dir/depend
+	$(MAKE) -f CMakeFiles/mav_nonlinear_mpc_package.dir/build.make CMakeFiles/mav_nonlinear_mpc_package.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target mav_nonlinear_mpc_package"
+.PHONY : CMakeFiles/mav_nonlinear_mpc_package.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/mav_nonlinear_mpc_package.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 19
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/mav_nonlinear_mpc_package.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/mav_nonlinear_mpc_package.dir/rule
+
+# Convenience name for target.
+mav_nonlinear_mpc_package: CMakeFiles/mav_nonlinear_mpc_package.dir/rule
+
+.PHONY : mav_nonlinear_mpc_package
+
+# clean rule for target.
+CMakeFiles/mav_nonlinear_mpc_package.dir/clean:
+	$(MAKE) -f CMakeFiles/mav_nonlinear_mpc_package.dir/build.make CMakeFiles/mav_nonlinear_mpc_package.dir/clean
+.PHONY : CMakeFiles/mav_nonlinear_mpc_package.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/run_tests.dir
+
+# All Build rule for target.
+CMakeFiles/run_tests.dir/all:
+	$(MAKE) -f CMakeFiles/run_tests.dir/build.make CMakeFiles/run_tests.dir/depend
+	$(MAKE) -f CMakeFiles/run_tests.dir/build.make CMakeFiles/run_tests.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target run_tests"
+.PHONY : CMakeFiles/run_tests.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/run_tests.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/run_tests.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/run_tests.dir/rule
+
+# Convenience name for target.
+run_tests: CMakeFiles/run_tests.dir/rule
+
+.PHONY : run_tests
+
+# clean rule for target.
+CMakeFiles/run_tests.dir/clean:
+	$(MAKE) -f CMakeFiles/run_tests.dir/build.make CMakeFiles/run_tests.dir/clean
+.PHONY : CMakeFiles/run_tests.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/std_msgs_generate_messages_nodejs.dir
+
+# All Build rule for target.
+CMakeFiles/std_msgs_generate_messages_nodejs.dir/all:
+	$(MAKE) -f CMakeFiles/std_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/std_msgs_generate_messages_nodejs.dir/depend
+	$(MAKE) -f CMakeFiles/std_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/std_msgs_generate_messages_nodejs.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target std_msgs_generate_messages_nodejs"
+.PHONY : CMakeFiles/std_msgs_generate_messages_nodejs.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/std_msgs_generate_messages_nodejs.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/std_msgs_generate_messages_nodejs.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/std_msgs_generate_messages_nodejs.dir/rule
+
+# Convenience name for target.
+std_msgs_generate_messages_nodejs: CMakeFiles/std_msgs_generate_messages_nodejs.dir/rule
+
+.PHONY : std_msgs_generate_messages_nodejs
+
+# clean rule for target.
+CMakeFiles/std_msgs_generate_messages_nodejs.dir/clean:
+	$(MAKE) -f CMakeFiles/std_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/std_msgs_generate_messages_nodejs.dir/clean
+.PHONY : CMakeFiles/std_msgs_generate_messages_nodejs.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/geometry_msgs_generate_messages_eus.dir
+
+# All Build rule for target.
+CMakeFiles/geometry_msgs_generate_messages_eus.dir/all:
+	$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_eus.dir/build.make CMakeFiles/geometry_msgs_generate_messages_eus.dir/depend
+	$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_eus.dir/build.make CMakeFiles/geometry_msgs_generate_messages_eus.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target geometry_msgs_generate_messages_eus"
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_eus.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/geometry_msgs_generate_messages_eus.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/geometry_msgs_generate_messages_eus.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_eus.dir/rule
+
+# Convenience name for target.
+geometry_msgs_generate_messages_eus: CMakeFiles/geometry_msgs_generate_messages_eus.dir/rule
+
+.PHONY : geometry_msgs_generate_messages_eus
+
+# clean rule for target.
+CMakeFiles/geometry_msgs_generate_messages_eus.dir/clean:
+	$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_eus.dir/build.make CMakeFiles/geometry_msgs_generate_messages_eus.dir/clean
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_eus.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/std_msgs_generate_messages_py.dir
+
+# All Build rule for target.
+CMakeFiles/std_msgs_generate_messages_py.dir/all:
+	$(MAKE) -f CMakeFiles/std_msgs_generate_messages_py.dir/build.make CMakeFiles/std_msgs_generate_messages_py.dir/depend
+	$(MAKE) -f CMakeFiles/std_msgs_generate_messages_py.dir/build.make CMakeFiles/std_msgs_generate_messages_py.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target std_msgs_generate_messages_py"
+.PHONY : CMakeFiles/std_msgs_generate_messages_py.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/std_msgs_generate_messages_py.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/std_msgs_generate_messages_py.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/std_msgs_generate_messages_py.dir/rule
+
+# Convenience name for target.
+std_msgs_generate_messages_py: CMakeFiles/std_msgs_generate_messages_py.dir/rule
+
+.PHONY : std_msgs_generate_messages_py
+
+# clean rule for target.
+CMakeFiles/std_msgs_generate_messages_py.dir/clean:
+	$(MAKE) -f CMakeFiles/std_msgs_generate_messages_py.dir/build.make CMakeFiles/std_msgs_generate_messages_py.dir/clean
+.PHONY : CMakeFiles/std_msgs_generate_messages_py.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/tf_generate_messages_nodejs.dir
+
+# All Build rule for target.
+CMakeFiles/tf_generate_messages_nodejs.dir/all:
+	$(MAKE) -f CMakeFiles/tf_generate_messages_nodejs.dir/build.make CMakeFiles/tf_generate_messages_nodejs.dir/depend
+	$(MAKE) -f CMakeFiles/tf_generate_messages_nodejs.dir/build.make CMakeFiles/tf_generate_messages_nodejs.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target tf_generate_messages_nodejs"
+.PHONY : CMakeFiles/tf_generate_messages_nodejs.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/tf_generate_messages_nodejs.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf_generate_messages_nodejs.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/tf_generate_messages_nodejs.dir/rule
+
+# Convenience name for target.
+tf_generate_messages_nodejs: CMakeFiles/tf_generate_messages_nodejs.dir/rule
+
+.PHONY : tf_generate_messages_nodejs
+
+# clean rule for target.
+CMakeFiles/tf_generate_messages_nodejs.dir/clean:
+	$(MAKE) -f CMakeFiles/tf_generate_messages_nodejs.dir/build.make CMakeFiles/tf_generate_messages_nodejs.dir/clean
+.PHONY : CMakeFiles/tf_generate_messages_nodejs.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/geometry_msgs_generate_messages_cpp.dir
+
+# All Build rule for target.
+CMakeFiles/geometry_msgs_generate_messages_cpp.dir/all:
+	$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_cpp.dir/depend
+	$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target geometry_msgs_generate_messages_cpp"
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_cpp.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/geometry_msgs_generate_messages_cpp.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/geometry_msgs_generate_messages_cpp.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_cpp.dir/rule
+
+# Convenience name for target.
+geometry_msgs_generate_messages_cpp: CMakeFiles/geometry_msgs_generate_messages_cpp.dir/rule
+
+.PHONY : geometry_msgs_generate_messages_cpp
+
+# clean rule for target.
+CMakeFiles/geometry_msgs_generate_messages_cpp.dir/clean:
+	$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_cpp.dir/clean
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_cpp.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir
+
+# All Build rule for target.
+CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/all:
+	$(MAKE) -f CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/build.make CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/depend
+	$(MAKE) -f CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/build.make CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target dynamic_reconfigure_generate_messages_nodejs"
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/rule
+
+# Convenience name for target.
+dynamic_reconfigure_generate_messages_nodejs: CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/rule
+
+.PHONY : dynamic_reconfigure_generate_messages_nodejs
+
+# clean rule for target.
+CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/clean:
+	$(MAKE) -f CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/build.make CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/clean
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/tf2_msgs_generate_messages_py.dir
+
+# All Build rule for target.
+CMakeFiles/tf2_msgs_generate_messages_py.dir/all:
+	$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_py.dir/build.make CMakeFiles/tf2_msgs_generate_messages_py.dir/depend
+	$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_py.dir/build.make CMakeFiles/tf2_msgs_generate_messages_py.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target tf2_msgs_generate_messages_py"
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_py.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/tf2_msgs_generate_messages_py.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf2_msgs_generate_messages_py.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_py.dir/rule
+
+# Convenience name for target.
+tf2_msgs_generate_messages_py: CMakeFiles/tf2_msgs_generate_messages_py.dir/rule
+
+.PHONY : tf2_msgs_generate_messages_py
+
+# clean rule for target.
+CMakeFiles/tf2_msgs_generate_messages_py.dir/clean:
+	$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_py.dir/build.make CMakeFiles/tf2_msgs_generate_messages_py.dir/clean
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_py.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir
+
+# All Build rule for target.
+CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/all:
+	$(MAKE) -f CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/build.make CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/depend
+	$(MAKE) -f CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/build.make CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target dynamic_reconfigure_generate_messages_eus"
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/rule
+
+# Convenience name for target.
+dynamic_reconfigure_generate_messages_eus: CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/rule
+
+.PHONY : dynamic_reconfigure_generate_messages_eus
+
+# clean rule for target.
+CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/clean:
+	$(MAKE) -f CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/build.make CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/clean
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/geometry_msgs_generate_messages_nodejs.dir
+
+# All Build rule for target.
+CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/all:
+	$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/depend
+	$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target geometry_msgs_generate_messages_nodejs"
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/rule
+
+# Convenience name for target.
+geometry_msgs_generate_messages_nodejs: CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/rule
+
+.PHONY : geometry_msgs_generate_messages_nodejs
+
+# clean rule for target.
+CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/clean:
+	$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/clean
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/geometry_msgs_generate_messages_py.dir
+
+# All Build rule for target.
+CMakeFiles/geometry_msgs_generate_messages_py.dir/all:
+	$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_py.dir/build.make CMakeFiles/geometry_msgs_generate_messages_py.dir/depend
+	$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_py.dir/build.make CMakeFiles/geometry_msgs_generate_messages_py.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target geometry_msgs_generate_messages_py"
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_py.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/geometry_msgs_generate_messages_py.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/geometry_msgs_generate_messages_py.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_py.dir/rule
+
+# Convenience name for target.
+geometry_msgs_generate_messages_py: CMakeFiles/geometry_msgs_generate_messages_py.dir/rule
+
+.PHONY : geometry_msgs_generate_messages_py
+
+# clean rule for target.
+CMakeFiles/geometry_msgs_generate_messages_py.dir/clean:
+	$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_py.dir/build.make CMakeFiles/geometry_msgs_generate_messages_py.dir/clean
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_py.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/tf2_msgs_generate_messages_eus.dir
+
+# All Build rule for target.
+CMakeFiles/tf2_msgs_generate_messages_eus.dir/all:
+	$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_eus.dir/build.make CMakeFiles/tf2_msgs_generate_messages_eus.dir/depend
+	$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_eus.dir/build.make CMakeFiles/tf2_msgs_generate_messages_eus.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target tf2_msgs_generate_messages_eus"
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_eus.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/tf2_msgs_generate_messages_eus.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf2_msgs_generate_messages_eus.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_eus.dir/rule
+
+# Convenience name for target.
+tf2_msgs_generate_messages_eus: CMakeFiles/tf2_msgs_generate_messages_eus.dir/rule
+
+.PHONY : tf2_msgs_generate_messages_eus
+
+# clean rule for target.
+CMakeFiles/tf2_msgs_generate_messages_eus.dir/clean:
+	$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_eus.dir/build.make CMakeFiles/tf2_msgs_generate_messages_eus.dir/clean
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_eus.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/sensor_msgs_generate_messages_py.dir
+
+# All Build rule for target.
+CMakeFiles/sensor_msgs_generate_messages_py.dir/all:
+	$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_py.dir/build.make CMakeFiles/sensor_msgs_generate_messages_py.dir/depend
+	$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_py.dir/build.make CMakeFiles/sensor_msgs_generate_messages_py.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target sensor_msgs_generate_messages_py"
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_py.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/sensor_msgs_generate_messages_py.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/sensor_msgs_generate_messages_py.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_py.dir/rule
+
+# Convenience name for target.
+sensor_msgs_generate_messages_py: CMakeFiles/sensor_msgs_generate_messages_py.dir/rule
+
+.PHONY : sensor_msgs_generate_messages_py
+
+# clean rule for target.
+CMakeFiles/sensor_msgs_generate_messages_py.dir/clean:
+	$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_py.dir/build.make CMakeFiles/sensor_msgs_generate_messages_py.dir/clean
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_py.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/sensor_msgs_generate_messages_eus.dir
+
+# All Build rule for target.
+CMakeFiles/sensor_msgs_generate_messages_eus.dir/all:
+	$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_eus.dir/build.make CMakeFiles/sensor_msgs_generate_messages_eus.dir/depend
+	$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_eus.dir/build.make CMakeFiles/sensor_msgs_generate_messages_eus.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target sensor_msgs_generate_messages_eus"
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_eus.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/sensor_msgs_generate_messages_eus.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/sensor_msgs_generate_messages_eus.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_eus.dir/rule
+
+# Convenience name for target.
+sensor_msgs_generate_messages_eus: CMakeFiles/sensor_msgs_generate_messages_eus.dir/rule
+
+.PHONY : sensor_msgs_generate_messages_eus
+
+# clean rule for target.
+CMakeFiles/sensor_msgs_generate_messages_eus.dir/clean:
+	$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_eus.dir/build.make CMakeFiles/sensor_msgs_generate_messages_eus.dir/clean
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_eus.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/sensor_msgs_generate_messages_lisp.dir
+
+# All Build rule for target.
+CMakeFiles/sensor_msgs_generate_messages_lisp.dir/all:
+	$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_lisp.dir/depend
+	$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target sensor_msgs_generate_messages_lisp"
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_lisp.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/sensor_msgs_generate_messages_lisp.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/sensor_msgs_generate_messages_lisp.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_lisp.dir/rule
+
+# Convenience name for target.
+sensor_msgs_generate_messages_lisp: CMakeFiles/sensor_msgs_generate_messages_lisp.dir/rule
+
+.PHONY : sensor_msgs_generate_messages_lisp
+
+# clean rule for target.
+CMakeFiles/sensor_msgs_generate_messages_lisp.dir/clean:
+	$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_lisp.dir/clean
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_lisp.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/sensor_msgs_generate_messages_nodejs.dir
+
+# All Build rule for target.
+CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/all:
+	$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/depend
+	$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target sensor_msgs_generate_messages_nodejs"
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/rule
+
+# Convenience name for target.
+sensor_msgs_generate_messages_nodejs: CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/rule
+
+.PHONY : sensor_msgs_generate_messages_nodejs
+
+# clean rule for target.
+CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/clean:
+	$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/clean
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir
+
+# All Build rule for target.
+CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/all:
+	$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/depend
+	$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target rosgraph_msgs_generate_messages_cpp"
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/rule
+
+# Convenience name for target.
+rosgraph_msgs_generate_messages_cpp: CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/rule
+
+.PHONY : rosgraph_msgs_generate_messages_cpp
+
+# clean rule for target.
+CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/clean:
+	$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/clean
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/actionlib_generate_messages_eus.dir
+
+# All Build rule for target.
+CMakeFiles/actionlib_generate_messages_eus.dir/all:
+	$(MAKE) -f CMakeFiles/actionlib_generate_messages_eus.dir/build.make CMakeFiles/actionlib_generate_messages_eus.dir/depend
+	$(MAKE) -f CMakeFiles/actionlib_generate_messages_eus.dir/build.make CMakeFiles/actionlib_generate_messages_eus.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target actionlib_generate_messages_eus"
+.PHONY : CMakeFiles/actionlib_generate_messages_eus.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/actionlib_generate_messages_eus.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_generate_messages_eus.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/actionlib_generate_messages_eus.dir/rule
+
+# Convenience name for target.
+actionlib_generate_messages_eus: CMakeFiles/actionlib_generate_messages_eus.dir/rule
+
+.PHONY : actionlib_generate_messages_eus
+
+# clean rule for target.
+CMakeFiles/actionlib_generate_messages_eus.dir/clean:
+	$(MAKE) -f CMakeFiles/actionlib_generate_messages_eus.dir/build.make CMakeFiles/actionlib_generate_messages_eus.dir/clean
+.PHONY : CMakeFiles/actionlib_generate_messages_eus.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/actionlib_msgs_generate_messages_cpp.dir
+
+# All Build rule for target.
+CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/all:
+	$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/depend
+	$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target actionlib_msgs_generate_messages_cpp"
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/rule
+
+# Convenience name for target.
+actionlib_msgs_generate_messages_cpp: CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/rule
+
+.PHONY : actionlib_msgs_generate_messages_cpp
+
+# clean rule for target.
+CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/clean:
+	$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/clean
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/actionlib_generate_messages_nodejs.dir
+
+# All Build rule for target.
+CMakeFiles/actionlib_generate_messages_nodejs.dir/all:
+	$(MAKE) -f CMakeFiles/actionlib_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_generate_messages_nodejs.dir/depend
+	$(MAKE) -f CMakeFiles/actionlib_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_generate_messages_nodejs.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target actionlib_generate_messages_nodejs"
+.PHONY : CMakeFiles/actionlib_generate_messages_nodejs.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/actionlib_generate_messages_nodejs.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_generate_messages_nodejs.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/actionlib_generate_messages_nodejs.dir/rule
+
+# Convenience name for target.
+actionlib_generate_messages_nodejs: CMakeFiles/actionlib_generate_messages_nodejs.dir/rule
+
+.PHONY : actionlib_generate_messages_nodejs
+
+# clean rule for target.
+CMakeFiles/actionlib_generate_messages_nodejs.dir/clean:
+	$(MAKE) -f CMakeFiles/actionlib_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_generate_messages_nodejs.dir/clean
+.PHONY : CMakeFiles/actionlib_generate_messages_nodejs.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/actionlib_generate_messages_py.dir
+
+# All Build rule for target.
+CMakeFiles/actionlib_generate_messages_py.dir/all:
+	$(MAKE) -f CMakeFiles/actionlib_generate_messages_py.dir/build.make CMakeFiles/actionlib_generate_messages_py.dir/depend
+	$(MAKE) -f CMakeFiles/actionlib_generate_messages_py.dir/build.make CMakeFiles/actionlib_generate_messages_py.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target actionlib_generate_messages_py"
+.PHONY : CMakeFiles/actionlib_generate_messages_py.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/actionlib_generate_messages_py.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_generate_messages_py.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/actionlib_generate_messages_py.dir/rule
+
+# Convenience name for target.
+actionlib_generate_messages_py: CMakeFiles/actionlib_generate_messages_py.dir/rule
+
+.PHONY : actionlib_generate_messages_py
+
+# clean rule for target.
+CMakeFiles/actionlib_generate_messages_py.dir/clean:
+	$(MAKE) -f CMakeFiles/actionlib_generate_messages_py.dir/build.make CMakeFiles/actionlib_generate_messages_py.dir/clean
+.PHONY : CMakeFiles/actionlib_generate_messages_py.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/tf_generate_messages_py.dir
+
+# All Build rule for target.
+CMakeFiles/tf_generate_messages_py.dir/all:
+	$(MAKE) -f CMakeFiles/tf_generate_messages_py.dir/build.make CMakeFiles/tf_generate_messages_py.dir/depend
+	$(MAKE) -f CMakeFiles/tf_generate_messages_py.dir/build.make CMakeFiles/tf_generate_messages_py.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target tf_generate_messages_py"
+.PHONY : CMakeFiles/tf_generate_messages_py.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/tf_generate_messages_py.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf_generate_messages_py.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/tf_generate_messages_py.dir/rule
+
+# Convenience name for target.
+tf_generate_messages_py: CMakeFiles/tf_generate_messages_py.dir/rule
+
+.PHONY : tf_generate_messages_py
+
+# clean rule for target.
+CMakeFiles/tf_generate_messages_py.dir/clean:
+	$(MAKE) -f CMakeFiles/tf_generate_messages_py.dir/build.make CMakeFiles/tf_generate_messages_py.dir/clean
+.PHONY : CMakeFiles/tf_generate_messages_py.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/std_msgs_generate_messages_eus.dir
+
+# All Build rule for target.
+CMakeFiles/std_msgs_generate_messages_eus.dir/all:
+	$(MAKE) -f CMakeFiles/std_msgs_generate_messages_eus.dir/build.make CMakeFiles/std_msgs_generate_messages_eus.dir/depend
+	$(MAKE) -f CMakeFiles/std_msgs_generate_messages_eus.dir/build.make CMakeFiles/std_msgs_generate_messages_eus.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target std_msgs_generate_messages_eus"
+.PHONY : CMakeFiles/std_msgs_generate_messages_eus.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/std_msgs_generate_messages_eus.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/std_msgs_generate_messages_eus.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/std_msgs_generate_messages_eus.dir/rule
+
+# Convenience name for target.
+std_msgs_generate_messages_eus: CMakeFiles/std_msgs_generate_messages_eus.dir/rule
+
+.PHONY : std_msgs_generate_messages_eus
+
+# clean rule for target.
+CMakeFiles/std_msgs_generate_messages_eus.dir/clean:
+	$(MAKE) -f CMakeFiles/std_msgs_generate_messages_eus.dir/build.make CMakeFiles/std_msgs_generate_messages_eus.dir/clean
+.PHONY : CMakeFiles/std_msgs_generate_messages_eus.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir
+
+# All Build rule for target.
+CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/all:
+	$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/depend
+	$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target actionlib_msgs_generate_messages_nodejs"
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/rule
+
+# Convenience name for target.
+actionlib_msgs_generate_messages_nodejs: CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/rule
+
+.PHONY : actionlib_msgs_generate_messages_nodejs
+
+# clean rule for target.
+CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/clean:
+	$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/clean
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/actionlib_msgs_generate_messages_lisp.dir
+
+# All Build rule for target.
+CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/all:
+	$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/depend
+	$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target actionlib_msgs_generate_messages_lisp"
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/rule
+
+# Convenience name for target.
+actionlib_msgs_generate_messages_lisp: CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/rule
+
+.PHONY : actionlib_msgs_generate_messages_lisp
+
+# clean rule for target.
+CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/clean:
+	$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/clean
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/tf2_msgs_generate_messages_lisp.dir
+
+# All Build rule for target.
+CMakeFiles/tf2_msgs_generate_messages_lisp.dir/all:
+	$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_lisp.dir/depend
+	$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target tf2_msgs_generate_messages_lisp"
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_lisp.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/tf2_msgs_generate_messages_lisp.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf2_msgs_generate_messages_lisp.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_lisp.dir/rule
+
+# Convenience name for target.
+tf2_msgs_generate_messages_lisp: CMakeFiles/tf2_msgs_generate_messages_lisp.dir/rule
+
+.PHONY : tf2_msgs_generate_messages_lisp
+
+# clean rule for target.
+CMakeFiles/tf2_msgs_generate_messages_lisp.dir/clean:
+	$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_lisp.dir/clean
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_lisp.dir/clean
+
+#=============================================================================
+# Target rules for target CMakeFiles/tf2_msgs_generate_messages_nodejs.dir
+
+# All Build rule for target.
+CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/all:
+	$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/depend
+	$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num= "Built target tf2_msgs_generate_messages_nodejs"
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/all
+
+# Build rule for subdir invocation for target.
+CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+	$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/rule
+
+# Convenience name for target.
+tf2_msgs_generate_messages_nodejs: CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/rule
+
+.PHONY : tf2_msgs_generate_messages_nodejs
+
+# clean rule for target.
+CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/clean:
+	$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/clean
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/clean
+
+#=============================================================================
+# Target rules for target gtest/googlemock/CMakeFiles/gmock_main.dir
+
+# All Build rule for target.
+gtest/googlemock/CMakeFiles/gmock_main.dir/all: gtest/googlemock/CMakeFiles/gmock.dir/all
+gtest/googlemock/CMakeFiles/gmock_main.dir/all: gtest/googletest/CMakeFiles/gtest.dir/all
+	$(MAKE) -f gtest/googlemock/CMakeFiles/gmock_main.dir/build.make gtest/googlemock/CMakeFiles/gmock_main.dir/depend
+	$(MAKE) -f gtest/googlemock/CMakeFiles/gmock_main.dir/build.make gtest/googlemock/CMakeFiles/gmock_main.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=3,4 "Built target gmock_main"
+.PHONY : gtest/googlemock/CMakeFiles/gmock_main.dir/all
+
+# Build rule for subdir invocation for target.
+gtest/googlemock/CMakeFiles/gmock_main.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 6
+	$(MAKE) -f CMakeFiles/Makefile2 gtest/googlemock/CMakeFiles/gmock_main.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : gtest/googlemock/CMakeFiles/gmock_main.dir/rule
+
+# Convenience name for target.
+gmock_main: gtest/googlemock/CMakeFiles/gmock_main.dir/rule
+
+.PHONY : gmock_main
+
+# clean rule for target.
+gtest/googlemock/CMakeFiles/gmock_main.dir/clean:
+	$(MAKE) -f gtest/googlemock/CMakeFiles/gmock_main.dir/build.make gtest/googlemock/CMakeFiles/gmock_main.dir/clean
+.PHONY : gtest/googlemock/CMakeFiles/gmock_main.dir/clean
+
+#=============================================================================
+# Target rules for target gtest/googlemock/CMakeFiles/gmock.dir
+
+# All Build rule for target.
+gtest/googlemock/CMakeFiles/gmock.dir/all: gtest/googletest/CMakeFiles/gtest.dir/all
+	$(MAKE) -f gtest/googlemock/CMakeFiles/gmock.dir/build.make gtest/googlemock/CMakeFiles/gmock.dir/depend
+	$(MAKE) -f gtest/googlemock/CMakeFiles/gmock.dir/build.make gtest/googlemock/CMakeFiles/gmock.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=1,2 "Built target gmock"
+.PHONY : gtest/googlemock/CMakeFiles/gmock.dir/all
+
+# Build rule for subdir invocation for target.
+gtest/googlemock/CMakeFiles/gmock.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 4
+	$(MAKE) -f CMakeFiles/Makefile2 gtest/googlemock/CMakeFiles/gmock.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : gtest/googlemock/CMakeFiles/gmock.dir/rule
+
+# Convenience name for target.
+gmock: gtest/googlemock/CMakeFiles/gmock.dir/rule
+
+.PHONY : gmock
+
+# clean rule for target.
+gtest/googlemock/CMakeFiles/gmock.dir/clean:
+	$(MAKE) -f gtest/googlemock/CMakeFiles/gmock.dir/build.make gtest/googlemock/CMakeFiles/gmock.dir/clean
+.PHONY : gtest/googlemock/CMakeFiles/gmock.dir/clean
+
+#=============================================================================
+# Target rules for target gtest/googletest/CMakeFiles/gtest_main.dir
+
+# All Build rule for target.
+gtest/googletest/CMakeFiles/gtest_main.dir/all: gtest/googletest/CMakeFiles/gtest.dir/all
+	$(MAKE) -f gtest/googletest/CMakeFiles/gtest_main.dir/build.make gtest/googletest/CMakeFiles/gtest_main.dir/depend
+	$(MAKE) -f gtest/googletest/CMakeFiles/gtest_main.dir/build.make gtest/googletest/CMakeFiles/gtest_main.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=7,8 "Built target gtest_main"
+.PHONY : gtest/googletest/CMakeFiles/gtest_main.dir/all
+
+# Build rule for subdir invocation for target.
+gtest/googletest/CMakeFiles/gtest_main.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 4
+	$(MAKE) -f CMakeFiles/Makefile2 gtest/googletest/CMakeFiles/gtest_main.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : gtest/googletest/CMakeFiles/gtest_main.dir/rule
+
+# Convenience name for target.
+gtest_main: gtest/googletest/CMakeFiles/gtest_main.dir/rule
+
+.PHONY : gtest_main
+
+# clean rule for target.
+gtest/googletest/CMakeFiles/gtest_main.dir/clean:
+	$(MAKE) -f gtest/googletest/CMakeFiles/gtest_main.dir/build.make gtest/googletest/CMakeFiles/gtest_main.dir/clean
+.PHONY : gtest/googletest/CMakeFiles/gtest_main.dir/clean
+
+#=============================================================================
+# Target rules for target gtest/googletest/CMakeFiles/gtest.dir
+
+# All Build rule for target.
+gtest/googletest/CMakeFiles/gtest.dir/all:
+	$(MAKE) -f gtest/googletest/CMakeFiles/gtest.dir/build.make gtest/googletest/CMakeFiles/gtest.dir/depend
+	$(MAKE) -f gtest/googletest/CMakeFiles/gtest.dir/build.make gtest/googletest/CMakeFiles/gtest.dir/build
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=5,6 "Built target gtest"
+.PHONY : gtest/googletest/CMakeFiles/gtest.dir/all
+
+# Build rule for subdir invocation for target.
+gtest/googletest/CMakeFiles/gtest.dir/rule: cmake_check_build_system
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 2
+	$(MAKE) -f CMakeFiles/Makefile2 gtest/googletest/CMakeFiles/gtest.dir/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : gtest/googletest/CMakeFiles/gtest.dir/rule
+
+# Convenience name for target.
+gtest: gtest/googletest/CMakeFiles/gtest.dir/rule
+
+.PHONY : gtest
+
+# clean rule for target.
+gtest/googletest/CMakeFiles/gtest.dir/clean:
+	$(MAKE) -f gtest/googletest/CMakeFiles/gtest.dir/build.make gtest/googletest/CMakeFiles/gtest.dir/clean
+.PHONY : gtest/googletest/CMakeFiles/gtest.dir/clean
+
+#=============================================================================
+# Special targets to cleanup operation of make.
+
+# Special rule to run CMake to check the build system integrity.
+# No rule that depends on this can have commands that come from listfiles
+# because they might be regenerated.
+cmake_check_build_system:
+	$(CMAKE_COMMAND) -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0
+.PHONY : cmake_check_build_system
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/TargetDirectories.txt b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/TargetDirectories.txt
new file mode 100644
index 0000000000000000000000000000000000000000..9da6d4e92aa500eab8a92b245342ee5648ddfd59
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/TargetDirectories.txt
@@ -0,0 +1,93 @@
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/install/strip.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/install/local.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/list_install_components.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rebuild_cache.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/test.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_gencfg.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_lisp.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_cpp.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_gencfg.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_cpp.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_py.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_cpp.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_lisp.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_py.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_eus.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_py.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_lisp.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_py.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/download_extra_data.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/doxygen.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_lisp.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/_catkin_empty_exported_target.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/clean_test_results.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_lisp.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_eus.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/install.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tests.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_cpp.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_cpp.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_eus.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_cpp.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_nodejs.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_package.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/run_tests.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_nodejs.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_eus.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_py.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_nodejs.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_cpp.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_py.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_py.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_eus.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_py.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_eus.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_lisp.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/edit_cache.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_eus.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_nodejs.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_py.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_py.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_eus.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_lisp.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/CMakeFiles/install/strip.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/CMakeFiles/install/local.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/CMakeFiles/install.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/CMakeFiles/list_install_components.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/CMakeFiles/rebuild_cache.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/CMakeFiles/edit_cache.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/CMakeFiles/test.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/install/strip.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/install/local.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/install.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/list_install_components.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/rebuild_cache.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/edit_cache.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/test.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/install/strip.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/install/local.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/install.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/list_install_components.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/rebuild_cache.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/edit_cache.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/test.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/_catkin_empty_exported_target.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/_catkin_empty_exported_target.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/_catkin_empty_exported_target.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/_catkin_empty_exported_target.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/_catkin_empty_exported_target.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..a4b233a4f10adad4543c52e95795dd308f88a842
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/_catkin_empty_exported_target.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for _catkin_empty_exported_target.
+
+# Include the progress variables for this target.
+include CMakeFiles/_catkin_empty_exported_target.dir/progress.make
+
+_catkin_empty_exported_target: CMakeFiles/_catkin_empty_exported_target.dir/build.make
+
+.PHONY : _catkin_empty_exported_target
+
+# Rule to build all files generated by this target.
+CMakeFiles/_catkin_empty_exported_target.dir/build: _catkin_empty_exported_target
+
+.PHONY : CMakeFiles/_catkin_empty_exported_target.dir/build
+
+CMakeFiles/_catkin_empty_exported_target.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/_catkin_empty_exported_target.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/_catkin_empty_exported_target.dir/clean
+
+CMakeFiles/_catkin_empty_exported_target.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/_catkin_empty_exported_target.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/_catkin_empty_exported_target.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/_catkin_empty_exported_target.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/_catkin_empty_exported_target.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..56a88ba918592a5b2cbb5fdb5c13781e8faf14e2
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/_catkin_empty_exported_target.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/_catkin_empty_exported_target.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/_catkin_empty_exported_target.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/_catkin_empty_exported_target.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/_catkin_empty_exported_target.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_cpp.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_cpp.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_cpp.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_cpp.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_cpp.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..2c7c8045a8d8c34283977fe6fe61d761b2ca2177
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_cpp.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for actionlib_generate_messages_cpp.
+
+# Include the progress variables for this target.
+include CMakeFiles/actionlib_generate_messages_cpp.dir/progress.make
+
+actionlib_generate_messages_cpp: CMakeFiles/actionlib_generate_messages_cpp.dir/build.make
+
+.PHONY : actionlib_generate_messages_cpp
+
+# Rule to build all files generated by this target.
+CMakeFiles/actionlib_generate_messages_cpp.dir/build: actionlib_generate_messages_cpp
+
+.PHONY : CMakeFiles/actionlib_generate_messages_cpp.dir/build
+
+CMakeFiles/actionlib_generate_messages_cpp.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/actionlib_generate_messages_cpp.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/actionlib_generate_messages_cpp.dir/clean
+
+CMakeFiles/actionlib_generate_messages_cpp.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_cpp.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/actionlib_generate_messages_cpp.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_cpp.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_cpp.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..acf4a50d93928d457f662aa9395696656db5c9a2
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_cpp.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/actionlib_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_cpp.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_cpp.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_cpp.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_cpp.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_cpp.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_cpp.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_cpp.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_cpp.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_cpp.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_eus.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_eus.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_eus.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_eus.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_eus.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..4654b7f841eb7442a2326a80f3a1ea5eae18df48
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_eus.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for actionlib_generate_messages_eus.
+
+# Include the progress variables for this target.
+include CMakeFiles/actionlib_generate_messages_eus.dir/progress.make
+
+actionlib_generate_messages_eus: CMakeFiles/actionlib_generate_messages_eus.dir/build.make
+
+.PHONY : actionlib_generate_messages_eus
+
+# Rule to build all files generated by this target.
+CMakeFiles/actionlib_generate_messages_eus.dir/build: actionlib_generate_messages_eus
+
+.PHONY : CMakeFiles/actionlib_generate_messages_eus.dir/build
+
+CMakeFiles/actionlib_generate_messages_eus.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/actionlib_generate_messages_eus.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/actionlib_generate_messages_eus.dir/clean
+
+CMakeFiles/actionlib_generate_messages_eus.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_eus.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/actionlib_generate_messages_eus.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_eus.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_eus.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..6bdc0a3cf1ea562d9d65c0093bc62b9cd84c2180
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_eus.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/actionlib_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_eus.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_eus.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_eus.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_eus.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_eus.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_eus.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_eus.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_eus.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_eus.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_lisp.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_lisp.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_lisp.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_lisp.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_lisp.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..051a21a5775d92a41d96ba17a7810c601014051b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_lisp.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for actionlib_generate_messages_lisp.
+
+# Include the progress variables for this target.
+include CMakeFiles/actionlib_generate_messages_lisp.dir/progress.make
+
+actionlib_generate_messages_lisp: CMakeFiles/actionlib_generate_messages_lisp.dir/build.make
+
+.PHONY : actionlib_generate_messages_lisp
+
+# Rule to build all files generated by this target.
+CMakeFiles/actionlib_generate_messages_lisp.dir/build: actionlib_generate_messages_lisp
+
+.PHONY : CMakeFiles/actionlib_generate_messages_lisp.dir/build
+
+CMakeFiles/actionlib_generate_messages_lisp.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/actionlib_generate_messages_lisp.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/actionlib_generate_messages_lisp.dir/clean
+
+CMakeFiles/actionlib_generate_messages_lisp.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_lisp.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/actionlib_generate_messages_lisp.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_lisp.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_lisp.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..fae152b067ae486eaa0adc218e0eec3f2644cce0
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_lisp.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/actionlib_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_lisp.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_lisp.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_lisp.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_lisp.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_lisp.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_lisp.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_lisp.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_lisp.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_lisp.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_nodejs.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_nodejs.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_nodejs.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_nodejs.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_nodejs.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..16b6a7daa56a7c914a3033e4fd4737daf9b16af6
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_nodejs.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for actionlib_generate_messages_nodejs.
+
+# Include the progress variables for this target.
+include CMakeFiles/actionlib_generate_messages_nodejs.dir/progress.make
+
+actionlib_generate_messages_nodejs: CMakeFiles/actionlib_generate_messages_nodejs.dir/build.make
+
+.PHONY : actionlib_generate_messages_nodejs
+
+# Rule to build all files generated by this target.
+CMakeFiles/actionlib_generate_messages_nodejs.dir/build: actionlib_generate_messages_nodejs
+
+.PHONY : CMakeFiles/actionlib_generate_messages_nodejs.dir/build
+
+CMakeFiles/actionlib_generate_messages_nodejs.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/actionlib_generate_messages_nodejs.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/actionlib_generate_messages_nodejs.dir/clean
+
+CMakeFiles/actionlib_generate_messages_nodejs.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_nodejs.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/actionlib_generate_messages_nodejs.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_nodejs.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_nodejs.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..6e65df1bf017f4b033448108c820440e1401075f
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_nodejs.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/actionlib_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_nodejs.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_nodejs.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_nodejs.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_nodejs.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_nodejs.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_nodejs.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_nodejs.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_nodejs.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_nodejs.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_py.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_py.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_py.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_py.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_py.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..fd904a648ab52d0e67676fe0b369ef22b0291738
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_py.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for actionlib_generate_messages_py.
+
+# Include the progress variables for this target.
+include CMakeFiles/actionlib_generate_messages_py.dir/progress.make
+
+actionlib_generate_messages_py: CMakeFiles/actionlib_generate_messages_py.dir/build.make
+
+.PHONY : actionlib_generate_messages_py
+
+# Rule to build all files generated by this target.
+CMakeFiles/actionlib_generate_messages_py.dir/build: actionlib_generate_messages_py
+
+.PHONY : CMakeFiles/actionlib_generate_messages_py.dir/build
+
+CMakeFiles/actionlib_generate_messages_py.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/actionlib_generate_messages_py.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/actionlib_generate_messages_py.dir/clean
+
+CMakeFiles/actionlib_generate_messages_py.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_py.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/actionlib_generate_messages_py.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_py.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_py.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..aa0e8de87f7bc12c984ef3e8f1effefd4367ac79
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_py.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/actionlib_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_py.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_py.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_py.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_py.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_py.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_py.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_py.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_py.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_generate_messages_py.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..f9abcc1c8a414e64bccc18ad3e31a57814ba6a03
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for actionlib_msgs_generate_messages_cpp.
+
+# Include the progress variables for this target.
+include CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/progress.make
+
+actionlib_msgs_generate_messages_cpp: CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build.make
+
+.PHONY : actionlib_msgs_generate_messages_cpp
+
+# Rule to build all files generated by this target.
+CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build: actionlib_msgs_generate_messages_cpp
+
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build
+
+CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/clean
+
+CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..9905c519a016805c9fa88ea42f5818ca0f28a3b8
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..b272ea2f9b03ce93e8b0ccfc5b1759cfbc796252
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for actionlib_msgs_generate_messages_eus.
+
+# Include the progress variables for this target.
+include CMakeFiles/actionlib_msgs_generate_messages_eus.dir/progress.make
+
+actionlib_msgs_generate_messages_eus: CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build.make
+
+.PHONY : actionlib_msgs_generate_messages_eus
+
+# Rule to build all files generated by this target.
+CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build: actionlib_msgs_generate_messages_eus
+
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build
+
+CMakeFiles/actionlib_msgs_generate_messages_eus.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/actionlib_msgs_generate_messages_eus.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_eus.dir/clean
+
+CMakeFiles/actionlib_msgs_generate_messages_eus.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_eus.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..cfaf9d54fd6aadbe42e55eeae53809c0fec4c1bf
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/actionlib_msgs_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..9dd3c7ec9a55563cfa63c99d494d239a176a1fd6
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for actionlib_msgs_generate_messages_lisp.
+
+# Include the progress variables for this target.
+include CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/progress.make
+
+actionlib_msgs_generate_messages_lisp: CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build.make
+
+.PHONY : actionlib_msgs_generate_messages_lisp
+
+# Rule to build all files generated by this target.
+CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build: actionlib_msgs_generate_messages_lisp
+
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build
+
+CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/clean
+
+CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..6cfb90fe93c1a0afa0647cb1f6fe30489004763d
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..c519a5b7e8aa1d56e55c8b9472b89668a757f724
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for actionlib_msgs_generate_messages_nodejs.
+
+# Include the progress variables for this target.
+include CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/progress.make
+
+actionlib_msgs_generate_messages_nodejs: CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build.make
+
+.PHONY : actionlib_msgs_generate_messages_nodejs
+
+# Rule to build all files generated by this target.
+CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build: actionlib_msgs_generate_messages_nodejs
+
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build
+
+CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/clean
+
+CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..65e5a401d7f26314a5b6360e55b4cad315c72624
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_py.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_py.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_py.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_py.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_py.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..f6c226e231fe6ee817d2c436f7e43057438a6870
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_py.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for actionlib_msgs_generate_messages_py.
+
+# Include the progress variables for this target.
+include CMakeFiles/actionlib_msgs_generate_messages_py.dir/progress.make
+
+actionlib_msgs_generate_messages_py: CMakeFiles/actionlib_msgs_generate_messages_py.dir/build.make
+
+.PHONY : actionlib_msgs_generate_messages_py
+
+# Rule to build all files generated by this target.
+CMakeFiles/actionlib_msgs_generate_messages_py.dir/build: actionlib_msgs_generate_messages_py
+
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_py.dir/build
+
+CMakeFiles/actionlib_msgs_generate_messages_py.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/actionlib_msgs_generate_messages_py.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_py.dir/clean
+
+CMakeFiles/actionlib_msgs_generate_messages_py.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_py.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/actionlib_msgs_generate_messages_py.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_py.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_py.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..00cd299c587f24eb0e3fb3fb5c7e1d4d3eb0f6eb
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_py.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/actionlib_msgs_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_py.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_py.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_py.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_py.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_py.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_py.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_py.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_py.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/actionlib_msgs_generate_messages_py.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/clean_test_results.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/clean_test_results.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/clean_test_results.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/clean_test_results.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/clean_test_results.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..214244a04ebf52443e5ea6f345a3a1565d05bc9e
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/clean_test_results.dir/build.make
@@ -0,0 +1,76 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for clean_test_results.
+
+# Include the progress variables for this target.
+include CMakeFiles/clean_test_results.dir/progress.make
+
+CMakeFiles/clean_test_results:
+	/usr/bin/python3 /opt/ros/noetic/share/catkin/cmake/test/remove_test_results.py /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/test_results
+
+clean_test_results: CMakeFiles/clean_test_results
+clean_test_results: CMakeFiles/clean_test_results.dir/build.make
+
+.PHONY : clean_test_results
+
+# Rule to build all files generated by this target.
+CMakeFiles/clean_test_results.dir/build: clean_test_results
+
+.PHONY : CMakeFiles/clean_test_results.dir/build
+
+CMakeFiles/clean_test_results.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/clean_test_results.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/clean_test_results.dir/clean
+
+CMakeFiles/clean_test_results.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/clean_test_results.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/clean_test_results.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/clean_test_results.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/clean_test_results.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..63bf0e0f4cda9ec3f7123aee2e30d09703661043
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/clean_test_results.dir/cmake_clean.cmake
@@ -0,0 +1,8 @@
+file(REMOVE_RECURSE
+  "CMakeFiles/clean_test_results"
+)
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/clean_test_results.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/clean_test_results.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/clean_test_results.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/clean_test_results.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/cmake.check_cache b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/cmake.check_cache
new file mode 100644
index 0000000000000000000000000000000000000000..3dccd731726d7faa8b29d8d7dba3b981a53ca497
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/cmake.check_cache
@@ -0,0 +1 @@
+# This file is generated by cmake for dependency checking of the CMakeCache.txt file
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/download_extra_data.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/download_extra_data.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/download_extra_data.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/download_extra_data.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/download_extra_data.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..3f09f348f9b5dbe18bd7391c4c957435fa5e31e3
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/download_extra_data.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for download_extra_data.
+
+# Include the progress variables for this target.
+include CMakeFiles/download_extra_data.dir/progress.make
+
+download_extra_data: CMakeFiles/download_extra_data.dir/build.make
+
+.PHONY : download_extra_data
+
+# Rule to build all files generated by this target.
+CMakeFiles/download_extra_data.dir/build: download_extra_data
+
+.PHONY : CMakeFiles/download_extra_data.dir/build
+
+CMakeFiles/download_extra_data.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/download_extra_data.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/download_extra_data.dir/clean
+
+CMakeFiles/download_extra_data.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/download_extra_data.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/download_extra_data.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/download_extra_data.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/download_extra_data.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..bf7d7e25c0800701682eb7dcc091389edb9f8952
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/download_extra_data.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/download_extra_data.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/download_extra_data.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/download_extra_data.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/download_extra_data.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/doxygen.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/doxygen.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/doxygen.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/doxygen.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/doxygen.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..039290d487421ede2a2212035e595a541c4a1c47
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/doxygen.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for doxygen.
+
+# Include the progress variables for this target.
+include CMakeFiles/doxygen.dir/progress.make
+
+doxygen: CMakeFiles/doxygen.dir/build.make
+
+.PHONY : doxygen
+
+# Rule to build all files generated by this target.
+CMakeFiles/doxygen.dir/build: doxygen
+
+.PHONY : CMakeFiles/doxygen.dir/build
+
+CMakeFiles/doxygen.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/doxygen.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/doxygen.dir/clean
+
+CMakeFiles/doxygen.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/doxygen.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/doxygen.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/doxygen.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/doxygen.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..ef20a758f2dfce53bd9a1326dac1182bbe19a225
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/doxygen.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/doxygen.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/doxygen.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/doxygen.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/doxygen.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_gencfg.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_gencfg.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_gencfg.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_gencfg.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_gencfg.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..b43e3b8a53a9eb60635cf8070e82f3d46e760670
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_gencfg.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for dynamic_reconfigure_gencfg.
+
+# Include the progress variables for this target.
+include CMakeFiles/dynamic_reconfigure_gencfg.dir/progress.make
+
+dynamic_reconfigure_gencfg: CMakeFiles/dynamic_reconfigure_gencfg.dir/build.make
+
+.PHONY : dynamic_reconfigure_gencfg
+
+# Rule to build all files generated by this target.
+CMakeFiles/dynamic_reconfigure_gencfg.dir/build: dynamic_reconfigure_gencfg
+
+.PHONY : CMakeFiles/dynamic_reconfigure_gencfg.dir/build
+
+CMakeFiles/dynamic_reconfigure_gencfg.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/dynamic_reconfigure_gencfg.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/dynamic_reconfigure_gencfg.dir/clean
+
+CMakeFiles/dynamic_reconfigure_gencfg.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_gencfg.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/dynamic_reconfigure_gencfg.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_gencfg.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_gencfg.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..b9e4b825d7b62f20adc3d6b3904ae6d01dd955ed
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_gencfg.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/dynamic_reconfigure_gencfg.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_gencfg.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_gencfg.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_gencfg.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_gencfg.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_gencfg.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_gencfg.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_gencfg.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_gencfg.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_gencfg.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..941f1167bccfba9b2acf9902d71bffed5f9c7d1b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for dynamic_reconfigure_generate_messages_cpp.
+
+# Include the progress variables for this target.
+include CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/progress.make
+
+dynamic_reconfigure_generate_messages_cpp: CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/build.make
+
+.PHONY : dynamic_reconfigure_generate_messages_cpp
+
+# Rule to build all files generated by this target.
+CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/build: dynamic_reconfigure_generate_messages_cpp
+
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/build
+
+CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/clean
+
+CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..4b6964900648ec0a6d7edff053283c93eb4d99ae
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_cpp.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..6c1cd154259fbe3f50dd16f470681829eeb8f449
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for dynamic_reconfigure_generate_messages_eus.
+
+# Include the progress variables for this target.
+include CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/progress.make
+
+dynamic_reconfigure_generate_messages_eus: CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/build.make
+
+.PHONY : dynamic_reconfigure_generate_messages_eus
+
+# Rule to build all files generated by this target.
+CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/build: dynamic_reconfigure_generate_messages_eus
+
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/build
+
+CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/clean
+
+CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..c5dc040672f1ef45eb17d08bec4122431024c0a2
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_eus.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..9c59f38a373a50a43fe3a2d5ff4edc61eae294e1
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for dynamic_reconfigure_generate_messages_lisp.
+
+# Include the progress variables for this target.
+include CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/progress.make
+
+dynamic_reconfigure_generate_messages_lisp: CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/build.make
+
+.PHONY : dynamic_reconfigure_generate_messages_lisp
+
+# Rule to build all files generated by this target.
+CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/build: dynamic_reconfigure_generate_messages_lisp
+
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/build
+
+CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/clean
+
+CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..4636c51bfdf3c2878b96eb05c2e8dca11540da2c
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_lisp.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..83525c0dd24dbbd80b5e738dca0ad12e505f8cae
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for dynamic_reconfigure_generate_messages_nodejs.
+
+# Include the progress variables for this target.
+include CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/progress.make
+
+dynamic_reconfigure_generate_messages_nodejs: CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/build.make
+
+.PHONY : dynamic_reconfigure_generate_messages_nodejs
+
+# Rule to build all files generated by this target.
+CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/build: dynamic_reconfigure_generate_messages_nodejs
+
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/build
+
+CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/clean
+
+CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..f8b0469105b050a21e22f6f361f9f7c70b7c6791
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_nodejs.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..e35ea11e9c8c0fc906de774df6ba1876e4f8eb47
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for dynamic_reconfigure_generate_messages_py.
+
+# Include the progress variables for this target.
+include CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/progress.make
+
+dynamic_reconfigure_generate_messages_py: CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/build.make
+
+.PHONY : dynamic_reconfigure_generate_messages_py
+
+# Rule to build all files generated by this target.
+CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/build: dynamic_reconfigure_generate_messages_py
+
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/build
+
+CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/clean
+
+CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..acecef0c9c3d3bc3a41a4704c473855b255fed6a
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/dynamic_reconfigure_generate_messages_py.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..9f653e3abbc85700c643218bfdafd370ca591caa
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for geometry_msgs_generate_messages_cpp.
+
+# Include the progress variables for this target.
+include CMakeFiles/geometry_msgs_generate_messages_cpp.dir/progress.make
+
+geometry_msgs_generate_messages_cpp: CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build.make
+
+.PHONY : geometry_msgs_generate_messages_cpp
+
+# Rule to build all files generated by this target.
+CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build: geometry_msgs_generate_messages_cpp
+
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build
+
+CMakeFiles/geometry_msgs_generate_messages_cpp.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/geometry_msgs_generate_messages_cpp.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_cpp.dir/clean
+
+CMakeFiles/geometry_msgs_generate_messages_cpp.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_cpp.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..820ac958f43c6eebf66f6d6d990cc6f9ee92bdee
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/geometry_msgs_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_eus.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_eus.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_eus.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_eus.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_eus.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..3354b38084eec0103f8b1c672f5d2e002971aa1d
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_eus.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for geometry_msgs_generate_messages_eus.
+
+# Include the progress variables for this target.
+include CMakeFiles/geometry_msgs_generate_messages_eus.dir/progress.make
+
+geometry_msgs_generate_messages_eus: CMakeFiles/geometry_msgs_generate_messages_eus.dir/build.make
+
+.PHONY : geometry_msgs_generate_messages_eus
+
+# Rule to build all files generated by this target.
+CMakeFiles/geometry_msgs_generate_messages_eus.dir/build: geometry_msgs_generate_messages_eus
+
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_eus.dir/build
+
+CMakeFiles/geometry_msgs_generate_messages_eus.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/geometry_msgs_generate_messages_eus.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_eus.dir/clean
+
+CMakeFiles/geometry_msgs_generate_messages_eus.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_eus.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_eus.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_eus.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_eus.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..67f285a2b286be7fc34e84068b61e34e06956953
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_eus.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/geometry_msgs_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_eus.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_eus.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_eus.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_eus.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_eus.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_eus.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_eus.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_eus.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_eus.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..11ed8d9d3313ec6addb204e5e631bbb2d83883e8
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for geometry_msgs_generate_messages_lisp.
+
+# Include the progress variables for this target.
+include CMakeFiles/geometry_msgs_generate_messages_lisp.dir/progress.make
+
+geometry_msgs_generate_messages_lisp: CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build.make
+
+.PHONY : geometry_msgs_generate_messages_lisp
+
+# Rule to build all files generated by this target.
+CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build: geometry_msgs_generate_messages_lisp
+
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build
+
+CMakeFiles/geometry_msgs_generate_messages_lisp.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/geometry_msgs_generate_messages_lisp.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_lisp.dir/clean
+
+CMakeFiles/geometry_msgs_generate_messages_lisp.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_lisp.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..1e1c8fa8835a35da1844bebfcf48761dffbbb744
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/geometry_msgs_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..ccb5636e12130370d9c438e5e51886b214bb6626
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for geometry_msgs_generate_messages_nodejs.
+
+# Include the progress variables for this target.
+include CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/progress.make
+
+geometry_msgs_generate_messages_nodejs: CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build.make
+
+.PHONY : geometry_msgs_generate_messages_nodejs
+
+# Rule to build all files generated by this target.
+CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build: geometry_msgs_generate_messages_nodejs
+
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build
+
+CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/clean
+
+CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..a10d1c0a7d1c206f0b4fa6bad096f015b45ac47e
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_py.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_py.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_py.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_py.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_py.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..2922ffa4b6c8c6a0fe1323bd1eaa653d20825a71
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_py.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for geometry_msgs_generate_messages_py.
+
+# Include the progress variables for this target.
+include CMakeFiles/geometry_msgs_generate_messages_py.dir/progress.make
+
+geometry_msgs_generate_messages_py: CMakeFiles/geometry_msgs_generate_messages_py.dir/build.make
+
+.PHONY : geometry_msgs_generate_messages_py
+
+# Rule to build all files generated by this target.
+CMakeFiles/geometry_msgs_generate_messages_py.dir/build: geometry_msgs_generate_messages_py
+
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_py.dir/build
+
+CMakeFiles/geometry_msgs_generate_messages_py.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/geometry_msgs_generate_messages_py.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_py.dir/clean
+
+CMakeFiles/geometry_msgs_generate_messages_py.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_py.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/geometry_msgs_generate_messages_py.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_py.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_py.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..37b46276801d2babea1a13a48a7cfd37a2e3ef6c
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_py.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/geometry_msgs_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_py.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_py.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_py.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_py.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_py.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_py.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_py.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_py.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/geometry_msgs_generate_messages_py.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_gencfg.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_gencfg.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..c4766d0403e8dd655ef37765f084b6de220cbc59
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_gencfg.dir/DependInfo.cmake
@@ -0,0 +1,20 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Pairs of files generated by the same build rule.
+set(CMAKE_MULTIPLE_OUTPUT_PAIRS
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/python3/dist-packages/mav_nonlinear_mpc/cfg/NonLinearMPCConfig.py" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h"
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig-usage.dox" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h"
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig.dox" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h"
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig.wikidoc" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h"
+  )
+
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_gencfg.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_gencfg.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..db7683c816c3f5f295084acb14c4788654fab10f
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_gencfg.dir/build.make
@@ -0,0 +1,100 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for mav_nonlinear_mpc_gencfg.
+
+# Include the progress variables for this target.
+include CMakeFiles/mav_nonlinear_mpc_gencfg.dir/progress.make
+
+CMakeFiles/mav_nonlinear_mpc_gencfg: devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h
+CMakeFiles/mav_nonlinear_mpc_gencfg: devel/lib/python3/dist-packages/mav_nonlinear_mpc/cfg/NonLinearMPCConfig.py
+
+
+devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h: ../cfg/NonLinearMPC.cfg
+devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h: /opt/ros/noetic/share/dynamic_reconfigure/templates/ConfigType.py.template
+devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h: /opt/ros/noetic/share/dynamic_reconfigure/templates/ConfigType.h.template
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --blue --bold --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_1) "Generating dynamic reconfigure files from cfg/NonLinearMPC.cfg: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/python3/dist-packages/mav_nonlinear_mpc/cfg/NonLinearMPCConfig.py"
+	catkin_generated/env_cached.sh /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/setup_custom_pythonpath.sh /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/cfg/NonLinearMPC.cfg /opt/ros/noetic/share/dynamic_reconfigure/cmake/.. /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/share/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/include/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/python3/dist-packages/mav_nonlinear_mpc
+
+devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig.dox: devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h
+	@$(CMAKE_COMMAND) -E touch_nocreate devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig.dox
+
+devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig-usage.dox: devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h
+	@$(CMAKE_COMMAND) -E touch_nocreate devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig-usage.dox
+
+devel/lib/python3/dist-packages/mav_nonlinear_mpc/cfg/NonLinearMPCConfig.py: devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h
+	@$(CMAKE_COMMAND) -E touch_nocreate devel/lib/python3/dist-packages/mav_nonlinear_mpc/cfg/NonLinearMPCConfig.py
+
+devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig.wikidoc: devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h
+	@$(CMAKE_COMMAND) -E touch_nocreate devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig.wikidoc
+
+mav_nonlinear_mpc_gencfg: CMakeFiles/mav_nonlinear_mpc_gencfg
+mav_nonlinear_mpc_gencfg: devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h
+mav_nonlinear_mpc_gencfg: devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig.dox
+mav_nonlinear_mpc_gencfg: devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig-usage.dox
+mav_nonlinear_mpc_gencfg: devel/lib/python3/dist-packages/mav_nonlinear_mpc/cfg/NonLinearMPCConfig.py
+mav_nonlinear_mpc_gencfg: devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig.wikidoc
+mav_nonlinear_mpc_gencfg: CMakeFiles/mav_nonlinear_mpc_gencfg.dir/build.make
+
+.PHONY : mav_nonlinear_mpc_gencfg
+
+# Rule to build all files generated by this target.
+CMakeFiles/mav_nonlinear_mpc_gencfg.dir/build: mav_nonlinear_mpc_gencfg
+
+.PHONY : CMakeFiles/mav_nonlinear_mpc_gencfg.dir/build
+
+CMakeFiles/mav_nonlinear_mpc_gencfg.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/mav_nonlinear_mpc_gencfg.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/mav_nonlinear_mpc_gencfg.dir/clean
+
+CMakeFiles/mav_nonlinear_mpc_gencfg.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_gencfg.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/mav_nonlinear_mpc_gencfg.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_gencfg.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_gencfg.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..90057d0115c31bddc47438f5875f596b383666a6
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_gencfg.dir/cmake_clean.cmake
@@ -0,0 +1,13 @@
+file(REMOVE_RECURSE
+  "CMakeFiles/mav_nonlinear_mpc_gencfg"
+  "devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h"
+  "devel/lib/python3/dist-packages/mav_nonlinear_mpc/cfg/NonLinearMPCConfig.py"
+  "devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig-usage.dox"
+  "devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig.dox"
+  "devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig.wikidoc"
+)
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/mav_nonlinear_mpc_gencfg.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_gencfg.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_gencfg.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_gencfg.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_gencfg.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_gencfg.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_gencfg.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_gencfg.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_gencfg.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..153b0f2a73ace86a9c7118fc830ca2291ec6280f
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_gencfg.dir/progress.make
@@ -0,0 +1,2 @@
+CMAKE_PROGRESS_1 = 9
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/C.includecache b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/C.includecache
new file mode 100644
index 0000000000000000000000000000000000000000..18226847a7bdbd5512819cbf474fb5b85085e1c1
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/C.includecache
@@ -0,0 +1,52 @@
+#IncludeRegexLine: ^[ 	]*[#%][ 	]*(include|import)[ 	]*[<"]([^">]+)([">])
+
+#IncludeRegexScan: ^.*$
+
+#IncludeRegexComplain: ^$
+
+#IncludeRegexTransform: 
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_auxiliary_functions.c
+acado_auxiliary_functions.h
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_auxiliary_functions.h
+stdio.h
+-
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_auxiliary_functions.h
+acado_common.h
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_common.h
+Windows.h
+-
+unistd.h
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/unistd.h
+mach/mach_time.h
+-
+time.h
+-
+sys/stat.h
+-
+sys/time.h
+-
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_common.h
+math.h
+-
+string.h
+-
+acado_qpoases_interface.hpp
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_qpoases_interface.hpp
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_integrator.c
+acado_common.h
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_common.h
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_qpoases_interface.hpp
+stdio.h
+-
+math.h
+-
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_solver.c
+acado_common.h
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_common.h
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/CXX.includecache b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/CXX.includecache
new file mode 100644
index 0000000000000000000000000000000000000000..dce65138c15feb750b939a1873f046d35ca32cbd
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/CXX.includecache
@@ -0,0 +1,2686 @@
+#IncludeRegexLine: ^[ 	]*[#%][ 	]*(include|import)[ 	]*[<"]([^">]+)([">])
+
+#IncludeRegexScan: ^.*$
+
+#IncludeRegexComplain: ^$
+
+#IncludeRegexTransform: 
+
+../include/mav_nonlinear_mpc/nonlinear_mpc.h
+ros/ros.h
+-
+Eigen/Eigen
+-
+stdio.h
+-
+acado_common.h
+../include/mav_nonlinear_mpc/acado_common.h
+acado_auxiliary_functions.h
+../include/mav_nonlinear_mpc/acado_auxiliary_functions.h
+std_srvs/Empty.h
+-
+geometry_msgs/Twist.h
+-
+geometry_msgs/PoseStamped.h
+-
+gazebo_msgs/GetModelState.h
+-
+
+/home/simhe502/catkin_ws/devel/include/geometry_msgs/Point.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+
+/home/simhe502/catkin_ws/devel/include/geometry_msgs/PointStamped.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+std_msgs/Header.h
+-
+geometry_msgs/Point.h
+-
+
+/home/simhe502/catkin_ws/devel/include/geometry_msgs/Pose.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+geometry_msgs/Point.h
+-
+geometry_msgs/Quaternion.h
+-
+
+/home/simhe502/catkin_ws/devel/include/geometry_msgs/PoseStamped.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+std_msgs/Header.h
+-
+geometry_msgs/Pose.h
+-
+
+/home/simhe502/catkin_ws/devel/include/geometry_msgs/Quaternion.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+
+/home/simhe502/catkin_ws/devel/include/geometry_msgs/QuaternionStamped.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+std_msgs/Header.h
+-
+geometry_msgs/Quaternion.h
+-
+
+/home/simhe502/catkin_ws/devel/include/geometry_msgs/Transform.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+geometry_msgs/Vector3.h
+-
+geometry_msgs/Quaternion.h
+-
+
+/home/simhe502/catkin_ws/devel/include/geometry_msgs/TransformStamped.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+std_msgs/Header.h
+-
+geometry_msgs/Transform.h
+-
+
+/home/simhe502/catkin_ws/devel/include/geometry_msgs/Twist.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+geometry_msgs/Vector3.h
+-
+geometry_msgs/Vector3.h
+-
+
+/home/simhe502/catkin_ws/devel/include/geometry_msgs/Vector3.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+
+/home/simhe502/catkin_ws/devel/include/geometry_msgs/Vector3Stamped.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+std_msgs/Header.h
+-
+geometry_msgs/Vector3.h
+-
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_common.h
+math.h
+-
+string.h
+-
+acado_qpoases_interface.hpp
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_qpoases_interface.hpp
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_qpoases_interface.cpp
+acado_common.h
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_common.h
+INCLUDE/QProblem.hpp
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/INCLUDE/QProblem.hpp
+INCLUDE/EXTRAS/SolutionAnalysis.hpp
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/INCLUDE/EXTRAS/SolutionAnalysis.hpp
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_qpoases_interface.hpp
+stdio.h
+-
+math.h
+-
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Bounds.cpp
+Bounds.hpp
+-
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Constraints.cpp
+Constraints.hpp
+-
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/CyclingManager.cpp
+CyclingManager.hpp
+-
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp
+EXTRAS/SolutionAnalysis.hpp
+-
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Indexlist.cpp
+Indexlist.hpp
+-
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/MessageHandling.cpp
+MessageHandling.hpp
+-
+Utils.hpp
+-
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblem.cpp
+QProblem.hpp
+-
+stdio.h
+-
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblemB.cpp
+QProblemB.hpp
+-
+stdio.h
+-
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/SubjectTo.cpp
+SubjectTo.hpp
+-
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Utils.cpp
+math.h
+-
+windows.h
+-
+sys/stat.h
+-
+sys/time.h
+-
+mex.h
+-
+Utils.hpp
+-
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/src/nonlinear_mpc.cc
+tf/transform_datatypes.h
+-
+mav_nonlinear_mpc/nonlinear_mpc.h
+-
+
+/opt/ros/noetic/include/gazebo_msgs/GetModelState.h
+ros/service_traits.h
+-
+gazebo_msgs/GetModelStateRequest.h
+-
+gazebo_msgs/GetModelStateResponse.h
+-
+
+/opt/ros/noetic/include/gazebo_msgs/GetModelStateRequest.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+
+/opt/ros/noetic/include/gazebo_msgs/GetModelStateResponse.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+std_msgs/Header.h
+-
+geometry_msgs/Pose.h
+-
+geometry_msgs/Twist.h
+-
+
+/opt/ros/noetic/include/ros/advertise_options.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/message_traits.h
+/opt/ros/noetic/include/ros/ros/message_traits.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+
+/opt/ros/noetic/include/ros/advertise_service_options.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/service_callback_helper.h
+/opt/ros/noetic/include/ros/ros/service_callback_helper.h
+ros/service_traits.h
+/opt/ros/noetic/include/ros/ros/service_traits.h
+ros/message_traits.h
+/opt/ros/noetic/include/ros/ros/message_traits.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+
+/opt/ros/noetic/include/ros/assert.h
+ros/console.h
+/opt/ros/noetic/include/ros/ros/console.h
+ros/static_assert.h
+/opt/ros/noetic/include/ros/ros/static_assert.h
+ros/platform.h
+-
+stdlib.h
+-
+
+/opt/ros/noetic/include/ros/builtin_message_traits.h
+message_traits.h
+/opt/ros/noetic/include/ros/message_traits.h
+ros/time.h
+/opt/ros/noetic/include/ros/ros/time.h
+
+/opt/ros/noetic/include/ros/common.h
+stdint.h
+-
+assert.h
+-
+stddef.h
+-
+string
+-
+ros/assert.h
+/opt/ros/noetic/include/ros/ros/assert.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/serialized_message.h
+/opt/ros/noetic/include/ros/ros/serialized_message.h
+boost/shared_array.hpp
+-
+ros/macros.h
+-
+
+/opt/ros/noetic/include/ros/console.h
+console_backend.h
+/opt/ros/noetic/include/ros/console_backend.h
+cstdio
+-
+sstream
+-
+ros/time.h
+-
+cstdarg
+-
+ros/macros.h
+-
+map
+-
+vector
+-
+log4cxx/level.h
+/opt/ros/noetic/include/ros/log4cxx/level.h
+rosconsole/macros_generated.h
+/opt/ros/noetic/include/ros/rosconsole/macros_generated.h
+
+/opt/ros/noetic/include/ros/console_backend.h
+ros/macros.h
+-
+
+/opt/ros/noetic/include/ros/datatypes.h
+string
+-
+vector
+-
+map
+-
+set
+-
+list
+-
+boost/shared_ptr.hpp
+-
+
+/opt/ros/noetic/include/ros/duration.h
+iostream
+-
+math.h
+-
+stdexcept
+-
+climits
+-
+stdint.h
+-
+rostime_decl.h
+/opt/ros/noetic/include/ros/rostime_decl.h
+
+/opt/ros/noetic/include/ros/exception.h
+stdexcept
+-
+
+/opt/ros/noetic/include/ros/exceptions.h
+ros/exception.h
+-
+
+/opt/ros/noetic/include/ros/forwards.h
+string
+-
+vector
+-
+map
+-
+set
+-
+list
+-
+boost/shared_ptr.hpp
+-
+boost/make_shared.hpp
+-
+boost/weak_ptr.hpp
+-
+boost/function.hpp
+-
+ros/time.h
+-
+ros/macros.h
+-
+exceptions.h
+/opt/ros/noetic/include/ros/exceptions.h
+ros/datatypes.h
+/opt/ros/noetic/include/ros/ros/datatypes.h
+
+/opt/ros/noetic/include/ros/init.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/spinner.h
+/opt/ros/noetic/include/ros/ros/spinner.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+
+/opt/ros/noetic/include/ros/macros.h
+
+/opt/ros/noetic/include/ros/master.h
+forwards.h
+/opt/ros/noetic/include/ros/forwards.h
+xmlrpcpp/XmlRpcValue.h
+/opt/ros/noetic/include/ros/xmlrpcpp/XmlRpcValue.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+
+/opt/ros/noetic/include/ros/message.h
+ros/macros.h
+/opt/ros/noetic/include/ros/ros/macros.h
+ros/assert.h
+/opt/ros/noetic/include/ros/ros/assert.h
+string
+-
+string.h
+-
+boost/shared_ptr.hpp
+-
+boost/array.hpp
+-
+stdint.h
+-
+
+/opt/ros/noetic/include/ros/message_event.h
+ros/time.h
+/opt/ros/noetic/include/ros/ros/time.h
+ros/datatypes.h
+-
+ros/message_traits.h
+-
+boost/type_traits/is_void.hpp
+-
+boost/type_traits/is_base_of.hpp
+-
+boost/type_traits/is_const.hpp
+-
+boost/type_traits/add_const.hpp
+-
+boost/type_traits/remove_const.hpp
+-
+boost/utility/enable_if.hpp
+-
+boost/function.hpp
+-
+boost/make_shared.hpp
+-
+
+/opt/ros/noetic/include/ros/message_forward.h
+cstddef
+-
+memory
+-
+
+/opt/ros/noetic/include/ros/message_operations.h
+ostream
+-
+
+/opt/ros/noetic/include/ros/message_traits.h
+message_forward.h
+/opt/ros/noetic/include/ros/message_forward.h
+ros/time.h
+-
+string
+-
+boost/utility/enable_if.hpp
+-
+boost/type_traits/remove_const.hpp
+-
+boost/type_traits/remove_reference.hpp
+-
+
+/opt/ros/noetic/include/ros/names.h
+forwards.h
+/opt/ros/noetic/include/ros/forwards.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+
+/opt/ros/noetic/include/ros/node_handle.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/publisher.h
+/opt/ros/noetic/include/ros/ros/publisher.h
+ros/subscriber.h
+/opt/ros/noetic/include/ros/ros/subscriber.h
+ros/service_server.h
+/opt/ros/noetic/include/ros/ros/service_server.h
+ros/service_client.h
+/opt/ros/noetic/include/ros/ros/service_client.h
+ros/timer.h
+/opt/ros/noetic/include/ros/ros/timer.h
+ros/rate.h
+/opt/ros/noetic/include/ros/ros/rate.h
+ros/wall_timer.h
+/opt/ros/noetic/include/ros/ros/wall_timer.h
+ros/steady_timer.h
+/opt/ros/noetic/include/ros/ros/steady_timer.h
+ros/advertise_options.h
+/opt/ros/noetic/include/ros/ros/advertise_options.h
+ros/advertise_service_options.h
+/opt/ros/noetic/include/ros/ros/advertise_service_options.h
+ros/subscribe_options.h
+/opt/ros/noetic/include/ros/ros/subscribe_options.h
+ros/service_client_options.h
+/opt/ros/noetic/include/ros/ros/service_client_options.h
+ros/timer_options.h
+/opt/ros/noetic/include/ros/ros/timer_options.h
+ros/wall_timer_options.h
+/opt/ros/noetic/include/ros/ros/wall_timer_options.h
+ros/spinner.h
+/opt/ros/noetic/include/ros/ros/spinner.h
+ros/init.h
+/opt/ros/noetic/include/ros/ros/init.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+boost/bind.hpp
+-
+xmlrpcpp/XmlRpcValue.h
+-
+
+/opt/ros/noetic/include/ros/param.h
+forwards.h
+/opt/ros/noetic/include/ros/forwards.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+xmlrpcpp/XmlRpcValue.h
+/opt/ros/noetic/include/ros/xmlrpcpp/XmlRpcValue.h
+vector
+-
+map
+-
+
+/opt/ros/noetic/include/ros/parameter_adapter.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/message_event.h
+/opt/ros/noetic/include/ros/ros/message_event.h
+ros/static_assert.h
+-
+boost/type_traits/add_const.hpp
+-
+boost/type_traits/remove_const.hpp
+-
+boost/type_traits/remove_reference.hpp
+-
+
+/opt/ros/noetic/include/ros/platform.h
+stdlib.h
+-
+string
+-
+
+/opt/ros/noetic/include/ros/publisher.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/common.h
+/opt/ros/noetic/include/ros/ros/common.h
+ros/message.h
+/opt/ros/noetic/include/ros/ros/message.h
+ros/serialization.h
+/opt/ros/noetic/include/ros/ros/serialization.h
+boost/bind.hpp
+-
+boost/thread/mutex.hpp
+-
+
+/opt/ros/noetic/include/ros/rate.h
+ros/time.h
+/opt/ros/noetic/include/ros/ros/time.h
+rostime_decl.h
+/opt/ros/noetic/include/ros/rostime_decl.h
+
+/opt/ros/noetic/include/ros/ros.h
+ros/time.h
+/opt/ros/noetic/include/ros/ros/time.h
+ros/rate.h
+/opt/ros/noetic/include/ros/ros/rate.h
+ros/console.h
+/opt/ros/noetic/include/ros/ros/console.h
+ros/assert.h
+/opt/ros/noetic/include/ros/ros/assert.h
+ros/common.h
+/opt/ros/noetic/include/ros/ros/common.h
+ros/types.h
+/opt/ros/noetic/include/ros/ros/types.h
+ros/node_handle.h
+/opt/ros/noetic/include/ros/ros/node_handle.h
+ros/publisher.h
+/opt/ros/noetic/include/ros/ros/publisher.h
+ros/single_subscriber_publisher.h
+/opt/ros/noetic/include/ros/ros/single_subscriber_publisher.h
+ros/service_server.h
+/opt/ros/noetic/include/ros/ros/service_server.h
+ros/subscriber.h
+/opt/ros/noetic/include/ros/ros/subscriber.h
+ros/service.h
+/opt/ros/noetic/include/ros/ros/service.h
+ros/init.h
+/opt/ros/noetic/include/ros/ros/init.h
+ros/master.h
+/opt/ros/noetic/include/ros/ros/master.h
+ros/this_node.h
+/opt/ros/noetic/include/ros/ros/this_node.h
+ros/param.h
+/opt/ros/noetic/include/ros/ros/param.h
+ros/topic.h
+/opt/ros/noetic/include/ros/ros/topic.h
+ros/names.h
+/opt/ros/noetic/include/ros/ros/names.h
+
+/opt/ros/noetic/include/ros/roscpp_serialization_macros.h
+ros/macros.h
+-
+
+/opt/ros/noetic/include/ros/rostime_decl.h
+ros/macros.h
+-
+
+/opt/ros/noetic/include/ros/serialization.h
+roscpp_serialization_macros.h
+/opt/ros/noetic/include/ros/roscpp_serialization_macros.h
+ros/types.h
+-
+ros/time.h
+-
+serialized_message.h
+/opt/ros/noetic/include/ros/serialized_message.h
+ros/message_traits.h
+/opt/ros/noetic/include/ros/ros/message_traits.h
+ros/builtin_message_traits.h
+/opt/ros/noetic/include/ros/ros/builtin_message_traits.h
+ros/exception.h
+/opt/ros/noetic/include/ros/ros/exception.h
+ros/datatypes.h
+/opt/ros/noetic/include/ros/ros/datatypes.h
+vector
+-
+map
+-
+boost/array.hpp
+-
+boost/call_traits.hpp
+-
+boost/utility/enable_if.hpp
+-
+boost/mpl/and.hpp
+-
+boost/mpl/or.hpp
+-
+boost/mpl/not.hpp
+-
+cstring
+-
+
+/opt/ros/noetic/include/ros/serialized_message.h
+roscpp_serialization_macros.h
+/opt/ros/noetic/include/ros/roscpp_serialization_macros.h
+boost/shared_array.hpp
+-
+boost/shared_ptr.hpp
+-
+
+/opt/ros/noetic/include/ros/service.h
+string
+-
+ros/common.h
+/opt/ros/noetic/include/ros/ros/common.h
+ros/message.h
+/opt/ros/noetic/include/ros/ros/message.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/node_handle.h
+/opt/ros/noetic/include/ros/ros/node_handle.h
+ros/service_traits.h
+/opt/ros/noetic/include/ros/ros/service_traits.h
+ros/names.h
+/opt/ros/noetic/include/ros/ros/names.h
+boost/shared_ptr.hpp
+-
+
+/opt/ros/noetic/include/ros/service_callback_helper.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/common.h
+/opt/ros/noetic/include/ros/ros/common.h
+ros/message.h
+/opt/ros/noetic/include/ros/ros/message.h
+ros/message_traits.h
+/opt/ros/noetic/include/ros/ros/message_traits.h
+ros/service_traits.h
+/opt/ros/noetic/include/ros/ros/service_traits.h
+ros/serialization.h
+/opt/ros/noetic/include/ros/ros/serialization.h
+boost/type_traits/is_base_of.hpp
+-
+boost/utility/enable_if.hpp
+-
+
+/opt/ros/noetic/include/ros/service_client.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/common.h
+/opt/ros/noetic/include/ros/ros/common.h
+ros/service_traits.h
+/opt/ros/noetic/include/ros/ros/service_traits.h
+ros/serialization.h
+/opt/ros/noetic/include/ros/ros/serialization.h
+
+/opt/ros/noetic/include/ros/service_client_options.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+ros/service_traits.h
+/opt/ros/noetic/include/ros/ros/service_traits.h
+
+/opt/ros/noetic/include/ros/service_server.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+
+/opt/ros/noetic/include/ros/service_traits.h
+boost/type_traits/remove_reference.hpp
+-
+boost/type_traits/remove_const.hpp
+-
+
+/opt/ros/noetic/include/ros/single_subscriber_publisher.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/serialization.h
+/opt/ros/noetic/include/ros/ros/serialization.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+boost/utility.hpp
+-
+
+/opt/ros/noetic/include/ros/spinner.h
+ros/types.h
+/opt/ros/noetic/include/ros/ros/types.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+boost/shared_ptr.hpp
+-
+
+/opt/ros/noetic/include/ros/static_assert.h
+boost/static_assert.hpp
+-
+
+/opt/ros/noetic/include/ros/steady_timer.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+forwards.h
+/opt/ros/noetic/include/ros/forwards.h
+steady_timer_options.h
+/opt/ros/noetic/include/ros/steady_timer_options.h
+
+/opt/ros/noetic/include/ros/steady_timer_options.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+
+/opt/ros/noetic/include/ros/subscribe_options.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+ros/transport_hints.h
+/opt/ros/noetic/include/ros/ros/transport_hints.h
+ros/message_traits.h
+/opt/ros/noetic/include/ros/ros/message_traits.h
+subscription_callback_helper.h
+/opt/ros/noetic/include/ros/subscription_callback_helper.h
+
+/opt/ros/noetic/include/ros/subscriber.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/subscription_callback_helper.h
+/opt/ros/noetic/include/ros/ros/subscription_callback_helper.h
+
+/opt/ros/noetic/include/ros/subscription_callback_helper.h
+typeinfo
+-
+common.h
+/opt/ros/noetic/include/ros/common.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/parameter_adapter.h
+/opt/ros/noetic/include/ros/ros/parameter_adapter.h
+ros/message_traits.h
+/opt/ros/noetic/include/ros/ros/message_traits.h
+ros/builtin_message_traits.h
+/opt/ros/noetic/include/ros/ros/builtin_message_traits.h
+ros/serialization.h
+/opt/ros/noetic/include/ros/ros/serialization.h
+ros/message_event.h
+/opt/ros/noetic/include/ros/ros/message_event.h
+ros/static_assert.h
+-
+boost/type_traits/add_const.hpp
+-
+boost/type_traits/remove_const.hpp
+-
+boost/type_traits/remove_reference.hpp
+-
+boost/type_traits/is_base_of.hpp
+-
+boost/utility/enable_if.hpp
+-
+boost/make_shared.hpp
+-
+
+/opt/ros/noetic/include/ros/this_node.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+forwards.h
+/opt/ros/noetic/include/ros/forwards.h
+
+/opt/ros/noetic/include/ros/time.h
+ros/platform.h
+-
+iostream
+-
+cmath
+-
+ros/exception.h
+-
+duration.h
+/opt/ros/noetic/include/ros/duration.h
+boost/math/special_functions/round.hpp
+-
+rostime_decl.h
+/opt/ros/noetic/include/ros/rostime_decl.h
+sys/timeb.h
+-
+sys/time.h
+-
+
+/opt/ros/noetic/include/ros/timer.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+forwards.h
+/opt/ros/noetic/include/ros/forwards.h
+timer_options.h
+/opt/ros/noetic/include/ros/timer_options.h
+
+/opt/ros/noetic/include/ros/timer_options.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+
+/opt/ros/noetic/include/ros/topic.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+node_handle.h
+/opt/ros/noetic/include/ros/node_handle.h
+boost/shared_ptr.hpp
+-
+
+/opt/ros/noetic/include/ros/transport_hints.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+boost/lexical_cast.hpp
+-
+
+/opt/ros/noetic/include/ros/types.h
+stdint.h
+-
+
+/opt/ros/noetic/include/ros/wall_timer.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+forwards.h
+/opt/ros/noetic/include/ros/forwards.h
+wall_timer_options.h
+/opt/ros/noetic/include/ros/wall_timer_options.h
+
+/opt/ros/noetic/include/ros/wall_timer_options.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+
+/opt/ros/noetic/include/rosconsole/macros_generated.h
+
+/opt/ros/noetic/include/std_msgs/Header.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+
+/opt/ros/noetic/include/std_srvs/Empty.h
+ros/service_traits.h
+-
+std_srvs/EmptyRequest.h
+-
+std_srvs/EmptyResponse.h
+-
+
+/opt/ros/noetic/include/std_srvs/EmptyRequest.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+
+/opt/ros/noetic/include/std_srvs/EmptyResponse.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+
+/opt/ros/noetic/include/tf/LinearMath/Matrix3x3.h
+Vector3.h
+/opt/ros/noetic/include/tf/LinearMath/Vector3.h
+Quaternion.h
+/opt/ros/noetic/include/tf/LinearMath/Quaternion.h
+ros/macros.h
+-
+
+/opt/ros/noetic/include/tf/LinearMath/MinMax.h
+
+/opt/ros/noetic/include/tf/LinearMath/QuadWord.h
+Scalar.h
+/opt/ros/noetic/include/tf/LinearMath/Scalar.h
+MinMax.h
+/opt/ros/noetic/include/tf/LinearMath/MinMax.h
+altivec.h
+-
+
+/opt/ros/noetic/include/tf/LinearMath/Quaternion.h
+Vector3.h
+/opt/ros/noetic/include/tf/LinearMath/Vector3.h
+QuadWord.h
+/opt/ros/noetic/include/tf/LinearMath/QuadWord.h
+ros/macros.h
+-
+
+/opt/ros/noetic/include/tf/LinearMath/Scalar.h
+math.h
+-
+stdlib.h
+-
+cstdlib
+-
+cfloat
+-
+float.h
+-
+ppcintrinsics.h
+-
+assert.h
+-
+assert.h
+-
+assert.h
+-
+assert.h
+-
+
+/opt/ros/noetic/include/tf/LinearMath/Transform.h
+Matrix3x3.h
+/opt/ros/noetic/include/tf/LinearMath/Matrix3x3.h
+
+/opt/ros/noetic/include/tf/LinearMath/Vector3.h
+Scalar.h
+/opt/ros/noetic/include/tf/LinearMath/Scalar.h
+MinMax.h
+/opt/ros/noetic/include/tf/LinearMath/MinMax.h
+
+/opt/ros/noetic/include/tf/transform_datatypes.h
+string
+-
+geometry_msgs/PointStamped.h
+/opt/ros/noetic/include/tf/geometry_msgs/PointStamped.h
+geometry_msgs/Vector3Stamped.h
+/opt/ros/noetic/include/tf/geometry_msgs/Vector3Stamped.h
+geometry_msgs/QuaternionStamped.h
+/opt/ros/noetic/include/tf/geometry_msgs/QuaternionStamped.h
+geometry_msgs/TransformStamped.h
+/opt/ros/noetic/include/tf/geometry_msgs/TransformStamped.h
+geometry_msgs/PoseStamped.h
+/opt/ros/noetic/include/tf/geometry_msgs/PoseStamped.h
+tf/LinearMath/Transform.h
+/opt/ros/noetic/include/tf/tf/LinearMath/Transform.h
+ros/time.h
+/opt/ros/noetic/include/tf/ros/time.h
+ros/console.h
+/opt/ros/noetic/include/tf/ros/console.h
+
+/opt/ros/noetic/include/xmlrpcpp/XmlRpcDecl.h
+ros/macros.h
+-
+
+/opt/ros/noetic/include/xmlrpcpp/XmlRpcValue.h
+xmlrpcpp/XmlRpcDecl.h
+/opt/ros/noetic/include/xmlrpcpp/xmlrpcpp/XmlRpcDecl.h
+map
+-
+string
+-
+vector
+-
+time.h
+-
+
+/usr/include/eigen3/Eigen/Cholesky
+Core
+/usr/include/eigen3/Eigen/Core
+Jacobi
+/usr/include/eigen3/Eigen/Jacobi
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+src/Cholesky/LLT.h
+/usr/include/eigen3/Eigen/src/Cholesky/LLT.h
+src/Cholesky/LDLT.h
+/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h
+mkl_lapacke.h
+/usr/include/eigen3/Eigen/mkl_lapacke.h
+src/misc/lapacke.h
+/usr/include/eigen3/Eigen/src/misc/lapacke.h
+src/Cholesky/LLT_LAPACKE.h
+/usr/include/eigen3/Eigen/src/Cholesky/LLT_LAPACKE.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/Core
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+cuda_runtime.h
+-
+new
+-
+src/Core/util/Macros.h
+/usr/include/eigen3/Eigen/src/Core/util/Macros.h
+complex
+-
+src/Core/util/MKL_support.h
+/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h
+malloc.h
+-
+immintrin.h
+-
+mmintrin.h
+-
+emmintrin.h
+-
+xmmintrin.h
+-
+pmmintrin.h
+-
+tmmintrin.h
+-
+smmintrin.h
+-
+nmmintrin.h
+-
+immintrin.h
+-
+altivec.h
+-
+altivec.h
+-
+arm_neon.h
+-
+vecintrin.h
+-
+vector_types.h
+-
+host_defines.h
+-
+cuda_fp16.h
+-
+omp.h
+-
+cerrno
+-
+cstddef
+-
+cstdlib
+-
+cmath
+-
+cassert
+-
+functional
+-
+iosfwd
+-
+cstring
+-
+string
+-
+limits
+-
+climits
+-
+algorithm
+-
+type_traits
+-
+iostream
+-
+intrin.h
+-
+src/Core/util/Constants.h
+/usr/include/eigen3/Eigen/src/Core/util/Constants.h
+src/Core/util/Meta.h
+/usr/include/eigen3/Eigen/src/Core/util/Meta.h
+src/Core/util/ForwardDeclarations.h
+/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h
+src/Core/util/StaticAssert.h
+/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h
+src/Core/util/XprHelper.h
+/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h
+src/Core/util/Memory.h
+/usr/include/eigen3/Eigen/src/Core/util/Memory.h
+src/Core/NumTraits.h
+/usr/include/eigen3/Eigen/src/Core/NumTraits.h
+src/Core/MathFunctions.h
+/usr/include/eigen3/Eigen/src/Core/MathFunctions.h
+src/Core/GenericPacketMath.h
+/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h
+src/Core/MathFunctionsImpl.h
+/usr/include/eigen3/Eigen/src/Core/MathFunctionsImpl.h
+src/Core/arch/Default/ConjHelper.h
+/usr/include/eigen3/Eigen/src/Core/arch/Default/ConjHelper.h
+src/Core/arch/SSE/PacketMath.h
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h
+src/Core/arch/AVX/PacketMath.h
+/usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h
+src/Core/arch/AVX512/PacketMath.h
+/usr/include/eigen3/Eigen/src/Core/arch/AVX512/PacketMath.h
+src/Core/arch/AVX512/MathFunctions.h
+/usr/include/eigen3/Eigen/src/Core/arch/AVX512/MathFunctions.h
+src/Core/arch/SSE/PacketMath.h
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h
+src/Core/arch/SSE/Complex.h
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h
+src/Core/arch/SSE/MathFunctions.h
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h
+src/Core/arch/AVX/PacketMath.h
+/usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h
+src/Core/arch/AVX/MathFunctions.h
+/usr/include/eigen3/Eigen/src/Core/arch/AVX/MathFunctions.h
+src/Core/arch/AVX/Complex.h
+/usr/include/eigen3/Eigen/src/Core/arch/AVX/Complex.h
+src/Core/arch/AVX/TypeCasting.h
+/usr/include/eigen3/Eigen/src/Core/arch/AVX/TypeCasting.h
+src/Core/arch/SSE/TypeCasting.h
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/TypeCasting.h
+src/Core/arch/SSE/PacketMath.h
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h
+src/Core/arch/SSE/MathFunctions.h
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h
+src/Core/arch/SSE/Complex.h
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h
+src/Core/arch/SSE/TypeCasting.h
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/TypeCasting.h
+src/Core/arch/AltiVec/PacketMath.h
+/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h
+src/Core/arch/AltiVec/MathFunctions.h
+/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/MathFunctions.h
+src/Core/arch/AltiVec/Complex.h
+/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h
+src/Core/arch/NEON/PacketMath.h
+/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h
+src/Core/arch/NEON/MathFunctions.h
+/usr/include/eigen3/Eigen/src/Core/arch/NEON/MathFunctions.h
+src/Core/arch/NEON/Complex.h
+/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h
+src/Core/arch/ZVector/PacketMath.h
+/usr/include/eigen3/Eigen/src/Core/arch/ZVector/PacketMath.h
+src/Core/arch/ZVector/MathFunctions.h
+/usr/include/eigen3/Eigen/src/Core/arch/ZVector/MathFunctions.h
+src/Core/arch/ZVector/Complex.h
+/usr/include/eigen3/Eigen/src/Core/arch/ZVector/Complex.h
+src/Core/arch/CUDA/Half.h
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/Half.h
+src/Core/arch/CUDA/PacketMathHalf.h
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMathHalf.h
+src/Core/arch/CUDA/TypeCasting.h
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/TypeCasting.h
+src/Core/arch/CUDA/PacketMath.h
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMath.h
+src/Core/arch/CUDA/MathFunctions.h
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/MathFunctions.h
+src/Core/arch/Default/Settings.h
+/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h
+src/Core/functors/TernaryFunctors.h
+/usr/include/eigen3/Eigen/src/Core/functors/TernaryFunctors.h
+src/Core/functors/BinaryFunctors.h
+/usr/include/eigen3/Eigen/src/Core/functors/BinaryFunctors.h
+src/Core/functors/UnaryFunctors.h
+/usr/include/eigen3/Eigen/src/Core/functors/UnaryFunctors.h
+src/Core/functors/NullaryFunctors.h
+/usr/include/eigen3/Eigen/src/Core/functors/NullaryFunctors.h
+src/Core/functors/StlFunctors.h
+/usr/include/eigen3/Eigen/src/Core/functors/StlFunctors.h
+src/Core/functors/AssignmentFunctors.h
+/usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h
+src/Core/arch/CUDA/Complex.h
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/Complex.h
+src/Core/IO.h
+/usr/include/eigen3/Eigen/src/Core/IO.h
+src/Core/DenseCoeffsBase.h
+/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h
+src/Core/DenseBase.h
+/usr/include/eigen3/Eigen/src/Core/DenseBase.h
+src/Core/MatrixBase.h
+/usr/include/eigen3/Eigen/src/Core/MatrixBase.h
+src/Core/EigenBase.h
+/usr/include/eigen3/Eigen/src/Core/EigenBase.h
+src/Core/Product.h
+/usr/include/eigen3/Eigen/src/Core/Product.h
+src/Core/CoreEvaluators.h
+/usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h
+src/Core/AssignEvaluator.h
+/usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h
+src/Core/Assign.h
+/usr/include/eigen3/Eigen/src/Core/Assign.h
+src/Core/ArrayBase.h
+/usr/include/eigen3/Eigen/src/Core/ArrayBase.h
+src/Core/util/BlasUtil.h
+/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h
+src/Core/DenseStorage.h
+/usr/include/eigen3/Eigen/src/Core/DenseStorage.h
+src/Core/NestByValue.h
+/usr/include/eigen3/Eigen/src/Core/NestByValue.h
+src/Core/ReturnByValue.h
+/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h
+src/Core/NoAlias.h
+/usr/include/eigen3/Eigen/src/Core/NoAlias.h
+src/Core/PlainObjectBase.h
+/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h
+src/Core/Matrix.h
+/usr/include/eigen3/Eigen/src/Core/Matrix.h
+src/Core/Array.h
+/usr/include/eigen3/Eigen/src/Core/Array.h
+src/Core/CwiseTernaryOp.h
+/usr/include/eigen3/Eigen/src/Core/CwiseTernaryOp.h
+src/Core/CwiseBinaryOp.h
+/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h
+src/Core/CwiseUnaryOp.h
+/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h
+src/Core/CwiseNullaryOp.h
+/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h
+src/Core/CwiseUnaryView.h
+/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h
+src/Core/SelfCwiseBinaryOp.h
+/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h
+src/Core/Dot.h
+/usr/include/eigen3/Eigen/src/Core/Dot.h
+src/Core/StableNorm.h
+/usr/include/eigen3/Eigen/src/Core/StableNorm.h
+src/Core/Stride.h
+/usr/include/eigen3/Eigen/src/Core/Stride.h
+src/Core/MapBase.h
+/usr/include/eigen3/Eigen/src/Core/MapBase.h
+src/Core/Map.h
+/usr/include/eigen3/Eigen/src/Core/Map.h
+src/Core/Ref.h
+/usr/include/eigen3/Eigen/src/Core/Ref.h
+src/Core/Block.h
+/usr/include/eigen3/Eigen/src/Core/Block.h
+src/Core/VectorBlock.h
+/usr/include/eigen3/Eigen/src/Core/VectorBlock.h
+src/Core/Transpose.h
+/usr/include/eigen3/Eigen/src/Core/Transpose.h
+src/Core/DiagonalMatrix.h
+/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h
+src/Core/Diagonal.h
+/usr/include/eigen3/Eigen/src/Core/Diagonal.h
+src/Core/DiagonalProduct.h
+/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h
+src/Core/Redux.h
+/usr/include/eigen3/Eigen/src/Core/Redux.h
+src/Core/Visitor.h
+/usr/include/eigen3/Eigen/src/Core/Visitor.h
+src/Core/Fuzzy.h
+/usr/include/eigen3/Eigen/src/Core/Fuzzy.h
+src/Core/Swap.h
+/usr/include/eigen3/Eigen/src/Core/Swap.h
+src/Core/CommaInitializer.h
+/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h
+src/Core/GeneralProduct.h
+/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h
+src/Core/Solve.h
+/usr/include/eigen3/Eigen/src/Core/Solve.h
+src/Core/Inverse.h
+/usr/include/eigen3/Eigen/src/Core/Inverse.h
+src/Core/SolverBase.h
+/usr/include/eigen3/Eigen/src/Core/SolverBase.h
+src/Core/PermutationMatrix.h
+/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h
+src/Core/Transpositions.h
+/usr/include/eigen3/Eigen/src/Core/Transpositions.h
+src/Core/TriangularMatrix.h
+/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h
+src/Core/SelfAdjointView.h
+/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h
+src/Core/products/GeneralBlockPanelKernel.h
+/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h
+src/Core/products/Parallelizer.h
+/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h
+src/Core/ProductEvaluators.h
+/usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h
+src/Core/products/GeneralMatrixVector.h
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h
+src/Core/products/GeneralMatrixMatrix.h
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h
+src/Core/SolveTriangular.h
+/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h
+src/Core/products/GeneralMatrixMatrixTriangular.h
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h
+src/Core/products/SelfadjointMatrixVector.h
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h
+src/Core/products/SelfadjointMatrixMatrix.h
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h
+src/Core/products/SelfadjointProduct.h
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h
+src/Core/products/SelfadjointRank2Update.h
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h
+src/Core/products/TriangularMatrixVector.h
+/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h
+src/Core/products/TriangularMatrixMatrix.h
+/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h
+src/Core/products/TriangularSolverMatrix.h
+/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h
+src/Core/products/TriangularSolverVector.h
+/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h
+src/Core/BandMatrix.h
+/usr/include/eigen3/Eigen/src/Core/BandMatrix.h
+src/Core/CoreIterators.h
+/usr/include/eigen3/Eigen/src/Core/CoreIterators.h
+src/Core/ConditionEstimator.h
+/usr/include/eigen3/Eigen/src/Core/ConditionEstimator.h
+src/Core/BooleanRedux.h
+/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h
+src/Core/Select.h
+/usr/include/eigen3/Eigen/src/Core/Select.h
+src/Core/VectorwiseOp.h
+/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h
+src/Core/Random.h
+/usr/include/eigen3/Eigen/src/Core/Random.h
+src/Core/Replicate.h
+/usr/include/eigen3/Eigen/src/Core/Replicate.h
+src/Core/Reverse.h
+/usr/include/eigen3/Eigen/src/Core/Reverse.h
+src/Core/ArrayWrapper.h
+/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h
+src/Core/products/GeneralMatrixMatrix_BLAS.h
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_BLAS.h
+src/Core/products/GeneralMatrixVector_BLAS.h
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_BLAS.h
+src/Core/products/GeneralMatrixMatrixTriangular_BLAS.h
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_BLAS.h
+src/Core/products/SelfadjointMatrixMatrix_BLAS.h
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_BLAS.h
+src/Core/products/SelfadjointMatrixVector_BLAS.h
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_BLAS.h
+src/Core/products/TriangularMatrixMatrix_BLAS.h
+/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_BLAS.h
+src/Core/products/TriangularMatrixVector_BLAS.h
+/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_BLAS.h
+src/Core/products/TriangularSolverMatrix_BLAS.h
+/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_BLAS.h
+src/Core/Assign_MKL.h
+/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h
+src/Core/GlobalFunctions.h
+/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/Dense
+Core
+/usr/include/eigen3/Eigen/Core
+LU
+/usr/include/eigen3/Eigen/LU
+Cholesky
+/usr/include/eigen3/Eigen/Cholesky
+QR
+/usr/include/eigen3/Eigen/QR
+SVD
+/usr/include/eigen3/Eigen/SVD
+Geometry
+/usr/include/eigen3/Eigen/Geometry
+Eigenvalues
+/usr/include/eigen3/Eigen/Eigenvalues
+
+/usr/include/eigen3/Eigen/Eigen
+Dense
+/usr/include/eigen3/Eigen/Dense
+Sparse
+/usr/include/eigen3/Eigen/Sparse
+
+/usr/include/eigen3/Eigen/Eigenvalues
+Core
+/usr/include/eigen3/Eigen/Core
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+Cholesky
+/usr/include/eigen3/Eigen/Cholesky
+Jacobi
+/usr/include/eigen3/Eigen/Jacobi
+Householder
+/usr/include/eigen3/Eigen/Householder
+LU
+/usr/include/eigen3/Eigen/LU
+Geometry
+/usr/include/eigen3/Eigen/Geometry
+src/misc/RealSvd2x2.h
+/usr/include/eigen3/Eigen/src/misc/RealSvd2x2.h
+src/Eigenvalues/Tridiagonalization.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h
+src/Eigenvalues/RealSchur.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h
+src/Eigenvalues/EigenSolver.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h
+src/Eigenvalues/SelfAdjointEigenSolver.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h
+src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h
+src/Eigenvalues/HessenbergDecomposition.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h
+src/Eigenvalues/ComplexSchur.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h
+src/Eigenvalues/ComplexEigenSolver.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h
+src/Eigenvalues/RealQZ.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h
+src/Eigenvalues/GeneralizedEigenSolver.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h
+src/Eigenvalues/MatrixBaseEigenvalues.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h
+mkl_lapacke.h
+/usr/include/eigen3/Eigen/mkl_lapacke.h
+src/misc/lapacke.h
+/usr/include/eigen3/Eigen/src/misc/lapacke.h
+src/Eigenvalues/RealSchur_LAPACKE.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_LAPACKE.h
+src/Eigenvalues/ComplexSchur_LAPACKE.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_LAPACKE.h
+src/Eigenvalues/SelfAdjointEigenSolver_LAPACKE.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_LAPACKE.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/Geometry
+Core
+/usr/include/eigen3/Eigen/Core
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+SVD
+/usr/include/eigen3/Eigen/SVD
+LU
+/usr/include/eigen3/Eigen/LU
+limits
+-
+src/Geometry/OrthoMethods.h
+/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h
+src/Geometry/EulerAngles.h
+/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h
+src/Geometry/Homogeneous.h
+/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h
+src/Geometry/RotationBase.h
+/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h
+src/Geometry/Rotation2D.h
+/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h
+src/Geometry/Quaternion.h
+/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h
+src/Geometry/AngleAxis.h
+/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h
+src/Geometry/Transform.h
+/usr/include/eigen3/Eigen/src/Geometry/Transform.h
+src/Geometry/Translation.h
+/usr/include/eigen3/Eigen/src/Geometry/Translation.h
+src/Geometry/Scaling.h
+/usr/include/eigen3/Eigen/src/Geometry/Scaling.h
+src/Geometry/Hyperplane.h
+/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h
+src/Geometry/ParametrizedLine.h
+/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h
+src/Geometry/AlignedBox.h
+/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h
+src/Geometry/Umeyama.h
+/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h
+src/Geometry/arch/Geometry_SSE.h
+/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/Householder
+Core
+/usr/include/eigen3/Eigen/Core
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+src/Householder/Householder.h
+/usr/include/eigen3/Eigen/src/Householder/Householder.h
+src/Householder/HouseholderSequence.h
+/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h
+src/Householder/BlockHouseholder.h
+/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/IterativeLinearSolvers
+SparseCore
+/usr/include/eigen3/Eigen/SparseCore
+OrderingMethods
+/usr/include/eigen3/Eigen/OrderingMethods
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+Eigen/IterativeLinearSolvers
+-
+src/IterativeLinearSolvers/SolveWithGuess.h
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/SolveWithGuess.h
+src/IterativeLinearSolvers/IterativeSolverBase.h
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h
+src/IterativeLinearSolvers/BasicPreconditioners.h
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h
+src/IterativeLinearSolvers/ConjugateGradient.h
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h
+src/IterativeLinearSolvers/LeastSquareConjugateGradient.h
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/LeastSquareConjugateGradient.h
+src/IterativeLinearSolvers/BiCGSTAB.h
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h
+src/IterativeLinearSolvers/IncompleteLUT.h
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IncompleteLUT.h
+src/IterativeLinearSolvers/IncompleteCholesky.h
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IncompleteCholesky.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/Jacobi
+Core
+/usr/include/eigen3/Eigen/Core
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+src/Jacobi/Jacobi.h
+/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/LU
+Core
+/usr/include/eigen3/Eigen/Core
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+src/misc/Kernel.h
+/usr/include/eigen3/Eigen/src/misc/Kernel.h
+src/misc/Image.h
+/usr/include/eigen3/Eigen/src/misc/Image.h
+src/LU/FullPivLU.h
+/usr/include/eigen3/Eigen/src/LU/FullPivLU.h
+src/LU/PartialPivLU.h
+/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h
+mkl_lapacke.h
+/usr/include/eigen3/Eigen/mkl_lapacke.h
+src/misc/lapacke.h
+/usr/include/eigen3/Eigen/src/misc/lapacke.h
+src/LU/PartialPivLU_LAPACKE.h
+/usr/include/eigen3/Eigen/src/LU/PartialPivLU_LAPACKE.h
+src/LU/Determinant.h
+/usr/include/eigen3/Eigen/src/LU/Determinant.h
+src/LU/InverseImpl.h
+/usr/include/eigen3/Eigen/src/LU/InverseImpl.h
+src/LU/arch/Inverse_SSE.h
+/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/OrderingMethods
+SparseCore
+/usr/include/eigen3/Eigen/SparseCore
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+src/OrderingMethods/Amd.h
+/usr/include/eigen3/Eigen/src/OrderingMethods/Amd.h
+src/OrderingMethods/Ordering.h
+/usr/include/eigen3/Eigen/src/OrderingMethods/Ordering.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/QR
+Core
+/usr/include/eigen3/Eigen/Core
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+Cholesky
+/usr/include/eigen3/Eigen/Cholesky
+Jacobi
+/usr/include/eigen3/Eigen/Jacobi
+Householder
+/usr/include/eigen3/Eigen/Householder
+src/QR/HouseholderQR.h
+/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h
+src/QR/FullPivHouseholderQR.h
+/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h
+src/QR/ColPivHouseholderQR.h
+/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h
+src/QR/CompleteOrthogonalDecomposition.h
+/usr/include/eigen3/Eigen/src/QR/CompleteOrthogonalDecomposition.h
+mkl_lapacke.h
+/usr/include/eigen3/Eigen/mkl_lapacke.h
+src/misc/lapacke.h
+/usr/include/eigen3/Eigen/src/misc/lapacke.h
+src/QR/HouseholderQR_LAPACKE.h
+/usr/include/eigen3/Eigen/src/QR/HouseholderQR_LAPACKE.h
+src/QR/ColPivHouseholderQR_LAPACKE.h
+/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_LAPACKE.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/SVD
+QR
+/usr/include/eigen3/Eigen/QR
+Householder
+/usr/include/eigen3/Eigen/Householder
+Jacobi
+/usr/include/eigen3/Eigen/Jacobi
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+src/misc/RealSvd2x2.h
+/usr/include/eigen3/Eigen/src/misc/RealSvd2x2.h
+src/SVD/UpperBidiagonalization.h
+/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h
+src/SVD/SVDBase.h
+/usr/include/eigen3/Eigen/src/SVD/SVDBase.h
+src/SVD/JacobiSVD.h
+/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h
+src/SVD/BDCSVD.h
+/usr/include/eigen3/Eigen/src/SVD/BDCSVD.h
+mkl_lapacke.h
+/usr/include/eigen3/Eigen/mkl_lapacke.h
+src/misc/lapacke.h
+/usr/include/eigen3/Eigen/src/misc/lapacke.h
+src/SVD/JacobiSVD_LAPACKE.h
+/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_LAPACKE.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/Sparse
+Eigen/Sparse
+-
+SparseCore
+/usr/include/eigen3/Eigen/SparseCore
+OrderingMethods
+/usr/include/eigen3/Eigen/OrderingMethods
+SparseCholesky
+/usr/include/eigen3/Eigen/SparseCholesky
+SparseLU
+/usr/include/eigen3/Eigen/SparseLU
+SparseQR
+/usr/include/eigen3/Eigen/SparseQR
+IterativeLinearSolvers
+/usr/include/eigen3/Eigen/IterativeLinearSolvers
+
+/usr/include/eigen3/Eigen/SparseCholesky
+SparseCore
+/usr/include/eigen3/Eigen/SparseCore
+OrderingMethods
+/usr/include/eigen3/Eigen/OrderingMethods
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+src/SparseCholesky/SimplicialCholesky.h
+/usr/include/eigen3/Eigen/src/SparseCholesky/SimplicialCholesky.h
+src/SparseCholesky/SimplicialCholesky_impl.h
+/usr/include/eigen3/Eigen/src/SparseCholesky/SimplicialCholesky_impl.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/SparseCore
+Core
+/usr/include/eigen3/Eigen/Core
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+vector
+-
+map
+-
+cstdlib
+-
+cstring
+-
+algorithm
+-
+src/SparseCore/SparseUtil.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseUtil.h
+src/SparseCore/SparseMatrixBase.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseMatrixBase.h
+src/SparseCore/SparseAssign.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseAssign.h
+src/SparseCore/CompressedStorage.h
+/usr/include/eigen3/Eigen/src/SparseCore/CompressedStorage.h
+src/SparseCore/AmbiVector.h
+/usr/include/eigen3/Eigen/src/SparseCore/AmbiVector.h
+src/SparseCore/SparseCompressedBase.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseCompressedBase.h
+src/SparseCore/SparseMatrix.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseMatrix.h
+src/SparseCore/SparseMap.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseMap.h
+src/SparseCore/MappedSparseMatrix.h
+/usr/include/eigen3/Eigen/src/SparseCore/MappedSparseMatrix.h
+src/SparseCore/SparseVector.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseVector.h
+src/SparseCore/SparseRef.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseRef.h
+src/SparseCore/SparseCwiseUnaryOp.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseCwiseUnaryOp.h
+src/SparseCore/SparseCwiseBinaryOp.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseCwiseBinaryOp.h
+src/SparseCore/SparseTranspose.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseTranspose.h
+src/SparseCore/SparseBlock.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseBlock.h
+src/SparseCore/SparseDot.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseDot.h
+src/SparseCore/SparseRedux.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseRedux.h
+src/SparseCore/SparseView.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseView.h
+src/SparseCore/SparseDiagonalProduct.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseDiagonalProduct.h
+src/SparseCore/ConservativeSparseSparseProduct.h
+/usr/include/eigen3/Eigen/src/SparseCore/ConservativeSparseSparseProduct.h
+src/SparseCore/SparseSparseProductWithPruning.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseSparseProductWithPruning.h
+src/SparseCore/SparseProduct.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseProduct.h
+src/SparseCore/SparseDenseProduct.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseDenseProduct.h
+src/SparseCore/SparseSelfAdjointView.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseSelfAdjointView.h
+src/SparseCore/SparseTriangularView.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseTriangularView.h
+src/SparseCore/TriangularSolver.h
+/usr/include/eigen3/Eigen/src/SparseCore/TriangularSolver.h
+src/SparseCore/SparsePermutation.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparsePermutation.h
+src/SparseCore/SparseFuzzy.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseFuzzy.h
+src/SparseCore/SparseSolverBase.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseSolverBase.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/SparseLU
+SparseCore
+/usr/include/eigen3/Eigen/SparseCore
+OrderingMethods
+/usr/include/eigen3/Eigen/OrderingMethods
+src/SparseLU/SparseLU_gemm_kernel.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_gemm_kernel.h
+src/SparseLU/SparseLU_Structs.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Structs.h
+src/SparseLU/SparseLU_SupernodalMatrix.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h
+src/SparseLU/SparseLUImpl.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLUImpl.h
+src/SparseCore/SparseColEtree.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseColEtree.h
+src/SparseLU/SparseLU_Memory.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Memory.h
+src/SparseLU/SparseLU_heap_relax_snode.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_heap_relax_snode.h
+src/SparseLU/SparseLU_relax_snode.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_relax_snode.h
+src/SparseLU/SparseLU_pivotL.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_pivotL.h
+src/SparseLU/SparseLU_panel_dfs.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_panel_dfs.h
+src/SparseLU/SparseLU_kernel_bmod.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_kernel_bmod.h
+src/SparseLU/SparseLU_panel_bmod.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_panel_bmod.h
+src/SparseLU/SparseLU_column_dfs.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_column_dfs.h
+src/SparseLU/SparseLU_column_bmod.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_column_bmod.h
+src/SparseLU/SparseLU_copy_to_ucol.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_copy_to_ucol.h
+src/SparseLU/SparseLU_pruneL.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_pruneL.h
+src/SparseLU/SparseLU_Utils.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Utils.h
+src/SparseLU/SparseLU.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU.h
+
+/usr/include/eigen3/Eigen/SparseQR
+SparseCore
+/usr/include/eigen3/Eigen/SparseCore
+OrderingMethods
+/usr/include/eigen3/Eigen/OrderingMethods
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+OrderingMethods
+/usr/include/eigen3/Eigen/OrderingMethods
+src/SparseCore/SparseColEtree.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseColEtree.h
+src/SparseQR/SparseQR.h
+/usr/include/eigen3/Eigen/src/SparseQR/SparseQR.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h
+
+/usr/include/eigen3/Eigen/src/Cholesky/LLT.h
+
+/usr/include/eigen3/Eigen/src/Cholesky/LLT_LAPACKE.h
+
+/usr/include/eigen3/Eigen/src/Core/Array.h
+
+/usr/include/eigen3/Eigen/src/Core/ArrayBase.h
+../plugins/CommonCwiseUnaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h
+../plugins/MatrixCwiseUnaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h
+../plugins/ArrayCwiseUnaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h
+../plugins/CommonCwiseBinaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h
+../plugins/MatrixCwiseBinaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h
+../plugins/ArrayCwiseBinaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h
+
+/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h
+
+/usr/include/eigen3/Eigen/src/Core/Assign.h
+
+/usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h
+
+/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h
+
+/usr/include/eigen3/Eigen/src/Core/BandMatrix.h
+
+/usr/include/eigen3/Eigen/src/Core/Block.h
+
+/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h
+
+/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h
+
+/usr/include/eigen3/Eigen/src/Core/ConditionEstimator.h
+
+/usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h
+
+/usr/include/eigen3/Eigen/src/Core/CoreIterators.h
+
+/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h
+
+/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h
+
+/usr/include/eigen3/Eigen/src/Core/CwiseTernaryOp.h
+
+/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h
+
+/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h
+
+/usr/include/eigen3/Eigen/src/Core/DenseBase.h
+../plugins/BlockMethods.h
+/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h
+
+/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h
+
+/usr/include/eigen3/Eigen/src/Core/DenseStorage.h
+
+/usr/include/eigen3/Eigen/src/Core/Diagonal.h
+
+/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h
+
+/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h
+
+/usr/include/eigen3/Eigen/src/Core/Dot.h
+
+/usr/include/eigen3/Eigen/src/Core/EigenBase.h
+
+/usr/include/eigen3/Eigen/src/Core/Fuzzy.h
+
+/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h
+
+/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h
+
+/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h
+
+/usr/include/eigen3/Eigen/src/Core/IO.h
+
+/usr/include/eigen3/Eigen/src/Core/Inverse.h
+
+/usr/include/eigen3/Eigen/src/Core/Map.h
+
+/usr/include/eigen3/Eigen/src/Core/MapBase.h
+
+/usr/include/eigen3/Eigen/src/Core/MathFunctions.h
+
+/usr/include/eigen3/Eigen/src/Core/MathFunctionsImpl.h
+
+/usr/include/eigen3/Eigen/src/Core/Matrix.h
+
+/usr/include/eigen3/Eigen/src/Core/MatrixBase.h
+../plugins/CommonCwiseUnaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h
+../plugins/CommonCwiseBinaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h
+../plugins/MatrixCwiseUnaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h
+../plugins/MatrixCwiseBinaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h
+
+/usr/include/eigen3/Eigen/src/Core/NestByValue.h
+
+/usr/include/eigen3/Eigen/src/Core/NoAlias.h
+
+/usr/include/eigen3/Eigen/src/Core/NumTraits.h
+
+/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h
+
+/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h
+
+/usr/include/eigen3/Eigen/src/Core/Product.h
+
+/usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h
+
+/usr/include/eigen3/Eigen/src/Core/Random.h
+
+/usr/include/eigen3/Eigen/src/Core/Redux.h
+
+/usr/include/eigen3/Eigen/src/Core/Ref.h
+
+/usr/include/eigen3/Eigen/src/Core/Replicate.h
+
+/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h
+
+/usr/include/eigen3/Eigen/src/Core/Reverse.h
+
+/usr/include/eigen3/Eigen/src/Core/Select.h
+
+/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h
+
+/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h
+
+/usr/include/eigen3/Eigen/src/Core/Solve.h
+
+/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h
+
+/usr/include/eigen3/Eigen/src/Core/SolverBase.h
+
+/usr/include/eigen3/Eigen/src/Core/StableNorm.h
+
+/usr/include/eigen3/Eigen/src/Core/Stride.h
+
+/usr/include/eigen3/Eigen/src/Core/Swap.h
+
+/usr/include/eigen3/Eigen/src/Core/Transpose.h
+
+/usr/include/eigen3/Eigen/src/Core/Transpositions.h
+
+/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h
+
+/usr/include/eigen3/Eigen/src/Core/VectorBlock.h
+
+/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h
+
+/usr/include/eigen3/Eigen/src/Core/Visitor.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/AVX/Complex.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/AVX/MathFunctions.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/AVX/TypeCasting.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/AVX512/MathFunctions.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/AVX512/PacketMath.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/MathFunctions.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/Complex.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/Half.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/MathFunctions.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMath.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMathHalf.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/TypeCasting.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/Default/ConjHelper.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/NEON/MathFunctions.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/TypeCasting.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/ZVector/Complex.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/ZVector/MathFunctions.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/ZVector/PacketMath.h
+stdint.h
+-
+
+/usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h
+
+/usr/include/eigen3/Eigen/src/Core/functors/BinaryFunctors.h
+
+/usr/include/eigen3/Eigen/src/Core/functors/NullaryFunctors.h
+
+/usr/include/eigen3/Eigen/src/Core/functors/StlFunctors.h
+
+/usr/include/eigen3/Eigen/src/Core/functors/TernaryFunctors.h
+
+/usr/include/eigen3/Eigen/src/Core/functors/UnaryFunctors.h
+
+/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h
+
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h
+
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h
+
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_BLAS.h
+
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_BLAS.h
+
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h
+
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_BLAS.h
+
+/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h
+
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h
+
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_BLAS.h
+
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h
+
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_BLAS.h
+
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h
+
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h
+
+/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h
+
+/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_BLAS.h
+
+/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h
+
+/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_BLAS.h
+
+/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h
+
+/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_BLAS.h
+
+/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h
+
+/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h
+
+/usr/include/eigen3/Eigen/src/Core/util/Constants.h
+
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h
+
+/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h
+mkl.h
+-
+../../misc/blas.h
+/usr/include/eigen3/Eigen/src/misc/blas.h
+
+/usr/include/eigen3/Eigen/src/Core/util/Macros.h
+cstdlib
+-
+iostream
+-
+
+/usr/include/eigen3/Eigen/src/Core/util/Memory.h
+
+/usr/include/eigen3/Eigen/src/Core/util/Meta.h
+cfloat
+-
+math_constants.h
+-
+cstdint
+-
+
+/usr/include/eigen3/Eigen/src/Core/util/NonMPL2.h
+
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h
+
+/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h
+./ComplexSchur.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h
+./HessenbergDecomposition.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_LAPACKE.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h
+./RealSchur.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h
+./RealQZ.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h
+./Tridiagonalization.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h
+./HessenbergDecomposition.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_LAPACKE.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h
+./Tridiagonalization.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_LAPACKE.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h
+
+/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h
+
+/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h
+
+/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h
+
+/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h
+
+/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h
+
+/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h
+
+/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h
+
+/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h
+
+/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h
+
+/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h
+
+/usr/include/eigen3/Eigen/src/Geometry/Scaling.h
+
+/usr/include/eigen3/Eigen/src/Geometry/Transform.h
+
+/usr/include/eigen3/Eigen/src/Geometry/Translation.h
+
+/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h
+
+/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h
+
+/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h
+
+/usr/include/eigen3/Eigen/src/Householder/Householder.h
+
+/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h
+
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h
+
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h
+
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h
+
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IncompleteCholesky.h
+vector
+-
+list
+-
+
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IncompleteLUT.h
+
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h
+
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/LeastSquareConjugateGradient.h
+
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/SolveWithGuess.h
+
+/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h
+
+/usr/include/eigen3/Eigen/src/LU/Determinant.h
+
+/usr/include/eigen3/Eigen/src/LU/FullPivLU.h
+
+/usr/include/eigen3/Eigen/src/LU/InverseImpl.h
+
+/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h
+
+/usr/include/eigen3/Eigen/src/LU/PartialPivLU_LAPACKE.h
+
+/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h
+
+/usr/include/eigen3/Eigen/src/OrderingMethods/Amd.h
+../Core/util/NonMPL2.h
+/usr/include/eigen3/Eigen/src/Core/util/NonMPL2.h
+
+/usr/include/eigen3/Eigen/src/OrderingMethods/Eigen_Colamd.h
+
+/usr/include/eigen3/Eigen/src/OrderingMethods/Ordering.h
+Eigen_Colamd.h
+/usr/include/eigen3/Eigen/src/OrderingMethods/Eigen_Colamd.h
+
+/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h
+
+/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_LAPACKE.h
+
+/usr/include/eigen3/Eigen/src/QR/CompleteOrthogonalDecomposition.h
+
+/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h
+
+/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h
+
+/usr/include/eigen3/Eigen/src/QR/HouseholderQR_LAPACKE.h
+
+/usr/include/eigen3/Eigen/src/SVD/BDCSVD.h
+
+/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h
+
+/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_LAPACKE.h
+
+/usr/include/eigen3/Eigen/src/SVD/SVDBase.h
+
+/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h
+
+/usr/include/eigen3/Eigen/src/SparseCholesky/SimplicialCholesky.h
+
+/usr/include/eigen3/Eigen/src/SparseCholesky/SimplicialCholesky_impl.h
+../Core/util/NonMPL2.h
+/usr/include/eigen3/Eigen/src/Core/util/NonMPL2.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/AmbiVector.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/CompressedStorage.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/ConservativeSparseSparseProduct.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/MappedSparseMatrix.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseAssign.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseBlock.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseColEtree.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseCompressedBase.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseCwiseBinaryOp.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseCwiseUnaryOp.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseDenseProduct.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseDiagonalProduct.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseDot.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseFuzzy.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseMap.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseMatrix.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseMatrixBase.h
+../plugins/CommonCwiseUnaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h
+../plugins/CommonCwiseBinaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h
+../plugins/MatrixCwiseUnaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h
+../plugins/MatrixCwiseBinaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h
+../plugins/BlockMethods.h
+/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparsePermutation.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseProduct.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseRedux.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseRef.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseSelfAdjointView.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseSolverBase.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseSparseProductWithPruning.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseTranspose.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseTriangularView.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseUtil.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseVector.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseView.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/TriangularSolver.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLUImpl.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Memory.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Structs.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Utils.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_column_bmod.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_column_dfs.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_copy_to_ucol.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_gemm_kernel.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_heap_relax_snode.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_kernel_bmod.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_panel_bmod.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_panel_dfs.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_pivotL.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_pruneL.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_relax_snode.h
+
+/usr/include/eigen3/Eigen/src/SparseQR/SparseQR.h
+
+/usr/include/eigen3/Eigen/src/misc/Image.h
+
+/usr/include/eigen3/Eigen/src/misc/Kernel.h
+
+/usr/include/eigen3/Eigen/src/misc/RealSvd2x2.h
+
+/usr/include/eigen3/Eigen/src/misc/blas.h
+
+/usr/include/eigen3/Eigen/src/misc/lapacke.h
+lapacke_config.h
+/usr/include/eigen3/Eigen/src/misc/lapacke_config.h
+stdlib.h
+-
+complex.h
+-
+complex.h
+-
+lapacke_mangling.h
+/usr/include/eigen3/Eigen/src/misc/lapacke_mangling.h
+
+/usr/include/eigen3/Eigen/src/misc/lapacke_mangling.h
+
+/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h
+
+/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h
+
+/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h
+
+/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h
+
+/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h
+
+/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h
+
+/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h
+
+acado_auxiliary_functions.h
+acado_common.h
+acado_common.h
+Windows.h
+-
+unistd.h
+unistd.h
+mach/mach_time.h
+-
+time.h
+-
+sys/stat.h
+-
+sys/time.h
+-
+
+acado_common.h
+math.h
+-
+string.h
+-
+acado_qpoases_interface.hpp
+acado_qpoases_interface.hpp
+
+acado_qpoases_interface.hpp
+stdio.h
+-
+math.h
+-
+
+qpoases/INCLUDE/Bounds.hpp
+SubjectTo.hpp
+-
+Bounds.ipp
+-
+
+qpoases/INCLUDE/Constants.hpp
+acado_qpoases_interface.hpp
+qpoases/INCLUDE/acado_qpoases_interface.hpp
+
+qpoases/INCLUDE/Constraints.hpp
+SubjectTo.hpp
+-
+Constraints.ipp
+-
+
+qpoases/INCLUDE/CyclingManager.hpp
+Utils.hpp
+-
+CyclingManager.ipp
+-
+
+qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp
+QProblem.hpp
+-
+
+qpoases/INCLUDE/Indexlist.hpp
+Utils.hpp
+-
+Indexlist.ipp
+-
+
+qpoases/INCLUDE/MessageHandling.hpp
+stdio.h
+-
+Types.hpp
+-
+Constants.hpp
+-
+MessageHandling.ipp
+-
+
+qpoases/INCLUDE/QProblem.hpp
+QProblemB.hpp
+-
+Constraints.hpp
+-
+CyclingManager.hpp
+-
+QProblem.ipp
+-
+
+qpoases/INCLUDE/QProblemB.hpp
+Bounds.hpp
+-
+QProblemB.ipp
+-
+
+qpoases/INCLUDE/SubjectTo.hpp
+Indexlist.hpp
+-
+SubjectTo.ipp
+-
+
+qpoases/INCLUDE/Types.hpp
+
+qpoases/INCLUDE/Utils.hpp
+MessageHandling.hpp
+-
+Utils.ipp
+-
+
+qpoases/SRC/Bounds.ipp
+
+qpoases/SRC/Constraints.ipp
+
+qpoases/SRC/CyclingManager.ipp
+
+qpoases/SRC/Indexlist.ipp
+
+qpoases/SRC/MessageHandling.ipp
+
+qpoases/SRC/QProblem.ipp
+
+qpoases/SRC/QProblemB.ipp
+math.h
+-
+
+qpoases/SRC/SubjectTo.ipp
+
+qpoases/SRC/Utils.ipp
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..d1cc9f0a7b12e057f1b7b90a414d8b2be97dc2d5
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/DependInfo.cmake
@@ -0,0 +1,80 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  "C"
+  "CXX"
+  )
+# The set of files for implicit dependencies of each language:
+set(CMAKE_DEPENDS_CHECK_C
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_auxiliary_functions.c" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_auxiliary_functions.c.o"
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_integrator.c" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_integrator.c.o"
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_solver.c" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_solver.c.o"
+  )
+set(CMAKE_C_COMPILER_ID "GNU")
+
+# Preprocessor definitions for this target.
+set(CMAKE_TARGET_DEFINITIONS_C
+  "ROSCONSOLE_BACKEND_LOG4CXX"
+  "ROS_BUILD_SHARED_LIBS=1"
+  "ROS_PACKAGE_NAME=\"mav_nonlinear_mpc\""
+  "mav_nonlinear_mpc_lib_EXPORTS"
+  )
+
+# The include file search paths:
+set(CMAKE_C_TARGET_INCLUDE_PATH
+  "devel/include"
+  "../include"
+  "/home/simhe502/catkin_ws/devel/include"
+  "/home/simhe502/catkin_ws/src/common_msgs/sensor_msgs/include"
+  "/opt/ros/noetic/include"
+  "/opt/ros/noetic/share/xmlrpcpp/cmake/../../../include/xmlrpcpp"
+  "/usr/include/eigen3"
+  "."
+  "qpoases"
+  "qpoases/INCLUDE"
+  "qpoases/SRC"
+  )
+set(CMAKE_DEPENDS_CHECK_CXX
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_qpoases_interface.cpp" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o"
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Bounds.cpp" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o"
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Constraints.cpp" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o"
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/CyclingManager.cpp" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.o"
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o"
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Indexlist.cpp" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.o"
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/MessageHandling.cpp" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.o"
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblem.cpp" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o"
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblemB.cpp" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o"
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/SubjectTo.cpp" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o"
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Utils.cpp" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.o"
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/src/nonlinear_mpc.cc" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o"
+  )
+set(CMAKE_CXX_COMPILER_ID "GNU")
+
+# Preprocessor definitions for this target.
+set(CMAKE_TARGET_DEFINITIONS_CXX
+  "ROSCONSOLE_BACKEND_LOG4CXX"
+  "ROS_BUILD_SHARED_LIBS=1"
+  "ROS_PACKAGE_NAME=\"mav_nonlinear_mpc\""
+  "mav_nonlinear_mpc_lib_EXPORTS"
+  )
+
+# The include file search paths:
+set(CMAKE_CXX_TARGET_INCLUDE_PATH
+  "devel/include"
+  "../include"
+  "/home/simhe502/catkin_ws/devel/include"
+  "/home/simhe502/catkin_ws/src/common_msgs/sensor_msgs/include"
+  "/opt/ros/noetic/include"
+  "/opt/ros/noetic/share/xmlrpcpp/cmake/../../../include/xmlrpcpp"
+  "/usr/include/eigen3"
+  "."
+  "qpoases"
+  "qpoases/INCLUDE"
+  "qpoases/SRC"
+  )
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..03eb2ecba073166b4017e8acd238a51fc030e49c
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/build.make
@@ -0,0 +1,354 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Include any dependencies generated for this target.
+include CMakeFiles/mav_nonlinear_mpc_lib.dir/depend.make
+
+# Include the progress variables for this target.
+include CMakeFiles/mav_nonlinear_mpc_lib.dir/progress.make
+
+# Include the compile flags for this target's objects.
+include CMakeFiles/mav_nonlinear_mpc_lib.dir/flags.make
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: CMakeFiles/mav_nonlinear_mpc_lib.dir/flags.make
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: ../src/nonlinear_mpc.cc
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_1) "Building CXX object CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o"
+	/usr/bin/c++  $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -o CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o -c /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/src/nonlinear_mpc.cc
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.i: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.i"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/src/nonlinear_mpc.cc > CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.i
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.s: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.s"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/src/nonlinear_mpc.cc -o CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.s
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o: CMakeFiles/mav_nonlinear_mpc_lib.dir/flags.make
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o: qpoases/SRC/Bounds.cpp
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_2) "Building CXX object CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o"
+	/usr/bin/c++  $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o -c /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Bounds.cpp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.i: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.i"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Bounds.cpp > CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.i
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.s: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.s"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Bounds.cpp -o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.s
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o: CMakeFiles/mav_nonlinear_mpc_lib.dir/flags.make
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o: qpoases/SRC/Constraints.cpp
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_3) "Building CXX object CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o"
+	/usr/bin/c++  $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o -c /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Constraints.cpp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.i: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.i"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Constraints.cpp > CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.i
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.s: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.s"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Constraints.cpp -o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.s
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.o: CMakeFiles/mav_nonlinear_mpc_lib.dir/flags.make
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.o: qpoases/SRC/CyclingManager.cpp
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_4) "Building CXX object CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.o"
+	/usr/bin/c++  $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.o -c /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/CyclingManager.cpp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.i: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.i"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/CyclingManager.cpp > CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.i
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.s: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.s"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/CyclingManager.cpp -o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.s
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.o: CMakeFiles/mav_nonlinear_mpc_lib.dir/flags.make
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.o: qpoases/SRC/Indexlist.cpp
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_5) "Building CXX object CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.o"
+	/usr/bin/c++  $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.o -c /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Indexlist.cpp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.i: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.i"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Indexlist.cpp > CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.i
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.s: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.s"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Indexlist.cpp -o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.s
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.o: CMakeFiles/mav_nonlinear_mpc_lib.dir/flags.make
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.o: qpoases/SRC/MessageHandling.cpp
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_6) "Building CXX object CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.o"
+	/usr/bin/c++  $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.o -c /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/MessageHandling.cpp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.i: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.i"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/MessageHandling.cpp > CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.i
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.s: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.s"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/MessageHandling.cpp -o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.s
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: CMakeFiles/mav_nonlinear_mpc_lib.dir/flags.make
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/SRC/QProblem.cpp
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_7) "Building CXX object CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o"
+	/usr/bin/c++  $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o -c /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblem.cpp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.i: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.i"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblem.cpp > CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.i
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.s: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.s"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblem.cpp -o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.s
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o: CMakeFiles/mav_nonlinear_mpc_lib.dir/flags.make
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o: qpoases/SRC/QProblemB.cpp
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_8) "Building CXX object CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o"
+	/usr/bin/c++  $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o -c /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblemB.cpp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.i: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.i"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblemB.cpp > CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.i
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.s: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.s"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblemB.cpp -o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.s
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o: CMakeFiles/mav_nonlinear_mpc_lib.dir/flags.make
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o: qpoases/SRC/SubjectTo.cpp
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_9) "Building CXX object CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o"
+	/usr/bin/c++  $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o -c /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/SubjectTo.cpp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.i: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.i"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/SubjectTo.cpp > CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.i
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.s: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.s"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/SubjectTo.cpp -o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.s
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.o: CMakeFiles/mav_nonlinear_mpc_lib.dir/flags.make
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.o: qpoases/SRC/Utils.cpp
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_10) "Building CXX object CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.o"
+	/usr/bin/c++  $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.o -c /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Utils.cpp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.i: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.i"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Utils.cpp > CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.i
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.s: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.s"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Utils.cpp -o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.s
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: CMakeFiles/mav_nonlinear_mpc_lib.dir/flags.make
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/SRC/EXTRAS/SolutionAnalysis.cpp
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_11) "Building CXX object CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o"
+	/usr/bin/c++  $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o -c /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.i: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.i"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp > CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.i
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.s: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.s"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp -o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.s
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: CMakeFiles/mav_nonlinear_mpc_lib.dir/flags.make
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: acado_qpoases_interface.cpp
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_12) "Building CXX object CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o"
+	/usr/bin/c++  $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -o CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o -c /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_qpoases_interface.cpp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.i: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.i"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_qpoases_interface.cpp > CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.i
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.s: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.s"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_qpoases_interface.cpp -o CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.s
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_integrator.c.o: CMakeFiles/mav_nonlinear_mpc_lib.dir/flags.make
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_integrator.c.o: acado_integrator.c
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_13) "Building C object CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_integrator.c.o"
+	/usr/bin/cc $(C_DEFINES) $(C_INCLUDES) $(C_FLAGS) -o CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_integrator.c.o   -c /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_integrator.c
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_integrator.c.i: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing C source to CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_integrator.c.i"
+	/usr/bin/cc $(C_DEFINES) $(C_INCLUDES) $(C_FLAGS) -E /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_integrator.c > CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_integrator.c.i
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_integrator.c.s: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling C source to assembly CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_integrator.c.s"
+	/usr/bin/cc $(C_DEFINES) $(C_INCLUDES) $(C_FLAGS) -S /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_integrator.c -o CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_integrator.c.s
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_solver.c.o: CMakeFiles/mav_nonlinear_mpc_lib.dir/flags.make
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_solver.c.o: acado_solver.c
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_14) "Building C object CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_solver.c.o"
+	/usr/bin/cc $(C_DEFINES) $(C_INCLUDES) $(C_FLAGS) -o CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_solver.c.o   -c /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_solver.c
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_solver.c.i: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing C source to CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_solver.c.i"
+	/usr/bin/cc $(C_DEFINES) $(C_INCLUDES) $(C_FLAGS) -E /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_solver.c > CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_solver.c.i
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_solver.c.s: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling C source to assembly CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_solver.c.s"
+	/usr/bin/cc $(C_DEFINES) $(C_INCLUDES) $(C_FLAGS) -S /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_solver.c -o CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_solver.c.s
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_auxiliary_functions.c.o: CMakeFiles/mav_nonlinear_mpc_lib.dir/flags.make
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_auxiliary_functions.c.o: acado_auxiliary_functions.c
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_15) "Building C object CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_auxiliary_functions.c.o"
+	/usr/bin/cc $(C_DEFINES) $(C_INCLUDES) $(C_FLAGS) -o CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_auxiliary_functions.c.o   -c /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_auxiliary_functions.c
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_auxiliary_functions.c.i: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing C source to CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_auxiliary_functions.c.i"
+	/usr/bin/cc $(C_DEFINES) $(C_INCLUDES) $(C_FLAGS) -E /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_auxiliary_functions.c > CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_auxiliary_functions.c.i
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_auxiliary_functions.c.s: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling C source to assembly CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_auxiliary_functions.c.s"
+	/usr/bin/cc $(C_DEFINES) $(C_INCLUDES) $(C_FLAGS) -S /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_auxiliary_functions.c -o CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_auxiliary_functions.c.s
+
+# Object files for target mav_nonlinear_mpc_lib
+mav_nonlinear_mpc_lib_OBJECTS = \
+"CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o" \
+"CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o" \
+"CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o" \
+"CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.o" \
+"CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.o" \
+"CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.o" \
+"CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o" \
+"CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o" \
+"CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o" \
+"CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.o" \
+"CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o" \
+"CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o" \
+"CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_integrator.c.o" \
+"CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_solver.c.o" \
+"CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_auxiliary_functions.c.o"
+
+# External object files for target mav_nonlinear_mpc_lib
+mav_nonlinear_mpc_lib_EXTERNAL_OBJECTS =
+
+devel/lib/libmav_nonlinear_mpc_lib.so: CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o
+devel/lib/libmav_nonlinear_mpc_lib.so: CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o
+devel/lib/libmav_nonlinear_mpc_lib.so: CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o
+devel/lib/libmav_nonlinear_mpc_lib.so: CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.o
+devel/lib/libmav_nonlinear_mpc_lib.so: CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.o
+devel/lib/libmav_nonlinear_mpc_lib.so: CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.o
+devel/lib/libmav_nonlinear_mpc_lib.so: CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o
+devel/lib/libmav_nonlinear_mpc_lib.so: CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o
+devel/lib/libmav_nonlinear_mpc_lib.so: CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o
+devel/lib/libmav_nonlinear_mpc_lib.so: CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.o
+devel/lib/libmav_nonlinear_mpc_lib.so: CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o
+devel/lib/libmav_nonlinear_mpc_lib.so: CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o
+devel/lib/libmav_nonlinear_mpc_lib.so: CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_integrator.c.o
+devel/lib/libmav_nonlinear_mpc_lib.so: CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_solver.c.o
+devel/lib/libmav_nonlinear_mpc_lib.so: CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_auxiliary_functions.c.o
+devel/lib/libmav_nonlinear_mpc_lib.so: CMakeFiles/mav_nonlinear_mpc_lib.dir/build.make
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/libdynamic_reconfigure_config_init_mutex.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/libtf.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/libtf2_ros.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/libactionlib.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/libmessage_filters.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/libroscpp.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /usr/lib/x86_64-linux-gnu/libpthread.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.71.0
+devel/lib/libmav_nonlinear_mpc_lib.so: /usr/lib/x86_64-linux-gnu/libboost_filesystem.so.1.71.0
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/libxmlrpcpp.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/libtf2.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/libroscpp_serialization.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/librosconsole.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/librosconsole_log4cxx.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/librosconsole_backend_interface.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /usr/lib/x86_64-linux-gnu/liblog4cxx.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /usr/lib/x86_64-linux-gnu/libboost_regex.so.1.71.0
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/librostime.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /usr/lib/x86_64-linux-gnu/libboost_date_time.so.1.71.0
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/libcpp_common.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /usr/lib/x86_64-linux-gnu/libboost_system.so.1.71.0
+devel/lib/libmav_nonlinear_mpc_lib.so: /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.71.0
+devel/lib/libmav_nonlinear_mpc_lib.so: /usr/lib/x86_64-linux-gnu/libconsole_bridge.so.0.4
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/libdynamic_reconfigure_config_init_mutex.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/libtf.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/libtf2_ros.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/libactionlib.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/libmessage_filters.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/libroscpp.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /usr/lib/x86_64-linux-gnu/libpthread.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.71.0
+devel/lib/libmav_nonlinear_mpc_lib.so: /usr/lib/x86_64-linux-gnu/libboost_filesystem.so.1.71.0
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/libxmlrpcpp.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/libtf2.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/libroscpp_serialization.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/librosconsole.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/librosconsole_log4cxx.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/librosconsole_backend_interface.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /usr/lib/x86_64-linux-gnu/liblog4cxx.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /usr/lib/x86_64-linux-gnu/libboost_regex.so.1.71.0
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/librostime.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /usr/lib/x86_64-linux-gnu/libboost_date_time.so.1.71.0
+devel/lib/libmav_nonlinear_mpc_lib.so: /opt/ros/noetic/lib/libcpp_common.so
+devel/lib/libmav_nonlinear_mpc_lib.so: /usr/lib/x86_64-linux-gnu/libboost_system.so.1.71.0
+devel/lib/libmav_nonlinear_mpc_lib.so: /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.71.0
+devel/lib/libmav_nonlinear_mpc_lib.so: /usr/lib/x86_64-linux-gnu/libconsole_bridge.so.0.4
+devel/lib/libmav_nonlinear_mpc_lib.so: CMakeFiles/mav_nonlinear_mpc_lib.dir/link.txt
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --bold --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_16) "Linking CXX shared library devel/lib/libmav_nonlinear_mpc_lib.so"
+	$(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/mav_nonlinear_mpc_lib.dir/link.txt --verbose=$(VERBOSE)
+
+# Rule to build all files generated by this target.
+CMakeFiles/mav_nonlinear_mpc_lib.dir/build: devel/lib/libmav_nonlinear_mpc_lib.so
+
+.PHONY : CMakeFiles/mav_nonlinear_mpc_lib.dir/build
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/mav_nonlinear_mpc_lib.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/mav_nonlinear_mpc_lib.dir/clean
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/mav_nonlinear_mpc_lib.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..4efe0e7ad3d666e491d7cb9ab1ca343a865527ad
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/cmake_clean.cmake
@@ -0,0 +1,24 @@
+file(REMOVE_RECURSE
+  "CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_auxiliary_functions.c.o"
+  "CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_integrator.c.o"
+  "CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o"
+  "CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_solver.c.o"
+  "CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o"
+  "CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o"
+  "CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.o"
+  "CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o"
+  "CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.o"
+  "CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.o"
+  "CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o"
+  "CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o"
+  "CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o"
+  "CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.o"
+  "CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o"
+  "devel/lib/libmav_nonlinear_mpc_lib.pdb"
+  "devel/lib/libmav_nonlinear_mpc_lib.so"
+)
+
+# Per-language clean rules from dependency scanning.
+foreach(lang C CXX)
+  include(CMakeFiles/mav_nonlinear_mpc_lib.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..e83ca13a4097b1b6223d3d39b0376a085f19bf16
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/depend.internal
@@ -0,0 +1,555 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_auxiliary_functions.c.o
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_auxiliary_functions.c
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_auxiliary_functions.h
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_common.h
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_qpoases_interface.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_integrator.c.o
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_common.h
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_integrator.c
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_qpoases_interface.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_solver.c.o
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_common.h
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_qpoases_interface.hpp
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_solver.c
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_common.h
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_qpoases_interface.cpp
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/acado_qpoases_interface.hpp
+ qpoases/INCLUDE/Bounds.hpp
+ qpoases/INCLUDE/Constants.hpp
+ qpoases/INCLUDE/Constraints.hpp
+ qpoases/INCLUDE/CyclingManager.hpp
+ qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp
+ qpoases/INCLUDE/Indexlist.hpp
+ qpoases/INCLUDE/MessageHandling.hpp
+ qpoases/INCLUDE/QProblem.hpp
+ qpoases/INCLUDE/QProblemB.hpp
+ qpoases/INCLUDE/SubjectTo.hpp
+ qpoases/INCLUDE/Types.hpp
+ qpoases/INCLUDE/Utils.hpp
+ qpoases/SRC/Bounds.ipp
+ qpoases/SRC/Constraints.ipp
+ qpoases/SRC/CyclingManager.ipp
+ qpoases/SRC/Indexlist.ipp
+ qpoases/SRC/MessageHandling.ipp
+ qpoases/SRC/QProblem.ipp
+ qpoases/SRC/QProblemB.ipp
+ qpoases/SRC/SubjectTo.ipp
+ qpoases/SRC/Utils.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Bounds.cpp
+ acado_qpoases_interface.hpp
+ qpoases/INCLUDE/Bounds.hpp
+ qpoases/INCLUDE/Constants.hpp
+ qpoases/INCLUDE/Indexlist.hpp
+ qpoases/INCLUDE/MessageHandling.hpp
+ qpoases/INCLUDE/SubjectTo.hpp
+ qpoases/INCLUDE/Types.hpp
+ qpoases/INCLUDE/Utils.hpp
+ qpoases/SRC/Bounds.ipp
+ qpoases/SRC/Indexlist.ipp
+ qpoases/SRC/MessageHandling.ipp
+ qpoases/SRC/SubjectTo.ipp
+ qpoases/SRC/Utils.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Constraints.cpp
+ acado_qpoases_interface.hpp
+ qpoases/INCLUDE/Constants.hpp
+ qpoases/INCLUDE/Constraints.hpp
+ qpoases/INCLUDE/Indexlist.hpp
+ qpoases/INCLUDE/MessageHandling.hpp
+ qpoases/INCLUDE/SubjectTo.hpp
+ qpoases/INCLUDE/Types.hpp
+ qpoases/INCLUDE/Utils.hpp
+ qpoases/SRC/Constraints.ipp
+ qpoases/SRC/Indexlist.ipp
+ qpoases/SRC/MessageHandling.ipp
+ qpoases/SRC/SubjectTo.ipp
+ qpoases/SRC/Utils.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.o
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/CyclingManager.cpp
+ acado_qpoases_interface.hpp
+ qpoases/INCLUDE/Constants.hpp
+ qpoases/INCLUDE/CyclingManager.hpp
+ qpoases/INCLUDE/MessageHandling.hpp
+ qpoases/INCLUDE/Types.hpp
+ qpoases/INCLUDE/Utils.hpp
+ qpoases/SRC/CyclingManager.ipp
+ qpoases/SRC/MessageHandling.ipp
+ qpoases/SRC/Utils.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp
+ acado_qpoases_interface.hpp
+ qpoases/INCLUDE/Bounds.hpp
+ qpoases/INCLUDE/Constants.hpp
+ qpoases/INCLUDE/Constraints.hpp
+ qpoases/INCLUDE/CyclingManager.hpp
+ qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp
+ qpoases/INCLUDE/Indexlist.hpp
+ qpoases/INCLUDE/MessageHandling.hpp
+ qpoases/INCLUDE/QProblem.hpp
+ qpoases/INCLUDE/QProblemB.hpp
+ qpoases/INCLUDE/SubjectTo.hpp
+ qpoases/INCLUDE/Types.hpp
+ qpoases/INCLUDE/Utils.hpp
+ qpoases/SRC/Bounds.ipp
+ qpoases/SRC/Constraints.ipp
+ qpoases/SRC/CyclingManager.ipp
+ qpoases/SRC/Indexlist.ipp
+ qpoases/SRC/MessageHandling.ipp
+ qpoases/SRC/QProblem.ipp
+ qpoases/SRC/QProblemB.ipp
+ qpoases/SRC/SubjectTo.ipp
+ qpoases/SRC/Utils.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.o
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Indexlist.cpp
+ acado_qpoases_interface.hpp
+ qpoases/INCLUDE/Constants.hpp
+ qpoases/INCLUDE/Indexlist.hpp
+ qpoases/INCLUDE/MessageHandling.hpp
+ qpoases/INCLUDE/Types.hpp
+ qpoases/INCLUDE/Utils.hpp
+ qpoases/SRC/Indexlist.ipp
+ qpoases/SRC/MessageHandling.ipp
+ qpoases/SRC/Utils.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.o
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/MessageHandling.cpp
+ acado_qpoases_interface.hpp
+ qpoases/INCLUDE/Constants.hpp
+ qpoases/INCLUDE/MessageHandling.hpp
+ qpoases/INCLUDE/Types.hpp
+ qpoases/INCLUDE/Utils.hpp
+ qpoases/SRC/MessageHandling.ipp
+ qpoases/SRC/Utils.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblem.cpp
+ acado_qpoases_interface.hpp
+ qpoases/INCLUDE/Bounds.hpp
+ qpoases/INCLUDE/Constants.hpp
+ qpoases/INCLUDE/Constraints.hpp
+ qpoases/INCLUDE/CyclingManager.hpp
+ qpoases/INCLUDE/Indexlist.hpp
+ qpoases/INCLUDE/MessageHandling.hpp
+ qpoases/INCLUDE/QProblem.hpp
+ qpoases/INCLUDE/QProblemB.hpp
+ qpoases/INCLUDE/SubjectTo.hpp
+ qpoases/INCLUDE/Types.hpp
+ qpoases/INCLUDE/Utils.hpp
+ qpoases/SRC/Bounds.ipp
+ qpoases/SRC/Constraints.ipp
+ qpoases/SRC/CyclingManager.ipp
+ qpoases/SRC/Indexlist.ipp
+ qpoases/SRC/MessageHandling.ipp
+ qpoases/SRC/QProblem.ipp
+ qpoases/SRC/QProblemB.ipp
+ qpoases/SRC/SubjectTo.ipp
+ qpoases/SRC/Utils.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblemB.cpp
+ acado_qpoases_interface.hpp
+ qpoases/INCLUDE/Bounds.hpp
+ qpoases/INCLUDE/Constants.hpp
+ qpoases/INCLUDE/Indexlist.hpp
+ qpoases/INCLUDE/MessageHandling.hpp
+ qpoases/INCLUDE/QProblemB.hpp
+ qpoases/INCLUDE/SubjectTo.hpp
+ qpoases/INCLUDE/Types.hpp
+ qpoases/INCLUDE/Utils.hpp
+ qpoases/SRC/Bounds.ipp
+ qpoases/SRC/Indexlist.ipp
+ qpoases/SRC/MessageHandling.ipp
+ qpoases/SRC/QProblemB.ipp
+ qpoases/SRC/SubjectTo.ipp
+ qpoases/SRC/Utils.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/SubjectTo.cpp
+ acado_qpoases_interface.hpp
+ qpoases/INCLUDE/Constants.hpp
+ qpoases/INCLUDE/Indexlist.hpp
+ qpoases/INCLUDE/MessageHandling.hpp
+ qpoases/INCLUDE/SubjectTo.hpp
+ qpoases/INCLUDE/Types.hpp
+ qpoases/INCLUDE/Utils.hpp
+ qpoases/SRC/Indexlist.ipp
+ qpoases/SRC/MessageHandling.ipp
+ qpoases/SRC/SubjectTo.ipp
+ qpoases/SRC/Utils.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.o
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Utils.cpp
+ acado_qpoases_interface.hpp
+ qpoases/INCLUDE/Constants.hpp
+ qpoases/INCLUDE/MessageHandling.hpp
+ qpoases/INCLUDE/Types.hpp
+ qpoases/INCLUDE/Utils.hpp
+ qpoases/SRC/MessageHandling.ipp
+ qpoases/SRC/Utils.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o
+ ../include/mav_nonlinear_mpc/nonlinear_mpc.h
+ /home/simhe502/catkin_ws/devel/include/geometry_msgs/Point.h
+ /home/simhe502/catkin_ws/devel/include/geometry_msgs/PointStamped.h
+ /home/simhe502/catkin_ws/devel/include/geometry_msgs/Pose.h
+ /home/simhe502/catkin_ws/devel/include/geometry_msgs/PoseStamped.h
+ /home/simhe502/catkin_ws/devel/include/geometry_msgs/Quaternion.h
+ /home/simhe502/catkin_ws/devel/include/geometry_msgs/QuaternionStamped.h
+ /home/simhe502/catkin_ws/devel/include/geometry_msgs/Transform.h
+ /home/simhe502/catkin_ws/devel/include/geometry_msgs/TransformStamped.h
+ /home/simhe502/catkin_ws/devel/include/geometry_msgs/Twist.h
+ /home/simhe502/catkin_ws/devel/include/geometry_msgs/Vector3.h
+ /home/simhe502/catkin_ws/devel/include/geometry_msgs/Vector3Stamped.h
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/src/nonlinear_mpc.cc
+ /opt/ros/noetic/include/gazebo_msgs/GetModelState.h
+ /opt/ros/noetic/include/gazebo_msgs/GetModelStateRequest.h
+ /opt/ros/noetic/include/gazebo_msgs/GetModelStateResponse.h
+ /opt/ros/noetic/include/ros/advertise_options.h
+ /opt/ros/noetic/include/ros/advertise_service_options.h
+ /opt/ros/noetic/include/ros/assert.h
+ /opt/ros/noetic/include/ros/builtin_message_traits.h
+ /opt/ros/noetic/include/ros/common.h
+ /opt/ros/noetic/include/ros/console.h
+ /opt/ros/noetic/include/ros/console_backend.h
+ /opt/ros/noetic/include/ros/datatypes.h
+ /opt/ros/noetic/include/ros/duration.h
+ /opt/ros/noetic/include/ros/exception.h
+ /opt/ros/noetic/include/ros/exceptions.h
+ /opt/ros/noetic/include/ros/forwards.h
+ /opt/ros/noetic/include/ros/init.h
+ /opt/ros/noetic/include/ros/macros.h
+ /opt/ros/noetic/include/ros/master.h
+ /opt/ros/noetic/include/ros/message.h
+ /opt/ros/noetic/include/ros/message_event.h
+ /opt/ros/noetic/include/ros/message_forward.h
+ /opt/ros/noetic/include/ros/message_operations.h
+ /opt/ros/noetic/include/ros/message_traits.h
+ /opt/ros/noetic/include/ros/names.h
+ /opt/ros/noetic/include/ros/node_handle.h
+ /opt/ros/noetic/include/ros/param.h
+ /opt/ros/noetic/include/ros/parameter_adapter.h
+ /opt/ros/noetic/include/ros/platform.h
+ /opt/ros/noetic/include/ros/publisher.h
+ /opt/ros/noetic/include/ros/rate.h
+ /opt/ros/noetic/include/ros/ros.h
+ /opt/ros/noetic/include/ros/roscpp_serialization_macros.h
+ /opt/ros/noetic/include/ros/rostime_decl.h
+ /opt/ros/noetic/include/ros/serialization.h
+ /opt/ros/noetic/include/ros/serialized_message.h
+ /opt/ros/noetic/include/ros/service.h
+ /opt/ros/noetic/include/ros/service_callback_helper.h
+ /opt/ros/noetic/include/ros/service_client.h
+ /opt/ros/noetic/include/ros/service_client_options.h
+ /opt/ros/noetic/include/ros/service_server.h
+ /opt/ros/noetic/include/ros/service_traits.h
+ /opt/ros/noetic/include/ros/single_subscriber_publisher.h
+ /opt/ros/noetic/include/ros/spinner.h
+ /opt/ros/noetic/include/ros/static_assert.h
+ /opt/ros/noetic/include/ros/steady_timer.h
+ /opt/ros/noetic/include/ros/steady_timer_options.h
+ /opt/ros/noetic/include/ros/subscribe_options.h
+ /opt/ros/noetic/include/ros/subscriber.h
+ /opt/ros/noetic/include/ros/subscription_callback_helper.h
+ /opt/ros/noetic/include/ros/this_node.h
+ /opt/ros/noetic/include/ros/time.h
+ /opt/ros/noetic/include/ros/timer.h
+ /opt/ros/noetic/include/ros/timer_options.h
+ /opt/ros/noetic/include/ros/topic.h
+ /opt/ros/noetic/include/ros/transport_hints.h
+ /opt/ros/noetic/include/ros/types.h
+ /opt/ros/noetic/include/ros/wall_timer.h
+ /opt/ros/noetic/include/ros/wall_timer_options.h
+ /opt/ros/noetic/include/rosconsole/macros_generated.h
+ /opt/ros/noetic/include/std_msgs/Header.h
+ /opt/ros/noetic/include/std_srvs/Empty.h
+ /opt/ros/noetic/include/std_srvs/EmptyRequest.h
+ /opt/ros/noetic/include/std_srvs/EmptyResponse.h
+ /opt/ros/noetic/include/tf/LinearMath/Matrix3x3.h
+ /opt/ros/noetic/include/tf/LinearMath/MinMax.h
+ /opt/ros/noetic/include/tf/LinearMath/QuadWord.h
+ /opt/ros/noetic/include/tf/LinearMath/Quaternion.h
+ /opt/ros/noetic/include/tf/LinearMath/Scalar.h
+ /opt/ros/noetic/include/tf/LinearMath/Transform.h
+ /opt/ros/noetic/include/tf/LinearMath/Vector3.h
+ /opt/ros/noetic/include/tf/transform_datatypes.h
+ /opt/ros/noetic/include/xmlrpcpp/XmlRpcDecl.h
+ /opt/ros/noetic/include/xmlrpcpp/XmlRpcValue.h
+ /usr/include/eigen3/Eigen/Cholesky
+ /usr/include/eigen3/Eigen/Core
+ /usr/include/eigen3/Eigen/Dense
+ /usr/include/eigen3/Eigen/Eigen
+ /usr/include/eigen3/Eigen/Eigenvalues
+ /usr/include/eigen3/Eigen/Geometry
+ /usr/include/eigen3/Eigen/Householder
+ /usr/include/eigen3/Eigen/IterativeLinearSolvers
+ /usr/include/eigen3/Eigen/Jacobi
+ /usr/include/eigen3/Eigen/LU
+ /usr/include/eigen3/Eigen/OrderingMethods
+ /usr/include/eigen3/Eigen/QR
+ /usr/include/eigen3/Eigen/SVD
+ /usr/include/eigen3/Eigen/Sparse
+ /usr/include/eigen3/Eigen/SparseCholesky
+ /usr/include/eigen3/Eigen/SparseCore
+ /usr/include/eigen3/Eigen/SparseLU
+ /usr/include/eigen3/Eigen/SparseQR
+ /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h
+ /usr/include/eigen3/Eigen/src/Cholesky/LLT.h
+ /usr/include/eigen3/Eigen/src/Cholesky/LLT_LAPACKE.h
+ /usr/include/eigen3/Eigen/src/Core/Array.h
+ /usr/include/eigen3/Eigen/src/Core/ArrayBase.h
+ /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h
+ /usr/include/eigen3/Eigen/src/Core/Assign.h
+ /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h
+ /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h
+ /usr/include/eigen3/Eigen/src/Core/BandMatrix.h
+ /usr/include/eigen3/Eigen/src/Core/Block.h
+ /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h
+ /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h
+ /usr/include/eigen3/Eigen/src/Core/ConditionEstimator.h
+ /usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h
+ /usr/include/eigen3/Eigen/src/Core/CoreIterators.h
+ /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h
+ /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h
+ /usr/include/eigen3/Eigen/src/Core/CwiseTernaryOp.h
+ /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h
+ /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h
+ /usr/include/eigen3/Eigen/src/Core/DenseBase.h
+ /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h
+ /usr/include/eigen3/Eigen/src/Core/DenseStorage.h
+ /usr/include/eigen3/Eigen/src/Core/Diagonal.h
+ /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h
+ /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h
+ /usr/include/eigen3/Eigen/src/Core/Dot.h
+ /usr/include/eigen3/Eigen/src/Core/EigenBase.h
+ /usr/include/eigen3/Eigen/src/Core/Fuzzy.h
+ /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h
+ /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h
+ /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h
+ /usr/include/eigen3/Eigen/src/Core/IO.h
+ /usr/include/eigen3/Eigen/src/Core/Inverse.h
+ /usr/include/eigen3/Eigen/src/Core/Map.h
+ /usr/include/eigen3/Eigen/src/Core/MapBase.h
+ /usr/include/eigen3/Eigen/src/Core/MathFunctions.h
+ /usr/include/eigen3/Eigen/src/Core/MathFunctionsImpl.h
+ /usr/include/eigen3/Eigen/src/Core/Matrix.h
+ /usr/include/eigen3/Eigen/src/Core/MatrixBase.h
+ /usr/include/eigen3/Eigen/src/Core/NestByValue.h
+ /usr/include/eigen3/Eigen/src/Core/NoAlias.h
+ /usr/include/eigen3/Eigen/src/Core/NumTraits.h
+ /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h
+ /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h
+ /usr/include/eigen3/Eigen/src/Core/Product.h
+ /usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h
+ /usr/include/eigen3/Eigen/src/Core/Random.h
+ /usr/include/eigen3/Eigen/src/Core/Redux.h
+ /usr/include/eigen3/Eigen/src/Core/Ref.h
+ /usr/include/eigen3/Eigen/src/Core/Replicate.h
+ /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h
+ /usr/include/eigen3/Eigen/src/Core/Reverse.h
+ /usr/include/eigen3/Eigen/src/Core/Select.h
+ /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h
+ /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h
+ /usr/include/eigen3/Eigen/src/Core/Solve.h
+ /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h
+ /usr/include/eigen3/Eigen/src/Core/SolverBase.h
+ /usr/include/eigen3/Eigen/src/Core/StableNorm.h
+ /usr/include/eigen3/Eigen/src/Core/Stride.h
+ /usr/include/eigen3/Eigen/src/Core/Swap.h
+ /usr/include/eigen3/Eigen/src/Core/Transpose.h
+ /usr/include/eigen3/Eigen/src/Core/Transpositions.h
+ /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h
+ /usr/include/eigen3/Eigen/src/Core/VectorBlock.h
+ /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h
+ /usr/include/eigen3/Eigen/src/Core/Visitor.h
+ /usr/include/eigen3/Eigen/src/Core/arch/AVX/Complex.h
+ /usr/include/eigen3/Eigen/src/Core/arch/AVX/MathFunctions.h
+ /usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h
+ /usr/include/eigen3/Eigen/src/Core/arch/AVX/TypeCasting.h
+ /usr/include/eigen3/Eigen/src/Core/arch/AVX512/MathFunctions.h
+ /usr/include/eigen3/Eigen/src/Core/arch/AVX512/PacketMath.h
+ /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h
+ /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/MathFunctions.h
+ /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h
+ /usr/include/eigen3/Eigen/src/Core/arch/CUDA/Complex.h
+ /usr/include/eigen3/Eigen/src/Core/arch/CUDA/Half.h
+ /usr/include/eigen3/Eigen/src/Core/arch/CUDA/MathFunctions.h
+ /usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMath.h
+ /usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMathHalf.h
+ /usr/include/eigen3/Eigen/src/Core/arch/CUDA/TypeCasting.h
+ /usr/include/eigen3/Eigen/src/Core/arch/Default/ConjHelper.h
+ /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h
+ /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h
+ /usr/include/eigen3/Eigen/src/Core/arch/NEON/MathFunctions.h
+ /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h
+ /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h
+ /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h
+ /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h
+ /usr/include/eigen3/Eigen/src/Core/arch/SSE/TypeCasting.h
+ /usr/include/eigen3/Eigen/src/Core/arch/ZVector/Complex.h
+ /usr/include/eigen3/Eigen/src/Core/arch/ZVector/MathFunctions.h
+ /usr/include/eigen3/Eigen/src/Core/arch/ZVector/PacketMath.h
+ /usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h
+ /usr/include/eigen3/Eigen/src/Core/functors/BinaryFunctors.h
+ /usr/include/eigen3/Eigen/src/Core/functors/NullaryFunctors.h
+ /usr/include/eigen3/Eigen/src/Core/functors/StlFunctors.h
+ /usr/include/eigen3/Eigen/src/Core/functors/TernaryFunctors.h
+ /usr/include/eigen3/Eigen/src/Core/functors/UnaryFunctors.h
+ /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h
+ /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h
+ /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h
+ /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_BLAS.h
+ /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_BLAS.h
+ /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h
+ /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_BLAS.h
+ /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h
+ /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h
+ /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_BLAS.h
+ /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h
+ /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_BLAS.h
+ /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h
+ /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h
+ /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h
+ /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_BLAS.h
+ /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h
+ /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_BLAS.h
+ /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h
+ /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_BLAS.h
+ /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h
+ /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h
+ /usr/include/eigen3/Eigen/src/Core/util/Constants.h
+ /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+ /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h
+ /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h
+ /usr/include/eigen3/Eigen/src/Core/util/Macros.h
+ /usr/include/eigen3/Eigen/src/Core/util/Memory.h
+ /usr/include/eigen3/Eigen/src/Core/util/Meta.h
+ /usr/include/eigen3/Eigen/src/Core/util/NonMPL2.h
+ /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+ /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h
+ /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_LAPACKE.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_LAPACKE.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_LAPACKE.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h
+ /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h
+ /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h
+ /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h
+ /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h
+ /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h
+ /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h
+ /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h
+ /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h
+ /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h
+ /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h
+ /usr/include/eigen3/Eigen/src/Geometry/Scaling.h
+ /usr/include/eigen3/Eigen/src/Geometry/Transform.h
+ /usr/include/eigen3/Eigen/src/Geometry/Translation.h
+ /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h
+ /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h
+ /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h
+ /usr/include/eigen3/Eigen/src/Householder/Householder.h
+ /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h
+ /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h
+ /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h
+ /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h
+ /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IncompleteCholesky.h
+ /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IncompleteLUT.h
+ /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h
+ /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/LeastSquareConjugateGradient.h
+ /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/SolveWithGuess.h
+ /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h
+ /usr/include/eigen3/Eigen/src/LU/Determinant.h
+ /usr/include/eigen3/Eigen/src/LU/FullPivLU.h
+ /usr/include/eigen3/Eigen/src/LU/InverseImpl.h
+ /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h
+ /usr/include/eigen3/Eigen/src/LU/PartialPivLU_LAPACKE.h
+ /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h
+ /usr/include/eigen3/Eigen/src/OrderingMethods/Amd.h
+ /usr/include/eigen3/Eigen/src/OrderingMethods/Eigen_Colamd.h
+ /usr/include/eigen3/Eigen/src/OrderingMethods/Ordering.h
+ /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h
+ /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_LAPACKE.h
+ /usr/include/eigen3/Eigen/src/QR/CompleteOrthogonalDecomposition.h
+ /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h
+ /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h
+ /usr/include/eigen3/Eigen/src/QR/HouseholderQR_LAPACKE.h
+ /usr/include/eigen3/Eigen/src/SVD/BDCSVD.h
+ /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h
+ /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_LAPACKE.h
+ /usr/include/eigen3/Eigen/src/SVD/SVDBase.h
+ /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h
+ /usr/include/eigen3/Eigen/src/SparseCholesky/SimplicialCholesky.h
+ /usr/include/eigen3/Eigen/src/SparseCholesky/SimplicialCholesky_impl.h
+ /usr/include/eigen3/Eigen/src/SparseCore/AmbiVector.h
+ /usr/include/eigen3/Eigen/src/SparseCore/CompressedStorage.h
+ /usr/include/eigen3/Eigen/src/SparseCore/ConservativeSparseSparseProduct.h
+ /usr/include/eigen3/Eigen/src/SparseCore/MappedSparseMatrix.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseAssign.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseBlock.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseColEtree.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseCompressedBase.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseCwiseBinaryOp.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseCwiseUnaryOp.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseDenseProduct.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseDiagonalProduct.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseDot.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseFuzzy.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseMap.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseMatrix.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseMatrixBase.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparsePermutation.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseProduct.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseRedux.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseRef.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseSelfAdjointView.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseSolverBase.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseSparseProductWithPruning.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseTranspose.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseTriangularView.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseUtil.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseVector.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseView.h
+ /usr/include/eigen3/Eigen/src/SparseCore/TriangularSolver.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLUImpl.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Memory.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Structs.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Utils.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_column_bmod.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_column_dfs.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_copy_to_ucol.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_gemm_kernel.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_heap_relax_snode.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_kernel_bmod.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_panel_bmod.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_panel_dfs.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_pivotL.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_pruneL.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_relax_snode.h
+ /usr/include/eigen3/Eigen/src/SparseQR/SparseQR.h
+ /usr/include/eigen3/Eigen/src/misc/Image.h
+ /usr/include/eigen3/Eigen/src/misc/Kernel.h
+ /usr/include/eigen3/Eigen/src/misc/RealSvd2x2.h
+ /usr/include/eigen3/Eigen/src/misc/blas.h
+ /usr/include/eigen3/Eigen/src/misc/lapacke.h
+ /usr/include/eigen3/Eigen/src/misc/lapacke_mangling.h
+ /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h
+ /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h
+ /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h
+ /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h
+ /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h
+ /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h
+ /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h
+ acado_auxiliary_functions.h
+ acado_common.h
+ acado_qpoases_interface.hpp
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..7683ac9a752ea078ea25d6c68d18ea12dfac557f
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/depend.make
@@ -0,0 +1,555 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_auxiliary_functions.c.o: acado_auxiliary_functions.c
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_auxiliary_functions.c.o: acado_auxiliary_functions.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_auxiliary_functions.c.o: acado_common.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_auxiliary_functions.c.o: acado_qpoases_interface.hpp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_integrator.c.o: acado_common.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_integrator.c.o: acado_integrator.c
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_integrator.c.o: acado_qpoases_interface.hpp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_solver.c.o: acado_common.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_solver.c.o: acado_qpoases_interface.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_solver.c.o: acado_solver.c
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: acado_common.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: acado_qpoases_interface.cpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: acado_qpoases_interface.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/INCLUDE/Bounds.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/INCLUDE/Constants.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/INCLUDE/Constraints.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/INCLUDE/CyclingManager.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/INCLUDE/Indexlist.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/INCLUDE/MessageHandling.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/INCLUDE/QProblem.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/INCLUDE/QProblemB.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/INCLUDE/SubjectTo.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/INCLUDE/Types.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/INCLUDE/Utils.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/SRC/Bounds.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/SRC/Constraints.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/SRC/CyclingManager.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/SRC/Indexlist.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/SRC/MessageHandling.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/SRC/QProblem.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/SRC/QProblemB.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/SRC/SubjectTo.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o: qpoases/SRC/Utils.ipp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o: qpoases/SRC/Bounds.cpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o: acado_qpoases_interface.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o: qpoases/INCLUDE/Bounds.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o: qpoases/INCLUDE/Constants.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o: qpoases/INCLUDE/Indexlist.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o: qpoases/INCLUDE/MessageHandling.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o: qpoases/INCLUDE/SubjectTo.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o: qpoases/INCLUDE/Types.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o: qpoases/INCLUDE/Utils.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o: qpoases/SRC/Bounds.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o: qpoases/SRC/Indexlist.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o: qpoases/SRC/MessageHandling.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o: qpoases/SRC/SubjectTo.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o: qpoases/SRC/Utils.ipp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o: qpoases/SRC/Constraints.cpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o: acado_qpoases_interface.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o: qpoases/INCLUDE/Constants.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o: qpoases/INCLUDE/Constraints.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o: qpoases/INCLUDE/Indexlist.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o: qpoases/INCLUDE/MessageHandling.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o: qpoases/INCLUDE/SubjectTo.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o: qpoases/INCLUDE/Types.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o: qpoases/INCLUDE/Utils.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o: qpoases/SRC/Constraints.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o: qpoases/SRC/Indexlist.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o: qpoases/SRC/MessageHandling.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o: qpoases/SRC/SubjectTo.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o: qpoases/SRC/Utils.ipp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.o: qpoases/SRC/CyclingManager.cpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.o: acado_qpoases_interface.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.o: qpoases/INCLUDE/Constants.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.o: qpoases/INCLUDE/CyclingManager.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.o: qpoases/INCLUDE/MessageHandling.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.o: qpoases/INCLUDE/Types.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.o: qpoases/INCLUDE/Utils.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.o: qpoases/SRC/CyclingManager.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.o: qpoases/SRC/MessageHandling.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.o: qpoases/SRC/Utils.ipp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/SRC/EXTRAS/SolutionAnalysis.cpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: acado_qpoases_interface.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/INCLUDE/Bounds.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/INCLUDE/Constants.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/INCLUDE/Constraints.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/INCLUDE/CyclingManager.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/INCLUDE/Indexlist.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/INCLUDE/MessageHandling.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/INCLUDE/QProblem.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/INCLUDE/QProblemB.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/INCLUDE/SubjectTo.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/INCLUDE/Types.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/INCLUDE/Utils.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/SRC/Bounds.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/SRC/Constraints.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/SRC/CyclingManager.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/SRC/Indexlist.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/SRC/MessageHandling.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/SRC/QProblem.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/SRC/QProblemB.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/SRC/SubjectTo.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o: qpoases/SRC/Utils.ipp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.o: qpoases/SRC/Indexlist.cpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.o: acado_qpoases_interface.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.o: qpoases/INCLUDE/Constants.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.o: qpoases/INCLUDE/Indexlist.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.o: qpoases/INCLUDE/MessageHandling.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.o: qpoases/INCLUDE/Types.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.o: qpoases/INCLUDE/Utils.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.o: qpoases/SRC/Indexlist.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.o: qpoases/SRC/MessageHandling.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.o: qpoases/SRC/Utils.ipp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.o: qpoases/SRC/MessageHandling.cpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.o: acado_qpoases_interface.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.o: qpoases/INCLUDE/Constants.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.o: qpoases/INCLUDE/MessageHandling.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.o: qpoases/INCLUDE/Types.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.o: qpoases/INCLUDE/Utils.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.o: qpoases/SRC/MessageHandling.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.o: qpoases/SRC/Utils.ipp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/SRC/QProblem.cpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: acado_qpoases_interface.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/INCLUDE/Bounds.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/INCLUDE/Constants.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/INCLUDE/Constraints.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/INCLUDE/CyclingManager.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/INCLUDE/Indexlist.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/INCLUDE/MessageHandling.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/INCLUDE/QProblem.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/INCLUDE/QProblemB.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/INCLUDE/SubjectTo.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/INCLUDE/Types.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/INCLUDE/Utils.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/SRC/Bounds.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/SRC/Constraints.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/SRC/CyclingManager.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/SRC/Indexlist.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/SRC/MessageHandling.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/SRC/QProblem.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/SRC/QProblemB.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/SRC/SubjectTo.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o: qpoases/SRC/Utils.ipp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o: qpoases/SRC/QProblemB.cpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o: acado_qpoases_interface.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o: qpoases/INCLUDE/Bounds.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o: qpoases/INCLUDE/Constants.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o: qpoases/INCLUDE/Indexlist.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o: qpoases/INCLUDE/MessageHandling.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o: qpoases/INCLUDE/QProblemB.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o: qpoases/INCLUDE/SubjectTo.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o: qpoases/INCLUDE/Types.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o: qpoases/INCLUDE/Utils.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o: qpoases/SRC/Bounds.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o: qpoases/SRC/Indexlist.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o: qpoases/SRC/MessageHandling.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o: qpoases/SRC/QProblemB.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o: qpoases/SRC/SubjectTo.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o: qpoases/SRC/Utils.ipp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o: qpoases/SRC/SubjectTo.cpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o: acado_qpoases_interface.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o: qpoases/INCLUDE/Constants.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o: qpoases/INCLUDE/Indexlist.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o: qpoases/INCLUDE/MessageHandling.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o: qpoases/INCLUDE/SubjectTo.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o: qpoases/INCLUDE/Types.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o: qpoases/INCLUDE/Utils.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o: qpoases/SRC/Indexlist.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o: qpoases/SRC/MessageHandling.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o: qpoases/SRC/SubjectTo.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o: qpoases/SRC/Utils.ipp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.o: qpoases/SRC/Utils.cpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.o: acado_qpoases_interface.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.o: qpoases/INCLUDE/Constants.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.o: qpoases/INCLUDE/MessageHandling.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.o: qpoases/INCLUDE/Types.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.o: qpoases/INCLUDE/Utils.hpp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.o: qpoases/SRC/MessageHandling.ipp
+CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.o: qpoases/SRC/Utils.ipp
+
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: ../include/mav_nonlinear_mpc/nonlinear_mpc.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /home/simhe502/catkin_ws/devel/include/geometry_msgs/Point.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /home/simhe502/catkin_ws/devel/include/geometry_msgs/PointStamped.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /home/simhe502/catkin_ws/devel/include/geometry_msgs/Pose.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /home/simhe502/catkin_ws/devel/include/geometry_msgs/PoseStamped.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /home/simhe502/catkin_ws/devel/include/geometry_msgs/Quaternion.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /home/simhe502/catkin_ws/devel/include/geometry_msgs/QuaternionStamped.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /home/simhe502/catkin_ws/devel/include/geometry_msgs/Transform.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /home/simhe502/catkin_ws/devel/include/geometry_msgs/TransformStamped.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /home/simhe502/catkin_ws/devel/include/geometry_msgs/Twist.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /home/simhe502/catkin_ws/devel/include/geometry_msgs/Vector3.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /home/simhe502/catkin_ws/devel/include/geometry_msgs/Vector3Stamped.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: ../src/nonlinear_mpc.cc
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/gazebo_msgs/GetModelState.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/gazebo_msgs/GetModelStateRequest.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/gazebo_msgs/GetModelStateResponse.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/advertise_options.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/advertise_service_options.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/assert.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/builtin_message_traits.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/common.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/console.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/console_backend.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/datatypes.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/duration.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/exception.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/exceptions.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/forwards.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/init.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/macros.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/master.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/message.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/message_event.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/message_forward.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/message_operations.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/message_traits.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/names.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/node_handle.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/param.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/parameter_adapter.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/platform.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/publisher.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/rate.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/ros.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/roscpp_serialization_macros.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/rostime_decl.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/serialization.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/serialized_message.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/service.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/service_callback_helper.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/service_client.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/service_client_options.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/service_server.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/service_traits.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/single_subscriber_publisher.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/spinner.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/static_assert.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/steady_timer.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/steady_timer_options.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/subscribe_options.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/subscriber.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/subscription_callback_helper.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/this_node.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/time.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/timer.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/timer_options.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/topic.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/transport_hints.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/types.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/wall_timer.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/ros/wall_timer_options.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/rosconsole/macros_generated.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/std_msgs/Header.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/std_srvs/Empty.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/std_srvs/EmptyRequest.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/std_srvs/EmptyResponse.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/tf/LinearMath/Matrix3x3.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/tf/LinearMath/MinMax.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/tf/LinearMath/QuadWord.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/tf/LinearMath/Quaternion.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/tf/LinearMath/Scalar.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/tf/LinearMath/Transform.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/tf/LinearMath/Vector3.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/tf/transform_datatypes.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/xmlrpcpp/XmlRpcDecl.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /opt/ros/noetic/include/xmlrpcpp/XmlRpcValue.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/Cholesky
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/Core
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/Dense
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/Eigen
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/Eigenvalues
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/Geometry
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/Householder
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/IterativeLinearSolvers
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/Jacobi
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/LU
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/OrderingMethods
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/QR
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/SVD
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/Sparse
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/SparseCholesky
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/SparseCore
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/SparseLU
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/SparseQR
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_LAPACKE.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Array.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Assign.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Block.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/ConditionEstimator.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/CwiseTernaryOp.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Dot.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/IO.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Inverse.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Map.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/MathFunctionsImpl.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Product.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Random.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Redux.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Ref.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Select.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Solve.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/SolverBase.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Stride.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Swap.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/AVX/Complex.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/AVX/MathFunctions.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/AVX/TypeCasting.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/AVX512/MathFunctions.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/AVX512/PacketMath.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/MathFunctions.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/CUDA/Complex.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/CUDA/Half.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/CUDA/MathFunctions.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMath.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMathHalf.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/CUDA/TypeCasting.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/ConjHelper.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/MathFunctions.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/TypeCasting.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/ZVector/Complex.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/ZVector/MathFunctions.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/ZVector/PacketMath.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/functors/BinaryFunctors.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/functors/NullaryFunctors.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/functors/StlFunctors.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/functors/TernaryFunctors.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/functors/UnaryFunctors.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_BLAS.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_BLAS.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_BLAS.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_BLAS.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_BLAS.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_BLAS.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_BLAS.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_BLAS.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/util/NonMPL2.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_LAPACKE.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_LAPACKE.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_LAPACKE.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IncompleteCholesky.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IncompleteLUT.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/LeastSquareConjugateGradient.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/SolveWithGuess.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/LU/InverseImpl.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_LAPACKE.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/OrderingMethods/Amd.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/OrderingMethods/Eigen_Colamd.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/OrderingMethods/Ordering.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_LAPACKE.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/QR/CompleteOrthogonalDecomposition.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_LAPACKE.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SVD/BDCSVD.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_LAPACKE.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SVD/SVDBase.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCholesky/SimplicialCholesky.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCholesky/SimplicialCholesky_impl.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/AmbiVector.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/CompressedStorage.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/ConservativeSparseSparseProduct.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/MappedSparseMatrix.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseAssign.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseBlock.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseColEtree.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseCompressedBase.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseCwiseBinaryOp.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseCwiseUnaryOp.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseDenseProduct.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseDiagonalProduct.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseDot.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseFuzzy.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseMap.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseMatrix.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseMatrixBase.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparsePermutation.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseProduct.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseRedux.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseRef.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseSelfAdjointView.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseSolverBase.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseSparseProductWithPruning.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseTranspose.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseTriangularView.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseUtil.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseVector.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseView.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/TriangularSolver.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLUImpl.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Memory.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Structs.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Utils.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_column_bmod.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_column_dfs.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_copy_to_ucol.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_gemm_kernel.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_heap_relax_snode.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_kernel_bmod.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_panel_bmod.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_panel_dfs.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_pivotL.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_pruneL.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_relax_snode.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/SparseQR/SparseQR.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/misc/Image.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/misc/RealSvd2x2.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/misc/blas.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/misc/lapacke.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/misc/lapacke_mangling.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: acado_auxiliary_functions.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: acado_common.h
+CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o: acado_qpoases_interface.hpp
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/flags.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/flags.make
new file mode 100644
index 0000000000000000000000000000000000000000..430a48b7858df3732756063f2abfeaf13b3642fb
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/flags.make
@@ -0,0 +1,17 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# compile C with /usr/bin/cc
+# compile CXX with /usr/bin/c++
+C_FLAGS = -O3 -DNDEBUG -fPIC  
+
+C_DEFINES = -DROSCONSOLE_BACKEND_LOG4CXX -DROS_BUILD_SHARED_LIBS=1 -DROS_PACKAGE_NAME=\"mav_nonlinear_mpc\" -Dmav_nonlinear_mpc_lib_EXPORTS
+
+C_INCLUDES = -I/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/include -I/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/include -I/home/simhe502/catkin_ws/devel/include -I/home/simhe502/catkin_ws/src/common_msgs/sensor_msgs/include -I/opt/ros/noetic/include -I/opt/ros/noetic/share/xmlrpcpp/cmake/../../../include/xmlrpcpp -I/usr/include/eigen3 -I/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver -I/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases -I/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE -I/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC 
+
+CXX_FLAGS =  -std=c++11 -O3 -DNDEBUG -fPIC  
+
+CXX_DEFINES = -DROSCONSOLE_BACKEND_LOG4CXX -DROS_BUILD_SHARED_LIBS=1 -DROS_PACKAGE_NAME=\"mav_nonlinear_mpc\" -Dmav_nonlinear_mpc_lib_EXPORTS
+
+CXX_INCLUDES = -I/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/include -I/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/include -I/home/simhe502/catkin_ws/devel/include -I/home/simhe502/catkin_ws/src/common_msgs/sensor_msgs/include -I/opt/ros/noetic/include -I/opt/ros/noetic/share/xmlrpcpp/cmake/../../../include/xmlrpcpp -I/usr/include/eigen3 -I/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver -I/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases -I/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE -I/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC 
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/link.txt b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/link.txt
new file mode 100644
index 0000000000000000000000000000000000000000..5bca8fc3acef45077f3de144c620997a2381eea6
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/link.txt
@@ -0,0 +1 @@
+/usr/bin/c++ -fPIC  -std=c++11 -O3 -DNDEBUG  -shared -Wl,-soname,libmav_nonlinear_mpc_lib.so -o devel/lib/libmav_nonlinear_mpc_lib.so CMakeFiles/mav_nonlinear_mpc_lib.dir/src/nonlinear_mpc.cc.o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Bounds.cpp.o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Constraints.cpp.o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/CyclingManager.cpp.o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Indexlist.cpp.o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/MessageHandling.cpp.o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblem.cpp.o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/QProblemB.cpp.o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/SubjectTo.cpp.o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/Utils.cpp.o CMakeFiles/mav_nonlinear_mpc_lib.dir/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp.o CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_qpoases_interface.cpp.o CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_integrator.c.o CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_solver.c.o CMakeFiles/mav_nonlinear_mpc_lib.dir/acado_auxiliary_functions.c.o  -Wl,-rpath,/opt/ros/noetic/lib: /opt/ros/noetic/lib/libdynamic_reconfigure_config_init_mutex.so /opt/ros/noetic/lib/libtf.so /opt/ros/noetic/lib/libtf2_ros.so /opt/ros/noetic/lib/libactionlib.so /opt/ros/noetic/lib/libmessage_filters.so /opt/ros/noetic/lib/libroscpp.so -lpthread /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.71.0 /usr/lib/x86_64-linux-gnu/libboost_filesystem.so.1.71.0 /opt/ros/noetic/lib/libxmlrpcpp.so /opt/ros/noetic/lib/libtf2.so /opt/ros/noetic/lib/libroscpp_serialization.so /opt/ros/noetic/lib/librosconsole.so /opt/ros/noetic/lib/librosconsole_log4cxx.so /opt/ros/noetic/lib/librosconsole_backend_interface.so -llog4cxx /usr/lib/x86_64-linux-gnu/libboost_regex.so.1.71.0 /opt/ros/noetic/lib/librostime.so /usr/lib/x86_64-linux-gnu/libboost_date_time.so.1.71.0 /opt/ros/noetic/lib/libcpp_common.so /usr/lib/x86_64-linux-gnu/libboost_system.so.1.71.0 /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.71.0 /usr/lib/x86_64-linux-gnu/libconsole_bridge.so.0.4 /opt/ros/noetic/lib/libdynamic_reconfigure_config_init_mutex.so /opt/ros/noetic/lib/libtf.so /opt/ros/noetic/lib/libtf2_ros.so /opt/ros/noetic/lib/libactionlib.so /opt/ros/noetic/lib/libmessage_filters.so /opt/ros/noetic/lib/libroscpp.so -lpthread /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.71.0 /usr/lib/x86_64-linux-gnu/libboost_filesystem.so.1.71.0 /opt/ros/noetic/lib/libxmlrpcpp.so /opt/ros/noetic/lib/libtf2.so /opt/ros/noetic/lib/libroscpp_serialization.so /opt/ros/noetic/lib/librosconsole.so /opt/ros/noetic/lib/librosconsole_log4cxx.so /opt/ros/noetic/lib/librosconsole_backend_interface.so -llog4cxx /usr/lib/x86_64-linux-gnu/libboost_regex.so.1.71.0 /opt/ros/noetic/lib/librostime.so /usr/lib/x86_64-linux-gnu/libboost_date_time.so.1.71.0 /opt/ros/noetic/lib/libcpp_common.so /usr/lib/x86_64-linux-gnu/libboost_system.so.1.71.0 /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.71.0 /usr/lib/x86_64-linux-gnu/libconsole_bridge.so.0.4 
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..e6cabbba752849471655d90b010bc2afab975eca
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/progress.make
@@ -0,0 +1,17 @@
+CMAKE_PROGRESS_1 = 10
+CMAKE_PROGRESS_2 = 11
+CMAKE_PROGRESS_3 = 12
+CMAKE_PROGRESS_4 = 13
+CMAKE_PROGRESS_5 = 14
+CMAKE_PROGRESS_6 = 15
+CMAKE_PROGRESS_7 = 16
+CMAKE_PROGRESS_8 = 17
+CMAKE_PROGRESS_9 = 18
+CMAKE_PROGRESS_10 = 19
+CMAKE_PROGRESS_11 = 20
+CMAKE_PROGRESS_12 = 21
+CMAKE_PROGRESS_13 = 22
+CMAKE_PROGRESS_14 = 23
+CMAKE_PROGRESS_15 = 24
+CMAKE_PROGRESS_16 = 25
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_package.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_package.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_package.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_package.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_package.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..529bc2d80a08372b69136291135d11cb64b1e535
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_package.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for mav_nonlinear_mpc_package.
+
+# Include the progress variables for this target.
+include CMakeFiles/mav_nonlinear_mpc_package.dir/progress.make
+
+mav_nonlinear_mpc_package: CMakeFiles/mav_nonlinear_mpc_package.dir/build.make
+
+.PHONY : mav_nonlinear_mpc_package
+
+# Rule to build all files generated by this target.
+CMakeFiles/mav_nonlinear_mpc_package.dir/build: mav_nonlinear_mpc_package
+
+.PHONY : CMakeFiles/mav_nonlinear_mpc_package.dir/build
+
+CMakeFiles/mav_nonlinear_mpc_package.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/mav_nonlinear_mpc_package.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/mav_nonlinear_mpc_package.dir/clean
+
+CMakeFiles/mav_nonlinear_mpc_package.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_package.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/mav_nonlinear_mpc_package.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_package.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_package.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..702d9bb44593f89824377e2e32778a9aaa97f979
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_package.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/mav_nonlinear_mpc_package.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_package.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_package.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_package.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/CXX.includecache b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/CXX.includecache
new file mode 100644
index 0000000000000000000000000000000000000000..7f6d3134042eab295d5f4dca6b8998c37e1f653f
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/CXX.includecache
@@ -0,0 +1,2640 @@
+#IncludeRegexLine: ^[ 	]*[#%][ 	]*(include|import)[ 	]*[<"]([^">]+)([">])
+
+#IncludeRegexScan: ^.*$
+
+#IncludeRegexComplain: ^$
+
+#IncludeRegexTransform: 
+
+../include/mav_nonlinear_mpc/nonlinear_mpc.h
+ros/ros.h
+-
+Eigen/Eigen
+-
+stdio.h
+-
+acado_common.h
+../include/mav_nonlinear_mpc/acado_common.h
+acado_auxiliary_functions.h
+../include/mav_nonlinear_mpc/acado_auxiliary_functions.h
+std_srvs/Empty.h
+-
+geometry_msgs/Twist.h
+-
+geometry_msgs/PoseStamped.h
+-
+gazebo_msgs/GetModelState.h
+-
+
+../include/mav_nonlinear_mpc/nonlinear_mpc_node.h
+boost/bind.hpp
+-
+Eigen/Eigen
+-
+stdio.h
+-
+ros/ros.h
+-
+ros/callback_queue.h
+-
+dynamic_reconfigure/server.h
+-
+mav_nonlinear_mpc/NonLinearMPCConfig.h
+-
+mav_nonlinear_mpc/nonlinear_mpc.h
+-
+
+/home/simhe502/catkin_ws/devel/include/geometry_msgs/Point.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+
+/home/simhe502/catkin_ws/devel/include/geometry_msgs/Pose.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+geometry_msgs/Point.h
+-
+geometry_msgs/Quaternion.h
+-
+
+/home/simhe502/catkin_ws/devel/include/geometry_msgs/PoseStamped.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+std_msgs/Header.h
+-
+geometry_msgs/Pose.h
+-
+
+/home/simhe502/catkin_ws/devel/include/geometry_msgs/Quaternion.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+
+/home/simhe502/catkin_ws/devel/include/geometry_msgs/Twist.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+geometry_msgs/Vector3.h
+-
+geometry_msgs/Vector3.h
+-
+
+/home/simhe502/catkin_ws/devel/include/geometry_msgs/Vector3.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/src/nonlinear_mpc_node.cc
+ros/ros.h
+-
+mav_nonlinear_mpc/nonlinear_mpc_node.h
+-
+
+/opt/ros/noetic/include/dynamic_reconfigure/BoolParameter.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+
+/opt/ros/noetic/include/dynamic_reconfigure/Config.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+dynamic_reconfigure/BoolParameter.h
+-
+dynamic_reconfigure/IntParameter.h
+-
+dynamic_reconfigure/StrParameter.h
+-
+dynamic_reconfigure/DoubleParameter.h
+-
+dynamic_reconfigure/GroupState.h
+-
+
+/opt/ros/noetic/include/dynamic_reconfigure/ConfigDescription.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+dynamic_reconfigure/Group.h
+-
+dynamic_reconfigure/Config.h
+-
+dynamic_reconfigure/Config.h
+-
+dynamic_reconfigure/Config.h
+-
+
+/opt/ros/noetic/include/dynamic_reconfigure/DoubleParameter.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+
+/opt/ros/noetic/include/dynamic_reconfigure/Group.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+dynamic_reconfigure/ParamDescription.h
+-
+
+/opt/ros/noetic/include/dynamic_reconfigure/GroupState.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+
+/opt/ros/noetic/include/dynamic_reconfigure/IntParameter.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+
+/opt/ros/noetic/include/dynamic_reconfigure/ParamDescription.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+
+/opt/ros/noetic/include/dynamic_reconfigure/Reconfigure.h
+ros/service_traits.h
+-
+dynamic_reconfigure/ReconfigureRequest.h
+-
+dynamic_reconfigure/ReconfigureResponse.h
+-
+
+/opt/ros/noetic/include/dynamic_reconfigure/ReconfigureRequest.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+dynamic_reconfigure/Config.h
+-
+
+/opt/ros/noetic/include/dynamic_reconfigure/ReconfigureResponse.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+dynamic_reconfigure/Config.h
+-
+
+/opt/ros/noetic/include/dynamic_reconfigure/StrParameter.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+
+/opt/ros/noetic/include/dynamic_reconfigure/config_init_mutex.h
+boost/thread/mutex.hpp
+-
+ros/macros.h
+-
+
+/opt/ros/noetic/include/dynamic_reconfigure/config_tools.h
+string
+-
+vector
+-
+dynamic_reconfigure/Config.h
+-
+dynamic_reconfigure/Group.h
+-
+
+/opt/ros/noetic/include/dynamic_reconfigure/server.h
+boost/function.hpp
+-
+boost/thread/recursive_mutex.hpp
+-
+ros/node_handle.h
+-
+dynamic_reconfigure/ConfigDescription.h
+-
+dynamic_reconfigure/Reconfigure.h
+-
+
+/opt/ros/noetic/include/gazebo_msgs/GetModelState.h
+ros/service_traits.h
+-
+gazebo_msgs/GetModelStateRequest.h
+-
+gazebo_msgs/GetModelStateResponse.h
+-
+
+/opt/ros/noetic/include/gazebo_msgs/GetModelStateRequest.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+
+/opt/ros/noetic/include/gazebo_msgs/GetModelStateResponse.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+std_msgs/Header.h
+-
+geometry_msgs/Pose.h
+-
+geometry_msgs/Twist.h
+-
+
+/opt/ros/noetic/include/ros/advertise_options.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/message_traits.h
+/opt/ros/noetic/include/ros/ros/message_traits.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+
+/opt/ros/noetic/include/ros/advertise_service_options.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/service_callback_helper.h
+/opt/ros/noetic/include/ros/ros/service_callback_helper.h
+ros/service_traits.h
+/opt/ros/noetic/include/ros/ros/service_traits.h
+ros/message_traits.h
+/opt/ros/noetic/include/ros/ros/message_traits.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+
+/opt/ros/noetic/include/ros/assert.h
+ros/console.h
+/opt/ros/noetic/include/ros/ros/console.h
+ros/static_assert.h
+/opt/ros/noetic/include/ros/ros/static_assert.h
+ros/platform.h
+-
+stdlib.h
+-
+
+/opt/ros/noetic/include/ros/builtin_message_traits.h
+message_traits.h
+/opt/ros/noetic/include/ros/message_traits.h
+ros/time.h
+/opt/ros/noetic/include/ros/ros/time.h
+
+/opt/ros/noetic/include/ros/callback_queue.h
+ros/callback_queue_interface.h
+/opt/ros/noetic/include/ros/ros/callback_queue_interface.h
+ros/time.h
+/opt/ros/noetic/include/ros/ros/time.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+boost/shared_ptr.hpp
+-
+boost/thread/condition_variable.hpp
+-
+boost/thread/mutex.hpp
+-
+boost/thread/shared_mutex.hpp
+-
+boost/thread/tss.hpp
+-
+list
+-
+deque
+-
+
+/opt/ros/noetic/include/ros/callback_queue_interface.h
+boost/shared_ptr.hpp
+-
+common.h
+/opt/ros/noetic/include/ros/common.h
+ros/types.h
+/opt/ros/noetic/include/ros/ros/types.h
+
+/opt/ros/noetic/include/ros/common.h
+stdint.h
+-
+assert.h
+-
+stddef.h
+-
+string
+-
+ros/assert.h
+/opt/ros/noetic/include/ros/ros/assert.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/serialized_message.h
+/opt/ros/noetic/include/ros/ros/serialized_message.h
+boost/shared_array.hpp
+-
+ros/macros.h
+-
+
+/opt/ros/noetic/include/ros/console.h
+console_backend.h
+/opt/ros/noetic/include/ros/console_backend.h
+cstdio
+-
+sstream
+-
+ros/time.h
+-
+cstdarg
+-
+ros/macros.h
+-
+map
+-
+vector
+-
+log4cxx/level.h
+/opt/ros/noetic/include/ros/log4cxx/level.h
+rosconsole/macros_generated.h
+/opt/ros/noetic/include/ros/rosconsole/macros_generated.h
+
+/opt/ros/noetic/include/ros/console_backend.h
+ros/macros.h
+-
+
+/opt/ros/noetic/include/ros/datatypes.h
+string
+-
+vector
+-
+map
+-
+set
+-
+list
+-
+boost/shared_ptr.hpp
+-
+
+/opt/ros/noetic/include/ros/duration.h
+iostream
+-
+math.h
+-
+stdexcept
+-
+climits
+-
+stdint.h
+-
+rostime_decl.h
+/opt/ros/noetic/include/ros/rostime_decl.h
+
+/opt/ros/noetic/include/ros/exception.h
+stdexcept
+-
+
+/opt/ros/noetic/include/ros/exceptions.h
+ros/exception.h
+-
+
+/opt/ros/noetic/include/ros/forwards.h
+string
+-
+vector
+-
+map
+-
+set
+-
+list
+-
+boost/shared_ptr.hpp
+-
+boost/make_shared.hpp
+-
+boost/weak_ptr.hpp
+-
+boost/function.hpp
+-
+ros/time.h
+-
+ros/macros.h
+-
+exceptions.h
+/opt/ros/noetic/include/ros/exceptions.h
+ros/datatypes.h
+/opt/ros/noetic/include/ros/ros/datatypes.h
+
+/opt/ros/noetic/include/ros/init.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/spinner.h
+/opt/ros/noetic/include/ros/ros/spinner.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+
+/opt/ros/noetic/include/ros/macros.h
+
+/opt/ros/noetic/include/ros/master.h
+forwards.h
+/opt/ros/noetic/include/ros/forwards.h
+xmlrpcpp/XmlRpcValue.h
+/opt/ros/noetic/include/ros/xmlrpcpp/XmlRpcValue.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+
+/opt/ros/noetic/include/ros/message.h
+ros/macros.h
+/opt/ros/noetic/include/ros/ros/macros.h
+ros/assert.h
+/opt/ros/noetic/include/ros/ros/assert.h
+string
+-
+string.h
+-
+boost/shared_ptr.hpp
+-
+boost/array.hpp
+-
+stdint.h
+-
+
+/opt/ros/noetic/include/ros/message_event.h
+ros/time.h
+/opt/ros/noetic/include/ros/ros/time.h
+ros/datatypes.h
+-
+ros/message_traits.h
+-
+boost/type_traits/is_void.hpp
+-
+boost/type_traits/is_base_of.hpp
+-
+boost/type_traits/is_const.hpp
+-
+boost/type_traits/add_const.hpp
+-
+boost/type_traits/remove_const.hpp
+-
+boost/utility/enable_if.hpp
+-
+boost/function.hpp
+-
+boost/make_shared.hpp
+-
+
+/opt/ros/noetic/include/ros/message_forward.h
+cstddef
+-
+memory
+-
+
+/opt/ros/noetic/include/ros/message_operations.h
+ostream
+-
+
+/opt/ros/noetic/include/ros/message_traits.h
+message_forward.h
+/opt/ros/noetic/include/ros/message_forward.h
+ros/time.h
+-
+string
+-
+boost/utility/enable_if.hpp
+-
+boost/type_traits/remove_const.hpp
+-
+boost/type_traits/remove_reference.hpp
+-
+
+/opt/ros/noetic/include/ros/names.h
+forwards.h
+/opt/ros/noetic/include/ros/forwards.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+
+/opt/ros/noetic/include/ros/node_handle.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/publisher.h
+/opt/ros/noetic/include/ros/ros/publisher.h
+ros/subscriber.h
+/opt/ros/noetic/include/ros/ros/subscriber.h
+ros/service_server.h
+/opt/ros/noetic/include/ros/ros/service_server.h
+ros/service_client.h
+/opt/ros/noetic/include/ros/ros/service_client.h
+ros/timer.h
+/opt/ros/noetic/include/ros/ros/timer.h
+ros/rate.h
+/opt/ros/noetic/include/ros/ros/rate.h
+ros/wall_timer.h
+/opt/ros/noetic/include/ros/ros/wall_timer.h
+ros/steady_timer.h
+/opt/ros/noetic/include/ros/ros/steady_timer.h
+ros/advertise_options.h
+/opt/ros/noetic/include/ros/ros/advertise_options.h
+ros/advertise_service_options.h
+/opt/ros/noetic/include/ros/ros/advertise_service_options.h
+ros/subscribe_options.h
+/opt/ros/noetic/include/ros/ros/subscribe_options.h
+ros/service_client_options.h
+/opt/ros/noetic/include/ros/ros/service_client_options.h
+ros/timer_options.h
+/opt/ros/noetic/include/ros/ros/timer_options.h
+ros/wall_timer_options.h
+/opt/ros/noetic/include/ros/ros/wall_timer_options.h
+ros/spinner.h
+/opt/ros/noetic/include/ros/ros/spinner.h
+ros/init.h
+/opt/ros/noetic/include/ros/ros/init.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+boost/bind.hpp
+-
+xmlrpcpp/XmlRpcValue.h
+-
+
+/opt/ros/noetic/include/ros/param.h
+forwards.h
+/opt/ros/noetic/include/ros/forwards.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+xmlrpcpp/XmlRpcValue.h
+/opt/ros/noetic/include/ros/xmlrpcpp/XmlRpcValue.h
+vector
+-
+map
+-
+
+/opt/ros/noetic/include/ros/parameter_adapter.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/message_event.h
+/opt/ros/noetic/include/ros/ros/message_event.h
+ros/static_assert.h
+-
+boost/type_traits/add_const.hpp
+-
+boost/type_traits/remove_const.hpp
+-
+boost/type_traits/remove_reference.hpp
+-
+
+/opt/ros/noetic/include/ros/platform.h
+stdlib.h
+-
+string
+-
+
+/opt/ros/noetic/include/ros/publisher.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/common.h
+/opt/ros/noetic/include/ros/ros/common.h
+ros/message.h
+/opt/ros/noetic/include/ros/ros/message.h
+ros/serialization.h
+/opt/ros/noetic/include/ros/ros/serialization.h
+boost/bind.hpp
+-
+boost/thread/mutex.hpp
+-
+
+/opt/ros/noetic/include/ros/rate.h
+ros/time.h
+/opt/ros/noetic/include/ros/ros/time.h
+rostime_decl.h
+/opt/ros/noetic/include/ros/rostime_decl.h
+
+/opt/ros/noetic/include/ros/ros.h
+ros/time.h
+/opt/ros/noetic/include/ros/ros/time.h
+ros/rate.h
+/opt/ros/noetic/include/ros/ros/rate.h
+ros/console.h
+/opt/ros/noetic/include/ros/ros/console.h
+ros/assert.h
+/opt/ros/noetic/include/ros/ros/assert.h
+ros/common.h
+/opt/ros/noetic/include/ros/ros/common.h
+ros/types.h
+/opt/ros/noetic/include/ros/ros/types.h
+ros/node_handle.h
+/opt/ros/noetic/include/ros/ros/node_handle.h
+ros/publisher.h
+/opt/ros/noetic/include/ros/ros/publisher.h
+ros/single_subscriber_publisher.h
+/opt/ros/noetic/include/ros/ros/single_subscriber_publisher.h
+ros/service_server.h
+/opt/ros/noetic/include/ros/ros/service_server.h
+ros/subscriber.h
+/opt/ros/noetic/include/ros/ros/subscriber.h
+ros/service.h
+/opt/ros/noetic/include/ros/ros/service.h
+ros/init.h
+/opt/ros/noetic/include/ros/ros/init.h
+ros/master.h
+/opt/ros/noetic/include/ros/ros/master.h
+ros/this_node.h
+/opt/ros/noetic/include/ros/ros/this_node.h
+ros/param.h
+/opt/ros/noetic/include/ros/ros/param.h
+ros/topic.h
+/opt/ros/noetic/include/ros/ros/topic.h
+ros/names.h
+/opt/ros/noetic/include/ros/ros/names.h
+
+/opt/ros/noetic/include/ros/roscpp_serialization_macros.h
+ros/macros.h
+-
+
+/opt/ros/noetic/include/ros/rostime_decl.h
+ros/macros.h
+-
+
+/opt/ros/noetic/include/ros/serialization.h
+roscpp_serialization_macros.h
+/opt/ros/noetic/include/ros/roscpp_serialization_macros.h
+ros/types.h
+-
+ros/time.h
+-
+serialized_message.h
+/opt/ros/noetic/include/ros/serialized_message.h
+ros/message_traits.h
+/opt/ros/noetic/include/ros/ros/message_traits.h
+ros/builtin_message_traits.h
+/opt/ros/noetic/include/ros/ros/builtin_message_traits.h
+ros/exception.h
+/opt/ros/noetic/include/ros/ros/exception.h
+ros/datatypes.h
+/opt/ros/noetic/include/ros/ros/datatypes.h
+vector
+-
+map
+-
+boost/array.hpp
+-
+boost/call_traits.hpp
+-
+boost/utility/enable_if.hpp
+-
+boost/mpl/and.hpp
+-
+boost/mpl/or.hpp
+-
+boost/mpl/not.hpp
+-
+cstring
+-
+
+/opt/ros/noetic/include/ros/serialized_message.h
+roscpp_serialization_macros.h
+/opt/ros/noetic/include/ros/roscpp_serialization_macros.h
+boost/shared_array.hpp
+-
+boost/shared_ptr.hpp
+-
+
+/opt/ros/noetic/include/ros/service.h
+string
+-
+ros/common.h
+/opt/ros/noetic/include/ros/ros/common.h
+ros/message.h
+/opt/ros/noetic/include/ros/ros/message.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/node_handle.h
+/opt/ros/noetic/include/ros/ros/node_handle.h
+ros/service_traits.h
+/opt/ros/noetic/include/ros/ros/service_traits.h
+ros/names.h
+/opt/ros/noetic/include/ros/ros/names.h
+boost/shared_ptr.hpp
+-
+
+/opt/ros/noetic/include/ros/service_callback_helper.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/common.h
+/opt/ros/noetic/include/ros/ros/common.h
+ros/message.h
+/opt/ros/noetic/include/ros/ros/message.h
+ros/message_traits.h
+/opt/ros/noetic/include/ros/ros/message_traits.h
+ros/service_traits.h
+/opt/ros/noetic/include/ros/ros/service_traits.h
+ros/serialization.h
+/opt/ros/noetic/include/ros/ros/serialization.h
+boost/type_traits/is_base_of.hpp
+-
+boost/utility/enable_if.hpp
+-
+
+/opt/ros/noetic/include/ros/service_client.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/common.h
+/opt/ros/noetic/include/ros/ros/common.h
+ros/service_traits.h
+/opt/ros/noetic/include/ros/ros/service_traits.h
+ros/serialization.h
+/opt/ros/noetic/include/ros/ros/serialization.h
+
+/opt/ros/noetic/include/ros/service_client_options.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+ros/service_traits.h
+/opt/ros/noetic/include/ros/ros/service_traits.h
+
+/opt/ros/noetic/include/ros/service_server.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+
+/opt/ros/noetic/include/ros/service_traits.h
+boost/type_traits/remove_reference.hpp
+-
+boost/type_traits/remove_const.hpp
+-
+
+/opt/ros/noetic/include/ros/single_subscriber_publisher.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/serialization.h
+/opt/ros/noetic/include/ros/ros/serialization.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+boost/utility.hpp
+-
+
+/opt/ros/noetic/include/ros/spinner.h
+ros/types.h
+/opt/ros/noetic/include/ros/ros/types.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+boost/shared_ptr.hpp
+-
+
+/opt/ros/noetic/include/ros/static_assert.h
+boost/static_assert.hpp
+-
+
+/opt/ros/noetic/include/ros/steady_timer.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+forwards.h
+/opt/ros/noetic/include/ros/forwards.h
+steady_timer_options.h
+/opt/ros/noetic/include/ros/steady_timer_options.h
+
+/opt/ros/noetic/include/ros/steady_timer_options.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+
+/opt/ros/noetic/include/ros/subscribe_options.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+ros/transport_hints.h
+/opt/ros/noetic/include/ros/ros/transport_hints.h
+ros/message_traits.h
+/opt/ros/noetic/include/ros/ros/message_traits.h
+subscription_callback_helper.h
+/opt/ros/noetic/include/ros/subscription_callback_helper.h
+
+/opt/ros/noetic/include/ros/subscriber.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/subscription_callback_helper.h
+/opt/ros/noetic/include/ros/ros/subscription_callback_helper.h
+
+/opt/ros/noetic/include/ros/subscription_callback_helper.h
+typeinfo
+-
+common.h
+/opt/ros/noetic/include/ros/common.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+ros/parameter_adapter.h
+/opt/ros/noetic/include/ros/ros/parameter_adapter.h
+ros/message_traits.h
+/opt/ros/noetic/include/ros/ros/message_traits.h
+ros/builtin_message_traits.h
+/opt/ros/noetic/include/ros/ros/builtin_message_traits.h
+ros/serialization.h
+/opt/ros/noetic/include/ros/ros/serialization.h
+ros/message_event.h
+/opt/ros/noetic/include/ros/ros/message_event.h
+ros/static_assert.h
+-
+boost/type_traits/add_const.hpp
+-
+boost/type_traits/remove_const.hpp
+-
+boost/type_traits/remove_reference.hpp
+-
+boost/type_traits/is_base_of.hpp
+-
+boost/utility/enable_if.hpp
+-
+boost/make_shared.hpp
+-
+
+/opt/ros/noetic/include/ros/this_node.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+forwards.h
+/opt/ros/noetic/include/ros/forwards.h
+
+/opt/ros/noetic/include/ros/time.h
+ros/platform.h
+-
+iostream
+-
+cmath
+-
+ros/exception.h
+-
+duration.h
+/opt/ros/noetic/include/ros/duration.h
+boost/math/special_functions/round.hpp
+-
+rostime_decl.h
+/opt/ros/noetic/include/ros/rostime_decl.h
+sys/timeb.h
+-
+sys/time.h
+-
+
+/opt/ros/noetic/include/ros/timer.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+forwards.h
+/opt/ros/noetic/include/ros/forwards.h
+timer_options.h
+/opt/ros/noetic/include/ros/timer_options.h
+
+/opt/ros/noetic/include/ros/timer_options.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+
+/opt/ros/noetic/include/ros/topic.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+node_handle.h
+/opt/ros/noetic/include/ros/node_handle.h
+boost/shared_ptr.hpp
+-
+
+/opt/ros/noetic/include/ros/transport_hints.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+boost/lexical_cast.hpp
+-
+
+/opt/ros/noetic/include/ros/types.h
+stdint.h
+-
+
+/opt/ros/noetic/include/ros/wall_timer.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+forwards.h
+/opt/ros/noetic/include/ros/forwards.h
+wall_timer_options.h
+/opt/ros/noetic/include/ros/wall_timer_options.h
+
+/opt/ros/noetic/include/ros/wall_timer_options.h
+common.h
+/opt/ros/noetic/include/ros/common.h
+ros/forwards.h
+/opt/ros/noetic/include/ros/ros/forwards.h
+
+/opt/ros/noetic/include/rosconsole/macros_generated.h
+
+/opt/ros/noetic/include/std_msgs/Header.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+
+/opt/ros/noetic/include/std_srvs/Empty.h
+ros/service_traits.h
+-
+std_srvs/EmptyRequest.h
+-
+std_srvs/EmptyResponse.h
+-
+
+/opt/ros/noetic/include/std_srvs/EmptyRequest.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+
+/opt/ros/noetic/include/std_srvs/EmptyResponse.h
+string
+-
+vector
+-
+memory
+-
+ros/types.h
+-
+ros/serialization.h
+-
+ros/builtin_message_traits.h
+-
+ros/message_operations.h
+-
+
+/opt/ros/noetic/include/xmlrpcpp/XmlRpcDecl.h
+ros/macros.h
+-
+
+/opt/ros/noetic/include/xmlrpcpp/XmlRpcValue.h
+xmlrpcpp/XmlRpcDecl.h
+/opt/ros/noetic/include/xmlrpcpp/xmlrpcpp/XmlRpcDecl.h
+map
+-
+string
+-
+vector
+-
+time.h
+-
+
+/usr/include/eigen3/Eigen/Cholesky
+Core
+/usr/include/eigen3/Eigen/Core
+Jacobi
+/usr/include/eigen3/Eigen/Jacobi
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+src/Cholesky/LLT.h
+/usr/include/eigen3/Eigen/src/Cholesky/LLT.h
+src/Cholesky/LDLT.h
+/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h
+mkl_lapacke.h
+/usr/include/eigen3/Eigen/mkl_lapacke.h
+src/misc/lapacke.h
+/usr/include/eigen3/Eigen/src/misc/lapacke.h
+src/Cholesky/LLT_LAPACKE.h
+/usr/include/eigen3/Eigen/src/Cholesky/LLT_LAPACKE.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/Core
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+cuda_runtime.h
+-
+new
+-
+src/Core/util/Macros.h
+/usr/include/eigen3/Eigen/src/Core/util/Macros.h
+complex
+-
+src/Core/util/MKL_support.h
+/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h
+malloc.h
+-
+immintrin.h
+-
+mmintrin.h
+-
+emmintrin.h
+-
+xmmintrin.h
+-
+pmmintrin.h
+-
+tmmintrin.h
+-
+smmintrin.h
+-
+nmmintrin.h
+-
+immintrin.h
+-
+altivec.h
+-
+altivec.h
+-
+arm_neon.h
+-
+vecintrin.h
+-
+vector_types.h
+-
+host_defines.h
+-
+cuda_fp16.h
+-
+omp.h
+-
+cerrno
+-
+cstddef
+-
+cstdlib
+-
+cmath
+-
+cassert
+-
+functional
+-
+iosfwd
+-
+cstring
+-
+string
+-
+limits
+-
+climits
+-
+algorithm
+-
+type_traits
+-
+iostream
+-
+intrin.h
+-
+src/Core/util/Constants.h
+/usr/include/eigen3/Eigen/src/Core/util/Constants.h
+src/Core/util/Meta.h
+/usr/include/eigen3/Eigen/src/Core/util/Meta.h
+src/Core/util/ForwardDeclarations.h
+/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h
+src/Core/util/StaticAssert.h
+/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h
+src/Core/util/XprHelper.h
+/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h
+src/Core/util/Memory.h
+/usr/include/eigen3/Eigen/src/Core/util/Memory.h
+src/Core/NumTraits.h
+/usr/include/eigen3/Eigen/src/Core/NumTraits.h
+src/Core/MathFunctions.h
+/usr/include/eigen3/Eigen/src/Core/MathFunctions.h
+src/Core/GenericPacketMath.h
+/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h
+src/Core/MathFunctionsImpl.h
+/usr/include/eigen3/Eigen/src/Core/MathFunctionsImpl.h
+src/Core/arch/Default/ConjHelper.h
+/usr/include/eigen3/Eigen/src/Core/arch/Default/ConjHelper.h
+src/Core/arch/SSE/PacketMath.h
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h
+src/Core/arch/AVX/PacketMath.h
+/usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h
+src/Core/arch/AVX512/PacketMath.h
+/usr/include/eigen3/Eigen/src/Core/arch/AVX512/PacketMath.h
+src/Core/arch/AVX512/MathFunctions.h
+/usr/include/eigen3/Eigen/src/Core/arch/AVX512/MathFunctions.h
+src/Core/arch/SSE/PacketMath.h
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h
+src/Core/arch/SSE/Complex.h
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h
+src/Core/arch/SSE/MathFunctions.h
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h
+src/Core/arch/AVX/PacketMath.h
+/usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h
+src/Core/arch/AVX/MathFunctions.h
+/usr/include/eigen3/Eigen/src/Core/arch/AVX/MathFunctions.h
+src/Core/arch/AVX/Complex.h
+/usr/include/eigen3/Eigen/src/Core/arch/AVX/Complex.h
+src/Core/arch/AVX/TypeCasting.h
+/usr/include/eigen3/Eigen/src/Core/arch/AVX/TypeCasting.h
+src/Core/arch/SSE/TypeCasting.h
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/TypeCasting.h
+src/Core/arch/SSE/PacketMath.h
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h
+src/Core/arch/SSE/MathFunctions.h
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h
+src/Core/arch/SSE/Complex.h
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h
+src/Core/arch/SSE/TypeCasting.h
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/TypeCasting.h
+src/Core/arch/AltiVec/PacketMath.h
+/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h
+src/Core/arch/AltiVec/MathFunctions.h
+/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/MathFunctions.h
+src/Core/arch/AltiVec/Complex.h
+/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h
+src/Core/arch/NEON/PacketMath.h
+/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h
+src/Core/arch/NEON/MathFunctions.h
+/usr/include/eigen3/Eigen/src/Core/arch/NEON/MathFunctions.h
+src/Core/arch/NEON/Complex.h
+/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h
+src/Core/arch/ZVector/PacketMath.h
+/usr/include/eigen3/Eigen/src/Core/arch/ZVector/PacketMath.h
+src/Core/arch/ZVector/MathFunctions.h
+/usr/include/eigen3/Eigen/src/Core/arch/ZVector/MathFunctions.h
+src/Core/arch/ZVector/Complex.h
+/usr/include/eigen3/Eigen/src/Core/arch/ZVector/Complex.h
+src/Core/arch/CUDA/Half.h
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/Half.h
+src/Core/arch/CUDA/PacketMathHalf.h
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMathHalf.h
+src/Core/arch/CUDA/TypeCasting.h
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/TypeCasting.h
+src/Core/arch/CUDA/PacketMath.h
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMath.h
+src/Core/arch/CUDA/MathFunctions.h
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/MathFunctions.h
+src/Core/arch/Default/Settings.h
+/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h
+src/Core/functors/TernaryFunctors.h
+/usr/include/eigen3/Eigen/src/Core/functors/TernaryFunctors.h
+src/Core/functors/BinaryFunctors.h
+/usr/include/eigen3/Eigen/src/Core/functors/BinaryFunctors.h
+src/Core/functors/UnaryFunctors.h
+/usr/include/eigen3/Eigen/src/Core/functors/UnaryFunctors.h
+src/Core/functors/NullaryFunctors.h
+/usr/include/eigen3/Eigen/src/Core/functors/NullaryFunctors.h
+src/Core/functors/StlFunctors.h
+/usr/include/eigen3/Eigen/src/Core/functors/StlFunctors.h
+src/Core/functors/AssignmentFunctors.h
+/usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h
+src/Core/arch/CUDA/Complex.h
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/Complex.h
+src/Core/IO.h
+/usr/include/eigen3/Eigen/src/Core/IO.h
+src/Core/DenseCoeffsBase.h
+/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h
+src/Core/DenseBase.h
+/usr/include/eigen3/Eigen/src/Core/DenseBase.h
+src/Core/MatrixBase.h
+/usr/include/eigen3/Eigen/src/Core/MatrixBase.h
+src/Core/EigenBase.h
+/usr/include/eigen3/Eigen/src/Core/EigenBase.h
+src/Core/Product.h
+/usr/include/eigen3/Eigen/src/Core/Product.h
+src/Core/CoreEvaluators.h
+/usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h
+src/Core/AssignEvaluator.h
+/usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h
+src/Core/Assign.h
+/usr/include/eigen3/Eigen/src/Core/Assign.h
+src/Core/ArrayBase.h
+/usr/include/eigen3/Eigen/src/Core/ArrayBase.h
+src/Core/util/BlasUtil.h
+/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h
+src/Core/DenseStorage.h
+/usr/include/eigen3/Eigen/src/Core/DenseStorage.h
+src/Core/NestByValue.h
+/usr/include/eigen3/Eigen/src/Core/NestByValue.h
+src/Core/ReturnByValue.h
+/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h
+src/Core/NoAlias.h
+/usr/include/eigen3/Eigen/src/Core/NoAlias.h
+src/Core/PlainObjectBase.h
+/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h
+src/Core/Matrix.h
+/usr/include/eigen3/Eigen/src/Core/Matrix.h
+src/Core/Array.h
+/usr/include/eigen3/Eigen/src/Core/Array.h
+src/Core/CwiseTernaryOp.h
+/usr/include/eigen3/Eigen/src/Core/CwiseTernaryOp.h
+src/Core/CwiseBinaryOp.h
+/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h
+src/Core/CwiseUnaryOp.h
+/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h
+src/Core/CwiseNullaryOp.h
+/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h
+src/Core/CwiseUnaryView.h
+/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h
+src/Core/SelfCwiseBinaryOp.h
+/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h
+src/Core/Dot.h
+/usr/include/eigen3/Eigen/src/Core/Dot.h
+src/Core/StableNorm.h
+/usr/include/eigen3/Eigen/src/Core/StableNorm.h
+src/Core/Stride.h
+/usr/include/eigen3/Eigen/src/Core/Stride.h
+src/Core/MapBase.h
+/usr/include/eigen3/Eigen/src/Core/MapBase.h
+src/Core/Map.h
+/usr/include/eigen3/Eigen/src/Core/Map.h
+src/Core/Ref.h
+/usr/include/eigen3/Eigen/src/Core/Ref.h
+src/Core/Block.h
+/usr/include/eigen3/Eigen/src/Core/Block.h
+src/Core/VectorBlock.h
+/usr/include/eigen3/Eigen/src/Core/VectorBlock.h
+src/Core/Transpose.h
+/usr/include/eigen3/Eigen/src/Core/Transpose.h
+src/Core/DiagonalMatrix.h
+/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h
+src/Core/Diagonal.h
+/usr/include/eigen3/Eigen/src/Core/Diagonal.h
+src/Core/DiagonalProduct.h
+/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h
+src/Core/Redux.h
+/usr/include/eigen3/Eigen/src/Core/Redux.h
+src/Core/Visitor.h
+/usr/include/eigen3/Eigen/src/Core/Visitor.h
+src/Core/Fuzzy.h
+/usr/include/eigen3/Eigen/src/Core/Fuzzy.h
+src/Core/Swap.h
+/usr/include/eigen3/Eigen/src/Core/Swap.h
+src/Core/CommaInitializer.h
+/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h
+src/Core/GeneralProduct.h
+/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h
+src/Core/Solve.h
+/usr/include/eigen3/Eigen/src/Core/Solve.h
+src/Core/Inverse.h
+/usr/include/eigen3/Eigen/src/Core/Inverse.h
+src/Core/SolverBase.h
+/usr/include/eigen3/Eigen/src/Core/SolverBase.h
+src/Core/PermutationMatrix.h
+/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h
+src/Core/Transpositions.h
+/usr/include/eigen3/Eigen/src/Core/Transpositions.h
+src/Core/TriangularMatrix.h
+/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h
+src/Core/SelfAdjointView.h
+/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h
+src/Core/products/GeneralBlockPanelKernel.h
+/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h
+src/Core/products/Parallelizer.h
+/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h
+src/Core/ProductEvaluators.h
+/usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h
+src/Core/products/GeneralMatrixVector.h
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h
+src/Core/products/GeneralMatrixMatrix.h
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h
+src/Core/SolveTriangular.h
+/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h
+src/Core/products/GeneralMatrixMatrixTriangular.h
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h
+src/Core/products/SelfadjointMatrixVector.h
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h
+src/Core/products/SelfadjointMatrixMatrix.h
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h
+src/Core/products/SelfadjointProduct.h
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h
+src/Core/products/SelfadjointRank2Update.h
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h
+src/Core/products/TriangularMatrixVector.h
+/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h
+src/Core/products/TriangularMatrixMatrix.h
+/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h
+src/Core/products/TriangularSolverMatrix.h
+/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h
+src/Core/products/TriangularSolverVector.h
+/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h
+src/Core/BandMatrix.h
+/usr/include/eigen3/Eigen/src/Core/BandMatrix.h
+src/Core/CoreIterators.h
+/usr/include/eigen3/Eigen/src/Core/CoreIterators.h
+src/Core/ConditionEstimator.h
+/usr/include/eigen3/Eigen/src/Core/ConditionEstimator.h
+src/Core/BooleanRedux.h
+/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h
+src/Core/Select.h
+/usr/include/eigen3/Eigen/src/Core/Select.h
+src/Core/VectorwiseOp.h
+/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h
+src/Core/Random.h
+/usr/include/eigen3/Eigen/src/Core/Random.h
+src/Core/Replicate.h
+/usr/include/eigen3/Eigen/src/Core/Replicate.h
+src/Core/Reverse.h
+/usr/include/eigen3/Eigen/src/Core/Reverse.h
+src/Core/ArrayWrapper.h
+/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h
+src/Core/products/GeneralMatrixMatrix_BLAS.h
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_BLAS.h
+src/Core/products/GeneralMatrixVector_BLAS.h
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_BLAS.h
+src/Core/products/GeneralMatrixMatrixTriangular_BLAS.h
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_BLAS.h
+src/Core/products/SelfadjointMatrixMatrix_BLAS.h
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_BLAS.h
+src/Core/products/SelfadjointMatrixVector_BLAS.h
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_BLAS.h
+src/Core/products/TriangularMatrixMatrix_BLAS.h
+/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_BLAS.h
+src/Core/products/TriangularMatrixVector_BLAS.h
+/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_BLAS.h
+src/Core/products/TriangularSolverMatrix_BLAS.h
+/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_BLAS.h
+src/Core/Assign_MKL.h
+/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h
+src/Core/GlobalFunctions.h
+/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/Dense
+Core
+/usr/include/eigen3/Eigen/Core
+LU
+/usr/include/eigen3/Eigen/LU
+Cholesky
+/usr/include/eigen3/Eigen/Cholesky
+QR
+/usr/include/eigen3/Eigen/QR
+SVD
+/usr/include/eigen3/Eigen/SVD
+Geometry
+/usr/include/eigen3/Eigen/Geometry
+Eigenvalues
+/usr/include/eigen3/Eigen/Eigenvalues
+
+/usr/include/eigen3/Eigen/Eigen
+Dense
+/usr/include/eigen3/Eigen/Dense
+Sparse
+/usr/include/eigen3/Eigen/Sparse
+
+/usr/include/eigen3/Eigen/Eigenvalues
+Core
+/usr/include/eigen3/Eigen/Core
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+Cholesky
+/usr/include/eigen3/Eigen/Cholesky
+Jacobi
+/usr/include/eigen3/Eigen/Jacobi
+Householder
+/usr/include/eigen3/Eigen/Householder
+LU
+/usr/include/eigen3/Eigen/LU
+Geometry
+/usr/include/eigen3/Eigen/Geometry
+src/misc/RealSvd2x2.h
+/usr/include/eigen3/Eigen/src/misc/RealSvd2x2.h
+src/Eigenvalues/Tridiagonalization.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h
+src/Eigenvalues/RealSchur.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h
+src/Eigenvalues/EigenSolver.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h
+src/Eigenvalues/SelfAdjointEigenSolver.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h
+src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h
+src/Eigenvalues/HessenbergDecomposition.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h
+src/Eigenvalues/ComplexSchur.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h
+src/Eigenvalues/ComplexEigenSolver.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h
+src/Eigenvalues/RealQZ.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h
+src/Eigenvalues/GeneralizedEigenSolver.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h
+src/Eigenvalues/MatrixBaseEigenvalues.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h
+mkl_lapacke.h
+/usr/include/eigen3/Eigen/mkl_lapacke.h
+src/misc/lapacke.h
+/usr/include/eigen3/Eigen/src/misc/lapacke.h
+src/Eigenvalues/RealSchur_LAPACKE.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_LAPACKE.h
+src/Eigenvalues/ComplexSchur_LAPACKE.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_LAPACKE.h
+src/Eigenvalues/SelfAdjointEigenSolver_LAPACKE.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_LAPACKE.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/Geometry
+Core
+/usr/include/eigen3/Eigen/Core
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+SVD
+/usr/include/eigen3/Eigen/SVD
+LU
+/usr/include/eigen3/Eigen/LU
+limits
+-
+src/Geometry/OrthoMethods.h
+/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h
+src/Geometry/EulerAngles.h
+/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h
+src/Geometry/Homogeneous.h
+/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h
+src/Geometry/RotationBase.h
+/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h
+src/Geometry/Rotation2D.h
+/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h
+src/Geometry/Quaternion.h
+/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h
+src/Geometry/AngleAxis.h
+/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h
+src/Geometry/Transform.h
+/usr/include/eigen3/Eigen/src/Geometry/Transform.h
+src/Geometry/Translation.h
+/usr/include/eigen3/Eigen/src/Geometry/Translation.h
+src/Geometry/Scaling.h
+/usr/include/eigen3/Eigen/src/Geometry/Scaling.h
+src/Geometry/Hyperplane.h
+/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h
+src/Geometry/ParametrizedLine.h
+/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h
+src/Geometry/AlignedBox.h
+/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h
+src/Geometry/Umeyama.h
+/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h
+src/Geometry/arch/Geometry_SSE.h
+/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/Householder
+Core
+/usr/include/eigen3/Eigen/Core
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+src/Householder/Householder.h
+/usr/include/eigen3/Eigen/src/Householder/Householder.h
+src/Householder/HouseholderSequence.h
+/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h
+src/Householder/BlockHouseholder.h
+/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/IterativeLinearSolvers
+SparseCore
+/usr/include/eigen3/Eigen/SparseCore
+OrderingMethods
+/usr/include/eigen3/Eigen/OrderingMethods
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+Eigen/IterativeLinearSolvers
+-
+src/IterativeLinearSolvers/SolveWithGuess.h
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/SolveWithGuess.h
+src/IterativeLinearSolvers/IterativeSolverBase.h
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h
+src/IterativeLinearSolvers/BasicPreconditioners.h
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h
+src/IterativeLinearSolvers/ConjugateGradient.h
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h
+src/IterativeLinearSolvers/LeastSquareConjugateGradient.h
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/LeastSquareConjugateGradient.h
+src/IterativeLinearSolvers/BiCGSTAB.h
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h
+src/IterativeLinearSolvers/IncompleteLUT.h
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IncompleteLUT.h
+src/IterativeLinearSolvers/IncompleteCholesky.h
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IncompleteCholesky.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/Jacobi
+Core
+/usr/include/eigen3/Eigen/Core
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+src/Jacobi/Jacobi.h
+/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/LU
+Core
+/usr/include/eigen3/Eigen/Core
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+src/misc/Kernel.h
+/usr/include/eigen3/Eigen/src/misc/Kernel.h
+src/misc/Image.h
+/usr/include/eigen3/Eigen/src/misc/Image.h
+src/LU/FullPivLU.h
+/usr/include/eigen3/Eigen/src/LU/FullPivLU.h
+src/LU/PartialPivLU.h
+/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h
+mkl_lapacke.h
+/usr/include/eigen3/Eigen/mkl_lapacke.h
+src/misc/lapacke.h
+/usr/include/eigen3/Eigen/src/misc/lapacke.h
+src/LU/PartialPivLU_LAPACKE.h
+/usr/include/eigen3/Eigen/src/LU/PartialPivLU_LAPACKE.h
+src/LU/Determinant.h
+/usr/include/eigen3/Eigen/src/LU/Determinant.h
+src/LU/InverseImpl.h
+/usr/include/eigen3/Eigen/src/LU/InverseImpl.h
+src/LU/arch/Inverse_SSE.h
+/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/OrderingMethods
+SparseCore
+/usr/include/eigen3/Eigen/SparseCore
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+src/OrderingMethods/Amd.h
+/usr/include/eigen3/Eigen/src/OrderingMethods/Amd.h
+src/OrderingMethods/Ordering.h
+/usr/include/eigen3/Eigen/src/OrderingMethods/Ordering.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/QR
+Core
+/usr/include/eigen3/Eigen/Core
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+Cholesky
+/usr/include/eigen3/Eigen/Cholesky
+Jacobi
+/usr/include/eigen3/Eigen/Jacobi
+Householder
+/usr/include/eigen3/Eigen/Householder
+src/QR/HouseholderQR.h
+/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h
+src/QR/FullPivHouseholderQR.h
+/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h
+src/QR/ColPivHouseholderQR.h
+/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h
+src/QR/CompleteOrthogonalDecomposition.h
+/usr/include/eigen3/Eigen/src/QR/CompleteOrthogonalDecomposition.h
+mkl_lapacke.h
+/usr/include/eigen3/Eigen/mkl_lapacke.h
+src/misc/lapacke.h
+/usr/include/eigen3/Eigen/src/misc/lapacke.h
+src/QR/HouseholderQR_LAPACKE.h
+/usr/include/eigen3/Eigen/src/QR/HouseholderQR_LAPACKE.h
+src/QR/ColPivHouseholderQR_LAPACKE.h
+/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_LAPACKE.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/SVD
+QR
+/usr/include/eigen3/Eigen/QR
+Householder
+/usr/include/eigen3/Eigen/Householder
+Jacobi
+/usr/include/eigen3/Eigen/Jacobi
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+src/misc/RealSvd2x2.h
+/usr/include/eigen3/Eigen/src/misc/RealSvd2x2.h
+src/SVD/UpperBidiagonalization.h
+/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h
+src/SVD/SVDBase.h
+/usr/include/eigen3/Eigen/src/SVD/SVDBase.h
+src/SVD/JacobiSVD.h
+/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h
+src/SVD/BDCSVD.h
+/usr/include/eigen3/Eigen/src/SVD/BDCSVD.h
+mkl_lapacke.h
+/usr/include/eigen3/Eigen/mkl_lapacke.h
+src/misc/lapacke.h
+/usr/include/eigen3/Eigen/src/misc/lapacke.h
+src/SVD/JacobiSVD_LAPACKE.h
+/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_LAPACKE.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/Sparse
+Eigen/Sparse
+-
+SparseCore
+/usr/include/eigen3/Eigen/SparseCore
+OrderingMethods
+/usr/include/eigen3/Eigen/OrderingMethods
+SparseCholesky
+/usr/include/eigen3/Eigen/SparseCholesky
+SparseLU
+/usr/include/eigen3/Eigen/SparseLU
+SparseQR
+/usr/include/eigen3/Eigen/SparseQR
+IterativeLinearSolvers
+/usr/include/eigen3/Eigen/IterativeLinearSolvers
+
+/usr/include/eigen3/Eigen/SparseCholesky
+SparseCore
+/usr/include/eigen3/Eigen/SparseCore
+OrderingMethods
+/usr/include/eigen3/Eigen/OrderingMethods
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+src/SparseCholesky/SimplicialCholesky.h
+/usr/include/eigen3/Eigen/src/SparseCholesky/SimplicialCholesky.h
+src/SparseCholesky/SimplicialCholesky_impl.h
+/usr/include/eigen3/Eigen/src/SparseCholesky/SimplicialCholesky_impl.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/SparseCore
+Core
+/usr/include/eigen3/Eigen/Core
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+vector
+-
+map
+-
+cstdlib
+-
+cstring
+-
+algorithm
+-
+src/SparseCore/SparseUtil.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseUtil.h
+src/SparseCore/SparseMatrixBase.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseMatrixBase.h
+src/SparseCore/SparseAssign.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseAssign.h
+src/SparseCore/CompressedStorage.h
+/usr/include/eigen3/Eigen/src/SparseCore/CompressedStorage.h
+src/SparseCore/AmbiVector.h
+/usr/include/eigen3/Eigen/src/SparseCore/AmbiVector.h
+src/SparseCore/SparseCompressedBase.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseCompressedBase.h
+src/SparseCore/SparseMatrix.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseMatrix.h
+src/SparseCore/SparseMap.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseMap.h
+src/SparseCore/MappedSparseMatrix.h
+/usr/include/eigen3/Eigen/src/SparseCore/MappedSparseMatrix.h
+src/SparseCore/SparseVector.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseVector.h
+src/SparseCore/SparseRef.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseRef.h
+src/SparseCore/SparseCwiseUnaryOp.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseCwiseUnaryOp.h
+src/SparseCore/SparseCwiseBinaryOp.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseCwiseBinaryOp.h
+src/SparseCore/SparseTranspose.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseTranspose.h
+src/SparseCore/SparseBlock.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseBlock.h
+src/SparseCore/SparseDot.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseDot.h
+src/SparseCore/SparseRedux.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseRedux.h
+src/SparseCore/SparseView.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseView.h
+src/SparseCore/SparseDiagonalProduct.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseDiagonalProduct.h
+src/SparseCore/ConservativeSparseSparseProduct.h
+/usr/include/eigen3/Eigen/src/SparseCore/ConservativeSparseSparseProduct.h
+src/SparseCore/SparseSparseProductWithPruning.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseSparseProductWithPruning.h
+src/SparseCore/SparseProduct.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseProduct.h
+src/SparseCore/SparseDenseProduct.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseDenseProduct.h
+src/SparseCore/SparseSelfAdjointView.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseSelfAdjointView.h
+src/SparseCore/SparseTriangularView.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseTriangularView.h
+src/SparseCore/TriangularSolver.h
+/usr/include/eigen3/Eigen/src/SparseCore/TriangularSolver.h
+src/SparseCore/SparsePermutation.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparsePermutation.h
+src/SparseCore/SparseFuzzy.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseFuzzy.h
+src/SparseCore/SparseSolverBase.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseSolverBase.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/SparseLU
+SparseCore
+/usr/include/eigen3/Eigen/SparseCore
+OrderingMethods
+/usr/include/eigen3/Eigen/OrderingMethods
+src/SparseLU/SparseLU_gemm_kernel.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_gemm_kernel.h
+src/SparseLU/SparseLU_Structs.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Structs.h
+src/SparseLU/SparseLU_SupernodalMatrix.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h
+src/SparseLU/SparseLUImpl.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLUImpl.h
+src/SparseCore/SparseColEtree.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseColEtree.h
+src/SparseLU/SparseLU_Memory.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Memory.h
+src/SparseLU/SparseLU_heap_relax_snode.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_heap_relax_snode.h
+src/SparseLU/SparseLU_relax_snode.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_relax_snode.h
+src/SparseLU/SparseLU_pivotL.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_pivotL.h
+src/SparseLU/SparseLU_panel_dfs.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_panel_dfs.h
+src/SparseLU/SparseLU_kernel_bmod.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_kernel_bmod.h
+src/SparseLU/SparseLU_panel_bmod.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_panel_bmod.h
+src/SparseLU/SparseLU_column_dfs.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_column_dfs.h
+src/SparseLU/SparseLU_column_bmod.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_column_bmod.h
+src/SparseLU/SparseLU_copy_to_ucol.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_copy_to_ucol.h
+src/SparseLU/SparseLU_pruneL.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_pruneL.h
+src/SparseLU/SparseLU_Utils.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Utils.h
+src/SparseLU/SparseLU.h
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU.h
+
+/usr/include/eigen3/Eigen/SparseQR
+SparseCore
+/usr/include/eigen3/Eigen/SparseCore
+OrderingMethods
+/usr/include/eigen3/Eigen/OrderingMethods
+src/Core/util/DisableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+OrderingMethods
+/usr/include/eigen3/Eigen/OrderingMethods
+src/SparseCore/SparseColEtree.h
+/usr/include/eigen3/Eigen/src/SparseCore/SparseColEtree.h
+src/SparseQR/SparseQR.h
+/usr/include/eigen3/Eigen/src/SparseQR/SparseQR.h
+src/Core/util/ReenableStupidWarnings.h
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h
+
+/usr/include/eigen3/Eigen/src/Cholesky/LLT.h
+
+/usr/include/eigen3/Eigen/src/Cholesky/LLT_LAPACKE.h
+
+/usr/include/eigen3/Eigen/src/Core/Array.h
+
+/usr/include/eigen3/Eigen/src/Core/ArrayBase.h
+../plugins/CommonCwiseUnaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h
+../plugins/MatrixCwiseUnaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h
+../plugins/ArrayCwiseUnaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h
+../plugins/CommonCwiseBinaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h
+../plugins/MatrixCwiseBinaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h
+../plugins/ArrayCwiseBinaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h
+
+/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h
+
+/usr/include/eigen3/Eigen/src/Core/Assign.h
+
+/usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h
+
+/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h
+
+/usr/include/eigen3/Eigen/src/Core/BandMatrix.h
+
+/usr/include/eigen3/Eigen/src/Core/Block.h
+
+/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h
+
+/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h
+
+/usr/include/eigen3/Eigen/src/Core/ConditionEstimator.h
+
+/usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h
+
+/usr/include/eigen3/Eigen/src/Core/CoreIterators.h
+
+/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h
+
+/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h
+
+/usr/include/eigen3/Eigen/src/Core/CwiseTernaryOp.h
+
+/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h
+
+/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h
+
+/usr/include/eigen3/Eigen/src/Core/DenseBase.h
+../plugins/BlockMethods.h
+/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h
+
+/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h
+
+/usr/include/eigen3/Eigen/src/Core/DenseStorage.h
+
+/usr/include/eigen3/Eigen/src/Core/Diagonal.h
+
+/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h
+
+/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h
+
+/usr/include/eigen3/Eigen/src/Core/Dot.h
+
+/usr/include/eigen3/Eigen/src/Core/EigenBase.h
+
+/usr/include/eigen3/Eigen/src/Core/Fuzzy.h
+
+/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h
+
+/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h
+
+/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h
+
+/usr/include/eigen3/Eigen/src/Core/IO.h
+
+/usr/include/eigen3/Eigen/src/Core/Inverse.h
+
+/usr/include/eigen3/Eigen/src/Core/Map.h
+
+/usr/include/eigen3/Eigen/src/Core/MapBase.h
+
+/usr/include/eigen3/Eigen/src/Core/MathFunctions.h
+
+/usr/include/eigen3/Eigen/src/Core/MathFunctionsImpl.h
+
+/usr/include/eigen3/Eigen/src/Core/Matrix.h
+
+/usr/include/eigen3/Eigen/src/Core/MatrixBase.h
+../plugins/CommonCwiseUnaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h
+../plugins/CommonCwiseBinaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h
+../plugins/MatrixCwiseUnaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h
+../plugins/MatrixCwiseBinaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h
+
+/usr/include/eigen3/Eigen/src/Core/NestByValue.h
+
+/usr/include/eigen3/Eigen/src/Core/NoAlias.h
+
+/usr/include/eigen3/Eigen/src/Core/NumTraits.h
+
+/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h
+
+/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h
+
+/usr/include/eigen3/Eigen/src/Core/Product.h
+
+/usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h
+
+/usr/include/eigen3/Eigen/src/Core/Random.h
+
+/usr/include/eigen3/Eigen/src/Core/Redux.h
+
+/usr/include/eigen3/Eigen/src/Core/Ref.h
+
+/usr/include/eigen3/Eigen/src/Core/Replicate.h
+
+/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h
+
+/usr/include/eigen3/Eigen/src/Core/Reverse.h
+
+/usr/include/eigen3/Eigen/src/Core/Select.h
+
+/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h
+
+/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h
+
+/usr/include/eigen3/Eigen/src/Core/Solve.h
+
+/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h
+
+/usr/include/eigen3/Eigen/src/Core/SolverBase.h
+
+/usr/include/eigen3/Eigen/src/Core/StableNorm.h
+
+/usr/include/eigen3/Eigen/src/Core/Stride.h
+
+/usr/include/eigen3/Eigen/src/Core/Swap.h
+
+/usr/include/eigen3/Eigen/src/Core/Transpose.h
+
+/usr/include/eigen3/Eigen/src/Core/Transpositions.h
+
+/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h
+
+/usr/include/eigen3/Eigen/src/Core/VectorBlock.h
+
+/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h
+
+/usr/include/eigen3/Eigen/src/Core/Visitor.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/AVX/Complex.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/AVX/MathFunctions.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/AVX/TypeCasting.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/AVX512/MathFunctions.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/AVX512/PacketMath.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/MathFunctions.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/Complex.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/Half.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/MathFunctions.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMath.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMathHalf.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/CUDA/TypeCasting.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/Default/ConjHelper.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/NEON/MathFunctions.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/SSE/TypeCasting.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/ZVector/Complex.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/ZVector/MathFunctions.h
+
+/usr/include/eigen3/Eigen/src/Core/arch/ZVector/PacketMath.h
+stdint.h
+-
+
+/usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h
+
+/usr/include/eigen3/Eigen/src/Core/functors/BinaryFunctors.h
+
+/usr/include/eigen3/Eigen/src/Core/functors/NullaryFunctors.h
+
+/usr/include/eigen3/Eigen/src/Core/functors/StlFunctors.h
+
+/usr/include/eigen3/Eigen/src/Core/functors/TernaryFunctors.h
+
+/usr/include/eigen3/Eigen/src/Core/functors/UnaryFunctors.h
+
+/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h
+
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h
+
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h
+
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_BLAS.h
+
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_BLAS.h
+
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h
+
+/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_BLAS.h
+
+/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h
+
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h
+
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_BLAS.h
+
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h
+
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_BLAS.h
+
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h
+
+/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h
+
+/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h
+
+/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_BLAS.h
+
+/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h
+
+/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_BLAS.h
+
+/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h
+
+/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_BLAS.h
+
+/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h
+
+/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h
+
+/usr/include/eigen3/Eigen/src/Core/util/Constants.h
+
+/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h
+
+/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h
+mkl.h
+-
+../../misc/blas.h
+/usr/include/eigen3/Eigen/src/misc/blas.h
+
+/usr/include/eigen3/Eigen/src/Core/util/Macros.h
+cstdlib
+-
+iostream
+-
+
+/usr/include/eigen3/Eigen/src/Core/util/Memory.h
+
+/usr/include/eigen3/Eigen/src/Core/util/Meta.h
+cfloat
+-
+math_constants.h
+-
+cstdint
+-
+
+/usr/include/eigen3/Eigen/src/Core/util/NonMPL2.h
+
+/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+
+/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h
+
+/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h
+./ComplexSchur.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h
+./HessenbergDecomposition.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_LAPACKE.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h
+./RealSchur.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h
+./RealQZ.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h
+./Tridiagonalization.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h
+./HessenbergDecomposition.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_LAPACKE.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h
+./Tridiagonalization.h
+/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_LAPACKE.h
+
+/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h
+
+/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h
+
+/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h
+
+/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h
+
+/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h
+
+/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h
+
+/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h
+
+/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h
+
+/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h
+
+/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h
+
+/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h
+
+/usr/include/eigen3/Eigen/src/Geometry/Scaling.h
+
+/usr/include/eigen3/Eigen/src/Geometry/Transform.h
+
+/usr/include/eigen3/Eigen/src/Geometry/Translation.h
+
+/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h
+
+/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h
+
+/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h
+
+/usr/include/eigen3/Eigen/src/Householder/Householder.h
+
+/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h
+
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h
+
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h
+
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h
+
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IncompleteCholesky.h
+vector
+-
+list
+-
+
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IncompleteLUT.h
+
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h
+
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/LeastSquareConjugateGradient.h
+
+/usr/include/eigen3/Eigen/src/IterativeLinearSolvers/SolveWithGuess.h
+
+/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h
+
+/usr/include/eigen3/Eigen/src/LU/Determinant.h
+
+/usr/include/eigen3/Eigen/src/LU/FullPivLU.h
+
+/usr/include/eigen3/Eigen/src/LU/InverseImpl.h
+
+/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h
+
+/usr/include/eigen3/Eigen/src/LU/PartialPivLU_LAPACKE.h
+
+/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h
+
+/usr/include/eigen3/Eigen/src/OrderingMethods/Amd.h
+../Core/util/NonMPL2.h
+/usr/include/eigen3/Eigen/src/Core/util/NonMPL2.h
+
+/usr/include/eigen3/Eigen/src/OrderingMethods/Eigen_Colamd.h
+
+/usr/include/eigen3/Eigen/src/OrderingMethods/Ordering.h
+Eigen_Colamd.h
+/usr/include/eigen3/Eigen/src/OrderingMethods/Eigen_Colamd.h
+
+/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h
+
+/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_LAPACKE.h
+
+/usr/include/eigen3/Eigen/src/QR/CompleteOrthogonalDecomposition.h
+
+/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h
+
+/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h
+
+/usr/include/eigen3/Eigen/src/QR/HouseholderQR_LAPACKE.h
+
+/usr/include/eigen3/Eigen/src/SVD/BDCSVD.h
+
+/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h
+
+/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_LAPACKE.h
+
+/usr/include/eigen3/Eigen/src/SVD/SVDBase.h
+
+/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h
+
+/usr/include/eigen3/Eigen/src/SparseCholesky/SimplicialCholesky.h
+
+/usr/include/eigen3/Eigen/src/SparseCholesky/SimplicialCholesky_impl.h
+../Core/util/NonMPL2.h
+/usr/include/eigen3/Eigen/src/Core/util/NonMPL2.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/AmbiVector.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/CompressedStorage.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/ConservativeSparseSparseProduct.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/MappedSparseMatrix.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseAssign.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseBlock.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseColEtree.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseCompressedBase.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseCwiseBinaryOp.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseCwiseUnaryOp.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseDenseProduct.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseDiagonalProduct.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseDot.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseFuzzy.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseMap.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseMatrix.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseMatrixBase.h
+../plugins/CommonCwiseUnaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h
+../plugins/CommonCwiseBinaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h
+../plugins/MatrixCwiseUnaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h
+../plugins/MatrixCwiseBinaryOps.h
+/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h
+../plugins/BlockMethods.h
+/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparsePermutation.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseProduct.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseRedux.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseRef.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseSelfAdjointView.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseSolverBase.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseSparseProductWithPruning.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseTranspose.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseTriangularView.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseUtil.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseVector.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/SparseView.h
+
+/usr/include/eigen3/Eigen/src/SparseCore/TriangularSolver.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLUImpl.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Memory.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Structs.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Utils.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_column_bmod.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_column_dfs.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_copy_to_ucol.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_gemm_kernel.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_heap_relax_snode.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_kernel_bmod.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_panel_bmod.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_panel_dfs.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_pivotL.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_pruneL.h
+
+/usr/include/eigen3/Eigen/src/SparseLU/SparseLU_relax_snode.h
+
+/usr/include/eigen3/Eigen/src/SparseQR/SparseQR.h
+
+/usr/include/eigen3/Eigen/src/misc/Image.h
+
+/usr/include/eigen3/Eigen/src/misc/Kernel.h
+
+/usr/include/eigen3/Eigen/src/misc/RealSvd2x2.h
+
+/usr/include/eigen3/Eigen/src/misc/blas.h
+
+/usr/include/eigen3/Eigen/src/misc/lapacke.h
+lapacke_config.h
+/usr/include/eigen3/Eigen/src/misc/lapacke_config.h
+stdlib.h
+-
+complex.h
+-
+complex.h
+-
+lapacke_mangling.h
+/usr/include/eigen3/Eigen/src/misc/lapacke_mangling.h
+
+/usr/include/eigen3/Eigen/src/misc/lapacke_mangling.h
+
+/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h
+
+/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h
+
+/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h
+
+/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h
+
+/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h
+
+/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h
+
+/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h
+
+acado_auxiliary_functions.h
+acado_common.h
+acado_common.h
+Windows.h
+-
+unistd.h
+unistd.h
+mach/mach_time.h
+-
+time.h
+-
+sys/stat.h
+-
+sys/time.h
+-
+
+acado_common.h
+math.h
+-
+string.h
+-
+acado_qpoases_interface.hpp
+acado_qpoases_interface.hpp
+
+acado_qpoases_interface.hpp
+stdio.h
+-
+math.h
+-
+
+devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h
+dynamic_reconfigure/config_tools.h
+-
+limits
+-
+ros/node_handle.h
+-
+dynamic_reconfigure/ConfigDescription.h
+-
+dynamic_reconfigure/ParamDescription.h
+-
+dynamic_reconfigure/Group.h
+-
+dynamic_reconfigure/config_init_mutex.h
+-
+boost/any.hpp
+-
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..52b9e887c889261f9f00f4ff0b74ed62a0c21cb1
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/DependInfo.cmake
@@ -0,0 +1,39 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  "CXX"
+  )
+# The set of files for implicit dependencies of each language:
+set(CMAKE_DEPENDS_CHECK_CXX
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/src/nonlinear_mpc_node.cc" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o"
+  )
+set(CMAKE_CXX_COMPILER_ID "GNU")
+
+# Preprocessor definitions for this target.
+set(CMAKE_TARGET_DEFINITIONS_CXX
+  "ROSCONSOLE_BACKEND_LOG4CXX"
+  "ROS_BUILD_SHARED_LIBS=1"
+  "ROS_PACKAGE_NAME=\"mav_nonlinear_mpc\""
+  )
+
+# The include file search paths:
+set(CMAKE_CXX_TARGET_INCLUDE_PATH
+  "devel/include"
+  "../include"
+  "/home/simhe502/catkin_ws/devel/include"
+  "/home/simhe502/catkin_ws/src/common_msgs/sensor_msgs/include"
+  "/opt/ros/noetic/include"
+  "/opt/ros/noetic/share/xmlrpcpp/cmake/../../../include/xmlrpcpp"
+  "/usr/include/eigen3"
+  "."
+  "qpoases"
+  "qpoases/INCLUDE"
+  "qpoases/SRC"
+  )
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/mav_nonlinear_mpc_lib.dir/DependInfo.cmake"
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..22da9215a3cf569196da205dd4e77486966ca0cc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/build.make
@@ -0,0 +1,145 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Include any dependencies generated for this target.
+include CMakeFiles/nonlinear_mpc_node.dir/depend.make
+
+# Include the progress variables for this target.
+include CMakeFiles/nonlinear_mpc_node.dir/progress.make
+
+# Include the compile flags for this target's objects.
+include CMakeFiles/nonlinear_mpc_node.dir/flags.make
+
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: CMakeFiles/nonlinear_mpc_node.dir/flags.make
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: ../src/nonlinear_mpc_node.cc
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_1) "Building CXX object CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o"
+	/usr/bin/c++  $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -o CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o -c /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/src/nonlinear_mpc_node.cc
+
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.i: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.i"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/src/nonlinear_mpc_node.cc > CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.i
+
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.s: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.s"
+	/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/src/nonlinear_mpc_node.cc -o CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.s
+
+# Object files for target nonlinear_mpc_node
+nonlinear_mpc_node_OBJECTS = \
+"CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o"
+
+# External object files for target nonlinear_mpc_node
+nonlinear_mpc_node_EXTERNAL_OBJECTS =
+
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: CMakeFiles/nonlinear_mpc_node.dir/build.make
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/libdynamic_reconfigure_config_init_mutex.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/libtf.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/libtf2_ros.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/libactionlib.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/libmessage_filters.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/libroscpp.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /usr/lib/x86_64-linux-gnu/libpthread.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.71.0
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /usr/lib/x86_64-linux-gnu/libboost_filesystem.so.1.71.0
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/libxmlrpcpp.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/libtf2.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/libroscpp_serialization.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/librosconsole.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/librosconsole_log4cxx.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/librosconsole_backend_interface.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /usr/lib/x86_64-linux-gnu/liblog4cxx.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /usr/lib/x86_64-linux-gnu/libboost_regex.so.1.71.0
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/librostime.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /usr/lib/x86_64-linux-gnu/libboost_date_time.so.1.71.0
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/libcpp_common.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /usr/lib/x86_64-linux-gnu/libboost_system.so.1.71.0
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.71.0
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /usr/lib/x86_64-linux-gnu/libconsole_bridge.so.0.4
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: devel/lib/libmav_nonlinear_mpc_lib.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/libdynamic_reconfigure_config_init_mutex.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/libtf.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/libtf2_ros.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/libactionlib.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/libmessage_filters.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/libroscpp.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /usr/lib/x86_64-linux-gnu/libpthread.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.71.0
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /usr/lib/x86_64-linux-gnu/libboost_filesystem.so.1.71.0
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/libxmlrpcpp.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/libtf2.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/libroscpp_serialization.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/librosconsole.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/librosconsole_log4cxx.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/librosconsole_backend_interface.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /usr/lib/x86_64-linux-gnu/liblog4cxx.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /usr/lib/x86_64-linux-gnu/libboost_regex.so.1.71.0
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/librostime.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /usr/lib/x86_64-linux-gnu/libboost_date_time.so.1.71.0
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /opt/ros/noetic/lib/libcpp_common.so
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /usr/lib/x86_64-linux-gnu/libboost_system.so.1.71.0
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.71.0
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: /usr/lib/x86_64-linux-gnu/libconsole_bridge.so.0.4
+devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node: CMakeFiles/nonlinear_mpc_node.dir/link.txt
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --bold --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_2) "Linking CXX executable devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node"
+	$(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/nonlinear_mpc_node.dir/link.txt --verbose=$(VERBOSE)
+
+# Rule to build all files generated by this target.
+CMakeFiles/nonlinear_mpc_node.dir/build: devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node
+
+.PHONY : CMakeFiles/nonlinear_mpc_node.dir/build
+
+CMakeFiles/nonlinear_mpc_node.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/nonlinear_mpc_node.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/nonlinear_mpc_node.dir/clean
+
+CMakeFiles/nonlinear_mpc_node.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/nonlinear_mpc_node.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..c9b35523438a12d32a80e7db1b4407d1e75121c9
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/cmake_clean.cmake
@@ -0,0 +1,10 @@
+file(REMOVE_RECURSE
+  "CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o"
+  "devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node"
+  "devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node.pdb"
+)
+
+# Per-language clean rules from dependency scanning.
+foreach(lang CXX)
+  include(CMakeFiles/nonlinear_mpc_node.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..aa69d3af5bb14e6bc9668c9b96b0efc22450b4ae
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/depend.internal
@@ -0,0 +1,376 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o
+ ../include/mav_nonlinear_mpc/nonlinear_mpc.h
+ ../include/mav_nonlinear_mpc/nonlinear_mpc_node.h
+ /home/simhe502/catkin_ws/devel/include/geometry_msgs/Point.h
+ /home/simhe502/catkin_ws/devel/include/geometry_msgs/Pose.h
+ /home/simhe502/catkin_ws/devel/include/geometry_msgs/PoseStamped.h
+ /home/simhe502/catkin_ws/devel/include/geometry_msgs/Quaternion.h
+ /home/simhe502/catkin_ws/devel/include/geometry_msgs/Twist.h
+ /home/simhe502/catkin_ws/devel/include/geometry_msgs/Vector3.h
+ /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/src/nonlinear_mpc_node.cc
+ /opt/ros/noetic/include/dynamic_reconfigure/BoolParameter.h
+ /opt/ros/noetic/include/dynamic_reconfigure/Config.h
+ /opt/ros/noetic/include/dynamic_reconfigure/ConfigDescription.h
+ /opt/ros/noetic/include/dynamic_reconfigure/DoubleParameter.h
+ /opt/ros/noetic/include/dynamic_reconfigure/Group.h
+ /opt/ros/noetic/include/dynamic_reconfigure/GroupState.h
+ /opt/ros/noetic/include/dynamic_reconfigure/IntParameter.h
+ /opt/ros/noetic/include/dynamic_reconfigure/ParamDescription.h
+ /opt/ros/noetic/include/dynamic_reconfigure/Reconfigure.h
+ /opt/ros/noetic/include/dynamic_reconfigure/ReconfigureRequest.h
+ /opt/ros/noetic/include/dynamic_reconfigure/ReconfigureResponse.h
+ /opt/ros/noetic/include/dynamic_reconfigure/StrParameter.h
+ /opt/ros/noetic/include/dynamic_reconfigure/config_init_mutex.h
+ /opt/ros/noetic/include/dynamic_reconfigure/config_tools.h
+ /opt/ros/noetic/include/dynamic_reconfigure/server.h
+ /opt/ros/noetic/include/gazebo_msgs/GetModelState.h
+ /opt/ros/noetic/include/gazebo_msgs/GetModelStateRequest.h
+ /opt/ros/noetic/include/gazebo_msgs/GetModelStateResponse.h
+ /opt/ros/noetic/include/ros/advertise_options.h
+ /opt/ros/noetic/include/ros/advertise_service_options.h
+ /opt/ros/noetic/include/ros/assert.h
+ /opt/ros/noetic/include/ros/builtin_message_traits.h
+ /opt/ros/noetic/include/ros/callback_queue.h
+ /opt/ros/noetic/include/ros/callback_queue_interface.h
+ /opt/ros/noetic/include/ros/common.h
+ /opt/ros/noetic/include/ros/console.h
+ /opt/ros/noetic/include/ros/console_backend.h
+ /opt/ros/noetic/include/ros/datatypes.h
+ /opt/ros/noetic/include/ros/duration.h
+ /opt/ros/noetic/include/ros/exception.h
+ /opt/ros/noetic/include/ros/exceptions.h
+ /opt/ros/noetic/include/ros/forwards.h
+ /opt/ros/noetic/include/ros/init.h
+ /opt/ros/noetic/include/ros/macros.h
+ /opt/ros/noetic/include/ros/master.h
+ /opt/ros/noetic/include/ros/message.h
+ /opt/ros/noetic/include/ros/message_event.h
+ /opt/ros/noetic/include/ros/message_forward.h
+ /opt/ros/noetic/include/ros/message_operations.h
+ /opt/ros/noetic/include/ros/message_traits.h
+ /opt/ros/noetic/include/ros/names.h
+ /opt/ros/noetic/include/ros/node_handle.h
+ /opt/ros/noetic/include/ros/param.h
+ /opt/ros/noetic/include/ros/parameter_adapter.h
+ /opt/ros/noetic/include/ros/platform.h
+ /opt/ros/noetic/include/ros/publisher.h
+ /opt/ros/noetic/include/ros/rate.h
+ /opt/ros/noetic/include/ros/ros.h
+ /opt/ros/noetic/include/ros/roscpp_serialization_macros.h
+ /opt/ros/noetic/include/ros/rostime_decl.h
+ /opt/ros/noetic/include/ros/serialization.h
+ /opt/ros/noetic/include/ros/serialized_message.h
+ /opt/ros/noetic/include/ros/service.h
+ /opt/ros/noetic/include/ros/service_callback_helper.h
+ /opt/ros/noetic/include/ros/service_client.h
+ /opt/ros/noetic/include/ros/service_client_options.h
+ /opt/ros/noetic/include/ros/service_server.h
+ /opt/ros/noetic/include/ros/service_traits.h
+ /opt/ros/noetic/include/ros/single_subscriber_publisher.h
+ /opt/ros/noetic/include/ros/spinner.h
+ /opt/ros/noetic/include/ros/static_assert.h
+ /opt/ros/noetic/include/ros/steady_timer.h
+ /opt/ros/noetic/include/ros/steady_timer_options.h
+ /opt/ros/noetic/include/ros/subscribe_options.h
+ /opt/ros/noetic/include/ros/subscriber.h
+ /opt/ros/noetic/include/ros/subscription_callback_helper.h
+ /opt/ros/noetic/include/ros/this_node.h
+ /opt/ros/noetic/include/ros/time.h
+ /opt/ros/noetic/include/ros/timer.h
+ /opt/ros/noetic/include/ros/timer_options.h
+ /opt/ros/noetic/include/ros/topic.h
+ /opt/ros/noetic/include/ros/transport_hints.h
+ /opt/ros/noetic/include/ros/types.h
+ /opt/ros/noetic/include/ros/wall_timer.h
+ /opt/ros/noetic/include/ros/wall_timer_options.h
+ /opt/ros/noetic/include/rosconsole/macros_generated.h
+ /opt/ros/noetic/include/std_msgs/Header.h
+ /opt/ros/noetic/include/std_srvs/Empty.h
+ /opt/ros/noetic/include/std_srvs/EmptyRequest.h
+ /opt/ros/noetic/include/std_srvs/EmptyResponse.h
+ /opt/ros/noetic/include/xmlrpcpp/XmlRpcDecl.h
+ /opt/ros/noetic/include/xmlrpcpp/XmlRpcValue.h
+ /usr/include/eigen3/Eigen/Cholesky
+ /usr/include/eigen3/Eigen/Core
+ /usr/include/eigen3/Eigen/Dense
+ /usr/include/eigen3/Eigen/Eigen
+ /usr/include/eigen3/Eigen/Eigenvalues
+ /usr/include/eigen3/Eigen/Geometry
+ /usr/include/eigen3/Eigen/Householder
+ /usr/include/eigen3/Eigen/IterativeLinearSolvers
+ /usr/include/eigen3/Eigen/Jacobi
+ /usr/include/eigen3/Eigen/LU
+ /usr/include/eigen3/Eigen/OrderingMethods
+ /usr/include/eigen3/Eigen/QR
+ /usr/include/eigen3/Eigen/SVD
+ /usr/include/eigen3/Eigen/Sparse
+ /usr/include/eigen3/Eigen/SparseCholesky
+ /usr/include/eigen3/Eigen/SparseCore
+ /usr/include/eigen3/Eigen/SparseLU
+ /usr/include/eigen3/Eigen/SparseQR
+ /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h
+ /usr/include/eigen3/Eigen/src/Cholesky/LLT.h
+ /usr/include/eigen3/Eigen/src/Cholesky/LLT_LAPACKE.h
+ /usr/include/eigen3/Eigen/src/Core/Array.h
+ /usr/include/eigen3/Eigen/src/Core/ArrayBase.h
+ /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h
+ /usr/include/eigen3/Eigen/src/Core/Assign.h
+ /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h
+ /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h
+ /usr/include/eigen3/Eigen/src/Core/BandMatrix.h
+ /usr/include/eigen3/Eigen/src/Core/Block.h
+ /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h
+ /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h
+ /usr/include/eigen3/Eigen/src/Core/ConditionEstimator.h
+ /usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h
+ /usr/include/eigen3/Eigen/src/Core/CoreIterators.h
+ /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h
+ /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h
+ /usr/include/eigen3/Eigen/src/Core/CwiseTernaryOp.h
+ /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h
+ /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h
+ /usr/include/eigen3/Eigen/src/Core/DenseBase.h
+ /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h
+ /usr/include/eigen3/Eigen/src/Core/DenseStorage.h
+ /usr/include/eigen3/Eigen/src/Core/Diagonal.h
+ /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h
+ /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h
+ /usr/include/eigen3/Eigen/src/Core/Dot.h
+ /usr/include/eigen3/Eigen/src/Core/EigenBase.h
+ /usr/include/eigen3/Eigen/src/Core/Fuzzy.h
+ /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h
+ /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h
+ /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h
+ /usr/include/eigen3/Eigen/src/Core/IO.h
+ /usr/include/eigen3/Eigen/src/Core/Inverse.h
+ /usr/include/eigen3/Eigen/src/Core/Map.h
+ /usr/include/eigen3/Eigen/src/Core/MapBase.h
+ /usr/include/eigen3/Eigen/src/Core/MathFunctions.h
+ /usr/include/eigen3/Eigen/src/Core/MathFunctionsImpl.h
+ /usr/include/eigen3/Eigen/src/Core/Matrix.h
+ /usr/include/eigen3/Eigen/src/Core/MatrixBase.h
+ /usr/include/eigen3/Eigen/src/Core/NestByValue.h
+ /usr/include/eigen3/Eigen/src/Core/NoAlias.h
+ /usr/include/eigen3/Eigen/src/Core/NumTraits.h
+ /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h
+ /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h
+ /usr/include/eigen3/Eigen/src/Core/Product.h
+ /usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h
+ /usr/include/eigen3/Eigen/src/Core/Random.h
+ /usr/include/eigen3/Eigen/src/Core/Redux.h
+ /usr/include/eigen3/Eigen/src/Core/Ref.h
+ /usr/include/eigen3/Eigen/src/Core/Replicate.h
+ /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h
+ /usr/include/eigen3/Eigen/src/Core/Reverse.h
+ /usr/include/eigen3/Eigen/src/Core/Select.h
+ /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h
+ /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h
+ /usr/include/eigen3/Eigen/src/Core/Solve.h
+ /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h
+ /usr/include/eigen3/Eigen/src/Core/SolverBase.h
+ /usr/include/eigen3/Eigen/src/Core/StableNorm.h
+ /usr/include/eigen3/Eigen/src/Core/Stride.h
+ /usr/include/eigen3/Eigen/src/Core/Swap.h
+ /usr/include/eigen3/Eigen/src/Core/Transpose.h
+ /usr/include/eigen3/Eigen/src/Core/Transpositions.h
+ /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h
+ /usr/include/eigen3/Eigen/src/Core/VectorBlock.h
+ /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h
+ /usr/include/eigen3/Eigen/src/Core/Visitor.h
+ /usr/include/eigen3/Eigen/src/Core/arch/AVX/Complex.h
+ /usr/include/eigen3/Eigen/src/Core/arch/AVX/MathFunctions.h
+ /usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h
+ /usr/include/eigen3/Eigen/src/Core/arch/AVX/TypeCasting.h
+ /usr/include/eigen3/Eigen/src/Core/arch/AVX512/MathFunctions.h
+ /usr/include/eigen3/Eigen/src/Core/arch/AVX512/PacketMath.h
+ /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h
+ /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/MathFunctions.h
+ /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h
+ /usr/include/eigen3/Eigen/src/Core/arch/CUDA/Complex.h
+ /usr/include/eigen3/Eigen/src/Core/arch/CUDA/Half.h
+ /usr/include/eigen3/Eigen/src/Core/arch/CUDA/MathFunctions.h
+ /usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMath.h
+ /usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMathHalf.h
+ /usr/include/eigen3/Eigen/src/Core/arch/CUDA/TypeCasting.h
+ /usr/include/eigen3/Eigen/src/Core/arch/Default/ConjHelper.h
+ /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h
+ /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h
+ /usr/include/eigen3/Eigen/src/Core/arch/NEON/MathFunctions.h
+ /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h
+ /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h
+ /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h
+ /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h
+ /usr/include/eigen3/Eigen/src/Core/arch/SSE/TypeCasting.h
+ /usr/include/eigen3/Eigen/src/Core/arch/ZVector/Complex.h
+ /usr/include/eigen3/Eigen/src/Core/arch/ZVector/MathFunctions.h
+ /usr/include/eigen3/Eigen/src/Core/arch/ZVector/PacketMath.h
+ /usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h
+ /usr/include/eigen3/Eigen/src/Core/functors/BinaryFunctors.h
+ /usr/include/eigen3/Eigen/src/Core/functors/NullaryFunctors.h
+ /usr/include/eigen3/Eigen/src/Core/functors/StlFunctors.h
+ /usr/include/eigen3/Eigen/src/Core/functors/TernaryFunctors.h
+ /usr/include/eigen3/Eigen/src/Core/functors/UnaryFunctors.h
+ /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h
+ /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h
+ /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h
+ /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_BLAS.h
+ /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_BLAS.h
+ /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h
+ /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_BLAS.h
+ /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h
+ /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h
+ /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_BLAS.h
+ /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h
+ /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_BLAS.h
+ /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h
+ /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h
+ /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h
+ /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_BLAS.h
+ /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h
+ /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_BLAS.h
+ /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h
+ /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_BLAS.h
+ /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h
+ /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h
+ /usr/include/eigen3/Eigen/src/Core/util/Constants.h
+ /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+ /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h
+ /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h
+ /usr/include/eigen3/Eigen/src/Core/util/Macros.h
+ /usr/include/eigen3/Eigen/src/Core/util/Memory.h
+ /usr/include/eigen3/Eigen/src/Core/util/Meta.h
+ /usr/include/eigen3/Eigen/src/Core/util/NonMPL2.h
+ /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+ /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h
+ /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_LAPACKE.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_LAPACKE.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_LAPACKE.h
+ /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h
+ /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h
+ /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h
+ /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h
+ /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h
+ /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h
+ /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h
+ /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h
+ /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h
+ /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h
+ /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h
+ /usr/include/eigen3/Eigen/src/Geometry/Scaling.h
+ /usr/include/eigen3/Eigen/src/Geometry/Transform.h
+ /usr/include/eigen3/Eigen/src/Geometry/Translation.h
+ /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h
+ /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h
+ /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h
+ /usr/include/eigen3/Eigen/src/Householder/Householder.h
+ /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h
+ /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h
+ /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h
+ /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h
+ /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IncompleteCholesky.h
+ /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IncompleteLUT.h
+ /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h
+ /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/LeastSquareConjugateGradient.h
+ /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/SolveWithGuess.h
+ /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h
+ /usr/include/eigen3/Eigen/src/LU/Determinant.h
+ /usr/include/eigen3/Eigen/src/LU/FullPivLU.h
+ /usr/include/eigen3/Eigen/src/LU/InverseImpl.h
+ /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h
+ /usr/include/eigen3/Eigen/src/LU/PartialPivLU_LAPACKE.h
+ /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h
+ /usr/include/eigen3/Eigen/src/OrderingMethods/Amd.h
+ /usr/include/eigen3/Eigen/src/OrderingMethods/Eigen_Colamd.h
+ /usr/include/eigen3/Eigen/src/OrderingMethods/Ordering.h
+ /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h
+ /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_LAPACKE.h
+ /usr/include/eigen3/Eigen/src/QR/CompleteOrthogonalDecomposition.h
+ /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h
+ /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h
+ /usr/include/eigen3/Eigen/src/QR/HouseholderQR_LAPACKE.h
+ /usr/include/eigen3/Eigen/src/SVD/BDCSVD.h
+ /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h
+ /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_LAPACKE.h
+ /usr/include/eigen3/Eigen/src/SVD/SVDBase.h
+ /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h
+ /usr/include/eigen3/Eigen/src/SparseCholesky/SimplicialCholesky.h
+ /usr/include/eigen3/Eigen/src/SparseCholesky/SimplicialCholesky_impl.h
+ /usr/include/eigen3/Eigen/src/SparseCore/AmbiVector.h
+ /usr/include/eigen3/Eigen/src/SparseCore/CompressedStorage.h
+ /usr/include/eigen3/Eigen/src/SparseCore/ConservativeSparseSparseProduct.h
+ /usr/include/eigen3/Eigen/src/SparseCore/MappedSparseMatrix.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseAssign.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseBlock.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseColEtree.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseCompressedBase.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseCwiseBinaryOp.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseCwiseUnaryOp.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseDenseProduct.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseDiagonalProduct.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseDot.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseFuzzy.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseMap.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseMatrix.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseMatrixBase.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparsePermutation.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseProduct.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseRedux.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseRef.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseSelfAdjointView.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseSolverBase.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseSparseProductWithPruning.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseTranspose.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseTriangularView.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseUtil.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseVector.h
+ /usr/include/eigen3/Eigen/src/SparseCore/SparseView.h
+ /usr/include/eigen3/Eigen/src/SparseCore/TriangularSolver.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLUImpl.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Memory.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Structs.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Utils.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_column_bmod.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_column_dfs.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_copy_to_ucol.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_gemm_kernel.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_heap_relax_snode.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_kernel_bmod.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_panel_bmod.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_panel_dfs.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_pivotL.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_pruneL.h
+ /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_relax_snode.h
+ /usr/include/eigen3/Eigen/src/SparseQR/SparseQR.h
+ /usr/include/eigen3/Eigen/src/misc/Image.h
+ /usr/include/eigen3/Eigen/src/misc/Kernel.h
+ /usr/include/eigen3/Eigen/src/misc/RealSvd2x2.h
+ /usr/include/eigen3/Eigen/src/misc/blas.h
+ /usr/include/eigen3/Eigen/src/misc/lapacke.h
+ /usr/include/eigen3/Eigen/src/misc/lapacke_mangling.h
+ /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h
+ /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h
+ /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h
+ /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h
+ /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h
+ /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h
+ /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h
+ acado_auxiliary_functions.h
+ acado_common.h
+ acado_qpoases_interface.hpp
+ devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..3863e7c6ad2459b34c9b7e6fac8250e16634c399
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/depend.make
@@ -0,0 +1,376 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: ../include/mav_nonlinear_mpc/nonlinear_mpc.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: ../include/mav_nonlinear_mpc/nonlinear_mpc_node.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /home/simhe502/catkin_ws/devel/include/geometry_msgs/Point.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /home/simhe502/catkin_ws/devel/include/geometry_msgs/Pose.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /home/simhe502/catkin_ws/devel/include/geometry_msgs/PoseStamped.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /home/simhe502/catkin_ws/devel/include/geometry_msgs/Quaternion.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /home/simhe502/catkin_ws/devel/include/geometry_msgs/Twist.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /home/simhe502/catkin_ws/devel/include/geometry_msgs/Vector3.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: ../src/nonlinear_mpc_node.cc
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/dynamic_reconfigure/BoolParameter.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/dynamic_reconfigure/Config.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/dynamic_reconfigure/ConfigDescription.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/dynamic_reconfigure/DoubleParameter.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/dynamic_reconfigure/Group.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/dynamic_reconfigure/GroupState.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/dynamic_reconfigure/IntParameter.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/dynamic_reconfigure/ParamDescription.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/dynamic_reconfigure/Reconfigure.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/dynamic_reconfigure/ReconfigureRequest.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/dynamic_reconfigure/ReconfigureResponse.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/dynamic_reconfigure/StrParameter.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/dynamic_reconfigure/config_init_mutex.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/dynamic_reconfigure/config_tools.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/dynamic_reconfigure/server.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/gazebo_msgs/GetModelState.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/gazebo_msgs/GetModelStateRequest.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/gazebo_msgs/GetModelStateResponse.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/advertise_options.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/advertise_service_options.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/assert.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/builtin_message_traits.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/callback_queue.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/callback_queue_interface.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/common.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/console.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/console_backend.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/datatypes.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/duration.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/exception.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/exceptions.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/forwards.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/init.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/macros.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/master.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/message.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/message_event.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/message_forward.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/message_operations.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/message_traits.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/names.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/node_handle.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/param.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/parameter_adapter.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/platform.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/publisher.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/rate.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/ros.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/roscpp_serialization_macros.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/rostime_decl.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/serialization.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/serialized_message.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/service.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/service_callback_helper.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/service_client.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/service_client_options.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/service_server.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/service_traits.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/single_subscriber_publisher.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/spinner.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/static_assert.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/steady_timer.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/steady_timer_options.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/subscribe_options.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/subscriber.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/subscription_callback_helper.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/this_node.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/time.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/timer.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/timer_options.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/topic.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/transport_hints.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/types.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/wall_timer.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/ros/wall_timer_options.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/rosconsole/macros_generated.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/std_msgs/Header.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/std_srvs/Empty.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/std_srvs/EmptyRequest.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/std_srvs/EmptyResponse.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/xmlrpcpp/XmlRpcDecl.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /opt/ros/noetic/include/xmlrpcpp/XmlRpcValue.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/Cholesky
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/Core
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/Dense
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/Eigen
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/Eigenvalues
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/Geometry
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/Householder
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/IterativeLinearSolvers
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/Jacobi
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/LU
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/OrderingMethods
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/QR
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/SVD
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/Sparse
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/SparseCholesky
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/SparseCore
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/SparseLU
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/SparseQR
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_LAPACKE.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Array.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Assign.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Block.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/ConditionEstimator.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/CwiseTernaryOp.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Dot.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/IO.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Inverse.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Map.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/MathFunctionsImpl.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Product.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Random.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Redux.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Ref.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Select.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Solve.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/SolverBase.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Stride.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Swap.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/AVX/Complex.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/AVX/MathFunctions.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/AVX/TypeCasting.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/AVX512/MathFunctions.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/AVX512/PacketMath.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/MathFunctions.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/CUDA/Complex.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/CUDA/Half.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/CUDA/MathFunctions.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMath.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMathHalf.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/CUDA/TypeCasting.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/ConjHelper.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/MathFunctions.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/TypeCasting.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/ZVector/Complex.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/ZVector/MathFunctions.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/arch/ZVector/PacketMath.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/functors/BinaryFunctors.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/functors/NullaryFunctors.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/functors/StlFunctors.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/functors/TernaryFunctors.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/functors/UnaryFunctors.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_BLAS.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_BLAS.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_BLAS.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_BLAS.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_BLAS.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_BLAS.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_BLAS.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_BLAS.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/util/NonMPL2.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_LAPACKE.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_LAPACKE.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_LAPACKE.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IncompleteCholesky.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IncompleteLUT.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/LeastSquareConjugateGradient.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/IterativeLinearSolvers/SolveWithGuess.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/LU/InverseImpl.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_LAPACKE.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/OrderingMethods/Amd.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/OrderingMethods/Eigen_Colamd.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/OrderingMethods/Ordering.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_LAPACKE.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/QR/CompleteOrthogonalDecomposition.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_LAPACKE.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SVD/BDCSVD.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_LAPACKE.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SVD/SVDBase.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCholesky/SimplicialCholesky.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCholesky/SimplicialCholesky_impl.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/AmbiVector.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/CompressedStorage.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/ConservativeSparseSparseProduct.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/MappedSparseMatrix.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseAssign.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseBlock.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseColEtree.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseCompressedBase.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseCwiseBinaryOp.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseCwiseUnaryOp.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseDenseProduct.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseDiagonalProduct.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseDot.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseFuzzy.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseMap.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseMatrix.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseMatrixBase.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparsePermutation.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseProduct.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseRedux.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseRef.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseSelfAdjointView.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseSolverBase.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseSparseProductWithPruning.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseTranspose.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseTriangularView.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseUtil.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseVector.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/SparseView.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseCore/TriangularSolver.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLUImpl.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Memory.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Structs.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_Utils.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_column_bmod.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_column_dfs.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_copy_to_ucol.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_gemm_kernel.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_heap_relax_snode.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_kernel_bmod.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_panel_bmod.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_panel_dfs.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_pivotL.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_pruneL.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseLU/SparseLU_relax_snode.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/SparseQR/SparseQR.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/misc/Image.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/misc/RealSvd2x2.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/misc/blas.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/misc/lapacke.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/misc/lapacke_mangling.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: acado_auxiliary_functions.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: acado_common.h
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: acado_qpoases_interface.hpp
+CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o: devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/flags.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/flags.make
new file mode 100644
index 0000000000000000000000000000000000000000..f8a0be5e7862755cb816c296f09a6d734e5ea2b5
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/flags.make
@@ -0,0 +1,10 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# compile CXX with /usr/bin/c++
+CXX_FLAGS =  -std=c++11 -O3 -DNDEBUG  
+
+CXX_DEFINES = -DROSCONSOLE_BACKEND_LOG4CXX -DROS_BUILD_SHARED_LIBS=1 -DROS_PACKAGE_NAME=\"mav_nonlinear_mpc\"
+
+CXX_INCLUDES = -I/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/include -I/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/include -I/home/simhe502/catkin_ws/devel/include -I/home/simhe502/catkin_ws/src/common_msgs/sensor_msgs/include -I/opt/ros/noetic/include -I/opt/ros/noetic/share/xmlrpcpp/cmake/../../../include/xmlrpcpp -I/usr/include/eigen3 -I/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver -I/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases -I/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE -I/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC 
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/link.txt b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/link.txt
new file mode 100644
index 0000000000000000000000000000000000000000..1e808cc56ae7d3088bf1f1425112a5fdba3e5423
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/link.txt
@@ -0,0 +1 @@
+/usr/bin/c++   -std=c++11 -O3 -DNDEBUG  -rdynamic CMakeFiles/nonlinear_mpc_node.dir/src/nonlinear_mpc_node.cc.o  -o devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node  -Wl,-rpath,/opt/ros/noetic/lib:/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib: /opt/ros/noetic/lib/libdynamic_reconfigure_config_init_mutex.so /opt/ros/noetic/lib/libtf.so /opt/ros/noetic/lib/libtf2_ros.so /opt/ros/noetic/lib/libactionlib.so /opt/ros/noetic/lib/libmessage_filters.so /opt/ros/noetic/lib/libroscpp.so -lpthread /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.71.0 /usr/lib/x86_64-linux-gnu/libboost_filesystem.so.1.71.0 /opt/ros/noetic/lib/libxmlrpcpp.so /opt/ros/noetic/lib/libtf2.so /opt/ros/noetic/lib/libroscpp_serialization.so /opt/ros/noetic/lib/librosconsole.so /opt/ros/noetic/lib/librosconsole_log4cxx.so /opt/ros/noetic/lib/librosconsole_backend_interface.so -llog4cxx /usr/lib/x86_64-linux-gnu/libboost_regex.so.1.71.0 /opt/ros/noetic/lib/librostime.so /usr/lib/x86_64-linux-gnu/libboost_date_time.so.1.71.0 /opt/ros/noetic/lib/libcpp_common.so /usr/lib/x86_64-linux-gnu/libboost_system.so.1.71.0 /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.71.0 /usr/lib/x86_64-linux-gnu/libconsole_bridge.so.0.4 devel/lib/libmav_nonlinear_mpc_lib.so /opt/ros/noetic/lib/libdynamic_reconfigure_config_init_mutex.so /opt/ros/noetic/lib/libtf.so /opt/ros/noetic/lib/libtf2_ros.so /opt/ros/noetic/lib/libactionlib.so /opt/ros/noetic/lib/libmessage_filters.so /opt/ros/noetic/lib/libroscpp.so -lpthread /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.71.0 /usr/lib/x86_64-linux-gnu/libboost_filesystem.so.1.71.0 /opt/ros/noetic/lib/libxmlrpcpp.so /opt/ros/noetic/lib/libtf2.so /opt/ros/noetic/lib/libroscpp_serialization.so /opt/ros/noetic/lib/librosconsole.so /opt/ros/noetic/lib/librosconsole_log4cxx.so /opt/ros/noetic/lib/librosconsole_backend_interface.so -llog4cxx /usr/lib/x86_64-linux-gnu/libboost_regex.so.1.71.0 /opt/ros/noetic/lib/librostime.so /usr/lib/x86_64-linux-gnu/libboost_date_time.so.1.71.0 /opt/ros/noetic/lib/libcpp_common.so /usr/lib/x86_64-linux-gnu/libboost_system.so.1.71.0 /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.71.0 /usr/lib/x86_64-linux-gnu/libconsole_bridge.so.0.4 
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..3244467eda05b3e61da6a3fa7ca49829960aa1fc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/nonlinear_mpc_node.dir/progress.make
@@ -0,0 +1,3 @@
+CMAKE_PROGRESS_1 = 26
+CMAKE_PROGRESS_2 = 27
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/progress.marks b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/progress.marks
new file mode 100644
index 0000000000000000000000000000000000000000..d6b24041cf04154f8f902651969675021f4d93a5
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/progress.marks
@@ -0,0 +1 @@
+19
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_cpp.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_cpp.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_cpp.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_cpp.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_cpp.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..3fdd3037ab37e650a2d58daea71694f45a10bed0
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_cpp.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for roscpp_generate_messages_cpp.
+
+# Include the progress variables for this target.
+include CMakeFiles/roscpp_generate_messages_cpp.dir/progress.make
+
+roscpp_generate_messages_cpp: CMakeFiles/roscpp_generate_messages_cpp.dir/build.make
+
+.PHONY : roscpp_generate_messages_cpp
+
+# Rule to build all files generated by this target.
+CMakeFiles/roscpp_generate_messages_cpp.dir/build: roscpp_generate_messages_cpp
+
+.PHONY : CMakeFiles/roscpp_generate_messages_cpp.dir/build
+
+CMakeFiles/roscpp_generate_messages_cpp.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/roscpp_generate_messages_cpp.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/roscpp_generate_messages_cpp.dir/clean
+
+CMakeFiles/roscpp_generate_messages_cpp.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_cpp.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/roscpp_generate_messages_cpp.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_cpp.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_cpp.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..bf353654a022affaf54224fbd1c18177f271b037
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_cpp.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/roscpp_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_cpp.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_cpp.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_cpp.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_cpp.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_cpp.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_cpp.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_cpp.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_cpp.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_cpp.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_eus.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_eus.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_eus.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_eus.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_eus.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..a14f52d4271d88238ce9fb4ecf5529e98d3ee60b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_eus.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for roscpp_generate_messages_eus.
+
+# Include the progress variables for this target.
+include CMakeFiles/roscpp_generate_messages_eus.dir/progress.make
+
+roscpp_generate_messages_eus: CMakeFiles/roscpp_generate_messages_eus.dir/build.make
+
+.PHONY : roscpp_generate_messages_eus
+
+# Rule to build all files generated by this target.
+CMakeFiles/roscpp_generate_messages_eus.dir/build: roscpp_generate_messages_eus
+
+.PHONY : CMakeFiles/roscpp_generate_messages_eus.dir/build
+
+CMakeFiles/roscpp_generate_messages_eus.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/roscpp_generate_messages_eus.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/roscpp_generate_messages_eus.dir/clean
+
+CMakeFiles/roscpp_generate_messages_eus.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_eus.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/roscpp_generate_messages_eus.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_eus.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_eus.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..61700fa61598b5a7c45ee26eac646fe367101992
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_eus.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/roscpp_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_eus.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_eus.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_eus.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_eus.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_eus.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_eus.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_eus.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_eus.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_eus.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_lisp.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_lisp.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_lisp.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_lisp.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_lisp.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..db43be4a83fb359880a147c6e2d572e4083605cb
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_lisp.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for roscpp_generate_messages_lisp.
+
+# Include the progress variables for this target.
+include CMakeFiles/roscpp_generate_messages_lisp.dir/progress.make
+
+roscpp_generate_messages_lisp: CMakeFiles/roscpp_generate_messages_lisp.dir/build.make
+
+.PHONY : roscpp_generate_messages_lisp
+
+# Rule to build all files generated by this target.
+CMakeFiles/roscpp_generate_messages_lisp.dir/build: roscpp_generate_messages_lisp
+
+.PHONY : CMakeFiles/roscpp_generate_messages_lisp.dir/build
+
+CMakeFiles/roscpp_generate_messages_lisp.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/roscpp_generate_messages_lisp.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/roscpp_generate_messages_lisp.dir/clean
+
+CMakeFiles/roscpp_generate_messages_lisp.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_lisp.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/roscpp_generate_messages_lisp.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_lisp.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_lisp.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..492a50bd91a039addba1281e459d4aee16b465e4
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_lisp.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/roscpp_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_lisp.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_lisp.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_lisp.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_lisp.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_lisp.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_lisp.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_lisp.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_lisp.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_lisp.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_nodejs.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_nodejs.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_nodejs.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_nodejs.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_nodejs.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..bfecfd4f7f278eddac9747ed2d0179fe360de6a9
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_nodejs.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for roscpp_generate_messages_nodejs.
+
+# Include the progress variables for this target.
+include CMakeFiles/roscpp_generate_messages_nodejs.dir/progress.make
+
+roscpp_generate_messages_nodejs: CMakeFiles/roscpp_generate_messages_nodejs.dir/build.make
+
+.PHONY : roscpp_generate_messages_nodejs
+
+# Rule to build all files generated by this target.
+CMakeFiles/roscpp_generate_messages_nodejs.dir/build: roscpp_generate_messages_nodejs
+
+.PHONY : CMakeFiles/roscpp_generate_messages_nodejs.dir/build
+
+CMakeFiles/roscpp_generate_messages_nodejs.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/roscpp_generate_messages_nodejs.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/roscpp_generate_messages_nodejs.dir/clean
+
+CMakeFiles/roscpp_generate_messages_nodejs.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_nodejs.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/roscpp_generate_messages_nodejs.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_nodejs.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_nodejs.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..37945a670242e2de6d8465b3474da9eb383ab588
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_nodejs.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/roscpp_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_nodejs.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_nodejs.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_nodejs.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_nodejs.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_nodejs.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_nodejs.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_nodejs.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_nodejs.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_nodejs.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_py.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_py.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_py.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_py.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_py.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..a34c39428dbae885f30d8371f3a6f0a03321b3bb
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_py.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for roscpp_generate_messages_py.
+
+# Include the progress variables for this target.
+include CMakeFiles/roscpp_generate_messages_py.dir/progress.make
+
+roscpp_generate_messages_py: CMakeFiles/roscpp_generate_messages_py.dir/build.make
+
+.PHONY : roscpp_generate_messages_py
+
+# Rule to build all files generated by this target.
+CMakeFiles/roscpp_generate_messages_py.dir/build: roscpp_generate_messages_py
+
+.PHONY : CMakeFiles/roscpp_generate_messages_py.dir/build
+
+CMakeFiles/roscpp_generate_messages_py.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/roscpp_generate_messages_py.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/roscpp_generate_messages_py.dir/clean
+
+CMakeFiles/roscpp_generate_messages_py.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_py.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/roscpp_generate_messages_py.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_py.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_py.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..2c13747338b810ad1480558faa521f8adb7d395b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_py.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/roscpp_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_py.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_py.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_py.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_py.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_py.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_py.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_py.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_py.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/roscpp_generate_messages_py.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..86f859ef4134842d520e72f333fdc43ca8ec48b1
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for rosgraph_msgs_generate_messages_cpp.
+
+# Include the progress variables for this target.
+include CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/progress.make
+
+rosgraph_msgs_generate_messages_cpp: CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build.make
+
+.PHONY : rosgraph_msgs_generate_messages_cpp
+
+# Rule to build all files generated by this target.
+CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build: rosgraph_msgs_generate_messages_cpp
+
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build
+
+CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/clean
+
+CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..720bdd0edac46cb588da30503f36902d22b1f3bd
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..cf0bbd3713e0c9a2c01821c72100661f3d19b3f4
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for rosgraph_msgs_generate_messages_eus.
+
+# Include the progress variables for this target.
+include CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/progress.make
+
+rosgraph_msgs_generate_messages_eus: CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build.make
+
+.PHONY : rosgraph_msgs_generate_messages_eus
+
+# Rule to build all files generated by this target.
+CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build: rosgraph_msgs_generate_messages_eus
+
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build
+
+CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/clean
+
+CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..5610f8400a30f1c9e738841c6a11b635aaeb3648
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..a710cf8f6da2e821b9cf85cefe68f5abc1f6f6ed
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for rosgraph_msgs_generate_messages_lisp.
+
+# Include the progress variables for this target.
+include CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/progress.make
+
+rosgraph_msgs_generate_messages_lisp: CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build.make
+
+.PHONY : rosgraph_msgs_generate_messages_lisp
+
+# Rule to build all files generated by this target.
+CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build: rosgraph_msgs_generate_messages_lisp
+
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build
+
+CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/clean
+
+CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..cdd6e3fce75ecbc3ad7295b674353e85f77ba7a5
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..ca76558bd376b19d3dc0f309198ff2716849b746
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for rosgraph_msgs_generate_messages_nodejs.
+
+# Include the progress variables for this target.
+include CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/progress.make
+
+rosgraph_msgs_generate_messages_nodejs: CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build.make
+
+.PHONY : rosgraph_msgs_generate_messages_nodejs
+
+# Rule to build all files generated by this target.
+CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build: rosgraph_msgs_generate_messages_nodejs
+
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build
+
+CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/clean
+
+CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..37bf13dc24b1724d4b85b9617056c744d5e99df3
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..8134fce4fb7648780bb686b7668972dc34f356d5
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for rosgraph_msgs_generate_messages_py.
+
+# Include the progress variables for this target.
+include CMakeFiles/rosgraph_msgs_generate_messages_py.dir/progress.make
+
+rosgraph_msgs_generate_messages_py: CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build.make
+
+.PHONY : rosgraph_msgs_generate_messages_py
+
+# Rule to build all files generated by this target.
+CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build: rosgraph_msgs_generate_messages_py
+
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build
+
+CMakeFiles/rosgraph_msgs_generate_messages_py.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/rosgraph_msgs_generate_messages_py.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_py.dir/clean
+
+CMakeFiles/rosgraph_msgs_generate_messages_py.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_py.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..de801d4c76b9fbe39fc2cdad82bc436399718f92
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/rosgraph_msgs_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/run_tests.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/run_tests.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/run_tests.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/run_tests.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/run_tests.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..a7e1919a78e6e3e91d47163cc8dfeed39c1c00bc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/run_tests.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for run_tests.
+
+# Include the progress variables for this target.
+include CMakeFiles/run_tests.dir/progress.make
+
+run_tests: CMakeFiles/run_tests.dir/build.make
+
+.PHONY : run_tests
+
+# Rule to build all files generated by this target.
+CMakeFiles/run_tests.dir/build: run_tests
+
+.PHONY : CMakeFiles/run_tests.dir/build
+
+CMakeFiles/run_tests.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/run_tests.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/run_tests.dir/clean
+
+CMakeFiles/run_tests.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/run_tests.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/run_tests.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/run_tests.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/run_tests.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..e67d34f6d11ce305bbc51c998454c8d9cc3b7470
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/run_tests.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/run_tests.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/run_tests.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/run_tests.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/run_tests.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..4ac27d8f49d4f96cc4e3a98f5c6ff438e5e17562
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for sensor_msgs_generate_messages_cpp.
+
+# Include the progress variables for this target.
+include CMakeFiles/sensor_msgs_generate_messages_cpp.dir/progress.make
+
+sensor_msgs_generate_messages_cpp: CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build.make
+
+.PHONY : sensor_msgs_generate_messages_cpp
+
+# Rule to build all files generated by this target.
+CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build: sensor_msgs_generate_messages_cpp
+
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build
+
+CMakeFiles/sensor_msgs_generate_messages_cpp.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/sensor_msgs_generate_messages_cpp.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_cpp.dir/clean
+
+CMakeFiles/sensor_msgs_generate_messages_cpp.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_cpp.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..1716093339a5610e028fb149280807108a20bb24
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/sensor_msgs_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_eus.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_eus.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_eus.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_eus.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_eus.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..5dc13d84426fa87038993f4b2e07aa0956c8f328
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_eus.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for sensor_msgs_generate_messages_eus.
+
+# Include the progress variables for this target.
+include CMakeFiles/sensor_msgs_generate_messages_eus.dir/progress.make
+
+sensor_msgs_generate_messages_eus: CMakeFiles/sensor_msgs_generate_messages_eus.dir/build.make
+
+.PHONY : sensor_msgs_generate_messages_eus
+
+# Rule to build all files generated by this target.
+CMakeFiles/sensor_msgs_generate_messages_eus.dir/build: sensor_msgs_generate_messages_eus
+
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_eus.dir/build
+
+CMakeFiles/sensor_msgs_generate_messages_eus.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/sensor_msgs_generate_messages_eus.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_eus.dir/clean
+
+CMakeFiles/sensor_msgs_generate_messages_eus.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_eus.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_eus.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_eus.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_eus.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..eabddd7b0ca0480a31b3c0545a1766520a35cc8a
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_eus.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/sensor_msgs_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_eus.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_eus.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_eus.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_eus.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_eus.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_eus.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_eus.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_eus.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_eus.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..ee16d802f685823d618e60cf1a0135eef134e723
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for sensor_msgs_generate_messages_lisp.
+
+# Include the progress variables for this target.
+include CMakeFiles/sensor_msgs_generate_messages_lisp.dir/progress.make
+
+sensor_msgs_generate_messages_lisp: CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build.make
+
+.PHONY : sensor_msgs_generate_messages_lisp
+
+# Rule to build all files generated by this target.
+CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build: sensor_msgs_generate_messages_lisp
+
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build
+
+CMakeFiles/sensor_msgs_generate_messages_lisp.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/sensor_msgs_generate_messages_lisp.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_lisp.dir/clean
+
+CMakeFiles/sensor_msgs_generate_messages_lisp.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_lisp.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..ecc0226b38bf588bc2b94b3b4012df624d73169d
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/sensor_msgs_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..446fbea4e4a49940c79424ed94cef473ad86807d
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for sensor_msgs_generate_messages_nodejs.
+
+# Include the progress variables for this target.
+include CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/progress.make
+
+sensor_msgs_generate_messages_nodejs: CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build.make
+
+.PHONY : sensor_msgs_generate_messages_nodejs
+
+# Rule to build all files generated by this target.
+CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build: sensor_msgs_generate_messages_nodejs
+
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build
+
+CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/clean
+
+CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..534a2e5b31a0561cb87b25a1496b229201fad8c8
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_py.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_py.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_py.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_py.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_py.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..670636200282bae34b643f47d563bf9665c09ab4
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_py.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for sensor_msgs_generate_messages_py.
+
+# Include the progress variables for this target.
+include CMakeFiles/sensor_msgs_generate_messages_py.dir/progress.make
+
+sensor_msgs_generate_messages_py: CMakeFiles/sensor_msgs_generate_messages_py.dir/build.make
+
+.PHONY : sensor_msgs_generate_messages_py
+
+# Rule to build all files generated by this target.
+CMakeFiles/sensor_msgs_generate_messages_py.dir/build: sensor_msgs_generate_messages_py
+
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_py.dir/build
+
+CMakeFiles/sensor_msgs_generate_messages_py.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/sensor_msgs_generate_messages_py.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_py.dir/clean
+
+CMakeFiles/sensor_msgs_generate_messages_py.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_py.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/sensor_msgs_generate_messages_py.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_py.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_py.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..a5188efec73b5f5a27435b62a5e9faabbbda323b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_py.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/sensor_msgs_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_py.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_py.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_py.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_py.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_py.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_py.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_py.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_py.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/sensor_msgs_generate_messages_py.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_cpp.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_cpp.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_cpp.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_cpp.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_cpp.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..e9e4038558fac3e9404b756ab72dacce886ec661
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_cpp.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for std_msgs_generate_messages_cpp.
+
+# Include the progress variables for this target.
+include CMakeFiles/std_msgs_generate_messages_cpp.dir/progress.make
+
+std_msgs_generate_messages_cpp: CMakeFiles/std_msgs_generate_messages_cpp.dir/build.make
+
+.PHONY : std_msgs_generate_messages_cpp
+
+# Rule to build all files generated by this target.
+CMakeFiles/std_msgs_generate_messages_cpp.dir/build: std_msgs_generate_messages_cpp
+
+.PHONY : CMakeFiles/std_msgs_generate_messages_cpp.dir/build
+
+CMakeFiles/std_msgs_generate_messages_cpp.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/std_msgs_generate_messages_cpp.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/std_msgs_generate_messages_cpp.dir/clean
+
+CMakeFiles/std_msgs_generate_messages_cpp.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_cpp.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/std_msgs_generate_messages_cpp.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_cpp.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_cpp.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..0d092bf7dcb1a5955b6c2c4eef8f16df0593f3ea
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_cpp.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/std_msgs_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_cpp.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_cpp.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_cpp.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_cpp.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_cpp.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_cpp.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_cpp.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_cpp.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_cpp.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_eus.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_eus.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_eus.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_eus.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_eus.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..3051cd010f15c2288756c8a7941a70a8b29fc170
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_eus.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for std_msgs_generate_messages_eus.
+
+# Include the progress variables for this target.
+include CMakeFiles/std_msgs_generate_messages_eus.dir/progress.make
+
+std_msgs_generate_messages_eus: CMakeFiles/std_msgs_generate_messages_eus.dir/build.make
+
+.PHONY : std_msgs_generate_messages_eus
+
+# Rule to build all files generated by this target.
+CMakeFiles/std_msgs_generate_messages_eus.dir/build: std_msgs_generate_messages_eus
+
+.PHONY : CMakeFiles/std_msgs_generate_messages_eus.dir/build
+
+CMakeFiles/std_msgs_generate_messages_eus.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/std_msgs_generate_messages_eus.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/std_msgs_generate_messages_eus.dir/clean
+
+CMakeFiles/std_msgs_generate_messages_eus.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_eus.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/std_msgs_generate_messages_eus.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_eus.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_eus.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..855155ec96fb985c24a72c15e128f656d9f6065a
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_eus.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/std_msgs_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_eus.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_eus.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_eus.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_eus.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_eus.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_eus.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_eus.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_eus.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_eus.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_lisp.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_lisp.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_lisp.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_lisp.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_lisp.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..0495f6115e765fe3e50c5ad385ca5736f3129cb0
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_lisp.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for std_msgs_generate_messages_lisp.
+
+# Include the progress variables for this target.
+include CMakeFiles/std_msgs_generate_messages_lisp.dir/progress.make
+
+std_msgs_generate_messages_lisp: CMakeFiles/std_msgs_generate_messages_lisp.dir/build.make
+
+.PHONY : std_msgs_generate_messages_lisp
+
+# Rule to build all files generated by this target.
+CMakeFiles/std_msgs_generate_messages_lisp.dir/build: std_msgs_generate_messages_lisp
+
+.PHONY : CMakeFiles/std_msgs_generate_messages_lisp.dir/build
+
+CMakeFiles/std_msgs_generate_messages_lisp.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/std_msgs_generate_messages_lisp.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/std_msgs_generate_messages_lisp.dir/clean
+
+CMakeFiles/std_msgs_generate_messages_lisp.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_lisp.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/std_msgs_generate_messages_lisp.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_lisp.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_lisp.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..b995112eab054ad92b9ec2bd7533b328f13f306e
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_lisp.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/std_msgs_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_lisp.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_lisp.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_lisp.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_lisp.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_lisp.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_lisp.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_lisp.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_lisp.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_lisp.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_nodejs.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_nodejs.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_nodejs.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_nodejs.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_nodejs.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..b3196de6727dde0507625c9c9b82a7f5ee3b3eb3
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_nodejs.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for std_msgs_generate_messages_nodejs.
+
+# Include the progress variables for this target.
+include CMakeFiles/std_msgs_generate_messages_nodejs.dir/progress.make
+
+std_msgs_generate_messages_nodejs: CMakeFiles/std_msgs_generate_messages_nodejs.dir/build.make
+
+.PHONY : std_msgs_generate_messages_nodejs
+
+# Rule to build all files generated by this target.
+CMakeFiles/std_msgs_generate_messages_nodejs.dir/build: std_msgs_generate_messages_nodejs
+
+.PHONY : CMakeFiles/std_msgs_generate_messages_nodejs.dir/build
+
+CMakeFiles/std_msgs_generate_messages_nodejs.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/std_msgs_generate_messages_nodejs.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/std_msgs_generate_messages_nodejs.dir/clean
+
+CMakeFiles/std_msgs_generate_messages_nodejs.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_nodejs.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/std_msgs_generate_messages_nodejs.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_nodejs.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_nodejs.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..f5f42ae06987e0d5a16acccec495927a20b926de
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_nodejs.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/std_msgs_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_nodejs.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_nodejs.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_nodejs.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_nodejs.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_nodejs.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_nodejs.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_nodejs.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_nodejs.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_nodejs.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_py.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_py.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_py.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_py.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_py.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..80cb9a680b4e32be9bc6eec0ae3cb9247d7ec670
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_py.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for std_msgs_generate_messages_py.
+
+# Include the progress variables for this target.
+include CMakeFiles/std_msgs_generate_messages_py.dir/progress.make
+
+std_msgs_generate_messages_py: CMakeFiles/std_msgs_generate_messages_py.dir/build.make
+
+.PHONY : std_msgs_generate_messages_py
+
+# Rule to build all files generated by this target.
+CMakeFiles/std_msgs_generate_messages_py.dir/build: std_msgs_generate_messages_py
+
+.PHONY : CMakeFiles/std_msgs_generate_messages_py.dir/build
+
+CMakeFiles/std_msgs_generate_messages_py.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/std_msgs_generate_messages_py.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/std_msgs_generate_messages_py.dir/clean
+
+CMakeFiles/std_msgs_generate_messages_py.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_py.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/std_msgs_generate_messages_py.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_py.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_py.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..15da12c8d9c8a0533d756cbfb4fbf902c32cf641
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_py.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/std_msgs_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_py.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_py.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_py.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_py.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_py.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_py.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_py.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_py.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/std_msgs_generate_messages_py.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tests.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tests.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tests.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tests.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tests.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..41e0d13addfae656259a677ac64366a421953de0
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tests.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for tests.
+
+# Include the progress variables for this target.
+include CMakeFiles/tests.dir/progress.make
+
+tests: CMakeFiles/tests.dir/build.make
+
+.PHONY : tests
+
+# Rule to build all files generated by this target.
+CMakeFiles/tests.dir/build: tests
+
+.PHONY : CMakeFiles/tests.dir/build
+
+CMakeFiles/tests.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/tests.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/tests.dir/clean
+
+CMakeFiles/tests.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tests.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/tests.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tests.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tests.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..910f04d829639aafb592cbe6806fdcd7276630ee
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tests.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/tests.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tests.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tests.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tests.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..78dd22c22147d726ff5504408c26718f33693005
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for tf2_msgs_generate_messages_cpp.
+
+# Include the progress variables for this target.
+include CMakeFiles/tf2_msgs_generate_messages_cpp.dir/progress.make
+
+tf2_msgs_generate_messages_cpp: CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build.make
+
+.PHONY : tf2_msgs_generate_messages_cpp
+
+# Rule to build all files generated by this target.
+CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build: tf2_msgs_generate_messages_cpp
+
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build
+
+CMakeFiles/tf2_msgs_generate_messages_cpp.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/tf2_msgs_generate_messages_cpp.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_cpp.dir/clean
+
+CMakeFiles/tf2_msgs_generate_messages_cpp.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_cpp.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..97cac24707eb62f163a1aabe67cd9ad93c7877c7
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/tf2_msgs_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_eus.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_eus.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_eus.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_eus.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_eus.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..871db4e7e3195a0a7ac23685da39849aa5df6b44
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_eus.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for tf2_msgs_generate_messages_eus.
+
+# Include the progress variables for this target.
+include CMakeFiles/tf2_msgs_generate_messages_eus.dir/progress.make
+
+tf2_msgs_generate_messages_eus: CMakeFiles/tf2_msgs_generate_messages_eus.dir/build.make
+
+.PHONY : tf2_msgs_generate_messages_eus
+
+# Rule to build all files generated by this target.
+CMakeFiles/tf2_msgs_generate_messages_eus.dir/build: tf2_msgs_generate_messages_eus
+
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_eus.dir/build
+
+CMakeFiles/tf2_msgs_generate_messages_eus.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/tf2_msgs_generate_messages_eus.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_eus.dir/clean
+
+CMakeFiles/tf2_msgs_generate_messages_eus.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_eus.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_eus.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_eus.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_eus.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..29107f6e415c584fd85e93636917fb1de455c9f3
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_eus.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/tf2_msgs_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_eus.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_eus.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_eus.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_eus.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_eus.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_eus.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_eus.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_eus.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_eus.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..d65725a504dd9b6a40bfb2266ee6ece72e4fba3a
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for tf2_msgs_generate_messages_lisp.
+
+# Include the progress variables for this target.
+include CMakeFiles/tf2_msgs_generate_messages_lisp.dir/progress.make
+
+tf2_msgs_generate_messages_lisp: CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build.make
+
+.PHONY : tf2_msgs_generate_messages_lisp
+
+# Rule to build all files generated by this target.
+CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build: tf2_msgs_generate_messages_lisp
+
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build
+
+CMakeFiles/tf2_msgs_generate_messages_lisp.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/tf2_msgs_generate_messages_lisp.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_lisp.dir/clean
+
+CMakeFiles/tf2_msgs_generate_messages_lisp.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_lisp.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..96188673f51948cce12b6fbeca02f43da7a6ca76
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/tf2_msgs_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..9948ba2168211225761e522130be6a65174541d9
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for tf2_msgs_generate_messages_nodejs.
+
+# Include the progress variables for this target.
+include CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/progress.make
+
+tf2_msgs_generate_messages_nodejs: CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build.make
+
+.PHONY : tf2_msgs_generate_messages_nodejs
+
+# Rule to build all files generated by this target.
+CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build: tf2_msgs_generate_messages_nodejs
+
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build
+
+CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/clean
+
+CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..bd97d95a76d7370ff6697d94c15fbe0b63dadd4c
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_py.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_py.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_py.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_py.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_py.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..175ab2f6cfd07000c0467a70f40fad17c2d6197a
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_py.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for tf2_msgs_generate_messages_py.
+
+# Include the progress variables for this target.
+include CMakeFiles/tf2_msgs_generate_messages_py.dir/progress.make
+
+tf2_msgs_generate_messages_py: CMakeFiles/tf2_msgs_generate_messages_py.dir/build.make
+
+.PHONY : tf2_msgs_generate_messages_py
+
+# Rule to build all files generated by this target.
+CMakeFiles/tf2_msgs_generate_messages_py.dir/build: tf2_msgs_generate_messages_py
+
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_py.dir/build
+
+CMakeFiles/tf2_msgs_generate_messages_py.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/tf2_msgs_generate_messages_py.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_py.dir/clean
+
+CMakeFiles/tf2_msgs_generate_messages_py.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_py.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/tf2_msgs_generate_messages_py.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_py.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_py.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..3effb9b40937aa28da2ed6aff22f78bfac689f9e
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_py.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/tf2_msgs_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_py.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_py.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_py.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_py.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_py.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_py.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_py.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_py.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf2_msgs_generate_messages_py.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_cpp.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_cpp.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_cpp.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_cpp.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_cpp.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..b7592af8b2557fe5561ab98fa222513a52661f89
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_cpp.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for tf_generate_messages_cpp.
+
+# Include the progress variables for this target.
+include CMakeFiles/tf_generate_messages_cpp.dir/progress.make
+
+tf_generate_messages_cpp: CMakeFiles/tf_generate_messages_cpp.dir/build.make
+
+.PHONY : tf_generate_messages_cpp
+
+# Rule to build all files generated by this target.
+CMakeFiles/tf_generate_messages_cpp.dir/build: tf_generate_messages_cpp
+
+.PHONY : CMakeFiles/tf_generate_messages_cpp.dir/build
+
+CMakeFiles/tf_generate_messages_cpp.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/tf_generate_messages_cpp.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/tf_generate_messages_cpp.dir/clean
+
+CMakeFiles/tf_generate_messages_cpp.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_cpp.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/tf_generate_messages_cpp.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_cpp.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_cpp.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..5378e2006e718d6c254097b440a0530e5f45f448
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_cpp.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/tf_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_cpp.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_cpp.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_cpp.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_cpp.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_cpp.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_cpp.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_cpp.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_cpp.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_cpp.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_eus.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_eus.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_eus.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_eus.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_eus.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..b61e52cc14f15cfae0ffb2759fa6d1f4c31b663b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_eus.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for tf_generate_messages_eus.
+
+# Include the progress variables for this target.
+include CMakeFiles/tf_generate_messages_eus.dir/progress.make
+
+tf_generate_messages_eus: CMakeFiles/tf_generate_messages_eus.dir/build.make
+
+.PHONY : tf_generate_messages_eus
+
+# Rule to build all files generated by this target.
+CMakeFiles/tf_generate_messages_eus.dir/build: tf_generate_messages_eus
+
+.PHONY : CMakeFiles/tf_generate_messages_eus.dir/build
+
+CMakeFiles/tf_generate_messages_eus.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/tf_generate_messages_eus.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/tf_generate_messages_eus.dir/clean
+
+CMakeFiles/tf_generate_messages_eus.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_eus.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/tf_generate_messages_eus.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_eus.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_eus.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..fbc2fb89ec0a32eb88956faebda8e25c7fb622d9
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_eus.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/tf_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_eus.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_eus.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_eus.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_eus.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_eus.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_eus.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_eus.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_eus.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_eus.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_lisp.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_lisp.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_lisp.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_lisp.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_lisp.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..82ac13d77339ee392c5a00b490646a89d633e65b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_lisp.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for tf_generate_messages_lisp.
+
+# Include the progress variables for this target.
+include CMakeFiles/tf_generate_messages_lisp.dir/progress.make
+
+tf_generate_messages_lisp: CMakeFiles/tf_generate_messages_lisp.dir/build.make
+
+.PHONY : tf_generate_messages_lisp
+
+# Rule to build all files generated by this target.
+CMakeFiles/tf_generate_messages_lisp.dir/build: tf_generate_messages_lisp
+
+.PHONY : CMakeFiles/tf_generate_messages_lisp.dir/build
+
+CMakeFiles/tf_generate_messages_lisp.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/tf_generate_messages_lisp.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/tf_generate_messages_lisp.dir/clean
+
+CMakeFiles/tf_generate_messages_lisp.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_lisp.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/tf_generate_messages_lisp.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_lisp.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_lisp.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..c66eb7b7ef6721407a840a8d16ac7bf075b03f7e
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_lisp.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/tf_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_lisp.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_lisp.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_lisp.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_lisp.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_lisp.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_lisp.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_lisp.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_lisp.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_lisp.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_nodejs.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_nodejs.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_nodejs.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_nodejs.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_nodejs.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..7b7663e401c121241b5eaef0e98fe9276f5e438e
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_nodejs.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for tf_generate_messages_nodejs.
+
+# Include the progress variables for this target.
+include CMakeFiles/tf_generate_messages_nodejs.dir/progress.make
+
+tf_generate_messages_nodejs: CMakeFiles/tf_generate_messages_nodejs.dir/build.make
+
+.PHONY : tf_generate_messages_nodejs
+
+# Rule to build all files generated by this target.
+CMakeFiles/tf_generate_messages_nodejs.dir/build: tf_generate_messages_nodejs
+
+.PHONY : CMakeFiles/tf_generate_messages_nodejs.dir/build
+
+CMakeFiles/tf_generate_messages_nodejs.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/tf_generate_messages_nodejs.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/tf_generate_messages_nodejs.dir/clean
+
+CMakeFiles/tf_generate_messages_nodejs.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_nodejs.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/tf_generate_messages_nodejs.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_nodejs.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_nodejs.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..ed543e14d544e5db77c27fca2dbef4b023418187
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_nodejs.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/tf_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_nodejs.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_nodejs.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_nodejs.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_nodejs.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_nodejs.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_nodejs.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_nodejs.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_nodejs.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_nodejs.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_py.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_py.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fab2149bf120962a1699d74b7373348dc4c117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_py.dir/DependInfo.cmake
@@ -0,0 +1,11 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  )
+# The set of files for implicit dependencies of each language:
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_py.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_py.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..cff35265c97052013e1e7fa2572e0299418c0218
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_py.dir/build.make
@@ -0,0 +1,72 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Utility rule file for tf_generate_messages_py.
+
+# Include the progress variables for this target.
+include CMakeFiles/tf_generate_messages_py.dir/progress.make
+
+tf_generate_messages_py: CMakeFiles/tf_generate_messages_py.dir/build.make
+
+.PHONY : tf_generate_messages_py
+
+# Rule to build all files generated by this target.
+CMakeFiles/tf_generate_messages_py.dir/build: tf_generate_messages_py
+
+.PHONY : CMakeFiles/tf_generate_messages_py.dir/build
+
+CMakeFiles/tf_generate_messages_py.dir/clean:
+	$(CMAKE_COMMAND) -P CMakeFiles/tf_generate_messages_py.dir/cmake_clean.cmake
+.PHONY : CMakeFiles/tf_generate_messages_py.dir/clean
+
+CMakeFiles/tf_generate_messages_py.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_py.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : CMakeFiles/tf_generate_messages_py.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_py.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_py.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..36912c76b955d4db65a82d8394e3f8a464ccdef0
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_py.dir/cmake_clean.cmake
@@ -0,0 +1,5 @@
+
+# Per-language clean rules from dependency scanning.
+foreach(lang )
+  include(CMakeFiles/tf_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_py.dir/depend.internal b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_py.dir/depend.internal
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_py.dir/depend.internal
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_py.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_py.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..f647855fc483eef4359d230d8e2650c6191dc079
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_py.dir/depend.make
@@ -0,0 +1,3 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_py.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_py.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8b137891791fe96927ad78e64b0aad7bded08bdc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles/tf_generate_messages_py.dir/progress.make
@@ -0,0 +1 @@
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CTestConfiguration.ini b/mav_control_rw/mav_nonlinear_mpc/solver/CTestConfiguration.ini
new file mode 100644
index 0000000000000000000000000000000000000000..6593c9ec21f6b9eda3fd047495346a6bfd3e0e33
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CTestConfiguration.ini
@@ -0,0 +1,105 @@
+# This file is configured by CMake automatically as DartConfiguration.tcl
+# If you choose not to use CMake, this file may be hand configured, by
+# filling in the required variables.
+
+
+# Configuration directories and files
+SourceDirectory: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+BuildDirectory: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Where to place the cost data store
+CostDataFile: 
+
+# Site is something like machine.domain, i.e. pragmatic.crd
+Site: olympen1-112
+
+# Build name is osname-revision-compiler, i.e. Linux-2.4.2-2smp-c++
+BuildName: 
+
+# Subprojects
+LabelsForSubprojects: 
+
+# Submission information
+SubmitURL: 
+
+# Dashboard start time
+NightlyStartTime: 
+
+# Commands for the build/test/submit cycle
+ConfigureCommand: "/usr/bin/cmake" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc"
+MakeCommand: 
+DefaultCTestConfigurationType: 
+
+# version control
+UpdateVersionOnly: 
+
+# CVS options
+# Default is "-d -P -A"
+CVSCommand: 
+CVSUpdateOptions: 
+
+# Subversion options
+SVNCommand: 
+SVNOptions: 
+SVNUpdateOptions: 
+
+# Git options
+GITCommand: 
+GITInitSubmodules: 
+GITUpdateOptions: 
+GITUpdateCustom: 
+
+# Perforce options
+P4Command: 
+P4Client: 
+P4Options: 
+P4UpdateOptions: 
+P4UpdateCustom: 
+
+# Generic update command
+UpdateCommand: 
+UpdateOptions: 
+UpdateType: 
+
+# Compiler info
+Compiler: /usr/bin/c++
+CompilerVersion: 9.4.0
+
+# Dynamic analysis (MemCheck)
+PurifyCommand: 
+ValgrindCommand: 
+ValgrindCommandOptions: 
+MemoryCheckType: 
+MemoryCheckSanitizerOptions: 
+MemoryCheckCommand: 
+MemoryCheckCommandOptions: 
+MemoryCheckSuppressionFile: 
+
+# Coverage
+CoverageCommand: 
+CoverageExtraFlags: 
+
+# Cluster commands
+SlurmBatchCommand: 
+SlurmRunCommand: 
+
+# Testing options
+# TimeOut is the amount of time in seconds to wait for processes
+# to complete during testing.  After TimeOut seconds, the
+# process will be summarily terminated.
+# Currently set to 25 minutes
+TimeOut: 
+
+# During parallel testing CTest will not start a new test if doing
+# so would cause the system load to exceed this value.
+TestLoad: 
+
+UseLaunchers: 
+CurlOptions: 
+# warning, if you add new options here that have to do with submit,
+# you have to update cmCTestSubmitCommand.cxx
+
+# For CTest submissions that timeout, these options
+# specify behavior for retrying the submission
+CTestSubmitRetryDelay: 
+CTestSubmitRetryCount: 
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CTestCustom.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CTestCustom.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..14956f319e3982ef0886cb4e45e5b67437a99b2a
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CTestCustom.cmake
@@ -0,0 +1,2 @@
+set(CTEST_CUSTOM_MAXIMUM_PASSED_TEST_OUTPUT_SIZE 0)
+set(CTEST_CUSTOM_MAXIMUM_FAILED_TEST_OUTPUT_SIZE 0)
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/CTestTestfile.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/CTestTestfile.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..59cc222dc83bb7829ee5fc12b8cbfee1cb835c18
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/CTestTestfile.cmake
@@ -0,0 +1,7 @@
+# CMake generated Testfile for 
+# Source directory: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+# Build directory: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+# 
+# This file includes the relevant testing commands required for 
+# testing this directory and lists subdirectories to be tested as well.
+subdirs("gtest")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/Makefile b/mav_control_rw/mav_nonlinear_mpc/solver/Makefile
new file mode 100644
index 0000000000000000000000000000000000000000..2c30c7a3144943a25a46b4c963df13fbcf0b644f
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/Makefile
@@ -0,0 +1,70 @@
+#
+#    This file was auto-generated using the ACADO Toolkit.
+#    
+#    While ACADO Toolkit is free software released under the terms of
+#    the GNU Lesser General Public License (LGPL), the generated code
+#    as such remains the property of the user who used ACADO Toolkit
+#    to generate this code. In particular, user dependent data of the code
+#    do not inherit the GNU LGPL license. On the other hand, parts of the
+#    generated code that are a direct copy of source code from the
+#    ACADO Toolkit or the software tools it is based on, remain, as derived
+#    work, automatically covered by the LGPL license.
+#    
+#    ACADO Toolkit is distributed in the hope that it will be useful,
+#    but WITHOUT ANY WARRANTY; without even the implied warranty of
+#    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+#    
+
+
+UNAME := $(shell uname)
+
+LDLIBS = -lm -lstdc++
+ifeq ($(UNAME), Linux)
+	LDLIBS += -lrt
+endif
+
+CCACHE_APP := $(shell which ccache 2>/dev/null)
+
+CFLAGS = -O3 -finline-functions -I. -I./qpoases
+CXXFLAGS = -O3 -finline-functions -I. -I./qpoases -I./qpoases/INCLUDE -I./qpoases/SRC
+CC     = $(CCACHE_APP) gcc
+CXX    = $(CCACHE_APP) g++
+
+OBJECTS = \
+	./qpoases/SRC/Bounds.o \
+	./qpoases/SRC/Constraints.o \
+	./qpoases/SRC/CyclingManager.o \
+	./qpoases/SRC/Indexlist.o \
+	./qpoases/SRC/MessageHandling.o \
+	./qpoases/SRC/QProblem.o \
+	./qpoases/SRC/QProblemB.o \
+	./qpoases/SRC/SubjectTo.o \
+	./qpoases/SRC/Utils.o \
+	./qpoases/SRC/EXTRAS/SolutionAnalysis.o \
+	acado_qpoases_interface.o \
+	acado_integrator.o \
+	acado_solver.o \
+	acado_auxiliary_functions.o
+
+.PHONY: all
+all: libacado_exported_rti.a test
+
+test: ${OBJECTS} test.o
+
+acado_qpoases_interface.o   : acado_qpoases_interface.hpp
+acado_solver.o              : acado_common.h
+acado_integrator.o          : acado_common.h
+acado_auxiliary_functions.o : acado_common.h \
+                              acado_auxiliary_functions.h
+test.o                      : acado_common.h \
+                              acado_qpoases_interface.hpp \
+                              acado_auxiliary_functions.h
+
+libacado_exported_rti.a: ${OBJECTS}
+	ar r $@ $?
+
+${OBJECTS} : acado_qpoases_interface.hpp
+
+.PHONY : clean
+clean :
+	-rm -f *.o *.a ./qpoases/*.o ./qpoases/SRC/*.o ./qpoases/SRC/*.a test
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/acado_auxiliary_functions.c b/mav_control_rw/mav_nonlinear_mpc/solver/acado_auxiliary_functions.c
new file mode 100644
index 0000000000000000000000000000000000000000..6f0bb705c8a8977ccd12f6b4b3b165ae9e5b094a
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/acado_auxiliary_functions.c
@@ -0,0 +1,212 @@
+/*
+ *    This file was auto-generated using the ACADO Toolkit.
+ *    
+ *    While ACADO Toolkit is free software released under the terms of
+ *    the GNU Lesser General Public License (LGPL), the generated code
+ *    as such remains the property of the user who used ACADO Toolkit
+ *    to generate this code. In particular, user dependent data of the code
+ *    do not inherit the GNU LGPL license. On the other hand, parts of the
+ *    generated code that are a direct copy of source code from the
+ *    ACADO Toolkit or the software tools it is based on, remain, as derived
+ *    work, automatically covered by the LGPL license.
+ *    
+ *    ACADO Toolkit is distributed in the hope that it will be useful,
+ *    but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ *    
+ */
+
+
+#include "acado_auxiliary_functions.h"
+
+#include <stdio.h>
+
+real_t* acado_getVariablesX( )
+{
+	return acadoVariables.x;
+}
+
+real_t* acado_getVariablesU( )
+{
+	return acadoVariables.u;
+}
+
+#if ACADO_NY > 0
+real_t* acado_getVariablesY( )
+{
+	return acadoVariables.y;
+}
+#endif
+
+#if ACADO_NYN > 0
+real_t* acado_getVariablesYN( )
+{
+	return acadoVariables.yN;
+}
+#endif
+
+real_t* acado_getVariablesX0( )
+{
+#if ACADO_INITIAL_VALUE_FIXED
+	return acadoVariables.x0;
+#else
+	return 0;
+#endif
+}
+
+/** Print differential variables. */
+void acado_printDifferentialVariables( )
+{
+	int i, j;
+	printf("\nDifferential variables:\n[\n");
+	for (i = 0; i < ACADO_N + 1; ++i)
+	{
+		for (j = 0; j < ACADO_NX; ++j)
+			printf("\t%e", acadoVariables.x[i * ACADO_NX + j]);
+		printf("\n");
+	}
+	printf("]\n\n");
+}
+
+/** Print control variables. */
+void acado_printControlVariables( )
+{
+	int i, j;
+	printf("\nControl variables:\n[\n");
+	for (i = 0; i < ACADO_N; ++i)
+	{
+		for (j = 0; j < ACADO_NU; ++j)
+			printf("\t%e", acadoVariables.u[i * ACADO_NU + j]);
+		printf("\n");
+	}
+	printf("]\n\n");
+}
+
+/** Print ACADO code generation notice. */
+void acado_printHeader( )
+{
+	printf(
+		"\nACADO Toolkit -- A Toolkit for Automatic Control and Dynamic Optimization.\n"
+		"Copyright (C) 2008-2015 by Boris Houska, Hans Joachim Ferreau,\n" 
+		"Milan Vukov and Rien Quirynen, KU Leuven.\n"
+	);
+	
+	printf(
+		"Developed within the Optimization in Engineering Center (OPTEC) under\n"
+		"supervision of Moritz Diehl. All rights reserved.\n\n"
+		"ACADO Toolkit is distributed under the terms of the GNU Lesser\n"
+		"General Public License 3 in the hope that it will be useful,\n"
+		"but WITHOUT ANY WARRANTY; without even the implied warranty of\n"
+		"MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the\n"
+		"GNU Lesser General Public License for more details.\n\n"
+	);
+}
+
+#if !(defined _DSPACE)
+#if (defined _WIN32 || defined _WIN64) && !(defined __MINGW32__ || defined __MINGW64__)
+
+void acado_tic( acado_timer* t )
+{
+	QueryPerformanceFrequency(&t->freq);
+	QueryPerformanceCounter(&t->tic);
+}
+
+real_t acado_toc( acado_timer* t )
+{
+	QueryPerformanceCounter(&t->toc);
+	return ((t->toc.QuadPart - t->tic.QuadPart) / (real_t)t->freq.QuadPart);
+}
+
+
+#elif (defined __APPLE__)
+
+void acado_tic( acado_timer* t )
+{
+    /* read current clock cycles */
+    t->tic = mach_absolute_time();
+}
+
+real_t acado_toc( acado_timer* t )
+{
+
+    uint64_t duration; /* elapsed time in clock cycles*/
+    
+    t->toc = mach_absolute_time();
+    duration = t->toc - t->tic;
+    
+    /*conversion from clock cycles to nanoseconds*/
+    mach_timebase_info(&(t->tinfo));
+    duration *= t->tinfo.numer;
+    duration /= t->tinfo.denom;
+
+    return (real_t)duration / 1e9;
+}
+
+#else
+
+#if __STDC_VERSION__ >= 199901L
+/* C99 mode */
+
+/* read current time */
+void acado_tic( acado_timer* t )
+{
+	gettimeofday(&t->tic, 0);
+}
+
+/* return time passed since last call to tic on this timer */
+real_t acado_toc( acado_timer* t )
+{
+	struct timeval temp;
+	
+	gettimeofday(&t->toc, 0);
+    
+	if ((t->toc.tv_usec - t->tic.tv_usec) < 0)
+	{
+		temp.tv_sec = t->toc.tv_sec - t->tic.tv_sec - 1;
+		temp.tv_usec = 1000000 + t->toc.tv_usec - t->tic.tv_usec;
+	}
+	else
+	{
+		temp.tv_sec = t->toc.tv_sec - t->tic.tv_sec;
+		temp.tv_usec = t->toc.tv_usec - t->tic.tv_usec;
+	}
+	
+	return (real_t)temp.tv_sec + (real_t)temp.tv_usec / 1e6;
+}
+
+#else
+/* ANSI */
+
+/* read current time */
+void acado_tic( acado_timer* t )
+{
+	clock_gettime(CLOCK_MONOTONIC, &t->tic);
+}
+
+
+/* return time passed since last call to tic on this timer */
+real_t acado_toc( acado_timer* t )
+{
+	struct timespec temp;
+    
+	clock_gettime(CLOCK_MONOTONIC, &t->toc);	
+    
+	if ((t->toc.tv_nsec - t->tic.tv_nsec) < 0)
+	{
+		temp.tv_sec = t->toc.tv_sec - t->tic.tv_sec - 1;
+		temp.tv_nsec = 1000000000+t->toc.tv_nsec - t->tic.tv_nsec;
+	}
+	else
+	{
+		temp.tv_sec = t->toc.tv_sec - t->tic.tv_sec;
+		temp.tv_nsec = t->toc.tv_nsec - t->tic.tv_nsec;
+	}
+	
+	return (real_t)temp.tv_sec + (real_t)temp.tv_nsec / 1e9;
+}
+
+#endif /* __STDC_VERSION__ >= 199901L */
+
+#endif /* (defined _WIN32 || _WIN64) */
+
+#endif
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/acado_auxiliary_functions.h b/mav_control_rw/mav_nonlinear_mpc/solver/acado_auxiliary_functions.h
new file mode 100644
index 0000000000000000000000000000000000000000..b1be0a661c0125b8fb6cbaf026dafb2760407afc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/acado_auxiliary_functions.h
@@ -0,0 +1,138 @@
+/*
+ *    This file was auto-generated using the ACADO Toolkit.
+ *    
+ *    While ACADO Toolkit is free software released under the terms of
+ *    the GNU Lesser General Public License (LGPL), the generated code
+ *    as such remains the property of the user who used ACADO Toolkit
+ *    to generate this code. In particular, user dependent data of the code
+ *    do not inherit the GNU LGPL license. On the other hand, parts of the
+ *    generated code that are a direct copy of source code from the
+ *    ACADO Toolkit or the software tools it is based on, remain, as derived
+ *    work, automatically covered by the LGPL license.
+ *    
+ *    ACADO Toolkit is distributed in the hope that it will be useful,
+ *    but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ *    
+ */
+
+
+#ifndef ACADO_AUXILIARY_FUNCTIONS_H
+#define ACADO_AUXILIARY_FUNCTIONS_H
+
+#include "acado_common.h"
+
+#ifndef __MATLAB__
+#ifdef __cplusplus
+extern "C"
+{
+#endif /* __cplusplus */
+#endif /* __MATLAB__ */
+
+/** Get pointer to the matrix with differential variables. */
+real_t* acado_getVariablesX( );
+
+/** Get pointer to the matrix with control variables. */
+real_t* acado_getVariablesU( );
+
+#if ACADO_NY > 0
+/** Get pointer to the matrix with references/measurements. */
+real_t* acado_getVariablesY( );
+#endif
+
+#if ACADO_NYN > 0
+/** Get pointer to the vector with references/measurement on the last node. */
+real_t* acado_getVariablesYN( );
+#endif
+
+/** Get pointer to the current state feedback vector. Only applicable for NMPC. */
+real_t* acado_getVariablesX0( );
+
+/** Print differential variables. */
+void acado_printDifferentialVariables( );
+
+/** Print control variables. */
+void acado_printControlVariables( );
+
+/** Print ACADO code generation notice. */
+void acado_printHeader( );
+
+/*
+ * A huge thanks goes to Alexander Domahidi from ETHZ, Switzerland, for 
+ * providing us with the following timing routines.
+ */
+
+#if !(defined _DSPACE)
+#if (defined _WIN32 || defined _WIN64) && !(defined __MINGW32__ || defined __MINGW64__)
+
+/* Use Windows QueryPerformanceCounter for timing. */
+#include <Windows.h>
+
+/** A structure for keeping internal timer data. */
+typedef struct acado_timer_
+{
+	LARGE_INTEGER tic;
+	LARGE_INTEGER toc;
+	LARGE_INTEGER freq;
+} acado_timer;
+
+
+#elif (defined __APPLE__)
+
+#include "unistd.h"
+#include <mach/mach_time.h>
+
+/** A structure for keeping internal timer data. */
+typedef struct acado_timer_
+{
+	uint64_t tic;
+	uint64_t toc;
+	mach_timebase_info_data_t tinfo;
+} acado_timer;
+
+#else
+
+/* Use POSIX clock_gettime() for timing on non-Windows machines. */
+#include <time.h>
+
+#if __STDC_VERSION__ >= 199901L
+/* C99 mode of operation. */
+
+#include <sys/stat.h>
+#include <sys/time.h>
+
+typedef struct acado_timer_
+{
+	struct timeval tic;
+	struct timeval toc;
+} acado_timer;
+
+#else
+/* ANSI C */
+
+/** A structure for keeping internal timer data. */
+typedef struct acado_timer_
+{
+	struct timespec tic;
+	struct timespec toc;
+} acado_timer;
+
+#endif /* __STDC_VERSION__ >= 199901L */
+
+#endif /* (defined _WIN32 || defined _WIN64) */
+
+/** A function for measurement of the current time. */
+void acado_tic( acado_timer* t );
+
+/** A function which returns the elapsed time. */
+real_t acado_toc( acado_timer* t );
+
+#endif
+
+#ifndef __MATLAB__
+#ifdef __cplusplus
+} /* extern "C" */
+#endif /* __cplusplus */
+#endif /* __MATLAB__ */
+
+#endif /* ACADO_AUXILIARY_FUNCTIONS_H */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/acado_common.h b/mav_control_rw/mav_nonlinear_mpc/solver/acado_common.h
new file mode 100644
index 0000000000000000000000000000000000000000..535b7e2e7c3d5501526ec31a1e95866029e325f5
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/acado_common.h
@@ -0,0 +1,399 @@
+/*
+ *    This file was auto-generated using the ACADO Toolkit.
+ *    
+ *    While ACADO Toolkit is free software released under the terms of
+ *    the GNU Lesser General Public License (LGPL), the generated code
+ *    as such remains the property of the user who used ACADO Toolkit
+ *    to generate this code. In particular, user dependent data of the code
+ *    do not inherit the GNU LGPL license. On the other hand, parts of the
+ *    generated code that are a direct copy of source code from the
+ *    ACADO Toolkit or the software tools it is based on, remain, as derived
+ *    work, automatically covered by the LGPL license.
+ *    
+ *    ACADO Toolkit is distributed in the hope that it will be useful,
+ *    but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ *    
+ */
+
+
+#ifndef ACADO_COMMON_H
+#define ACADO_COMMON_H
+
+#include <math.h>
+#include <string.h>
+
+#ifndef __MATLAB__
+#ifdef __cplusplus
+extern "C"
+{
+#endif /* __cplusplus */
+#endif /* __MATLAB__ */
+
+/** \defgroup ACADO ACADO CGT generated module. */
+/** @{ */
+
+/** qpOASES QP solver indicator. */
+#define ACADO_QPOASES  0
+#define ACADO_QPOASES3 1
+/** FORCES QP solver indicator.*/
+#define ACADO_FORCES   2
+/** qpDUNES QP solver indicator.*/
+#define ACADO_QPDUNES  3
+/** HPMPC QP solver indicator. */
+#define ACADO_HPMPC    4
+#define ACADO_GENERIC    5
+
+/** Indicator for determining the QP solver used by the ACADO solver code. */
+#define ACADO_QP_SOLVER ACADO_QPOASES
+
+#include "acado_qpoases_interface.hpp"
+
+
+/*
+ * Common definitions
+ */
+/** User defined block based condensing. */
+#define ACADO_BLOCK_CONDENSING 0
+/** Compute covariance matrix of the last state estimate. */
+#define ACADO_COMPUTE_COVARIANCE_MATRIX 0
+/** Flag indicating whether constraint values are hard-coded or not. */
+#define ACADO_HARDCODED_CONSTRAINT_VALUES 0
+/** Indicator for fixed initial state. */
+#define ACADO_INITIAL_STATE_FIXED 1
+/** Number of control/estimation intervals. */
+#define ACADO_N 20
+/** Number of online data values. */
+#define ACADO_NOD 20
+/** Number of path constraints. */
+#define ACADO_NPAC 10
+/** Number of control variables. */
+#define ACADO_NU 2
+/** Number of differential variables. */
+#define ACADO_NX 5
+/** Number of algebraic variables. */
+#define ACADO_NXA 0
+/** Number of differential derivative variables. */
+#define ACADO_NXD 0
+/** Number of references/measurements per node on the first N nodes. */
+#define ACADO_NY 8
+/** Number of references/measurements on the last (N + 1)st node. */
+#define ACADO_NYN 5
+/** Total number of QP optimization variables. */
+#define ACADO_QP_NV 40
+/** Number of integration steps per shooting interval. */
+#define ACADO_RK_NIS 2
+/** Number of Runge-Kutta stages per integration step. */
+#define ACADO_RK_NSTAGES 1
+/** Providing interface for arrival cost. */
+#define ACADO_USE_ARRIVAL_COST 0
+/** Indicator for usage of non-hard-coded linear terms in the objective. */
+#define ACADO_USE_LINEAR_TERMS 0
+/** Indicator for type of fixed weighting matrices. */
+#define ACADO_WEIGHTING_MATRICES_TYPE 2
+
+
+/*
+ * Globally used structure definitions
+ */
+
+/** The structure containing the user data.
+ * 
+ *  Via this structure the user "communicates" with the solver code.
+ */
+typedef struct ACADOvariables_
+{
+int dummy;
+/** Matrix of size: 21 x 5 (row major format)
+ * 
+ *  Matrix containing 21 differential variable vectors.
+ */
+real_t x[ 105 ];
+
+/** Matrix of size: 20 x 2 (row major format)
+ * 
+ *  Matrix containing 20 control variable vectors.
+ */
+real_t u[ 40 ];
+
+/** Matrix of size: 21 x 20 (row major format)
+ * 
+ *  Matrix containing 21 online data vectors.
+ */
+real_t od[ 420 ];
+
+/** Column vector of size: 160
+ * 
+ *  Matrix containing 20 reference/measurement vectors of size 8 for first 20 nodes.
+ */
+real_t y[ 160 ];
+
+/** Column vector of size: 5
+ * 
+ *  Reference/measurement vector for the 21. node.
+ */
+real_t yN[ 5 ];
+
+/** Matrix of size: 160 x 8 (row major format) */
+real_t W[ 1280 ];
+
+/** Matrix of size: 5 x 5 (row major format) */
+real_t WN[ 25 ];
+
+/** Column vector of size: 5
+ * 
+ *  Current state feedback vector.
+ */
+real_t x0[ 5 ];
+
+/** Column vector of size: 40
+ * 
+ *  Lower bounds values.
+ */
+real_t lbValues[ 40 ];
+
+/** Column vector of size: 40
+ * 
+ *  Upper bounds values.
+ */
+real_t ubValues[ 40 ];
+
+/** Column vector of size: 240
+ * 
+ *  Lower bounds values for affine constraints.
+ */
+real_t lbAValues[ 240 ];
+
+/** Column vector of size: 240
+ * 
+ *  Upper bounds values for affine constraints.
+ */
+real_t ubAValues[ 240 ];
+
+
+} ACADOvariables;
+
+/** Private workspace used by the auto-generated code.
+ * 
+ *  Data members of this structure are private to the solver.
+ *  In other words, the user code should not modify values of this 
+ *  structure. 
+ */
+typedef struct ACADOworkspace_
+{
+/** Column vector of size: 4 */
+real_t rhs_aux[ 4 ];
+
+/** Column vector of size: 100 */
+real_t d[ 100 ];
+
+/** Column vector of size: 160 */
+real_t Dy[ 160 ];
+
+/** Column vector of size: 5 */
+real_t DyN[ 5 ];
+
+/** Matrix of size: 100 x 5 (row major format) */
+real_t evGx[ 500 ];
+
+/** Matrix of size: 100 x 2 (row major format) */
+real_t evGu[ 200 ];
+
+/** Column vector of size: 98 */
+real_t objAuxVar[ 98 ];
+
+/** Row vector of size: 27 */
+real_t objValueIn[ 27 ];
+
+/** Row vector of size: 64 */
+real_t objValueOut[ 64 ];
+
+/** Matrix of size: 100 x 5 (row major format) */
+real_t Q1[ 500 ];
+
+/** Matrix of size: 100 x 8 (row major format) */
+real_t Q2[ 800 ];
+
+/** Matrix of size: 40 x 2 (row major format) */
+real_t R1[ 80 ];
+
+/** Matrix of size: 40 x 8 (row major format) */
+real_t R2[ 320 ];
+
+/** Matrix of size: 5 x 5 (row major format) */
+real_t QN1[ 25 ];
+
+/** Matrix of size: 5 x 5 (row major format) */
+real_t QN2[ 25 ];
+
+/** Column vector of size: 160 */
+real_t conAuxVar[ 160 ];
+
+/** Row vector of size: 27 */
+real_t conValueIn[ 27 ];
+
+/** Row vector of size: 80 */
+real_t conValueOut[ 80 ];
+
+/** Column vector of size: 200 */
+real_t evH[ 200 ];
+
+/** Matrix of size: 200 x 5 (row major format) */
+real_t evHx[ 1000 ];
+
+/** Matrix of size: 200 x 2 (row major format) */
+real_t evHu[ 400 ];
+
+/** Column vector of size: 10 */
+real_t evHxd[ 10 ];
+
+/** Column vector of size: 105 */
+real_t sbar[ 105 ];
+
+/** Column vector of size: 5 */
+real_t Dx0[ 5 ];
+
+/** Matrix of size: 100 x 5 (row major format) */
+real_t C[ 500 ];
+
+/** Matrix of size: 5 x 2 (row major format) */
+real_t W1[ 10 ];
+
+/** Matrix of size: 5 x 2 (row major format) */
+real_t W2[ 10 ];
+
+/** Matrix of size: 1050 x 2 (row major format) */
+real_t E[ 2100 ];
+
+/** Column vector of size: 105 */
+real_t QDy[ 105 ];
+
+/** Column vector of size: 5 */
+real_t w1[ 5 ];
+
+/** Column vector of size: 5 */
+real_t w2[ 5 ];
+
+/** Matrix of size: 40 x 40 (row major format) */
+real_t H[ 1600 ];
+
+/** Matrix of size: 240 x 40 (row major format) */
+real_t A[ 9600 ];
+
+/** Column vector of size: 40 */
+real_t g[ 40 ];
+
+/** Column vector of size: 40 */
+real_t lb[ 40 ];
+
+/** Column vector of size: 40 */
+real_t ub[ 40 ];
+
+/** Column vector of size: 240 */
+real_t lbA[ 240 ];
+
+/** Column vector of size: 240 */
+real_t ubA[ 240 ];
+
+/** Column vector of size: 40 */
+real_t x[ 40 ];
+
+/** Column vector of size: 280 */
+real_t y[ 280 ];
+
+
+} ACADOworkspace;
+
+/* 
+ * Forward function declarations. 
+ */
+
+
+/** Performs the integration and sensitivity propagation for one shooting interval.
+ *
+ *  \param rk_eta Working array of size 27 to pass the input values and return the results.
+ *  \param resetIntegrator The internal memory of the integrator can be reset.
+ *
+ *  \return Status code of the integrator.
+ */
+int acado_integrate( real_t* const rk_eta, int resetIntegrator );
+
+/** Export of an ACADO symbolic function.
+ *
+ *  \param in Input to the exported function.
+ *  \param out Output of the exported function.
+ */
+void acado_rhs(const real_t* in, real_t* out);
+
+/** Export of an ACADO symbolic function.
+ *
+ *  \param in Input to the exported function.
+ *  \param out Output of the exported function.
+ */
+void acado_diffs(const real_t* in, real_t* out);
+
+/** Preparation step of the RTI scheme.
+ *
+ *  \return Status of the integration module. =0: OK, otherwise the error code.
+ */
+int acado_preparationStep(  );
+
+/** Feedback/estimation step of the RTI scheme.
+ *
+ *  \return Status code of the qpOASES QP solver.
+ */
+int acado_feedbackStep(  );
+
+/** Solver initialization. Must be called once before any other function call.
+ *
+ *  \return =0: OK, otherwise an error code of a QP solver.
+ */
+int acado_initializeSolver(  );
+
+/** Initialize shooting nodes by a forward simulation starting from the first node.
+ */
+void acado_initializeNodesByForwardSimulation(  );
+
+/** Shift differential variables vector by one interval.
+ *
+ *  \param strategy Shifting strategy: 1. Initialize node 21 with xEnd. 2. Initialize node 21 by forward simulation.
+ *  \param xEnd Value for the x vector on the last node. If =0 the old value is used.
+ *  \param uEnd Value for the u vector on the second to last node. If =0 the old value is used.
+ */
+void acado_shiftStates( int strategy, real_t* const xEnd, real_t* const uEnd );
+
+/** Shift controls vector by one interval.
+ *
+ *  \param uEnd Value for the u vector on the second to last node. If =0 the old value is used.
+ */
+void acado_shiftControls( real_t* const uEnd );
+
+/** Get the KKT tolerance of the current iterate.
+ *
+ *  \return The KKT tolerance value.
+ */
+real_t acado_getKKT(  );
+
+/** Calculate the objective value.
+ *
+ *  \return Value of the objective function.
+ */
+real_t acado_getObjective(  );
+
+
+/* 
+ * Extern declarations. 
+ */
+
+extern ACADOworkspace acadoWorkspace;
+extern ACADOvariables acadoVariables;
+
+/** @} */
+
+#ifndef __MATLAB__
+#ifdef __cplusplus
+} /* extern "C" */
+#endif /* __cplusplus */
+#endif /* __MATLAB__ */
+
+#endif /* ACADO_COMMON_H */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/acado_integrator.c b/mav_control_rw/mav_nonlinear_mpc/solver/acado_integrator.c
new file mode 100644
index 0000000000000000000000000000000000000000..a1822381ef76de495a6e511dacb0959f7a1e5ca2
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/acado_integrator.c
@@ -0,0 +1,782 @@
+/*
+ *    This file was auto-generated using the ACADO Toolkit.
+ *    
+ *    While ACADO Toolkit is free software released under the terms of
+ *    the GNU Lesser General Public License (LGPL), the generated code
+ *    as such remains the property of the user who used ACADO Toolkit
+ *    to generate this code. In particular, user dependent data of the code
+ *    do not inherit the GNU LGPL license. On the other hand, parts of the
+ *    generated code that are a direct copy of source code from the
+ *    ACADO Toolkit or the software tools it is based on, remain, as derived
+ *    work, automatically covered by the LGPL license.
+ *    
+ *    ACADO Toolkit is distributed in the hope that it will be useful,
+ *    but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ *    
+ */
+
+
+#include "acado_common.h"
+
+
+real_t rk_dim5_swap;
+
+/** Column vector of size: 5 */
+real_t rk_dim5_bPerm[ 5 ];
+
+/** Column vector of size: 4 */
+real_t auxVar[ 4 ];
+
+real_t rk_ttt;
+
+/** Row vector of size: 27 */
+real_t rk_xxx[ 27 ];
+
+/** Column vector of size: 5 */
+real_t rk_kkk[ 5 ];
+
+/** Matrix of size: 5 x 5 (row major format) */
+real_t rk_A[ 25 ];
+
+/** Column vector of size: 5 */
+real_t rk_b[ 5 ];
+
+/** Row vector of size: 5 */
+int rk_dim5_perm[ 5 ];
+
+/** Column vector of size: 5 */
+real_t rk_rhsTemp[ 5 ];
+
+/** Row vector of size: 35 */
+real_t rk_diffsTemp2[ 35 ];
+
+/** Column vector of size: 5 */
+real_t rk_diffK[ 5 ];
+
+/** Matrix of size: 5 x 7 (row major format) */
+real_t rk_diffsPrev2[ 35 ];
+
+/** Matrix of size: 5 x 7 (row major format) */
+real_t rk_diffsNew2[ 35 ];
+
+#pragma omp threadprivate( auxVar, rk_ttt, rk_xxx, rk_kkk, rk_diffK, rk_rhsTemp, rk_dim5_perm, rk_A, rk_b, rk_diffsPrev2, rk_diffsNew2, rk_diffsTemp2, rk_dim5_swap, rk_dim5_bPerm )
+
+void acado_rhs(const real_t* in, real_t* out)
+{
+const real_t* xd = in;
+const real_t* u = in + 5;
+/* Vector of auxiliary variables; number of elements: 2. */
+real_t* a = auxVar;
+
+/* Compute intermediate quantities: */
+a[0] = (cos(xd[2]));
+a[1] = (sin(xd[2]));
+
+/* Compute outputs: */
+out[0] = (a[0]*xd[3]);
+out[1] = (a[1]*xd[3]);
+out[2] = xd[4];
+out[3] = u[0];
+out[4] = u[1];
+}
+
+
+
+void acado_diffs(const real_t* in, real_t* out)
+{
+const real_t* xd = in;
+/* Vector of auxiliary variables; number of elements: 4. */
+real_t* a = auxVar;
+
+/* Compute intermediate quantities: */
+a[0] = ((real_t)(-1.0000000000000000e+00)*(sin(xd[2])));
+a[1] = (cos(xd[2]));
+a[2] = (cos(xd[2]));
+a[3] = (sin(xd[2]));
+
+/* Compute outputs: */
+out[0] = (real_t)(0.0000000000000000e+00);
+out[1] = (real_t)(0.0000000000000000e+00);
+out[2] = (a[0]*xd[3]);
+out[3] = a[1];
+out[4] = (real_t)(0.0000000000000000e+00);
+out[5] = (real_t)(0.0000000000000000e+00);
+out[6] = (real_t)(0.0000000000000000e+00);
+out[7] = (real_t)(0.0000000000000000e+00);
+out[8] = (real_t)(0.0000000000000000e+00);
+out[9] = (a[2]*xd[3]);
+out[10] = a[3];
+out[11] = (real_t)(0.0000000000000000e+00);
+out[12] = (real_t)(0.0000000000000000e+00);
+out[13] = (real_t)(0.0000000000000000e+00);
+out[14] = (real_t)(0.0000000000000000e+00);
+out[15] = (real_t)(0.0000000000000000e+00);
+out[16] = (real_t)(0.0000000000000000e+00);
+out[17] = (real_t)(0.0000000000000000e+00);
+out[18] = (real_t)(1.0000000000000000e+00);
+out[19] = (real_t)(0.0000000000000000e+00);
+out[20] = (real_t)(0.0000000000000000e+00);
+out[21] = (real_t)(0.0000000000000000e+00);
+out[22] = (real_t)(0.0000000000000000e+00);
+out[23] = (real_t)(0.0000000000000000e+00);
+out[24] = (real_t)(0.0000000000000000e+00);
+out[25] = (real_t)(0.0000000000000000e+00);
+out[26] = (real_t)(1.0000000000000000e+00);
+out[27] = (real_t)(0.0000000000000000e+00);
+out[28] = (real_t)(0.0000000000000000e+00);
+out[29] = (real_t)(0.0000000000000000e+00);
+out[30] = (real_t)(0.0000000000000000e+00);
+out[31] = (real_t)(0.0000000000000000e+00);
+out[32] = (real_t)(0.0000000000000000e+00);
+out[33] = (real_t)(0.0000000000000000e+00);
+out[34] = (real_t)(1.0000000000000000e+00);
+}
+
+
+
+void acado_solve_dim5_triangular( real_t* const A, real_t* const b )
+{
+
+b[4] = b[4]/A[24];
+b[3] -= + A[19]*b[4];
+b[3] = b[3]/A[18];
+b[2] -= + A[14]*b[4];
+b[2] -= + A[13]*b[3];
+b[2] = b[2]/A[12];
+b[1] -= + A[9]*b[4];
+b[1] -= + A[8]*b[3];
+b[1] -= + A[7]*b[2];
+b[1] = b[1]/A[6];
+b[0] -= + A[4]*b[4];
+b[0] -= + A[3]*b[3];
+b[0] -= + A[2]*b[2];
+b[0] -= + A[1]*b[1];
+b[0] = b[0]/A[0];
+}
+
+real_t acado_solve_dim5_system( real_t* const A, real_t* const b, int* const rk_perm )
+{
+real_t det;
+
+int i;
+int j;
+int k;
+
+int indexMax;
+
+int intSwap;
+
+real_t valueMax;
+
+real_t temp;
+
+for (i = 0; i < 5; ++i)
+{
+rk_perm[i] = i;
+}
+det = 1.0000000000000000e+00;
+if(fabs(A[5]) > fabs(A[0]) && fabs(A[5]) > fabs(A[10]) && fabs(A[5]) > fabs(A[15]) && fabs(A[5]) > fabs(A[20])) {
+rk_dim5_swap = A[0];
+A[0] = A[5];
+A[5] = rk_dim5_swap;
+rk_dim5_swap = A[1];
+A[1] = A[6];
+A[6] = rk_dim5_swap;
+rk_dim5_swap = A[2];
+A[2] = A[7];
+A[7] = rk_dim5_swap;
+rk_dim5_swap = A[3];
+A[3] = A[8];
+A[8] = rk_dim5_swap;
+rk_dim5_swap = A[4];
+A[4] = A[9];
+A[9] = rk_dim5_swap;
+rk_dim5_swap = b[0];
+b[0] = b[1];
+b[1] = rk_dim5_swap;
+intSwap = rk_perm[0];
+rk_perm[0] = rk_perm[1];
+rk_perm[1] = intSwap;
+}
+else if(fabs(A[10]) > fabs(A[0]) && fabs(A[10]) > fabs(A[5]) && fabs(A[10]) > fabs(A[15]) && fabs(A[10]) > fabs(A[20])) {
+rk_dim5_swap = A[0];
+A[0] = A[10];
+A[10] = rk_dim5_swap;
+rk_dim5_swap = A[1];
+A[1] = A[11];
+A[11] = rk_dim5_swap;
+rk_dim5_swap = A[2];
+A[2] = A[12];
+A[12] = rk_dim5_swap;
+rk_dim5_swap = A[3];
+A[3] = A[13];
+A[13] = rk_dim5_swap;
+rk_dim5_swap = A[4];
+A[4] = A[14];
+A[14] = rk_dim5_swap;
+rk_dim5_swap = b[0];
+b[0] = b[2];
+b[2] = rk_dim5_swap;
+intSwap = rk_perm[0];
+rk_perm[0] = rk_perm[2];
+rk_perm[2] = intSwap;
+}
+else if(fabs(A[15]) > fabs(A[0]) && fabs(A[15]) > fabs(A[5]) && fabs(A[15]) > fabs(A[10]) && fabs(A[15]) > fabs(A[20])) {
+rk_dim5_swap = A[0];
+A[0] = A[15];
+A[15] = rk_dim5_swap;
+rk_dim5_swap = A[1];
+A[1] = A[16];
+A[16] = rk_dim5_swap;
+rk_dim5_swap = A[2];
+A[2] = A[17];
+A[17] = rk_dim5_swap;
+rk_dim5_swap = A[3];
+A[3] = A[18];
+A[18] = rk_dim5_swap;
+rk_dim5_swap = A[4];
+A[4] = A[19];
+A[19] = rk_dim5_swap;
+rk_dim5_swap = b[0];
+b[0] = b[3];
+b[3] = rk_dim5_swap;
+intSwap = rk_perm[0];
+rk_perm[0] = rk_perm[3];
+rk_perm[3] = intSwap;
+}
+else if(fabs(A[20]) > fabs(A[0]) && fabs(A[20]) > fabs(A[5]) && fabs(A[20]) > fabs(A[10]) && fabs(A[20]) > fabs(A[15])) {
+rk_dim5_swap = A[0];
+A[0] = A[20];
+A[20] = rk_dim5_swap;
+rk_dim5_swap = A[1];
+A[1] = A[21];
+A[21] = rk_dim5_swap;
+rk_dim5_swap = A[2];
+A[2] = A[22];
+A[22] = rk_dim5_swap;
+rk_dim5_swap = A[3];
+A[3] = A[23];
+A[23] = rk_dim5_swap;
+rk_dim5_swap = A[4];
+A[4] = A[24];
+A[24] = rk_dim5_swap;
+rk_dim5_swap = b[0];
+b[0] = b[4];
+b[4] = rk_dim5_swap;
+intSwap = rk_perm[0];
+rk_perm[0] = rk_perm[4];
+rk_perm[4] = intSwap;
+}
+
+A[5] = -A[5]/A[0];
+A[6] += + A[5]*A[1];
+A[7] += + A[5]*A[2];
+A[8] += + A[5]*A[3];
+A[9] += + A[5]*A[4];
+b[1] += + A[5]*b[0];
+
+A[10] = -A[10]/A[0];
+A[11] += + A[10]*A[1];
+A[12] += + A[10]*A[2];
+A[13] += + A[10]*A[3];
+A[14] += + A[10]*A[4];
+b[2] += + A[10]*b[0];
+
+A[15] = -A[15]/A[0];
+A[16] += + A[15]*A[1];
+A[17] += + A[15]*A[2];
+A[18] += + A[15]*A[3];
+A[19] += + A[15]*A[4];
+b[3] += + A[15]*b[0];
+
+A[20] = -A[20]/A[0];
+A[21] += + A[20]*A[1];
+A[22] += + A[20]*A[2];
+A[23] += + A[20]*A[3];
+A[24] += + A[20]*A[4];
+b[4] += + A[20]*b[0];
+
+det = + det*A[0];
+
+if(fabs(A[11]) > fabs(A[6]) && fabs(A[11]) > fabs(A[16]) && fabs(A[11]) > fabs(A[21])) {
+rk_dim5_swap = A[5];
+A[5] = A[10];
+A[10] = rk_dim5_swap;
+rk_dim5_swap = A[6];
+A[6] = A[11];
+A[11] = rk_dim5_swap;
+rk_dim5_swap = A[7];
+A[7] = A[12];
+A[12] = rk_dim5_swap;
+rk_dim5_swap = A[8];
+A[8] = A[13];
+A[13] = rk_dim5_swap;
+rk_dim5_swap = A[9];
+A[9] = A[14];
+A[14] = rk_dim5_swap;
+rk_dim5_swap = b[1];
+b[1] = b[2];
+b[2] = rk_dim5_swap;
+intSwap = rk_perm[1];
+rk_perm[1] = rk_perm[2];
+rk_perm[2] = intSwap;
+}
+else if(fabs(A[16]) > fabs(A[6]) && fabs(A[16]) > fabs(A[11]) && fabs(A[16]) > fabs(A[21])) {
+rk_dim5_swap = A[5];
+A[5] = A[15];
+A[15] = rk_dim5_swap;
+rk_dim5_swap = A[6];
+A[6] = A[16];
+A[16] = rk_dim5_swap;
+rk_dim5_swap = A[7];
+A[7] = A[17];
+A[17] = rk_dim5_swap;
+rk_dim5_swap = A[8];
+A[8] = A[18];
+A[18] = rk_dim5_swap;
+rk_dim5_swap = A[9];
+A[9] = A[19];
+A[19] = rk_dim5_swap;
+rk_dim5_swap = b[1];
+b[1] = b[3];
+b[3] = rk_dim5_swap;
+intSwap = rk_perm[1];
+rk_perm[1] = rk_perm[3];
+rk_perm[3] = intSwap;
+}
+else if(fabs(A[21]) > fabs(A[6]) && fabs(A[21]) > fabs(A[11]) && fabs(A[21]) > fabs(A[16])) {
+rk_dim5_swap = A[5];
+A[5] = A[20];
+A[20] = rk_dim5_swap;
+rk_dim5_swap = A[6];
+A[6] = A[21];
+A[21] = rk_dim5_swap;
+rk_dim5_swap = A[7];
+A[7] = A[22];
+A[22] = rk_dim5_swap;
+rk_dim5_swap = A[8];
+A[8] = A[23];
+A[23] = rk_dim5_swap;
+rk_dim5_swap = A[9];
+A[9] = A[24];
+A[24] = rk_dim5_swap;
+rk_dim5_swap = b[1];
+b[1] = b[4];
+b[4] = rk_dim5_swap;
+intSwap = rk_perm[1];
+rk_perm[1] = rk_perm[4];
+rk_perm[4] = intSwap;
+}
+
+A[11] = -A[11]/A[6];
+A[12] += + A[11]*A[7];
+A[13] += + A[11]*A[8];
+A[14] += + A[11]*A[9];
+b[2] += + A[11]*b[1];
+
+A[16] = -A[16]/A[6];
+A[17] += + A[16]*A[7];
+A[18] += + A[16]*A[8];
+A[19] += + A[16]*A[9];
+b[3] += + A[16]*b[1];
+
+A[21] = -A[21]/A[6];
+A[22] += + A[21]*A[7];
+A[23] += + A[21]*A[8];
+A[24] += + A[21]*A[9];
+b[4] += + A[21]*b[1];
+
+det = + det*A[6];
+
+if(fabs(A[17]) > fabs(A[12]) && fabs(A[17]) > fabs(A[22])) {
+rk_dim5_swap = A[10];
+A[10] = A[15];
+A[15] = rk_dim5_swap;
+rk_dim5_swap = A[11];
+A[11] = A[16];
+A[16] = rk_dim5_swap;
+rk_dim5_swap = A[12];
+A[12] = A[17];
+A[17] = rk_dim5_swap;
+rk_dim5_swap = A[13];
+A[13] = A[18];
+A[18] = rk_dim5_swap;
+rk_dim5_swap = A[14];
+A[14] = A[19];
+A[19] = rk_dim5_swap;
+rk_dim5_swap = b[2];
+b[2] = b[3];
+b[3] = rk_dim5_swap;
+intSwap = rk_perm[2];
+rk_perm[2] = rk_perm[3];
+rk_perm[3] = intSwap;
+}
+else if(fabs(A[22]) > fabs(A[12]) && fabs(A[22]) > fabs(A[17])) {
+rk_dim5_swap = A[10];
+A[10] = A[20];
+A[20] = rk_dim5_swap;
+rk_dim5_swap = A[11];
+A[11] = A[21];
+A[21] = rk_dim5_swap;
+rk_dim5_swap = A[12];
+A[12] = A[22];
+A[22] = rk_dim5_swap;
+rk_dim5_swap = A[13];
+A[13] = A[23];
+A[23] = rk_dim5_swap;
+rk_dim5_swap = A[14];
+A[14] = A[24];
+A[24] = rk_dim5_swap;
+rk_dim5_swap = b[2];
+b[2] = b[4];
+b[4] = rk_dim5_swap;
+intSwap = rk_perm[2];
+rk_perm[2] = rk_perm[4];
+rk_perm[4] = intSwap;
+}
+
+A[17] = -A[17]/A[12];
+A[18] += + A[17]*A[13];
+A[19] += + A[17]*A[14];
+b[3] += + A[17]*b[2];
+
+A[22] = -A[22]/A[12];
+A[23] += + A[22]*A[13];
+A[24] += + A[22]*A[14];
+b[4] += + A[22]*b[2];
+
+det = + det*A[12];
+
+if(fabs(A[23]) > fabs(A[18])) {
+rk_dim5_swap = A[15];
+A[15] = A[20];
+A[20] = rk_dim5_swap;
+rk_dim5_swap = A[16];
+A[16] = A[21];
+A[21] = rk_dim5_swap;
+rk_dim5_swap = A[17];
+A[17] = A[22];
+A[22] = rk_dim5_swap;
+rk_dim5_swap = A[18];
+A[18] = A[23];
+A[23] = rk_dim5_swap;
+rk_dim5_swap = A[19];
+A[19] = A[24];
+A[24] = rk_dim5_swap;
+rk_dim5_swap = b[3];
+b[3] = b[4];
+b[4] = rk_dim5_swap;
+intSwap = rk_perm[3];
+rk_perm[3] = rk_perm[4];
+rk_perm[4] = intSwap;
+}
+
+A[23] = -A[23]/A[18];
+A[24] += + A[23]*A[19];
+b[4] += + A[23]*b[3];
+
+det = + det*A[18];
+
+det = + det*A[24];
+
+det = fabs(det);
+acado_solve_dim5_triangular( A, b );
+return det;
+}
+
+void acado_solve_dim5_system_reuse( real_t* const A, real_t* const b, int* const rk_perm )
+{
+
+rk_dim5_bPerm[0] = b[rk_perm[0]];
+rk_dim5_bPerm[1] = b[rk_perm[1]];
+rk_dim5_bPerm[2] = b[rk_perm[2]];
+rk_dim5_bPerm[3] = b[rk_perm[3]];
+rk_dim5_bPerm[4] = b[rk_perm[4]];
+rk_dim5_bPerm[1] += A[5]*rk_dim5_bPerm[0];
+
+rk_dim5_bPerm[2] += A[10]*rk_dim5_bPerm[0];
+rk_dim5_bPerm[2] += A[11]*rk_dim5_bPerm[1];
+
+rk_dim5_bPerm[3] += A[15]*rk_dim5_bPerm[0];
+rk_dim5_bPerm[3] += A[16]*rk_dim5_bPerm[1];
+rk_dim5_bPerm[3] += A[17]*rk_dim5_bPerm[2];
+
+rk_dim5_bPerm[4] += A[20]*rk_dim5_bPerm[0];
+rk_dim5_bPerm[4] += A[21]*rk_dim5_bPerm[1];
+rk_dim5_bPerm[4] += A[22]*rk_dim5_bPerm[2];
+rk_dim5_bPerm[4] += A[23]*rk_dim5_bPerm[3];
+
+
+acado_solve_dim5_triangular( A, rk_dim5_bPerm );
+b[0] = rk_dim5_bPerm[0];
+b[1] = rk_dim5_bPerm[1];
+b[2] = rk_dim5_bPerm[2];
+b[3] = rk_dim5_bPerm[3];
+b[4] = rk_dim5_bPerm[4];
+}
+
+
+
+/** Column vector of size: 1 */
+static const real_t acado_Ah_mat[ 1 ] = 
+{ 7.4999999999999997e-02 };
+
+
+/* Fixed step size:0.15 */
+int acado_integrate( real_t* const rk_eta, int resetIntegrator )
+{
+int error;
+
+int i;
+int j;
+int k;
+int run;
+int run1;
+int tmp_index1;
+int tmp_index2;
+
+real_t det;
+
+rk_ttt = 0.0000000000000000e+00;
+rk_xxx[5] = rk_eta[40];
+rk_xxx[6] = rk_eta[41];
+rk_xxx[7] = rk_eta[42];
+rk_xxx[8] = rk_eta[43];
+rk_xxx[9] = rk_eta[44];
+rk_xxx[10] = rk_eta[45];
+rk_xxx[11] = rk_eta[46];
+rk_xxx[12] = rk_eta[47];
+rk_xxx[13] = rk_eta[48];
+rk_xxx[14] = rk_eta[49];
+rk_xxx[15] = rk_eta[50];
+rk_xxx[16] = rk_eta[51];
+rk_xxx[17] = rk_eta[52];
+rk_xxx[18] = rk_eta[53];
+rk_xxx[19] = rk_eta[54];
+rk_xxx[20] = rk_eta[55];
+rk_xxx[21] = rk_eta[56];
+rk_xxx[22] = rk_eta[57];
+rk_xxx[23] = rk_eta[58];
+rk_xxx[24] = rk_eta[59];
+rk_xxx[25] = rk_eta[60];
+rk_xxx[26] = rk_eta[61];
+
+for (run = 0; run < 2; ++run)
+{
+if( run > 0 ) {
+for (i = 0; i < 5; ++i)
+{
+rk_diffsPrev2[i * 7] = rk_eta[i * 5 + 5];
+rk_diffsPrev2[i * 7 + 1] = rk_eta[i * 5 + 6];
+rk_diffsPrev2[i * 7 + 2] = rk_eta[i * 5 + 7];
+rk_diffsPrev2[i * 7 + 3] = rk_eta[i * 5 + 8];
+rk_diffsPrev2[i * 7 + 4] = rk_eta[i * 5 + 9];
+rk_diffsPrev2[i * 7 + 5] = rk_eta[i * 2 + 30];
+rk_diffsPrev2[i * 7 + 6] = rk_eta[i * 2 + 31];
+}
+}
+if( resetIntegrator ) {
+for (i = 0; i < 1; ++i)
+{
+for (run1 = 0; run1 < 1; ++run1)
+{
+for (j = 0; j < 5; ++j)
+{
+rk_xxx[j] = rk_eta[j];
+tmp_index1 = j;
+rk_xxx[j] += + acado_Ah_mat[run1]*rk_kkk[tmp_index1];
+}
+acado_diffs( rk_xxx, &(rk_diffsTemp2[ run1 * 35 ]) );
+for (j = 0; j < 5; ++j)
+{
+tmp_index1 = (run1 * 5) + (j);
+rk_A[tmp_index1 * 5] = + acado_Ah_mat[run1]*rk_diffsTemp2[(run1 * 35) + (j * 7)];
+rk_A[tmp_index1 * 5 + 1] = + acado_Ah_mat[run1]*rk_diffsTemp2[(run1 * 35) + (j * 7 + 1)];
+rk_A[tmp_index1 * 5 + 2] = + acado_Ah_mat[run1]*rk_diffsTemp2[(run1 * 35) + (j * 7 + 2)];
+rk_A[tmp_index1 * 5 + 3] = + acado_Ah_mat[run1]*rk_diffsTemp2[(run1 * 35) + (j * 7 + 3)];
+rk_A[tmp_index1 * 5 + 4] = + acado_Ah_mat[run1]*rk_diffsTemp2[(run1 * 35) + (j * 7 + 4)];
+if( 0 == run1 ) rk_A[(tmp_index1 * 5) + (j)] -= 1.0000000000000000e+00;
+}
+acado_rhs( rk_xxx, rk_rhsTemp );
+rk_b[run1 * 5] = rk_kkk[run1] - rk_rhsTemp[0];
+rk_b[run1 * 5 + 1] = rk_kkk[run1 + 1] - rk_rhsTemp[1];
+rk_b[run1 * 5 + 2] = rk_kkk[run1 + 2] - rk_rhsTemp[2];
+rk_b[run1 * 5 + 3] = rk_kkk[run1 + 3] - rk_rhsTemp[3];
+rk_b[run1 * 5 + 4] = rk_kkk[run1 + 4] - rk_rhsTemp[4];
+}
+det = acado_solve_dim5_system( rk_A, rk_b, rk_dim5_perm );
+for (j = 0; j < 1; ++j)
+{
+rk_kkk[j] += rk_b[j * 5];
+rk_kkk[j + 1] += rk_b[j * 5 + 1];
+rk_kkk[j + 2] += rk_b[j * 5 + 2];
+rk_kkk[j + 3] += rk_b[j * 5 + 3];
+rk_kkk[j + 4] += rk_b[j * 5 + 4];
+}
+}
+}
+for (i = 0; i < 2; ++i)
+{
+for (run1 = 0; run1 < 1; ++run1)
+{
+for (j = 0; j < 5; ++j)
+{
+rk_xxx[j] = rk_eta[j];
+tmp_index1 = j;
+rk_xxx[j] += + acado_Ah_mat[run1]*rk_kkk[tmp_index1];
+}
+acado_rhs( rk_xxx, rk_rhsTemp );
+rk_b[run1 * 5] = rk_kkk[run1] - rk_rhsTemp[0];
+rk_b[run1 * 5 + 1] = rk_kkk[run1 + 1] - rk_rhsTemp[1];
+rk_b[run1 * 5 + 2] = rk_kkk[run1 + 2] - rk_rhsTemp[2];
+rk_b[run1 * 5 + 3] = rk_kkk[run1 + 3] - rk_rhsTemp[3];
+rk_b[run1 * 5 + 4] = rk_kkk[run1 + 4] - rk_rhsTemp[4];
+}
+acado_solve_dim5_system_reuse( rk_A, rk_b, rk_dim5_perm );
+for (j = 0; j < 1; ++j)
+{
+rk_kkk[j] += rk_b[j * 5];
+rk_kkk[j + 1] += rk_b[j * 5 + 1];
+rk_kkk[j + 2] += rk_b[j * 5 + 2];
+rk_kkk[j + 3] += rk_b[j * 5 + 3];
+rk_kkk[j + 4] += rk_b[j * 5 + 4];
+}
+}
+for (run1 = 0; run1 < 1; ++run1)
+{
+for (j = 0; j < 5; ++j)
+{
+rk_xxx[j] = rk_eta[j];
+tmp_index1 = j;
+rk_xxx[j] += + acado_Ah_mat[run1]*rk_kkk[tmp_index1];
+}
+acado_diffs( rk_xxx, &(rk_diffsTemp2[ run1 * 35 ]) );
+for (j = 0; j < 5; ++j)
+{
+tmp_index1 = (run1 * 5) + (j);
+rk_A[tmp_index1 * 5] = + acado_Ah_mat[run1]*rk_diffsTemp2[(run1 * 35) + (j * 7)];
+rk_A[tmp_index1 * 5 + 1] = + acado_Ah_mat[run1]*rk_diffsTemp2[(run1 * 35) + (j * 7 + 1)];
+rk_A[tmp_index1 * 5 + 2] = + acado_Ah_mat[run1]*rk_diffsTemp2[(run1 * 35) + (j * 7 + 2)];
+rk_A[tmp_index1 * 5 + 3] = + acado_Ah_mat[run1]*rk_diffsTemp2[(run1 * 35) + (j * 7 + 3)];
+rk_A[tmp_index1 * 5 + 4] = + acado_Ah_mat[run1]*rk_diffsTemp2[(run1 * 35) + (j * 7 + 4)];
+if( 0 == run1 ) rk_A[(tmp_index1 * 5) + (j)] -= 1.0000000000000000e+00;
+}
+}
+for (run1 = 0; run1 < 5; ++run1)
+{
+for (i = 0; i < 1; ++i)
+{
+rk_b[i * 5] = - rk_diffsTemp2[(i * 35) + (run1)];
+rk_b[i * 5 + 1] = - rk_diffsTemp2[(i * 35) + (run1 + 7)];
+rk_b[i * 5 + 2] = - rk_diffsTemp2[(i * 35) + (run1 + 14)];
+rk_b[i * 5 + 3] = - rk_diffsTemp2[(i * 35) + (run1 + 21)];
+rk_b[i * 5 + 4] = - rk_diffsTemp2[(i * 35) + (run1 + 28)];
+}
+if( 0 == run1 ) {
+det = acado_solve_dim5_system( rk_A, rk_b, rk_dim5_perm );
+}
+ else {
+acado_solve_dim5_system_reuse( rk_A, rk_b, rk_dim5_perm );
+}
+for (i = 0; i < 1; ++i)
+{
+rk_diffK[i] = rk_b[i * 5];
+rk_diffK[i + 1] = rk_b[i * 5 + 1];
+rk_diffK[i + 2] = rk_b[i * 5 + 2];
+rk_diffK[i + 3] = rk_b[i * 5 + 3];
+rk_diffK[i + 4] = rk_b[i * 5 + 4];
+}
+for (i = 0; i < 5; ++i)
+{
+rk_diffsNew2[(i * 7) + (run1)] = (i == run1-0);
+rk_diffsNew2[(i * 7) + (run1)] += + rk_diffK[i]*(real_t)1.4999999999999999e-01;
+}
+}
+for (run1 = 0; run1 < 2; ++run1)
+{
+for (i = 0; i < 1; ++i)
+{
+for (j = 0; j < 5; ++j)
+{
+tmp_index1 = (i * 5) + (j);
+tmp_index2 = (run1) + (j * 7);
+rk_b[tmp_index1] = - rk_diffsTemp2[(i * 35) + (tmp_index2 + 5)];
+}
+}
+acado_solve_dim5_system_reuse( rk_A, rk_b, rk_dim5_perm );
+for (i = 0; i < 1; ++i)
+{
+rk_diffK[i] = rk_b[i * 5];
+rk_diffK[i + 1] = rk_b[i * 5 + 1];
+rk_diffK[i + 2] = rk_b[i * 5 + 2];
+rk_diffK[i + 3] = rk_b[i * 5 + 3];
+rk_diffK[i + 4] = rk_b[i * 5 + 4];
+}
+for (i = 0; i < 5; ++i)
+{
+rk_diffsNew2[(i * 7) + (run1 + 5)] = + rk_diffK[i]*(real_t)1.4999999999999999e-01;
+}
+}
+rk_eta[0] += + rk_kkk[0]*(real_t)1.4999999999999999e-01;
+rk_eta[1] += + rk_kkk[1]*(real_t)1.4999999999999999e-01;
+rk_eta[2] += + rk_kkk[2]*(real_t)1.4999999999999999e-01;
+rk_eta[3] += + rk_kkk[3]*(real_t)1.4999999999999999e-01;
+rk_eta[4] += + rk_kkk[4]*(real_t)1.4999999999999999e-01;
+if( run == 0 ) {
+for (i = 0; i < 5; ++i)
+{
+for (j = 0; j < 5; ++j)
+{
+tmp_index2 = (j) + (i * 5);
+rk_eta[tmp_index2 + 5] = rk_diffsNew2[(i * 7) + (j)];
+}
+for (j = 0; j < 2; ++j)
+{
+tmp_index2 = (j) + (i * 2);
+rk_eta[tmp_index2 + 30] = rk_diffsNew2[(i * 7) + (j + 5)];
+}
+}
+}
+else {
+for (i = 0; i < 5; ++i)
+{
+for (j = 0; j < 5; ++j)
+{
+tmp_index2 = (j) + (i * 5);
+rk_eta[tmp_index2 + 5] = + rk_diffsNew2[i * 7]*rk_diffsPrev2[j];
+rk_eta[tmp_index2 + 5] += + rk_diffsNew2[i * 7 + 1]*rk_diffsPrev2[j + 7];
+rk_eta[tmp_index2 + 5] += + rk_diffsNew2[i * 7 + 2]*rk_diffsPrev2[j + 14];
+rk_eta[tmp_index2 + 5] += + rk_diffsNew2[i * 7 + 3]*rk_diffsPrev2[j + 21];
+rk_eta[tmp_index2 + 5] += + rk_diffsNew2[i * 7 + 4]*rk_diffsPrev2[j + 28];
+}
+for (j = 0; j < 2; ++j)
+{
+tmp_index2 = (j) + (i * 2);
+rk_eta[tmp_index2 + 30] = rk_diffsNew2[(i * 7) + (j + 5)];
+rk_eta[tmp_index2 + 30] += + rk_diffsNew2[i * 7]*rk_diffsPrev2[j + 5];
+rk_eta[tmp_index2 + 30] += + rk_diffsNew2[i * 7 + 1]*rk_diffsPrev2[j + 12];
+rk_eta[tmp_index2 + 30] += + rk_diffsNew2[i * 7 + 2]*rk_diffsPrev2[j + 19];
+rk_eta[tmp_index2 + 30] += + rk_diffsNew2[i * 7 + 3]*rk_diffsPrev2[j + 26];
+rk_eta[tmp_index2 + 30] += + rk_diffsNew2[i * 7 + 4]*rk_diffsPrev2[j + 33];
+}
+}
+}
+resetIntegrator = 0;
+rk_ttt += 5.0000000000000000e-01;
+}
+for (i = 0; i < 5; ++i)
+{
+}
+if( det < 1e-12 ) {
+error = 2;
+} else if( det < 1e-6 ) {
+error = 1;
+} else {
+error = 0;
+}
+return error;
+}
+
+
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/acado_qpoases_interface.cpp b/mav_control_rw/mav_nonlinear_mpc/solver/acado_qpoases_interface.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..dbd0cf9d8be1f8037f9e8de0cf33448e9d5cb326
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/acado_qpoases_interface.cpp
@@ -0,0 +1,70 @@
+/*
+ *    This file was auto-generated using the ACADO Toolkit.
+ *    
+ *    While ACADO Toolkit is free software released under the terms of
+ *    the GNU Lesser General Public License (LGPL), the generated code
+ *    as such remains the property of the user who used ACADO Toolkit
+ *    to generate this code. In particular, user dependent data of the code
+ *    do not inherit the GNU LGPL license. On the other hand, parts of the
+ *    generated code that are a direct copy of source code from the
+ *    ACADO Toolkit or the software tools it is based on, remain, as derived
+ *    work, automatically covered by the LGPL license.
+ *    
+ *    ACADO Toolkit is distributed in the hope that it will be useful,
+ *    but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ *    
+ */
+
+
+extern "C"
+{
+#include "acado_common.h"
+}
+
+#include "INCLUDE/QProblem.hpp"
+
+#if ACADO_COMPUTE_COVARIANCE_MATRIX == 1
+#include "INCLUDE/EXTRAS/SolutionAnalysis.hpp"
+#endif /* ACADO_COMPUTE_COVARIANCE_MATRIX */
+
+static int acado_nWSR;
+
+
+
+#if ACADO_COMPUTE_COVARIANCE_MATRIX == 1
+static SolutionAnalysis acado_sa;
+#endif /* ACADO_COMPUTE_COVARIANCE_MATRIX */
+
+int acado_solve( void )
+{
+	acado_nWSR = QPOASES_NWSRMAX;
+
+	QProblem qp(40, 240);
+	
+	returnValue retVal = qp.init(acadoWorkspace.H, acadoWorkspace.g, acadoWorkspace.A, acadoWorkspace.lb, acadoWorkspace.ub, acadoWorkspace.lbA, acadoWorkspace.ubA, acado_nWSR);
+
+    qp.getPrimalSolution( acadoWorkspace.x );
+    qp.getDualSolution( acadoWorkspace.y );
+	
+#if ACADO_COMPUTE_COVARIANCE_MATRIX == 1
+
+	if (retVal != SUCCESSFUL_RETURN)
+		return (int)retVal;
+		
+	retVal = acado_sa.getHessianInverse( &qp, );
+
+#endif /* ACADO_COMPUTE_COVARIANCE_MATRIX */
+
+	return (int)retVal;
+}
+
+int acado_getNWSR( void )
+{
+	return acado_nWSR;
+}
+
+const char* acado_getErrorString( int error )
+{
+	return MessageHandling::getErrorString( error );
+}
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/acado_qpoases_interface.hpp b/mav_control_rw/mav_nonlinear_mpc/solver/acado_qpoases_interface.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..8463a4bfa630d6444eab10b9c6562988aea31e61
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/acado_qpoases_interface.hpp
@@ -0,0 +1,65 @@
+/*
+ *    This file was auto-generated using the ACADO Toolkit.
+ *    
+ *    While ACADO Toolkit is free software released under the terms of
+ *    the GNU Lesser General Public License (LGPL), the generated code
+ *    as such remains the property of the user who used ACADO Toolkit
+ *    to generate this code. In particular, user dependent data of the code
+ *    do not inherit the GNU LGPL license. On the other hand, parts of the
+ *    generated code that are a direct copy of source code from the
+ *    ACADO Toolkit or the software tools it is based on, remain, as derived
+ *    work, automatically covered by the LGPL license.
+ *    
+ *    ACADO Toolkit is distributed in the hope that it will be useful,
+ *    but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ *    
+ */
+
+
+#ifndef QPOASES_HEADER
+#define QPOASES_HEADER
+
+#ifdef PC_DEBUG
+#include <stdio.h>
+#endif /* PC_DEBUG */
+
+#include <math.h>
+
+#ifdef __cplusplus
+#define EXTERNC extern "C"
+#else
+#define EXTERNC
+#endif
+
+/*
+ * A set of options for qpOASES
+ */
+
+/** Maximum number of optimization variables. */
+#define QPOASES_NVMAX      40
+/** Maximum number of constraints. */
+#define QPOASES_NCMAX      240
+/** Maximum number of working set recalculations. */
+#define QPOASES_NWSRMAX    840
+/** Print level for qpOASES. */
+#define QPOASES_PRINTLEVEL PL_NONE
+/** The value of EPS */
+#define QPOASES_EPS        2.221e-16
+/** Internally used floating point type */
+typedef double real_t;
+
+/*
+ * Forward function declarations
+ */
+
+/** A function that calls the QP solver */
+EXTERNC int acado_solve( void );
+
+/** Get the number of active set changes */
+EXTERNC int acado_getNWSR( void );
+
+/** Get the error string. */
+const char* acado_getErrorString( int error );
+
+#endif /* QPOASES_HEADER */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/acado_solver.c b/mav_control_rw/mav_nonlinear_mpc/solver/acado_solver.c
new file mode 100644
index 0000000000000000000000000000000000000000..b0b7b0e2b9034462bf40f826a166014da092a1e2
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/acado_solver.c
@@ -0,0 +1,4027 @@
+/*
+ *    This file was auto-generated using the ACADO Toolkit.
+ *    
+ *    While ACADO Toolkit is free software released under the terms of
+ *    the GNU Lesser General Public License (LGPL), the generated code
+ *    as such remains the property of the user who used ACADO Toolkit
+ *    to generate this code. In particular, user dependent data of the code
+ *    do not inherit the GNU LGPL license. On the other hand, parts of the
+ *    generated code that are a direct copy of source code from the
+ *    ACADO Toolkit or the software tools it is based on, remain, as derived
+ *    work, automatically covered by the LGPL license.
+ *    
+ *    ACADO Toolkit is distributed in the hope that it will be useful,
+ *    but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ *    
+ */
+
+
+#include "acado_common.h"
+
+
+
+
+/******************************************************************************/
+/*                                                                            */
+/* ACADO code generation                                                      */
+/*                                                                            */
+/******************************************************************************/
+
+
+/** Row vector of size: 62 */
+real_t state[ 62 ];
+
+int acado_modelSimulation(  )
+{
+int ret;
+
+int lRun1;
+ret = 0;
+#pragma omp parallel for private(lRun1, state) shared(acadoWorkspace, acadoVariables)
+for (lRun1 = 0; lRun1 < 20; ++lRun1)
+{
+state[0] = acadoVariables.x[lRun1 * 5];
+state[1] = acadoVariables.x[lRun1 * 5 + 1];
+state[2] = acadoVariables.x[lRun1 * 5 + 2];
+state[3] = acadoVariables.x[lRun1 * 5 + 3];
+state[4] = acadoVariables.x[lRun1 * 5 + 4];
+
+state[40] = acadoVariables.u[lRun1 * 2];
+state[41] = acadoVariables.u[lRun1 * 2 + 1];
+state[42] = acadoVariables.od[lRun1 * 20];
+state[43] = acadoVariables.od[lRun1 * 20 + 1];
+state[44] = acadoVariables.od[lRun1 * 20 + 2];
+state[45] = acadoVariables.od[lRun1 * 20 + 3];
+state[46] = acadoVariables.od[lRun1 * 20 + 4];
+state[47] = acadoVariables.od[lRun1 * 20 + 5];
+state[48] = acadoVariables.od[lRun1 * 20 + 6];
+state[49] = acadoVariables.od[lRun1 * 20 + 7];
+state[50] = acadoVariables.od[lRun1 * 20 + 8];
+state[51] = acadoVariables.od[lRun1 * 20 + 9];
+state[52] = acadoVariables.od[lRun1 * 20 + 10];
+state[53] = acadoVariables.od[lRun1 * 20 + 11];
+state[54] = acadoVariables.od[lRun1 * 20 + 12];
+state[55] = acadoVariables.od[lRun1 * 20 + 13];
+state[56] = acadoVariables.od[lRun1 * 20 + 14];
+state[57] = acadoVariables.od[lRun1 * 20 + 15];
+state[58] = acadoVariables.od[lRun1 * 20 + 16];
+state[59] = acadoVariables.od[lRun1 * 20 + 17];
+state[60] = acadoVariables.od[lRun1 * 20 + 18];
+state[61] = acadoVariables.od[lRun1 * 20 + 19];
+
+ret = acado_integrate(state, 1);
+
+acadoWorkspace.d[lRun1 * 5] = state[0] - acadoVariables.x[lRun1 * 5 + 5];
+acadoWorkspace.d[lRun1 * 5 + 1] = state[1] - acadoVariables.x[lRun1 * 5 + 6];
+acadoWorkspace.d[lRun1 * 5 + 2] = state[2] - acadoVariables.x[lRun1 * 5 + 7];
+acadoWorkspace.d[lRun1 * 5 + 3] = state[3] - acadoVariables.x[lRun1 * 5 + 8];
+acadoWorkspace.d[lRun1 * 5 + 4] = state[4] - acadoVariables.x[lRun1 * 5 + 9];
+
+acadoWorkspace.evGx[lRun1 * 25] = state[5];
+acadoWorkspace.evGx[lRun1 * 25 + 1] = state[6];
+acadoWorkspace.evGx[lRun1 * 25 + 2] = state[7];
+acadoWorkspace.evGx[lRun1 * 25 + 3] = state[8];
+acadoWorkspace.evGx[lRun1 * 25 + 4] = state[9];
+acadoWorkspace.evGx[lRun1 * 25 + 5] = state[10];
+acadoWorkspace.evGx[lRun1 * 25 + 6] = state[11];
+acadoWorkspace.evGx[lRun1 * 25 + 7] = state[12];
+acadoWorkspace.evGx[lRun1 * 25 + 8] = state[13];
+acadoWorkspace.evGx[lRun1 * 25 + 9] = state[14];
+acadoWorkspace.evGx[lRun1 * 25 + 10] = state[15];
+acadoWorkspace.evGx[lRun1 * 25 + 11] = state[16];
+acadoWorkspace.evGx[lRun1 * 25 + 12] = state[17];
+acadoWorkspace.evGx[lRun1 * 25 + 13] = state[18];
+acadoWorkspace.evGx[lRun1 * 25 + 14] = state[19];
+acadoWorkspace.evGx[lRun1 * 25 + 15] = state[20];
+acadoWorkspace.evGx[lRun1 * 25 + 16] = state[21];
+acadoWorkspace.evGx[lRun1 * 25 + 17] = state[22];
+acadoWorkspace.evGx[lRun1 * 25 + 18] = state[23];
+acadoWorkspace.evGx[lRun1 * 25 + 19] = state[24];
+acadoWorkspace.evGx[lRun1 * 25 + 20] = state[25];
+acadoWorkspace.evGx[lRun1 * 25 + 21] = state[26];
+acadoWorkspace.evGx[lRun1 * 25 + 22] = state[27];
+acadoWorkspace.evGx[lRun1 * 25 + 23] = state[28];
+acadoWorkspace.evGx[lRun1 * 25 + 24] = state[29];
+
+acadoWorkspace.evGu[lRun1 * 10] = state[30];
+acadoWorkspace.evGu[lRun1 * 10 + 1] = state[31];
+acadoWorkspace.evGu[lRun1 * 10 + 2] = state[32];
+acadoWorkspace.evGu[lRun1 * 10 + 3] = state[33];
+acadoWorkspace.evGu[lRun1 * 10 + 4] = state[34];
+acadoWorkspace.evGu[lRun1 * 10 + 5] = state[35];
+acadoWorkspace.evGu[lRun1 * 10 + 6] = state[36];
+acadoWorkspace.evGu[lRun1 * 10 + 7] = state[37];
+acadoWorkspace.evGu[lRun1 * 10 + 8] = state[38];
+acadoWorkspace.evGu[lRun1 * 10 + 9] = state[39];
+}
+return ret;
+}
+
+void acado_evaluateLSQ(const real_t* in, real_t* out)
+{
+const real_t* xd = in;
+const real_t* u = in + 5;
+const real_t* od = in + 7;
+/* Vector of auxiliary variables; number of elements: 98. */
+real_t* a = acadoWorkspace.objAuxVar;
+
+/* Compute intermediate quantities: */
+a[0] = (sqrt((((xd[0]-od[0])*(xd[0]-od[0]))+((xd[1]-od[10])*(xd[1]-od[10])))));
+a[1] = (exp(((real_t)(2.0000000000000000e+00)-a[0])));
+a[2] = (sqrt((((xd[0]-od[1])*(xd[0]-od[1]))+((xd[1]-od[11])*(xd[1]-od[11])))));
+a[3] = (exp(((real_t)(2.0000000000000000e+00)-a[2])));
+a[4] = (sqrt((((xd[0]-od[2])*(xd[0]-od[2]))+((xd[1]-od[12])*(xd[1]-od[12])))));
+a[5] = (exp(((real_t)(2.0000000000000000e+00)-a[4])));
+a[6] = (sqrt((((xd[0]-od[3])*(xd[0]-od[3]))+((xd[1]-od[13])*(xd[1]-od[13])))));
+a[7] = (exp(((real_t)(2.0000000000000000e+00)-a[6])));
+a[8] = (sqrt((((xd[0]-od[4])*(xd[0]-od[4]))+((xd[1]-od[14])*(xd[1]-od[14])))));
+a[9] = (exp(((real_t)(2.0000000000000000e+00)-a[8])));
+a[10] = (sqrt((((xd[0]-od[5])*(xd[0]-od[5]))+((xd[1]-od[15])*(xd[1]-od[15])))));
+a[11] = (exp(((real_t)(2.0000000000000000e+00)-a[10])));
+a[12] = (sqrt((((xd[0]-od[6])*(xd[0]-od[6]))+((xd[1]-od[16])*(xd[1]-od[16])))));
+a[13] = (exp(((real_t)(2.0000000000000000e+00)-a[12])));
+a[14] = (sqrt((((xd[0]-od[7])*(xd[0]-od[7]))+((xd[1]-od[17])*(xd[1]-od[17])))));
+a[15] = (exp(((real_t)(2.0000000000000000e+00)-a[14])));
+a[16] = (sqrt((((xd[0]-od[8])*(xd[0]-od[8]))+((xd[1]-od[18])*(xd[1]-od[18])))));
+a[17] = (exp(((real_t)(2.0000000000000000e+00)-a[16])));
+a[18] = (sqrt((((xd[0]-od[9])*(xd[0]-od[9]))+((xd[1]-od[19])*(xd[1]-od[19])))));
+a[19] = (exp(((real_t)(2.0000000000000000e+00)-a[18])));
+a[20] = (((((((((a[1]+a[3])+a[5])+a[7])+a[9])+a[11])+a[13])+a[15])+a[17])+a[19]);
+a[21] = (1.0/sqrt((((xd[0]-od[0])*(xd[0]-od[0]))+((xd[1]-od[10])*(xd[1]-od[10])))));
+a[22] = (a[21]*(real_t)(5.0000000000000000e-01));
+a[23] = (((xd[0]-od[0])+(xd[0]-od[0]))*a[22]);
+a[24] = (exp(((real_t)(2.0000000000000000e+00)-a[0])));
+a[25] = (((real_t)(0.0000000000000000e+00)-a[23])*a[24]);
+a[26] = (1.0/sqrt((((xd[0]-od[1])*(xd[0]-od[1]))+((xd[1]-od[11])*(xd[1]-od[11])))));
+a[27] = (a[26]*(real_t)(5.0000000000000000e-01));
+a[28] = (((xd[0]-od[1])+(xd[0]-od[1]))*a[27]);
+a[29] = (exp(((real_t)(2.0000000000000000e+00)-a[2])));
+a[30] = (((real_t)(0.0000000000000000e+00)-a[28])*a[29]);
+a[31] = (1.0/sqrt((((xd[0]-od[2])*(xd[0]-od[2]))+((xd[1]-od[12])*(xd[1]-od[12])))));
+a[32] = (a[31]*(real_t)(5.0000000000000000e-01));
+a[33] = (((xd[0]-od[2])+(xd[0]-od[2]))*a[32]);
+a[34] = (exp(((real_t)(2.0000000000000000e+00)-a[4])));
+a[35] = (((real_t)(0.0000000000000000e+00)-a[33])*a[34]);
+a[36] = (1.0/sqrt((((xd[0]-od[3])*(xd[0]-od[3]))+((xd[1]-od[13])*(xd[1]-od[13])))));
+a[37] = (a[36]*(real_t)(5.0000000000000000e-01));
+a[38] = (((xd[0]-od[3])+(xd[0]-od[3]))*a[37]);
+a[39] = (exp(((real_t)(2.0000000000000000e+00)-a[6])));
+a[40] = (((real_t)(0.0000000000000000e+00)-a[38])*a[39]);
+a[41] = (1.0/sqrt((((xd[0]-od[4])*(xd[0]-od[4]))+((xd[1]-od[14])*(xd[1]-od[14])))));
+a[42] = (a[41]*(real_t)(5.0000000000000000e-01));
+a[43] = (((xd[0]-od[4])+(xd[0]-od[4]))*a[42]);
+a[44] = (exp(((real_t)(2.0000000000000000e+00)-a[8])));
+a[45] = (((real_t)(0.0000000000000000e+00)-a[43])*a[44]);
+a[46] = (1.0/sqrt((((xd[0]-od[5])*(xd[0]-od[5]))+((xd[1]-od[15])*(xd[1]-od[15])))));
+a[47] = (a[46]*(real_t)(5.0000000000000000e-01));
+a[48] = (((xd[0]-od[5])+(xd[0]-od[5]))*a[47]);
+a[49] = (exp(((real_t)(2.0000000000000000e+00)-a[10])));
+a[50] = (((real_t)(0.0000000000000000e+00)-a[48])*a[49]);
+a[51] = (1.0/sqrt((((xd[0]-od[6])*(xd[0]-od[6]))+((xd[1]-od[16])*(xd[1]-od[16])))));
+a[52] = (a[51]*(real_t)(5.0000000000000000e-01));
+a[53] = (((xd[0]-od[6])+(xd[0]-od[6]))*a[52]);
+a[54] = (exp(((real_t)(2.0000000000000000e+00)-a[12])));
+a[55] = (((real_t)(0.0000000000000000e+00)-a[53])*a[54]);
+a[56] = (1.0/sqrt((((xd[0]-od[7])*(xd[0]-od[7]))+((xd[1]-od[17])*(xd[1]-od[17])))));
+a[57] = (a[56]*(real_t)(5.0000000000000000e-01));
+a[58] = (((xd[0]-od[7])+(xd[0]-od[7]))*a[57]);
+a[59] = (exp(((real_t)(2.0000000000000000e+00)-a[14])));
+a[60] = (((real_t)(0.0000000000000000e+00)-a[58])*a[59]);
+a[61] = (1.0/sqrt((((xd[0]-od[8])*(xd[0]-od[8]))+((xd[1]-od[18])*(xd[1]-od[18])))));
+a[62] = (a[61]*(real_t)(5.0000000000000000e-01));
+a[63] = (((xd[0]-od[8])+(xd[0]-od[8]))*a[62]);
+a[64] = (exp(((real_t)(2.0000000000000000e+00)-a[16])));
+a[65] = (((real_t)(0.0000000000000000e+00)-a[63])*a[64]);
+a[66] = (1.0/sqrt((((xd[0]-od[9])*(xd[0]-od[9]))+((xd[1]-od[19])*(xd[1]-od[19])))));
+a[67] = (a[66]*(real_t)(5.0000000000000000e-01));
+a[68] = (((xd[0]-od[9])+(xd[0]-od[9]))*a[67]);
+a[69] = (exp(((real_t)(2.0000000000000000e+00)-a[18])));
+a[70] = (((real_t)(0.0000000000000000e+00)-a[68])*a[69]);
+a[71] = (((((((((a[25]+a[30])+a[35])+a[40])+a[45])+a[50])+a[55])+a[60])+a[65])+a[70]);
+a[72] = (((xd[1]-od[10])+(xd[1]-od[10]))*a[22]);
+a[73] = (((real_t)(0.0000000000000000e+00)-a[72])*a[24]);
+a[74] = (((xd[1]-od[11])+(xd[1]-od[11]))*a[27]);
+a[75] = (((real_t)(0.0000000000000000e+00)-a[74])*a[29]);
+a[76] = (((xd[1]-od[12])+(xd[1]-od[12]))*a[32]);
+a[77] = (((real_t)(0.0000000000000000e+00)-a[76])*a[34]);
+a[78] = (((xd[1]-od[13])+(xd[1]-od[13]))*a[37]);
+a[79] = (((real_t)(0.0000000000000000e+00)-a[78])*a[39]);
+a[80] = (((xd[1]-od[14])+(xd[1]-od[14]))*a[42]);
+a[81] = (((real_t)(0.0000000000000000e+00)-a[80])*a[44]);
+a[82] = (((xd[1]-od[15])+(xd[1]-od[15]))*a[47]);
+a[83] = (((real_t)(0.0000000000000000e+00)-a[82])*a[49]);
+a[84] = (((xd[1]-od[16])+(xd[1]-od[16]))*a[52]);
+a[85] = (((real_t)(0.0000000000000000e+00)-a[84])*a[54]);
+a[86] = (((xd[1]-od[17])+(xd[1]-od[17]))*a[57]);
+a[87] = (((real_t)(0.0000000000000000e+00)-a[86])*a[59]);
+a[88] = (((xd[1]-od[18])+(xd[1]-od[18]))*a[62]);
+a[89] = (((real_t)(0.0000000000000000e+00)-a[88])*a[64]);
+a[90] = (((xd[1]-od[19])+(xd[1]-od[19]))*a[67]);
+a[91] = (((real_t)(0.0000000000000000e+00)-a[90])*a[69]);
+a[92] = (((((((((a[73]+a[75])+a[77])+a[79])+a[81])+a[83])+a[85])+a[87])+a[89])+a[91]);
+a[93] = (real_t)(0.0000000000000000e+00);
+a[94] = (real_t)(0.0000000000000000e+00);
+a[95] = (real_t)(0.0000000000000000e+00);
+a[96] = (real_t)(0.0000000000000000e+00);
+a[97] = (real_t)(0.0000000000000000e+00);
+
+/* Compute outputs: */
+out[0] = xd[0];
+out[1] = xd[1];
+out[2] = xd[2];
+out[3] = xd[3];
+out[4] = xd[4];
+out[5] = u[0];
+out[6] = u[1];
+out[7] = a[20];
+out[8] = (real_t)(1.0000000000000000e+00);
+out[9] = (real_t)(0.0000000000000000e+00);
+out[10] = (real_t)(0.0000000000000000e+00);
+out[11] = (real_t)(0.0000000000000000e+00);
+out[12] = (real_t)(0.0000000000000000e+00);
+out[13] = (real_t)(0.0000000000000000e+00);
+out[14] = (real_t)(1.0000000000000000e+00);
+out[15] = (real_t)(0.0000000000000000e+00);
+out[16] = (real_t)(0.0000000000000000e+00);
+out[17] = (real_t)(0.0000000000000000e+00);
+out[18] = (real_t)(0.0000000000000000e+00);
+out[19] = (real_t)(0.0000000000000000e+00);
+out[20] = (real_t)(1.0000000000000000e+00);
+out[21] = (real_t)(0.0000000000000000e+00);
+out[22] = (real_t)(0.0000000000000000e+00);
+out[23] = (real_t)(0.0000000000000000e+00);
+out[24] = (real_t)(0.0000000000000000e+00);
+out[25] = (real_t)(0.0000000000000000e+00);
+out[26] = (real_t)(1.0000000000000000e+00);
+out[27] = (real_t)(0.0000000000000000e+00);
+out[28] = (real_t)(0.0000000000000000e+00);
+out[29] = (real_t)(0.0000000000000000e+00);
+out[30] = (real_t)(0.0000000000000000e+00);
+out[31] = (real_t)(0.0000000000000000e+00);
+out[32] = (real_t)(1.0000000000000000e+00);
+out[33] = (real_t)(0.0000000000000000e+00);
+out[34] = (real_t)(0.0000000000000000e+00);
+out[35] = (real_t)(0.0000000000000000e+00);
+out[36] = (real_t)(0.0000000000000000e+00);
+out[37] = (real_t)(0.0000000000000000e+00);
+out[38] = (real_t)(0.0000000000000000e+00);
+out[39] = (real_t)(0.0000000000000000e+00);
+out[40] = (real_t)(0.0000000000000000e+00);
+out[41] = (real_t)(0.0000000000000000e+00);
+out[42] = (real_t)(0.0000000000000000e+00);
+out[43] = a[71];
+out[44] = a[92];
+out[45] = a[93];
+out[46] = a[94];
+out[47] = a[95];
+out[48] = (real_t)(0.0000000000000000e+00);
+out[49] = (real_t)(0.0000000000000000e+00);
+out[50] = (real_t)(0.0000000000000000e+00);
+out[51] = (real_t)(0.0000000000000000e+00);
+out[52] = (real_t)(0.0000000000000000e+00);
+out[53] = (real_t)(0.0000000000000000e+00);
+out[54] = (real_t)(0.0000000000000000e+00);
+out[55] = (real_t)(0.0000000000000000e+00);
+out[56] = (real_t)(0.0000000000000000e+00);
+out[57] = (real_t)(0.0000000000000000e+00);
+out[58] = (real_t)(1.0000000000000000e+00);
+out[59] = (real_t)(0.0000000000000000e+00);
+out[60] = (real_t)(0.0000000000000000e+00);
+out[61] = (real_t)(1.0000000000000000e+00);
+out[62] = a[96];
+out[63] = a[97];
+}
+
+void acado_evaluateLSQEndTerm(const real_t* in, real_t* out)
+{
+const real_t* xd = in;
+
+/* Compute outputs: */
+out[0] = xd[0];
+out[1] = xd[1];
+out[2] = xd[2];
+out[3] = xd[3];
+out[4] = xd[4];
+}
+
+void acado_evaluatePathConstraints(const real_t* in, real_t* out)
+{
+const real_t* xd = in;
+const real_t* od = in + 7;
+/* Vector of auxiliary variables; number of elements: 160. */
+real_t* a = acadoWorkspace.conAuxVar;
+
+/* Compute intermediate quantities: */
+a[0] = (sqrt((((xd[0]-od[0])*(xd[0]-od[0]))+((xd[1]-od[10])*(xd[1]-od[10])))));
+a[1] = (sqrt((((xd[0]-od[1])*(xd[0]-od[1]))+((xd[1]-od[11])*(xd[1]-od[11])))));
+a[2] = (sqrt((((xd[0]-od[2])*(xd[0]-od[2]))+((xd[1]-od[12])*(xd[1]-od[12])))));
+a[3] = (sqrt((((xd[0]-od[3])*(xd[0]-od[3]))+((xd[1]-od[13])*(xd[1]-od[13])))));
+a[4] = (sqrt((((xd[0]-od[4])*(xd[0]-od[4]))+((xd[1]-od[14])*(xd[1]-od[14])))));
+a[5] = (sqrt((((xd[0]-od[5])*(xd[0]-od[5]))+((xd[1]-od[15])*(xd[1]-od[15])))));
+a[6] = (sqrt((((xd[0]-od[6])*(xd[0]-od[6]))+((xd[1]-od[16])*(xd[1]-od[16])))));
+a[7] = (sqrt((((xd[0]-od[7])*(xd[0]-od[7]))+((xd[1]-od[17])*(xd[1]-od[17])))));
+a[8] = (sqrt((((xd[0]-od[8])*(xd[0]-od[8]))+((xd[1]-od[18])*(xd[1]-od[18])))));
+a[9] = (sqrt((((xd[0]-od[9])*(xd[0]-od[9]))+((xd[1]-od[19])*(xd[1]-od[19])))));
+a[10] = (xd[0]-od[0]);
+a[11] = (xd[0]-od[0]);
+a[12] = (a[10]+a[11]);
+a[13] = (1.0/sqrt((((xd[0]-od[0])*(xd[0]-od[0]))+((xd[1]-od[10])*(xd[1]-od[10])))));
+a[14] = (a[13]*(real_t)(5.0000000000000000e-01));
+a[15] = (a[12]*a[14]);
+a[16] = (xd[1]-od[10]);
+a[17] = (xd[1]-od[10]);
+a[18] = (a[16]+a[17]);
+a[19] = (a[18]*a[14]);
+a[20] = (real_t)(0.0000000000000000e+00);
+a[21] = (real_t)(0.0000000000000000e+00);
+a[22] = (real_t)(0.0000000000000000e+00);
+a[23] = (xd[0]-od[1]);
+a[24] = (xd[0]-od[1]);
+a[25] = (a[23]+a[24]);
+a[26] = (1.0/sqrt((((xd[0]-od[1])*(xd[0]-od[1]))+((xd[1]-od[11])*(xd[1]-od[11])))));
+a[27] = (a[26]*(real_t)(5.0000000000000000e-01));
+a[28] = (a[25]*a[27]);
+a[29] = (xd[1]-od[11]);
+a[30] = (xd[1]-od[11]);
+a[31] = (a[29]+a[30]);
+a[32] = (a[31]*a[27]);
+a[33] = (real_t)(0.0000000000000000e+00);
+a[34] = (real_t)(0.0000000000000000e+00);
+a[35] = (real_t)(0.0000000000000000e+00);
+a[36] = (xd[0]-od[2]);
+a[37] = (xd[0]-od[2]);
+a[38] = (a[36]+a[37]);
+a[39] = (1.0/sqrt((((xd[0]-od[2])*(xd[0]-od[2]))+((xd[1]-od[12])*(xd[1]-od[12])))));
+a[40] = (a[39]*(real_t)(5.0000000000000000e-01));
+a[41] = (a[38]*a[40]);
+a[42] = (xd[1]-od[12]);
+a[43] = (xd[1]-od[12]);
+a[44] = (a[42]+a[43]);
+a[45] = (a[44]*a[40]);
+a[46] = (real_t)(0.0000000000000000e+00);
+a[47] = (real_t)(0.0000000000000000e+00);
+a[48] = (real_t)(0.0000000000000000e+00);
+a[49] = (xd[0]-od[3]);
+a[50] = (xd[0]-od[3]);
+a[51] = (a[49]+a[50]);
+a[52] = (1.0/sqrt((((xd[0]-od[3])*(xd[0]-od[3]))+((xd[1]-od[13])*(xd[1]-od[13])))));
+a[53] = (a[52]*(real_t)(5.0000000000000000e-01));
+a[54] = (a[51]*a[53]);
+a[55] = (xd[1]-od[13]);
+a[56] = (xd[1]-od[13]);
+a[57] = (a[55]+a[56]);
+a[58] = (a[57]*a[53]);
+a[59] = (real_t)(0.0000000000000000e+00);
+a[60] = (real_t)(0.0000000000000000e+00);
+a[61] = (real_t)(0.0000000000000000e+00);
+a[62] = (xd[0]-od[4]);
+a[63] = (xd[0]-od[4]);
+a[64] = (a[62]+a[63]);
+a[65] = (1.0/sqrt((((xd[0]-od[4])*(xd[0]-od[4]))+((xd[1]-od[14])*(xd[1]-od[14])))));
+a[66] = (a[65]*(real_t)(5.0000000000000000e-01));
+a[67] = (a[64]*a[66]);
+a[68] = (xd[1]-od[14]);
+a[69] = (xd[1]-od[14]);
+a[70] = (a[68]+a[69]);
+a[71] = (a[70]*a[66]);
+a[72] = (real_t)(0.0000000000000000e+00);
+a[73] = (real_t)(0.0000000000000000e+00);
+a[74] = (real_t)(0.0000000000000000e+00);
+a[75] = (xd[0]-od[5]);
+a[76] = (xd[0]-od[5]);
+a[77] = (a[75]+a[76]);
+a[78] = (1.0/sqrt((((xd[0]-od[5])*(xd[0]-od[5]))+((xd[1]-od[15])*(xd[1]-od[15])))));
+a[79] = (a[78]*(real_t)(5.0000000000000000e-01));
+a[80] = (a[77]*a[79]);
+a[81] = (xd[1]-od[15]);
+a[82] = (xd[1]-od[15]);
+a[83] = (a[81]+a[82]);
+a[84] = (a[83]*a[79]);
+a[85] = (real_t)(0.0000000000000000e+00);
+a[86] = (real_t)(0.0000000000000000e+00);
+a[87] = (real_t)(0.0000000000000000e+00);
+a[88] = (xd[0]-od[6]);
+a[89] = (xd[0]-od[6]);
+a[90] = (a[88]+a[89]);
+a[91] = (1.0/sqrt((((xd[0]-od[6])*(xd[0]-od[6]))+((xd[1]-od[16])*(xd[1]-od[16])))));
+a[92] = (a[91]*(real_t)(5.0000000000000000e-01));
+a[93] = (a[90]*a[92]);
+a[94] = (xd[1]-od[16]);
+a[95] = (xd[1]-od[16]);
+a[96] = (a[94]+a[95]);
+a[97] = (a[96]*a[92]);
+a[98] = (real_t)(0.0000000000000000e+00);
+a[99] = (real_t)(0.0000000000000000e+00);
+a[100] = (real_t)(0.0000000000000000e+00);
+a[101] = (xd[0]-od[7]);
+a[102] = (xd[0]-od[7]);
+a[103] = (a[101]+a[102]);
+a[104] = (1.0/sqrt((((xd[0]-od[7])*(xd[0]-od[7]))+((xd[1]-od[17])*(xd[1]-od[17])))));
+a[105] = (a[104]*(real_t)(5.0000000000000000e-01));
+a[106] = (a[103]*a[105]);
+a[107] = (xd[1]-od[17]);
+a[108] = (xd[1]-od[17]);
+a[109] = (a[107]+a[108]);
+a[110] = (a[109]*a[105]);
+a[111] = (real_t)(0.0000000000000000e+00);
+a[112] = (real_t)(0.0000000000000000e+00);
+a[113] = (real_t)(0.0000000000000000e+00);
+a[114] = (xd[0]-od[8]);
+a[115] = (xd[0]-od[8]);
+a[116] = (a[114]+a[115]);
+a[117] = (1.0/sqrt((((xd[0]-od[8])*(xd[0]-od[8]))+((xd[1]-od[18])*(xd[1]-od[18])))));
+a[118] = (a[117]*(real_t)(5.0000000000000000e-01));
+a[119] = (a[116]*a[118]);
+a[120] = (xd[1]-od[18]);
+a[121] = (xd[1]-od[18]);
+a[122] = (a[120]+a[121]);
+a[123] = (a[122]*a[118]);
+a[124] = (real_t)(0.0000000000000000e+00);
+a[125] = (real_t)(0.0000000000000000e+00);
+a[126] = (real_t)(0.0000000000000000e+00);
+a[127] = (xd[0]-od[9]);
+a[128] = (xd[0]-od[9]);
+a[129] = (a[127]+a[128]);
+a[130] = (1.0/sqrt((((xd[0]-od[9])*(xd[0]-od[9]))+((xd[1]-od[19])*(xd[1]-od[19])))));
+a[131] = (a[130]*(real_t)(5.0000000000000000e-01));
+a[132] = (a[129]*a[131]);
+a[133] = (xd[1]-od[19]);
+a[134] = (xd[1]-od[19]);
+a[135] = (a[133]+a[134]);
+a[136] = (a[135]*a[131]);
+a[137] = (real_t)(0.0000000000000000e+00);
+a[138] = (real_t)(0.0000000000000000e+00);
+a[139] = (real_t)(0.0000000000000000e+00);
+a[140] = (real_t)(0.0000000000000000e+00);
+a[141] = (real_t)(0.0000000000000000e+00);
+a[142] = (real_t)(0.0000000000000000e+00);
+a[143] = (real_t)(0.0000000000000000e+00);
+a[144] = (real_t)(0.0000000000000000e+00);
+a[145] = (real_t)(0.0000000000000000e+00);
+a[146] = (real_t)(0.0000000000000000e+00);
+a[147] = (real_t)(0.0000000000000000e+00);
+a[148] = (real_t)(0.0000000000000000e+00);
+a[149] = (real_t)(0.0000000000000000e+00);
+a[150] = (real_t)(0.0000000000000000e+00);
+a[151] = (real_t)(0.0000000000000000e+00);
+a[152] = (real_t)(0.0000000000000000e+00);
+a[153] = (real_t)(0.0000000000000000e+00);
+a[154] = (real_t)(0.0000000000000000e+00);
+a[155] = (real_t)(0.0000000000000000e+00);
+a[156] = (real_t)(0.0000000000000000e+00);
+a[157] = (real_t)(0.0000000000000000e+00);
+a[158] = (real_t)(0.0000000000000000e+00);
+a[159] = (real_t)(0.0000000000000000e+00);
+
+/* Compute outputs: */
+out[0] = a[0];
+out[1] = a[1];
+out[2] = a[2];
+out[3] = a[3];
+out[4] = a[4];
+out[5] = a[5];
+out[6] = a[6];
+out[7] = a[7];
+out[8] = a[8];
+out[9] = a[9];
+out[10] = a[15];
+out[11] = a[19];
+out[12] = a[20];
+out[13] = a[21];
+out[14] = a[22];
+out[15] = a[28];
+out[16] = a[32];
+out[17] = a[33];
+out[18] = a[34];
+out[19] = a[35];
+out[20] = a[41];
+out[21] = a[45];
+out[22] = a[46];
+out[23] = a[47];
+out[24] = a[48];
+out[25] = a[54];
+out[26] = a[58];
+out[27] = a[59];
+out[28] = a[60];
+out[29] = a[61];
+out[30] = a[67];
+out[31] = a[71];
+out[32] = a[72];
+out[33] = a[73];
+out[34] = a[74];
+out[35] = a[80];
+out[36] = a[84];
+out[37] = a[85];
+out[38] = a[86];
+out[39] = a[87];
+out[40] = a[93];
+out[41] = a[97];
+out[42] = a[98];
+out[43] = a[99];
+out[44] = a[100];
+out[45] = a[106];
+out[46] = a[110];
+out[47] = a[111];
+out[48] = a[112];
+out[49] = a[113];
+out[50] = a[119];
+out[51] = a[123];
+out[52] = a[124];
+out[53] = a[125];
+out[54] = a[126];
+out[55] = a[132];
+out[56] = a[136];
+out[57] = a[137];
+out[58] = a[138];
+out[59] = a[139];
+out[60] = a[140];
+out[61] = a[141];
+out[62] = a[142];
+out[63] = a[143];
+out[64] = a[144];
+out[65] = a[145];
+out[66] = a[146];
+out[67] = a[147];
+out[68] = a[148];
+out[69] = a[149];
+out[70] = a[150];
+out[71] = a[151];
+out[72] = a[152];
+out[73] = a[153];
+out[74] = a[154];
+out[75] = a[155];
+out[76] = a[156];
+out[77] = a[157];
+out[78] = a[158];
+out[79] = a[159];
+}
+
+void acado_setObjQ1Q2( real_t* const tmpFx, real_t* const tmpObjS, real_t* const tmpQ1, real_t* const tmpQ2 )
+{
+tmpQ2[0] = + tmpFx[0]*tmpObjS[0] + tmpFx[5]*tmpObjS[8] + tmpFx[10]*tmpObjS[16] + tmpFx[15]*tmpObjS[24] + tmpFx[20]*tmpObjS[32] + tmpFx[25]*tmpObjS[40] + tmpFx[30]*tmpObjS[48] + tmpFx[35]*tmpObjS[56];
+tmpQ2[1] = + tmpFx[0]*tmpObjS[1] + tmpFx[5]*tmpObjS[9] + tmpFx[10]*tmpObjS[17] + tmpFx[15]*tmpObjS[25] + tmpFx[20]*tmpObjS[33] + tmpFx[25]*tmpObjS[41] + tmpFx[30]*tmpObjS[49] + tmpFx[35]*tmpObjS[57];
+tmpQ2[2] = + tmpFx[0]*tmpObjS[2] + tmpFx[5]*tmpObjS[10] + tmpFx[10]*tmpObjS[18] + tmpFx[15]*tmpObjS[26] + tmpFx[20]*tmpObjS[34] + tmpFx[25]*tmpObjS[42] + tmpFx[30]*tmpObjS[50] + tmpFx[35]*tmpObjS[58];
+tmpQ2[3] = + tmpFx[0]*tmpObjS[3] + tmpFx[5]*tmpObjS[11] + tmpFx[10]*tmpObjS[19] + tmpFx[15]*tmpObjS[27] + tmpFx[20]*tmpObjS[35] + tmpFx[25]*tmpObjS[43] + tmpFx[30]*tmpObjS[51] + tmpFx[35]*tmpObjS[59];
+tmpQ2[4] = + tmpFx[0]*tmpObjS[4] + tmpFx[5]*tmpObjS[12] + tmpFx[10]*tmpObjS[20] + tmpFx[15]*tmpObjS[28] + tmpFx[20]*tmpObjS[36] + tmpFx[25]*tmpObjS[44] + tmpFx[30]*tmpObjS[52] + tmpFx[35]*tmpObjS[60];
+tmpQ2[5] = + tmpFx[0]*tmpObjS[5] + tmpFx[5]*tmpObjS[13] + tmpFx[10]*tmpObjS[21] + tmpFx[15]*tmpObjS[29] + tmpFx[20]*tmpObjS[37] + tmpFx[25]*tmpObjS[45] + tmpFx[30]*tmpObjS[53] + tmpFx[35]*tmpObjS[61];
+tmpQ2[6] = + tmpFx[0]*tmpObjS[6] + tmpFx[5]*tmpObjS[14] + tmpFx[10]*tmpObjS[22] + tmpFx[15]*tmpObjS[30] + tmpFx[20]*tmpObjS[38] + tmpFx[25]*tmpObjS[46] + tmpFx[30]*tmpObjS[54] + tmpFx[35]*tmpObjS[62];
+tmpQ2[7] = + tmpFx[0]*tmpObjS[7] + tmpFx[5]*tmpObjS[15] + tmpFx[10]*tmpObjS[23] + tmpFx[15]*tmpObjS[31] + tmpFx[20]*tmpObjS[39] + tmpFx[25]*tmpObjS[47] + tmpFx[30]*tmpObjS[55] + tmpFx[35]*tmpObjS[63];
+tmpQ2[8] = + tmpFx[1]*tmpObjS[0] + tmpFx[6]*tmpObjS[8] + tmpFx[11]*tmpObjS[16] + tmpFx[16]*tmpObjS[24] + tmpFx[21]*tmpObjS[32] + tmpFx[26]*tmpObjS[40] + tmpFx[31]*tmpObjS[48] + tmpFx[36]*tmpObjS[56];
+tmpQ2[9] = + tmpFx[1]*tmpObjS[1] + tmpFx[6]*tmpObjS[9] + tmpFx[11]*tmpObjS[17] + tmpFx[16]*tmpObjS[25] + tmpFx[21]*tmpObjS[33] + tmpFx[26]*tmpObjS[41] + tmpFx[31]*tmpObjS[49] + tmpFx[36]*tmpObjS[57];
+tmpQ2[10] = + tmpFx[1]*tmpObjS[2] + tmpFx[6]*tmpObjS[10] + tmpFx[11]*tmpObjS[18] + tmpFx[16]*tmpObjS[26] + tmpFx[21]*tmpObjS[34] + tmpFx[26]*tmpObjS[42] + tmpFx[31]*tmpObjS[50] + tmpFx[36]*tmpObjS[58];
+tmpQ2[11] = + tmpFx[1]*tmpObjS[3] + tmpFx[6]*tmpObjS[11] + tmpFx[11]*tmpObjS[19] + tmpFx[16]*tmpObjS[27] + tmpFx[21]*tmpObjS[35] + tmpFx[26]*tmpObjS[43] + tmpFx[31]*tmpObjS[51] + tmpFx[36]*tmpObjS[59];
+tmpQ2[12] = + tmpFx[1]*tmpObjS[4] + tmpFx[6]*tmpObjS[12] + tmpFx[11]*tmpObjS[20] + tmpFx[16]*tmpObjS[28] + tmpFx[21]*tmpObjS[36] + tmpFx[26]*tmpObjS[44] + tmpFx[31]*tmpObjS[52] + tmpFx[36]*tmpObjS[60];
+tmpQ2[13] = + tmpFx[1]*tmpObjS[5] + tmpFx[6]*tmpObjS[13] + tmpFx[11]*tmpObjS[21] + tmpFx[16]*tmpObjS[29] + tmpFx[21]*tmpObjS[37] + tmpFx[26]*tmpObjS[45] + tmpFx[31]*tmpObjS[53] + tmpFx[36]*tmpObjS[61];
+tmpQ2[14] = + tmpFx[1]*tmpObjS[6] + tmpFx[6]*tmpObjS[14] + tmpFx[11]*tmpObjS[22] + tmpFx[16]*tmpObjS[30] + tmpFx[21]*tmpObjS[38] + tmpFx[26]*tmpObjS[46] + tmpFx[31]*tmpObjS[54] + tmpFx[36]*tmpObjS[62];
+tmpQ2[15] = + tmpFx[1]*tmpObjS[7] + tmpFx[6]*tmpObjS[15] + tmpFx[11]*tmpObjS[23] + tmpFx[16]*tmpObjS[31] + tmpFx[21]*tmpObjS[39] + tmpFx[26]*tmpObjS[47] + tmpFx[31]*tmpObjS[55] + tmpFx[36]*tmpObjS[63];
+tmpQ2[16] = + tmpFx[2]*tmpObjS[0] + tmpFx[7]*tmpObjS[8] + tmpFx[12]*tmpObjS[16] + tmpFx[17]*tmpObjS[24] + tmpFx[22]*tmpObjS[32] + tmpFx[27]*tmpObjS[40] + tmpFx[32]*tmpObjS[48] + tmpFx[37]*tmpObjS[56];
+tmpQ2[17] = + tmpFx[2]*tmpObjS[1] + tmpFx[7]*tmpObjS[9] + tmpFx[12]*tmpObjS[17] + tmpFx[17]*tmpObjS[25] + tmpFx[22]*tmpObjS[33] + tmpFx[27]*tmpObjS[41] + tmpFx[32]*tmpObjS[49] + tmpFx[37]*tmpObjS[57];
+tmpQ2[18] = + tmpFx[2]*tmpObjS[2] + tmpFx[7]*tmpObjS[10] + tmpFx[12]*tmpObjS[18] + tmpFx[17]*tmpObjS[26] + tmpFx[22]*tmpObjS[34] + tmpFx[27]*tmpObjS[42] + tmpFx[32]*tmpObjS[50] + tmpFx[37]*tmpObjS[58];
+tmpQ2[19] = + tmpFx[2]*tmpObjS[3] + tmpFx[7]*tmpObjS[11] + tmpFx[12]*tmpObjS[19] + tmpFx[17]*tmpObjS[27] + tmpFx[22]*tmpObjS[35] + tmpFx[27]*tmpObjS[43] + tmpFx[32]*tmpObjS[51] + tmpFx[37]*tmpObjS[59];
+tmpQ2[20] = + tmpFx[2]*tmpObjS[4] + tmpFx[7]*tmpObjS[12] + tmpFx[12]*tmpObjS[20] + tmpFx[17]*tmpObjS[28] + tmpFx[22]*tmpObjS[36] + tmpFx[27]*tmpObjS[44] + tmpFx[32]*tmpObjS[52] + tmpFx[37]*tmpObjS[60];
+tmpQ2[21] = + tmpFx[2]*tmpObjS[5] + tmpFx[7]*tmpObjS[13] + tmpFx[12]*tmpObjS[21] + tmpFx[17]*tmpObjS[29] + tmpFx[22]*tmpObjS[37] + tmpFx[27]*tmpObjS[45] + tmpFx[32]*tmpObjS[53] + tmpFx[37]*tmpObjS[61];
+tmpQ2[22] = + tmpFx[2]*tmpObjS[6] + tmpFx[7]*tmpObjS[14] + tmpFx[12]*tmpObjS[22] + tmpFx[17]*tmpObjS[30] + tmpFx[22]*tmpObjS[38] + tmpFx[27]*tmpObjS[46] + tmpFx[32]*tmpObjS[54] + tmpFx[37]*tmpObjS[62];
+tmpQ2[23] = + tmpFx[2]*tmpObjS[7] + tmpFx[7]*tmpObjS[15] + tmpFx[12]*tmpObjS[23] + tmpFx[17]*tmpObjS[31] + tmpFx[22]*tmpObjS[39] + tmpFx[27]*tmpObjS[47] + tmpFx[32]*tmpObjS[55] + tmpFx[37]*tmpObjS[63];
+tmpQ2[24] = + tmpFx[3]*tmpObjS[0] + tmpFx[8]*tmpObjS[8] + tmpFx[13]*tmpObjS[16] + tmpFx[18]*tmpObjS[24] + tmpFx[23]*tmpObjS[32] + tmpFx[28]*tmpObjS[40] + tmpFx[33]*tmpObjS[48] + tmpFx[38]*tmpObjS[56];
+tmpQ2[25] = + tmpFx[3]*tmpObjS[1] + tmpFx[8]*tmpObjS[9] + tmpFx[13]*tmpObjS[17] + tmpFx[18]*tmpObjS[25] + tmpFx[23]*tmpObjS[33] + tmpFx[28]*tmpObjS[41] + tmpFx[33]*tmpObjS[49] + tmpFx[38]*tmpObjS[57];
+tmpQ2[26] = + tmpFx[3]*tmpObjS[2] + tmpFx[8]*tmpObjS[10] + tmpFx[13]*tmpObjS[18] + tmpFx[18]*tmpObjS[26] + tmpFx[23]*tmpObjS[34] + tmpFx[28]*tmpObjS[42] + tmpFx[33]*tmpObjS[50] + tmpFx[38]*tmpObjS[58];
+tmpQ2[27] = + tmpFx[3]*tmpObjS[3] + tmpFx[8]*tmpObjS[11] + tmpFx[13]*tmpObjS[19] + tmpFx[18]*tmpObjS[27] + tmpFx[23]*tmpObjS[35] + tmpFx[28]*tmpObjS[43] + tmpFx[33]*tmpObjS[51] + tmpFx[38]*tmpObjS[59];
+tmpQ2[28] = + tmpFx[3]*tmpObjS[4] + tmpFx[8]*tmpObjS[12] + tmpFx[13]*tmpObjS[20] + tmpFx[18]*tmpObjS[28] + tmpFx[23]*tmpObjS[36] + tmpFx[28]*tmpObjS[44] + tmpFx[33]*tmpObjS[52] + tmpFx[38]*tmpObjS[60];
+tmpQ2[29] = + tmpFx[3]*tmpObjS[5] + tmpFx[8]*tmpObjS[13] + tmpFx[13]*tmpObjS[21] + tmpFx[18]*tmpObjS[29] + tmpFx[23]*tmpObjS[37] + tmpFx[28]*tmpObjS[45] + tmpFx[33]*tmpObjS[53] + tmpFx[38]*tmpObjS[61];
+tmpQ2[30] = + tmpFx[3]*tmpObjS[6] + tmpFx[8]*tmpObjS[14] + tmpFx[13]*tmpObjS[22] + tmpFx[18]*tmpObjS[30] + tmpFx[23]*tmpObjS[38] + tmpFx[28]*tmpObjS[46] + tmpFx[33]*tmpObjS[54] + tmpFx[38]*tmpObjS[62];
+tmpQ2[31] = + tmpFx[3]*tmpObjS[7] + tmpFx[8]*tmpObjS[15] + tmpFx[13]*tmpObjS[23] + tmpFx[18]*tmpObjS[31] + tmpFx[23]*tmpObjS[39] + tmpFx[28]*tmpObjS[47] + tmpFx[33]*tmpObjS[55] + tmpFx[38]*tmpObjS[63];
+tmpQ2[32] = + tmpFx[4]*tmpObjS[0] + tmpFx[9]*tmpObjS[8] + tmpFx[14]*tmpObjS[16] + tmpFx[19]*tmpObjS[24] + tmpFx[24]*tmpObjS[32] + tmpFx[29]*tmpObjS[40] + tmpFx[34]*tmpObjS[48] + tmpFx[39]*tmpObjS[56];
+tmpQ2[33] = + tmpFx[4]*tmpObjS[1] + tmpFx[9]*tmpObjS[9] + tmpFx[14]*tmpObjS[17] + tmpFx[19]*tmpObjS[25] + tmpFx[24]*tmpObjS[33] + tmpFx[29]*tmpObjS[41] + tmpFx[34]*tmpObjS[49] + tmpFx[39]*tmpObjS[57];
+tmpQ2[34] = + tmpFx[4]*tmpObjS[2] + tmpFx[9]*tmpObjS[10] + tmpFx[14]*tmpObjS[18] + tmpFx[19]*tmpObjS[26] + tmpFx[24]*tmpObjS[34] + tmpFx[29]*tmpObjS[42] + tmpFx[34]*tmpObjS[50] + tmpFx[39]*tmpObjS[58];
+tmpQ2[35] = + tmpFx[4]*tmpObjS[3] + tmpFx[9]*tmpObjS[11] + tmpFx[14]*tmpObjS[19] + tmpFx[19]*tmpObjS[27] + tmpFx[24]*tmpObjS[35] + tmpFx[29]*tmpObjS[43] + tmpFx[34]*tmpObjS[51] + tmpFx[39]*tmpObjS[59];
+tmpQ2[36] = + tmpFx[4]*tmpObjS[4] + tmpFx[9]*tmpObjS[12] + tmpFx[14]*tmpObjS[20] + tmpFx[19]*tmpObjS[28] + tmpFx[24]*tmpObjS[36] + tmpFx[29]*tmpObjS[44] + tmpFx[34]*tmpObjS[52] + tmpFx[39]*tmpObjS[60];
+tmpQ2[37] = + tmpFx[4]*tmpObjS[5] + tmpFx[9]*tmpObjS[13] + tmpFx[14]*tmpObjS[21] + tmpFx[19]*tmpObjS[29] + tmpFx[24]*tmpObjS[37] + tmpFx[29]*tmpObjS[45] + tmpFx[34]*tmpObjS[53] + tmpFx[39]*tmpObjS[61];
+tmpQ2[38] = + tmpFx[4]*tmpObjS[6] + tmpFx[9]*tmpObjS[14] + tmpFx[14]*tmpObjS[22] + tmpFx[19]*tmpObjS[30] + tmpFx[24]*tmpObjS[38] + tmpFx[29]*tmpObjS[46] + tmpFx[34]*tmpObjS[54] + tmpFx[39]*tmpObjS[62];
+tmpQ2[39] = + tmpFx[4]*tmpObjS[7] + tmpFx[9]*tmpObjS[15] + tmpFx[14]*tmpObjS[23] + tmpFx[19]*tmpObjS[31] + tmpFx[24]*tmpObjS[39] + tmpFx[29]*tmpObjS[47] + tmpFx[34]*tmpObjS[55] + tmpFx[39]*tmpObjS[63];
+tmpQ1[0] = + tmpQ2[0]*tmpFx[0] + tmpQ2[1]*tmpFx[5] + tmpQ2[2]*tmpFx[10] + tmpQ2[3]*tmpFx[15] + tmpQ2[4]*tmpFx[20] + tmpQ2[5]*tmpFx[25] + tmpQ2[6]*tmpFx[30] + tmpQ2[7]*tmpFx[35];
+tmpQ1[1] = + tmpQ2[0]*tmpFx[1] + tmpQ2[1]*tmpFx[6] + tmpQ2[2]*tmpFx[11] + tmpQ2[3]*tmpFx[16] + tmpQ2[4]*tmpFx[21] + tmpQ2[5]*tmpFx[26] + tmpQ2[6]*tmpFx[31] + tmpQ2[7]*tmpFx[36];
+tmpQ1[2] = + tmpQ2[0]*tmpFx[2] + tmpQ2[1]*tmpFx[7] + tmpQ2[2]*tmpFx[12] + tmpQ2[3]*tmpFx[17] + tmpQ2[4]*tmpFx[22] + tmpQ2[5]*tmpFx[27] + tmpQ2[6]*tmpFx[32] + tmpQ2[7]*tmpFx[37];
+tmpQ1[3] = + tmpQ2[0]*tmpFx[3] + tmpQ2[1]*tmpFx[8] + tmpQ2[2]*tmpFx[13] + tmpQ2[3]*tmpFx[18] + tmpQ2[4]*tmpFx[23] + tmpQ2[5]*tmpFx[28] + tmpQ2[6]*tmpFx[33] + tmpQ2[7]*tmpFx[38];
+tmpQ1[4] = + tmpQ2[0]*tmpFx[4] + tmpQ2[1]*tmpFx[9] + tmpQ2[2]*tmpFx[14] + tmpQ2[3]*tmpFx[19] + tmpQ2[4]*tmpFx[24] + tmpQ2[5]*tmpFx[29] + tmpQ2[6]*tmpFx[34] + tmpQ2[7]*tmpFx[39];
+tmpQ1[5] = + tmpQ2[8]*tmpFx[0] + tmpQ2[9]*tmpFx[5] + tmpQ2[10]*tmpFx[10] + tmpQ2[11]*tmpFx[15] + tmpQ2[12]*tmpFx[20] + tmpQ2[13]*tmpFx[25] + tmpQ2[14]*tmpFx[30] + tmpQ2[15]*tmpFx[35];
+tmpQ1[6] = + tmpQ2[8]*tmpFx[1] + tmpQ2[9]*tmpFx[6] + tmpQ2[10]*tmpFx[11] + tmpQ2[11]*tmpFx[16] + tmpQ2[12]*tmpFx[21] + tmpQ2[13]*tmpFx[26] + tmpQ2[14]*tmpFx[31] + tmpQ2[15]*tmpFx[36];
+tmpQ1[7] = + tmpQ2[8]*tmpFx[2] + tmpQ2[9]*tmpFx[7] + tmpQ2[10]*tmpFx[12] + tmpQ2[11]*tmpFx[17] + tmpQ2[12]*tmpFx[22] + tmpQ2[13]*tmpFx[27] + tmpQ2[14]*tmpFx[32] + tmpQ2[15]*tmpFx[37];
+tmpQ1[8] = + tmpQ2[8]*tmpFx[3] + tmpQ2[9]*tmpFx[8] + tmpQ2[10]*tmpFx[13] + tmpQ2[11]*tmpFx[18] + tmpQ2[12]*tmpFx[23] + tmpQ2[13]*tmpFx[28] + tmpQ2[14]*tmpFx[33] + tmpQ2[15]*tmpFx[38];
+tmpQ1[9] = + tmpQ2[8]*tmpFx[4] + tmpQ2[9]*tmpFx[9] + tmpQ2[10]*tmpFx[14] + tmpQ2[11]*tmpFx[19] + tmpQ2[12]*tmpFx[24] + tmpQ2[13]*tmpFx[29] + tmpQ2[14]*tmpFx[34] + tmpQ2[15]*tmpFx[39];
+tmpQ1[10] = + tmpQ2[16]*tmpFx[0] + tmpQ2[17]*tmpFx[5] + tmpQ2[18]*tmpFx[10] + tmpQ2[19]*tmpFx[15] + tmpQ2[20]*tmpFx[20] + tmpQ2[21]*tmpFx[25] + tmpQ2[22]*tmpFx[30] + tmpQ2[23]*tmpFx[35];
+tmpQ1[11] = + tmpQ2[16]*tmpFx[1] + tmpQ2[17]*tmpFx[6] + tmpQ2[18]*tmpFx[11] + tmpQ2[19]*tmpFx[16] + tmpQ2[20]*tmpFx[21] + tmpQ2[21]*tmpFx[26] + tmpQ2[22]*tmpFx[31] + tmpQ2[23]*tmpFx[36];
+tmpQ1[12] = + tmpQ2[16]*tmpFx[2] + tmpQ2[17]*tmpFx[7] + tmpQ2[18]*tmpFx[12] + tmpQ2[19]*tmpFx[17] + tmpQ2[20]*tmpFx[22] + tmpQ2[21]*tmpFx[27] + tmpQ2[22]*tmpFx[32] + tmpQ2[23]*tmpFx[37];
+tmpQ1[13] = + tmpQ2[16]*tmpFx[3] + tmpQ2[17]*tmpFx[8] + tmpQ2[18]*tmpFx[13] + tmpQ2[19]*tmpFx[18] + tmpQ2[20]*tmpFx[23] + tmpQ2[21]*tmpFx[28] + tmpQ2[22]*tmpFx[33] + tmpQ2[23]*tmpFx[38];
+tmpQ1[14] = + tmpQ2[16]*tmpFx[4] + tmpQ2[17]*tmpFx[9] + tmpQ2[18]*tmpFx[14] + tmpQ2[19]*tmpFx[19] + tmpQ2[20]*tmpFx[24] + tmpQ2[21]*tmpFx[29] + tmpQ2[22]*tmpFx[34] + tmpQ2[23]*tmpFx[39];
+tmpQ1[15] = + tmpQ2[24]*tmpFx[0] + tmpQ2[25]*tmpFx[5] + tmpQ2[26]*tmpFx[10] + tmpQ2[27]*tmpFx[15] + tmpQ2[28]*tmpFx[20] + tmpQ2[29]*tmpFx[25] + tmpQ2[30]*tmpFx[30] + tmpQ2[31]*tmpFx[35];
+tmpQ1[16] = + tmpQ2[24]*tmpFx[1] + tmpQ2[25]*tmpFx[6] + tmpQ2[26]*tmpFx[11] + tmpQ2[27]*tmpFx[16] + tmpQ2[28]*tmpFx[21] + tmpQ2[29]*tmpFx[26] + tmpQ2[30]*tmpFx[31] + tmpQ2[31]*tmpFx[36];
+tmpQ1[17] = + tmpQ2[24]*tmpFx[2] + tmpQ2[25]*tmpFx[7] + tmpQ2[26]*tmpFx[12] + tmpQ2[27]*tmpFx[17] + tmpQ2[28]*tmpFx[22] + tmpQ2[29]*tmpFx[27] + tmpQ2[30]*tmpFx[32] + tmpQ2[31]*tmpFx[37];
+tmpQ1[18] = + tmpQ2[24]*tmpFx[3] + tmpQ2[25]*tmpFx[8] + tmpQ2[26]*tmpFx[13] + tmpQ2[27]*tmpFx[18] + tmpQ2[28]*tmpFx[23] + tmpQ2[29]*tmpFx[28] + tmpQ2[30]*tmpFx[33] + tmpQ2[31]*tmpFx[38];
+tmpQ1[19] = + tmpQ2[24]*tmpFx[4] + tmpQ2[25]*tmpFx[9] + tmpQ2[26]*tmpFx[14] + tmpQ2[27]*tmpFx[19] + tmpQ2[28]*tmpFx[24] + tmpQ2[29]*tmpFx[29] + tmpQ2[30]*tmpFx[34] + tmpQ2[31]*tmpFx[39];
+tmpQ1[20] = + tmpQ2[32]*tmpFx[0] + tmpQ2[33]*tmpFx[5] + tmpQ2[34]*tmpFx[10] + tmpQ2[35]*tmpFx[15] + tmpQ2[36]*tmpFx[20] + tmpQ2[37]*tmpFx[25] + tmpQ2[38]*tmpFx[30] + tmpQ2[39]*tmpFx[35];
+tmpQ1[21] = + tmpQ2[32]*tmpFx[1] + tmpQ2[33]*tmpFx[6] + tmpQ2[34]*tmpFx[11] + tmpQ2[35]*tmpFx[16] + tmpQ2[36]*tmpFx[21] + tmpQ2[37]*tmpFx[26] + tmpQ2[38]*tmpFx[31] + tmpQ2[39]*tmpFx[36];
+tmpQ1[22] = + tmpQ2[32]*tmpFx[2] + tmpQ2[33]*tmpFx[7] + tmpQ2[34]*tmpFx[12] + tmpQ2[35]*tmpFx[17] + tmpQ2[36]*tmpFx[22] + tmpQ2[37]*tmpFx[27] + tmpQ2[38]*tmpFx[32] + tmpQ2[39]*tmpFx[37];
+tmpQ1[23] = + tmpQ2[32]*tmpFx[3] + tmpQ2[33]*tmpFx[8] + tmpQ2[34]*tmpFx[13] + tmpQ2[35]*tmpFx[18] + tmpQ2[36]*tmpFx[23] + tmpQ2[37]*tmpFx[28] + tmpQ2[38]*tmpFx[33] + tmpQ2[39]*tmpFx[38];
+tmpQ1[24] = + tmpQ2[32]*tmpFx[4] + tmpQ2[33]*tmpFx[9] + tmpQ2[34]*tmpFx[14] + tmpQ2[35]*tmpFx[19] + tmpQ2[36]*tmpFx[24] + tmpQ2[37]*tmpFx[29] + tmpQ2[38]*tmpFx[34] + tmpQ2[39]*tmpFx[39];
+}
+
+void acado_setObjR1R2( real_t* const tmpFu, real_t* const tmpObjS, real_t* const tmpR1, real_t* const tmpR2 )
+{
+tmpR2[0] = + tmpFu[0]*tmpObjS[0] + tmpFu[2]*tmpObjS[8] + tmpFu[4]*tmpObjS[16] + tmpFu[6]*tmpObjS[24] + tmpFu[8]*tmpObjS[32] + tmpFu[10]*tmpObjS[40] + tmpFu[12]*tmpObjS[48] + tmpFu[14]*tmpObjS[56];
+tmpR2[1] = + tmpFu[0]*tmpObjS[1] + tmpFu[2]*tmpObjS[9] + tmpFu[4]*tmpObjS[17] + tmpFu[6]*tmpObjS[25] + tmpFu[8]*tmpObjS[33] + tmpFu[10]*tmpObjS[41] + tmpFu[12]*tmpObjS[49] + tmpFu[14]*tmpObjS[57];
+tmpR2[2] = + tmpFu[0]*tmpObjS[2] + tmpFu[2]*tmpObjS[10] + tmpFu[4]*tmpObjS[18] + tmpFu[6]*tmpObjS[26] + tmpFu[8]*tmpObjS[34] + tmpFu[10]*tmpObjS[42] + tmpFu[12]*tmpObjS[50] + tmpFu[14]*tmpObjS[58];
+tmpR2[3] = + tmpFu[0]*tmpObjS[3] + tmpFu[2]*tmpObjS[11] + tmpFu[4]*tmpObjS[19] + tmpFu[6]*tmpObjS[27] + tmpFu[8]*tmpObjS[35] + tmpFu[10]*tmpObjS[43] + tmpFu[12]*tmpObjS[51] + tmpFu[14]*tmpObjS[59];
+tmpR2[4] = + tmpFu[0]*tmpObjS[4] + tmpFu[2]*tmpObjS[12] + tmpFu[4]*tmpObjS[20] + tmpFu[6]*tmpObjS[28] + tmpFu[8]*tmpObjS[36] + tmpFu[10]*tmpObjS[44] + tmpFu[12]*tmpObjS[52] + tmpFu[14]*tmpObjS[60];
+tmpR2[5] = + tmpFu[0]*tmpObjS[5] + tmpFu[2]*tmpObjS[13] + tmpFu[4]*tmpObjS[21] + tmpFu[6]*tmpObjS[29] + tmpFu[8]*tmpObjS[37] + tmpFu[10]*tmpObjS[45] + tmpFu[12]*tmpObjS[53] + tmpFu[14]*tmpObjS[61];
+tmpR2[6] = + tmpFu[0]*tmpObjS[6] + tmpFu[2]*tmpObjS[14] + tmpFu[4]*tmpObjS[22] + tmpFu[6]*tmpObjS[30] + tmpFu[8]*tmpObjS[38] + tmpFu[10]*tmpObjS[46] + tmpFu[12]*tmpObjS[54] + tmpFu[14]*tmpObjS[62];
+tmpR2[7] = + tmpFu[0]*tmpObjS[7] + tmpFu[2]*tmpObjS[15] + tmpFu[4]*tmpObjS[23] + tmpFu[6]*tmpObjS[31] + tmpFu[8]*tmpObjS[39] + tmpFu[10]*tmpObjS[47] + tmpFu[12]*tmpObjS[55] + tmpFu[14]*tmpObjS[63];
+tmpR2[8] = + tmpFu[1]*tmpObjS[0] + tmpFu[3]*tmpObjS[8] + tmpFu[5]*tmpObjS[16] + tmpFu[7]*tmpObjS[24] + tmpFu[9]*tmpObjS[32] + tmpFu[11]*tmpObjS[40] + tmpFu[13]*tmpObjS[48] + tmpFu[15]*tmpObjS[56];
+tmpR2[9] = + tmpFu[1]*tmpObjS[1] + tmpFu[3]*tmpObjS[9] + tmpFu[5]*tmpObjS[17] + tmpFu[7]*tmpObjS[25] + tmpFu[9]*tmpObjS[33] + tmpFu[11]*tmpObjS[41] + tmpFu[13]*tmpObjS[49] + tmpFu[15]*tmpObjS[57];
+tmpR2[10] = + tmpFu[1]*tmpObjS[2] + tmpFu[3]*tmpObjS[10] + tmpFu[5]*tmpObjS[18] + tmpFu[7]*tmpObjS[26] + tmpFu[9]*tmpObjS[34] + tmpFu[11]*tmpObjS[42] + tmpFu[13]*tmpObjS[50] + tmpFu[15]*tmpObjS[58];
+tmpR2[11] = + tmpFu[1]*tmpObjS[3] + tmpFu[3]*tmpObjS[11] + tmpFu[5]*tmpObjS[19] + tmpFu[7]*tmpObjS[27] + tmpFu[9]*tmpObjS[35] + tmpFu[11]*tmpObjS[43] + tmpFu[13]*tmpObjS[51] + tmpFu[15]*tmpObjS[59];
+tmpR2[12] = + tmpFu[1]*tmpObjS[4] + tmpFu[3]*tmpObjS[12] + tmpFu[5]*tmpObjS[20] + tmpFu[7]*tmpObjS[28] + tmpFu[9]*tmpObjS[36] + tmpFu[11]*tmpObjS[44] + tmpFu[13]*tmpObjS[52] + tmpFu[15]*tmpObjS[60];
+tmpR2[13] = + tmpFu[1]*tmpObjS[5] + tmpFu[3]*tmpObjS[13] + tmpFu[5]*tmpObjS[21] + tmpFu[7]*tmpObjS[29] + tmpFu[9]*tmpObjS[37] + tmpFu[11]*tmpObjS[45] + tmpFu[13]*tmpObjS[53] + tmpFu[15]*tmpObjS[61];
+tmpR2[14] = + tmpFu[1]*tmpObjS[6] + tmpFu[3]*tmpObjS[14] + tmpFu[5]*tmpObjS[22] + tmpFu[7]*tmpObjS[30] + tmpFu[9]*tmpObjS[38] + tmpFu[11]*tmpObjS[46] + tmpFu[13]*tmpObjS[54] + tmpFu[15]*tmpObjS[62];
+tmpR2[15] = + tmpFu[1]*tmpObjS[7] + tmpFu[3]*tmpObjS[15] + tmpFu[5]*tmpObjS[23] + tmpFu[7]*tmpObjS[31] + tmpFu[9]*tmpObjS[39] + tmpFu[11]*tmpObjS[47] + tmpFu[13]*tmpObjS[55] + tmpFu[15]*tmpObjS[63];
+tmpR1[0] = + tmpR2[0]*tmpFu[0] + tmpR2[1]*tmpFu[2] + tmpR2[2]*tmpFu[4] + tmpR2[3]*tmpFu[6] + tmpR2[4]*tmpFu[8] + tmpR2[5]*tmpFu[10] + tmpR2[6]*tmpFu[12] + tmpR2[7]*tmpFu[14];
+tmpR1[1] = + tmpR2[0]*tmpFu[1] + tmpR2[1]*tmpFu[3] + tmpR2[2]*tmpFu[5] + tmpR2[3]*tmpFu[7] + tmpR2[4]*tmpFu[9] + tmpR2[5]*tmpFu[11] + tmpR2[6]*tmpFu[13] + tmpR2[7]*tmpFu[15];
+tmpR1[2] = + tmpR2[8]*tmpFu[0] + tmpR2[9]*tmpFu[2] + tmpR2[10]*tmpFu[4] + tmpR2[11]*tmpFu[6] + tmpR2[12]*tmpFu[8] + tmpR2[13]*tmpFu[10] + tmpR2[14]*tmpFu[12] + tmpR2[15]*tmpFu[14];
+tmpR1[3] = + tmpR2[8]*tmpFu[1] + tmpR2[9]*tmpFu[3] + tmpR2[10]*tmpFu[5] + tmpR2[11]*tmpFu[7] + tmpR2[12]*tmpFu[9] + tmpR2[13]*tmpFu[11] + tmpR2[14]*tmpFu[13] + tmpR2[15]*tmpFu[15];
+}
+
+void acado_setObjQN1QN2( real_t* const tmpObjSEndTerm, real_t* const tmpQN1, real_t* const tmpQN2 )
+{
+tmpQN2[0] = +tmpObjSEndTerm[0];
+tmpQN2[1] = +tmpObjSEndTerm[1];
+tmpQN2[2] = +tmpObjSEndTerm[2];
+tmpQN2[3] = +tmpObjSEndTerm[3];
+tmpQN2[4] = +tmpObjSEndTerm[4];
+tmpQN2[5] = +tmpObjSEndTerm[5];
+tmpQN2[6] = +tmpObjSEndTerm[6];
+tmpQN2[7] = +tmpObjSEndTerm[7];
+tmpQN2[8] = +tmpObjSEndTerm[8];
+tmpQN2[9] = +tmpObjSEndTerm[9];
+tmpQN2[10] = +tmpObjSEndTerm[10];
+tmpQN2[11] = +tmpObjSEndTerm[11];
+tmpQN2[12] = +tmpObjSEndTerm[12];
+tmpQN2[13] = +tmpObjSEndTerm[13];
+tmpQN2[14] = +tmpObjSEndTerm[14];
+tmpQN2[15] = +tmpObjSEndTerm[15];
+tmpQN2[16] = +tmpObjSEndTerm[16];
+tmpQN2[17] = +tmpObjSEndTerm[17];
+tmpQN2[18] = +tmpObjSEndTerm[18];
+tmpQN2[19] = +tmpObjSEndTerm[19];
+tmpQN2[20] = +tmpObjSEndTerm[20];
+tmpQN2[21] = +tmpObjSEndTerm[21];
+tmpQN2[22] = +tmpObjSEndTerm[22];
+tmpQN2[23] = +tmpObjSEndTerm[23];
+tmpQN2[24] = +tmpObjSEndTerm[24];
+tmpQN1[0] = + tmpQN2[0];
+tmpQN1[1] = + tmpQN2[1];
+tmpQN1[2] = + tmpQN2[2];
+tmpQN1[3] = + tmpQN2[3];
+tmpQN1[4] = + tmpQN2[4];
+tmpQN1[5] = + tmpQN2[5];
+tmpQN1[6] = + tmpQN2[6];
+tmpQN1[7] = + tmpQN2[7];
+tmpQN1[8] = + tmpQN2[8];
+tmpQN1[9] = + tmpQN2[9];
+tmpQN1[10] = + tmpQN2[10];
+tmpQN1[11] = + tmpQN2[11];
+tmpQN1[12] = + tmpQN2[12];
+tmpQN1[13] = + tmpQN2[13];
+tmpQN1[14] = + tmpQN2[14];
+tmpQN1[15] = + tmpQN2[15];
+tmpQN1[16] = + tmpQN2[16];
+tmpQN1[17] = + tmpQN2[17];
+tmpQN1[18] = + tmpQN2[18];
+tmpQN1[19] = + tmpQN2[19];
+tmpQN1[20] = + tmpQN2[20];
+tmpQN1[21] = + tmpQN2[21];
+tmpQN1[22] = + tmpQN2[22];
+tmpQN1[23] = + tmpQN2[23];
+tmpQN1[24] = + tmpQN2[24];
+}
+
+void acado_evaluateObjective(  )
+{
+int runObj;
+for (runObj = 0; runObj < 20; ++runObj)
+{
+acadoWorkspace.objValueIn[0] = acadoVariables.x[runObj * 5];
+acadoWorkspace.objValueIn[1] = acadoVariables.x[runObj * 5 + 1];
+acadoWorkspace.objValueIn[2] = acadoVariables.x[runObj * 5 + 2];
+acadoWorkspace.objValueIn[3] = acadoVariables.x[runObj * 5 + 3];
+acadoWorkspace.objValueIn[4] = acadoVariables.x[runObj * 5 + 4];
+acadoWorkspace.objValueIn[5] = acadoVariables.u[runObj * 2];
+acadoWorkspace.objValueIn[6] = acadoVariables.u[runObj * 2 + 1];
+acadoWorkspace.objValueIn[7] = acadoVariables.od[runObj * 20];
+acadoWorkspace.objValueIn[8] = acadoVariables.od[runObj * 20 + 1];
+acadoWorkspace.objValueIn[9] = acadoVariables.od[runObj * 20 + 2];
+acadoWorkspace.objValueIn[10] = acadoVariables.od[runObj * 20 + 3];
+acadoWorkspace.objValueIn[11] = acadoVariables.od[runObj * 20 + 4];
+acadoWorkspace.objValueIn[12] = acadoVariables.od[runObj * 20 + 5];
+acadoWorkspace.objValueIn[13] = acadoVariables.od[runObj * 20 + 6];
+acadoWorkspace.objValueIn[14] = acadoVariables.od[runObj * 20 + 7];
+acadoWorkspace.objValueIn[15] = acadoVariables.od[runObj * 20 + 8];
+acadoWorkspace.objValueIn[16] = acadoVariables.od[runObj * 20 + 9];
+acadoWorkspace.objValueIn[17] = acadoVariables.od[runObj * 20 + 10];
+acadoWorkspace.objValueIn[18] = acadoVariables.od[runObj * 20 + 11];
+acadoWorkspace.objValueIn[19] = acadoVariables.od[runObj * 20 + 12];
+acadoWorkspace.objValueIn[20] = acadoVariables.od[runObj * 20 + 13];
+acadoWorkspace.objValueIn[21] = acadoVariables.od[runObj * 20 + 14];
+acadoWorkspace.objValueIn[22] = acadoVariables.od[runObj * 20 + 15];
+acadoWorkspace.objValueIn[23] = acadoVariables.od[runObj * 20 + 16];
+acadoWorkspace.objValueIn[24] = acadoVariables.od[runObj * 20 + 17];
+acadoWorkspace.objValueIn[25] = acadoVariables.od[runObj * 20 + 18];
+acadoWorkspace.objValueIn[26] = acadoVariables.od[runObj * 20 + 19];
+
+acado_evaluateLSQ( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut );
+acadoWorkspace.Dy[runObj * 8] = acadoWorkspace.objValueOut[0];
+acadoWorkspace.Dy[runObj * 8 + 1] = acadoWorkspace.objValueOut[1];
+acadoWorkspace.Dy[runObj * 8 + 2] = acadoWorkspace.objValueOut[2];
+acadoWorkspace.Dy[runObj * 8 + 3] = acadoWorkspace.objValueOut[3];
+acadoWorkspace.Dy[runObj * 8 + 4] = acadoWorkspace.objValueOut[4];
+acadoWorkspace.Dy[runObj * 8 + 5] = acadoWorkspace.objValueOut[5];
+acadoWorkspace.Dy[runObj * 8 + 6] = acadoWorkspace.objValueOut[6];
+acadoWorkspace.Dy[runObj * 8 + 7] = acadoWorkspace.objValueOut[7];
+
+acado_setObjQ1Q2( &(acadoWorkspace.objValueOut[ 8 ]), &(acadoVariables.W[ runObj * 64 ]), &(acadoWorkspace.Q1[ runObj * 25 ]), &(acadoWorkspace.Q2[ runObj * 40 ]) );
+
+acado_setObjR1R2( &(acadoWorkspace.objValueOut[ 48 ]), &(acadoVariables.W[ runObj * 64 ]), &(acadoWorkspace.R1[ runObj * 4 ]), &(acadoWorkspace.R2[ runObj * 16 ]) );
+
+}
+acadoWorkspace.objValueIn[0] = acadoVariables.x[100];
+acadoWorkspace.objValueIn[1] = acadoVariables.x[101];
+acadoWorkspace.objValueIn[2] = acadoVariables.x[102];
+acadoWorkspace.objValueIn[3] = acadoVariables.x[103];
+acadoWorkspace.objValueIn[4] = acadoVariables.x[104];
+acadoWorkspace.objValueIn[5] = acadoVariables.od[400];
+acadoWorkspace.objValueIn[6] = acadoVariables.od[401];
+acadoWorkspace.objValueIn[7] = acadoVariables.od[402];
+acadoWorkspace.objValueIn[8] = acadoVariables.od[403];
+acadoWorkspace.objValueIn[9] = acadoVariables.od[404];
+acadoWorkspace.objValueIn[10] = acadoVariables.od[405];
+acadoWorkspace.objValueIn[11] = acadoVariables.od[406];
+acadoWorkspace.objValueIn[12] = acadoVariables.od[407];
+acadoWorkspace.objValueIn[13] = acadoVariables.od[408];
+acadoWorkspace.objValueIn[14] = acadoVariables.od[409];
+acadoWorkspace.objValueIn[15] = acadoVariables.od[410];
+acadoWorkspace.objValueIn[16] = acadoVariables.od[411];
+acadoWorkspace.objValueIn[17] = acadoVariables.od[412];
+acadoWorkspace.objValueIn[18] = acadoVariables.od[413];
+acadoWorkspace.objValueIn[19] = acadoVariables.od[414];
+acadoWorkspace.objValueIn[20] = acadoVariables.od[415];
+acadoWorkspace.objValueIn[21] = acadoVariables.od[416];
+acadoWorkspace.objValueIn[22] = acadoVariables.od[417];
+acadoWorkspace.objValueIn[23] = acadoVariables.od[418];
+acadoWorkspace.objValueIn[24] = acadoVariables.od[419];
+acado_evaluateLSQEndTerm( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut );
+
+acadoWorkspace.DyN[0] = acadoWorkspace.objValueOut[0];
+acadoWorkspace.DyN[1] = acadoWorkspace.objValueOut[1];
+acadoWorkspace.DyN[2] = acadoWorkspace.objValueOut[2];
+acadoWorkspace.DyN[3] = acadoWorkspace.objValueOut[3];
+acadoWorkspace.DyN[4] = acadoWorkspace.objValueOut[4];
+
+acado_setObjQN1QN2( acadoVariables.WN, acadoWorkspace.QN1, acadoWorkspace.QN2 );
+
+}
+
+void acado_moveGxT( real_t* const Gx1, real_t* const Gx2 )
+{
+Gx2[0] = Gx1[0];
+Gx2[1] = Gx1[1];
+Gx2[2] = Gx1[2];
+Gx2[3] = Gx1[3];
+Gx2[4] = Gx1[4];
+Gx2[5] = Gx1[5];
+Gx2[6] = Gx1[6];
+Gx2[7] = Gx1[7];
+Gx2[8] = Gx1[8];
+Gx2[9] = Gx1[9];
+Gx2[10] = Gx1[10];
+Gx2[11] = Gx1[11];
+Gx2[12] = Gx1[12];
+Gx2[13] = Gx1[13];
+Gx2[14] = Gx1[14];
+Gx2[15] = Gx1[15];
+Gx2[16] = Gx1[16];
+Gx2[17] = Gx1[17];
+Gx2[18] = Gx1[18];
+Gx2[19] = Gx1[19];
+Gx2[20] = Gx1[20];
+Gx2[21] = Gx1[21];
+Gx2[22] = Gx1[22];
+Gx2[23] = Gx1[23];
+Gx2[24] = Gx1[24];
+}
+
+void acado_multGxGx( real_t* const Gx1, real_t* const Gx2, real_t* const Gx3 )
+{
+Gx3[0] = + Gx1[0]*Gx2[0] + Gx1[1]*Gx2[5] + Gx1[2]*Gx2[10] + Gx1[3]*Gx2[15] + Gx1[4]*Gx2[20];
+Gx3[1] = + Gx1[0]*Gx2[1] + Gx1[1]*Gx2[6] + Gx1[2]*Gx2[11] + Gx1[3]*Gx2[16] + Gx1[4]*Gx2[21];
+Gx3[2] = + Gx1[0]*Gx2[2] + Gx1[1]*Gx2[7] + Gx1[2]*Gx2[12] + Gx1[3]*Gx2[17] + Gx1[4]*Gx2[22];
+Gx3[3] = + Gx1[0]*Gx2[3] + Gx1[1]*Gx2[8] + Gx1[2]*Gx2[13] + Gx1[3]*Gx2[18] + Gx1[4]*Gx2[23];
+Gx3[4] = + Gx1[0]*Gx2[4] + Gx1[1]*Gx2[9] + Gx1[2]*Gx2[14] + Gx1[3]*Gx2[19] + Gx1[4]*Gx2[24];
+Gx3[5] = + Gx1[5]*Gx2[0] + Gx1[6]*Gx2[5] + Gx1[7]*Gx2[10] + Gx1[8]*Gx2[15] + Gx1[9]*Gx2[20];
+Gx3[6] = + Gx1[5]*Gx2[1] + Gx1[6]*Gx2[6] + Gx1[7]*Gx2[11] + Gx1[8]*Gx2[16] + Gx1[9]*Gx2[21];
+Gx3[7] = + Gx1[5]*Gx2[2] + Gx1[6]*Gx2[7] + Gx1[7]*Gx2[12] + Gx1[8]*Gx2[17] + Gx1[9]*Gx2[22];
+Gx3[8] = + Gx1[5]*Gx2[3] + Gx1[6]*Gx2[8] + Gx1[7]*Gx2[13] + Gx1[8]*Gx2[18] + Gx1[9]*Gx2[23];
+Gx3[9] = + Gx1[5]*Gx2[4] + Gx1[6]*Gx2[9] + Gx1[7]*Gx2[14] + Gx1[8]*Gx2[19] + Gx1[9]*Gx2[24];
+Gx3[10] = + Gx1[10]*Gx2[0] + Gx1[11]*Gx2[5] + Gx1[12]*Gx2[10] + Gx1[13]*Gx2[15] + Gx1[14]*Gx2[20];
+Gx3[11] = + Gx1[10]*Gx2[1] + Gx1[11]*Gx2[6] + Gx1[12]*Gx2[11] + Gx1[13]*Gx2[16] + Gx1[14]*Gx2[21];
+Gx3[12] = + Gx1[10]*Gx2[2] + Gx1[11]*Gx2[7] + Gx1[12]*Gx2[12] + Gx1[13]*Gx2[17] + Gx1[14]*Gx2[22];
+Gx3[13] = + Gx1[10]*Gx2[3] + Gx1[11]*Gx2[8] + Gx1[12]*Gx2[13] + Gx1[13]*Gx2[18] + Gx1[14]*Gx2[23];
+Gx3[14] = + Gx1[10]*Gx2[4] + Gx1[11]*Gx2[9] + Gx1[12]*Gx2[14] + Gx1[13]*Gx2[19] + Gx1[14]*Gx2[24];
+Gx3[15] = + Gx1[15]*Gx2[0] + Gx1[16]*Gx2[5] + Gx1[17]*Gx2[10] + Gx1[18]*Gx2[15] + Gx1[19]*Gx2[20];
+Gx3[16] = + Gx1[15]*Gx2[1] + Gx1[16]*Gx2[6] + Gx1[17]*Gx2[11] + Gx1[18]*Gx2[16] + Gx1[19]*Gx2[21];
+Gx3[17] = + Gx1[15]*Gx2[2] + Gx1[16]*Gx2[7] + Gx1[17]*Gx2[12] + Gx1[18]*Gx2[17] + Gx1[19]*Gx2[22];
+Gx3[18] = + Gx1[15]*Gx2[3] + Gx1[16]*Gx2[8] + Gx1[17]*Gx2[13] + Gx1[18]*Gx2[18] + Gx1[19]*Gx2[23];
+Gx3[19] = + Gx1[15]*Gx2[4] + Gx1[16]*Gx2[9] + Gx1[17]*Gx2[14] + Gx1[18]*Gx2[19] + Gx1[19]*Gx2[24];
+Gx3[20] = + Gx1[20]*Gx2[0] + Gx1[21]*Gx2[5] + Gx1[22]*Gx2[10] + Gx1[23]*Gx2[15] + Gx1[24]*Gx2[20];
+Gx3[21] = + Gx1[20]*Gx2[1] + Gx1[21]*Gx2[6] + Gx1[22]*Gx2[11] + Gx1[23]*Gx2[16] + Gx1[24]*Gx2[21];
+Gx3[22] = + Gx1[20]*Gx2[2] + Gx1[21]*Gx2[7] + Gx1[22]*Gx2[12] + Gx1[23]*Gx2[17] + Gx1[24]*Gx2[22];
+Gx3[23] = + Gx1[20]*Gx2[3] + Gx1[21]*Gx2[8] + Gx1[22]*Gx2[13] + Gx1[23]*Gx2[18] + Gx1[24]*Gx2[23];
+Gx3[24] = + Gx1[20]*Gx2[4] + Gx1[21]*Gx2[9] + Gx1[22]*Gx2[14] + Gx1[23]*Gx2[19] + Gx1[24]*Gx2[24];
+}
+
+void acado_multGxGu( real_t* const Gx1, real_t* const Gu1, real_t* const Gu2 )
+{
+Gu2[0] = + Gx1[0]*Gu1[0] + Gx1[1]*Gu1[2] + Gx1[2]*Gu1[4] + Gx1[3]*Gu1[6] + Gx1[4]*Gu1[8];
+Gu2[1] = + Gx1[0]*Gu1[1] + Gx1[1]*Gu1[3] + Gx1[2]*Gu1[5] + Gx1[3]*Gu1[7] + Gx1[4]*Gu1[9];
+Gu2[2] = + Gx1[5]*Gu1[0] + Gx1[6]*Gu1[2] + Gx1[7]*Gu1[4] + Gx1[8]*Gu1[6] + Gx1[9]*Gu1[8];
+Gu2[3] = + Gx1[5]*Gu1[1] + Gx1[6]*Gu1[3] + Gx1[7]*Gu1[5] + Gx1[8]*Gu1[7] + Gx1[9]*Gu1[9];
+Gu2[4] = + Gx1[10]*Gu1[0] + Gx1[11]*Gu1[2] + Gx1[12]*Gu1[4] + Gx1[13]*Gu1[6] + Gx1[14]*Gu1[8];
+Gu2[5] = + Gx1[10]*Gu1[1] + Gx1[11]*Gu1[3] + Gx1[12]*Gu1[5] + Gx1[13]*Gu1[7] + Gx1[14]*Gu1[9];
+Gu2[6] = + Gx1[15]*Gu1[0] + Gx1[16]*Gu1[2] + Gx1[17]*Gu1[4] + Gx1[18]*Gu1[6] + Gx1[19]*Gu1[8];
+Gu2[7] = + Gx1[15]*Gu1[1] + Gx1[16]*Gu1[3] + Gx1[17]*Gu1[5] + Gx1[18]*Gu1[7] + Gx1[19]*Gu1[9];
+Gu2[8] = + Gx1[20]*Gu1[0] + Gx1[21]*Gu1[2] + Gx1[22]*Gu1[4] + Gx1[23]*Gu1[6] + Gx1[24]*Gu1[8];
+Gu2[9] = + Gx1[20]*Gu1[1] + Gx1[21]*Gu1[3] + Gx1[22]*Gu1[5] + Gx1[23]*Gu1[7] + Gx1[24]*Gu1[9];
+}
+
+void acado_moveGuE( real_t* const Gu1, real_t* const Gu2 )
+{
+Gu2[0] = Gu1[0];
+Gu2[1] = Gu1[1];
+Gu2[2] = Gu1[2];
+Gu2[3] = Gu1[3];
+Gu2[4] = Gu1[4];
+Gu2[5] = Gu1[5];
+Gu2[6] = Gu1[6];
+Gu2[7] = Gu1[7];
+Gu2[8] = Gu1[8];
+Gu2[9] = Gu1[9];
+}
+
+void acado_multBTW1( real_t* const Gu1, real_t* const Gu2, int iRow, int iCol )
+{
+acadoWorkspace.H[(iRow * 80) + (iCol * 2)] = + Gu1[0]*Gu2[0] + Gu1[2]*Gu2[2] + Gu1[4]*Gu2[4] + Gu1[6]*Gu2[6] + Gu1[8]*Gu2[8];
+acadoWorkspace.H[(iRow * 80) + (iCol * 2 + 1)] = + Gu1[0]*Gu2[1] + Gu1[2]*Gu2[3] + Gu1[4]*Gu2[5] + Gu1[6]*Gu2[7] + Gu1[8]*Gu2[9];
+acadoWorkspace.H[(iRow * 80 + 40) + (iCol * 2)] = + Gu1[1]*Gu2[0] + Gu1[3]*Gu2[2] + Gu1[5]*Gu2[4] + Gu1[7]*Gu2[6] + Gu1[9]*Gu2[8];
+acadoWorkspace.H[(iRow * 80 + 40) + (iCol * 2 + 1)] = + Gu1[1]*Gu2[1] + Gu1[3]*Gu2[3] + Gu1[5]*Gu2[5] + Gu1[7]*Gu2[7] + Gu1[9]*Gu2[9];
+}
+
+void acado_multBTW1_R1( real_t* const R11, real_t* const Gu1, real_t* const Gu2, int iRow )
+{
+acadoWorkspace.H[iRow * 82] = + Gu1[0]*Gu2[0] + Gu1[2]*Gu2[2] + Gu1[4]*Gu2[4] + Gu1[6]*Gu2[6] + Gu1[8]*Gu2[8] + R11[0];
+acadoWorkspace.H[iRow * 82 + 1] = + Gu1[0]*Gu2[1] + Gu1[2]*Gu2[3] + Gu1[4]*Gu2[5] + Gu1[6]*Gu2[7] + Gu1[8]*Gu2[9] + R11[1];
+acadoWorkspace.H[iRow * 82 + 40] = + Gu1[1]*Gu2[0] + Gu1[3]*Gu2[2] + Gu1[5]*Gu2[4] + Gu1[7]*Gu2[6] + Gu1[9]*Gu2[8] + R11[2];
+acadoWorkspace.H[iRow * 82 + 41] = + Gu1[1]*Gu2[1] + Gu1[3]*Gu2[3] + Gu1[5]*Gu2[5] + Gu1[7]*Gu2[7] + Gu1[9]*Gu2[9] + R11[3];
+acadoWorkspace.H[iRow * 82] += 1.0000000000000000e-10;
+acadoWorkspace.H[iRow * 82 + 41] += 1.0000000000000000e-10;
+}
+
+void acado_multGxTGu( real_t* const Gx1, real_t* const Gu1, real_t* const Gu2 )
+{
+Gu2[0] = + Gx1[0]*Gu1[0] + Gx1[5]*Gu1[2] + Gx1[10]*Gu1[4] + Gx1[15]*Gu1[6] + Gx1[20]*Gu1[8];
+Gu2[1] = + Gx1[0]*Gu1[1] + Gx1[5]*Gu1[3] + Gx1[10]*Gu1[5] + Gx1[15]*Gu1[7] + Gx1[20]*Gu1[9];
+Gu2[2] = + Gx1[1]*Gu1[0] + Gx1[6]*Gu1[2] + Gx1[11]*Gu1[4] + Gx1[16]*Gu1[6] + Gx1[21]*Gu1[8];
+Gu2[3] = + Gx1[1]*Gu1[1] + Gx1[6]*Gu1[3] + Gx1[11]*Gu1[5] + Gx1[16]*Gu1[7] + Gx1[21]*Gu1[9];
+Gu2[4] = + Gx1[2]*Gu1[0] + Gx1[7]*Gu1[2] + Gx1[12]*Gu1[4] + Gx1[17]*Gu1[6] + Gx1[22]*Gu1[8];
+Gu2[5] = + Gx1[2]*Gu1[1] + Gx1[7]*Gu1[3] + Gx1[12]*Gu1[5] + Gx1[17]*Gu1[7] + Gx1[22]*Gu1[9];
+Gu2[6] = + Gx1[3]*Gu1[0] + Gx1[8]*Gu1[2] + Gx1[13]*Gu1[4] + Gx1[18]*Gu1[6] + Gx1[23]*Gu1[8];
+Gu2[7] = + Gx1[3]*Gu1[1] + Gx1[8]*Gu1[3] + Gx1[13]*Gu1[5] + Gx1[18]*Gu1[7] + Gx1[23]*Gu1[9];
+Gu2[8] = + Gx1[4]*Gu1[0] + Gx1[9]*Gu1[2] + Gx1[14]*Gu1[4] + Gx1[19]*Gu1[6] + Gx1[24]*Gu1[8];
+Gu2[9] = + Gx1[4]*Gu1[1] + Gx1[9]*Gu1[3] + Gx1[14]*Gu1[5] + Gx1[19]*Gu1[7] + Gx1[24]*Gu1[9];
+}
+
+void acado_multQEW2( real_t* const Q11, real_t* const Gu1, real_t* const Gu2, real_t* const Gu3 )
+{
+Gu3[0] = + Q11[0]*Gu1[0] + Q11[1]*Gu1[2] + Q11[2]*Gu1[4] + Q11[3]*Gu1[6] + Q11[4]*Gu1[8] + Gu2[0];
+Gu3[1] = + Q11[0]*Gu1[1] + Q11[1]*Gu1[3] + Q11[2]*Gu1[5] + Q11[3]*Gu1[7] + Q11[4]*Gu1[9] + Gu2[1];
+Gu3[2] = + Q11[5]*Gu1[0] + Q11[6]*Gu1[2] + Q11[7]*Gu1[4] + Q11[8]*Gu1[6] + Q11[9]*Gu1[8] + Gu2[2];
+Gu3[3] = + Q11[5]*Gu1[1] + Q11[6]*Gu1[3] + Q11[7]*Gu1[5] + Q11[8]*Gu1[7] + Q11[9]*Gu1[9] + Gu2[3];
+Gu3[4] = + Q11[10]*Gu1[0] + Q11[11]*Gu1[2] + Q11[12]*Gu1[4] + Q11[13]*Gu1[6] + Q11[14]*Gu1[8] + Gu2[4];
+Gu3[5] = + Q11[10]*Gu1[1] + Q11[11]*Gu1[3] + Q11[12]*Gu1[5] + Q11[13]*Gu1[7] + Q11[14]*Gu1[9] + Gu2[5];
+Gu3[6] = + Q11[15]*Gu1[0] + Q11[16]*Gu1[2] + Q11[17]*Gu1[4] + Q11[18]*Gu1[6] + Q11[19]*Gu1[8] + Gu2[6];
+Gu3[7] = + Q11[15]*Gu1[1] + Q11[16]*Gu1[3] + Q11[17]*Gu1[5] + Q11[18]*Gu1[7] + Q11[19]*Gu1[9] + Gu2[7];
+Gu3[8] = + Q11[20]*Gu1[0] + Q11[21]*Gu1[2] + Q11[22]*Gu1[4] + Q11[23]*Gu1[6] + Q11[24]*Gu1[8] + Gu2[8];
+Gu3[9] = + Q11[20]*Gu1[1] + Q11[21]*Gu1[3] + Q11[22]*Gu1[5] + Q11[23]*Gu1[7] + Q11[24]*Gu1[9] + Gu2[9];
+}
+
+void acado_macATw1QDy( real_t* const Gx1, real_t* const w11, real_t* const w12, real_t* const w13 )
+{
+w13[0] = + Gx1[0]*w11[0] + Gx1[5]*w11[1] + Gx1[10]*w11[2] + Gx1[15]*w11[3] + Gx1[20]*w11[4] + w12[0];
+w13[1] = + Gx1[1]*w11[0] + Gx1[6]*w11[1] + Gx1[11]*w11[2] + Gx1[16]*w11[3] + Gx1[21]*w11[4] + w12[1];
+w13[2] = + Gx1[2]*w11[0] + Gx1[7]*w11[1] + Gx1[12]*w11[2] + Gx1[17]*w11[3] + Gx1[22]*w11[4] + w12[2];
+w13[3] = + Gx1[3]*w11[0] + Gx1[8]*w11[1] + Gx1[13]*w11[2] + Gx1[18]*w11[3] + Gx1[23]*w11[4] + w12[3];
+w13[4] = + Gx1[4]*w11[0] + Gx1[9]*w11[1] + Gx1[14]*w11[2] + Gx1[19]*w11[3] + Gx1[24]*w11[4] + w12[4];
+}
+
+void acado_macBTw1( real_t* const Gu1, real_t* const w11, real_t* const U1 )
+{
+U1[0] += + Gu1[0]*w11[0] + Gu1[2]*w11[1] + Gu1[4]*w11[2] + Gu1[6]*w11[3] + Gu1[8]*w11[4];
+U1[1] += + Gu1[1]*w11[0] + Gu1[3]*w11[1] + Gu1[5]*w11[2] + Gu1[7]*w11[3] + Gu1[9]*w11[4];
+}
+
+void acado_macQSbarW2( real_t* const Q11, real_t* const w11, real_t* const w12, real_t* const w13 )
+{
+w13[0] = + Q11[0]*w11[0] + Q11[1]*w11[1] + Q11[2]*w11[2] + Q11[3]*w11[3] + Q11[4]*w11[4] + w12[0];
+w13[1] = + Q11[5]*w11[0] + Q11[6]*w11[1] + Q11[7]*w11[2] + Q11[8]*w11[3] + Q11[9]*w11[4] + w12[1];
+w13[2] = + Q11[10]*w11[0] + Q11[11]*w11[1] + Q11[12]*w11[2] + Q11[13]*w11[3] + Q11[14]*w11[4] + w12[2];
+w13[3] = + Q11[15]*w11[0] + Q11[16]*w11[1] + Q11[17]*w11[2] + Q11[18]*w11[3] + Q11[19]*w11[4] + w12[3];
+w13[4] = + Q11[20]*w11[0] + Q11[21]*w11[1] + Q11[22]*w11[2] + Q11[23]*w11[3] + Q11[24]*w11[4] + w12[4];
+}
+
+void acado_macASbar( real_t* const Gx1, real_t* const w11, real_t* const w12 )
+{
+w12[0] += + Gx1[0]*w11[0] + Gx1[1]*w11[1] + Gx1[2]*w11[2] + Gx1[3]*w11[3] + Gx1[4]*w11[4];
+w12[1] += + Gx1[5]*w11[0] + Gx1[6]*w11[1] + Gx1[7]*w11[2] + Gx1[8]*w11[3] + Gx1[9]*w11[4];
+w12[2] += + Gx1[10]*w11[0] + Gx1[11]*w11[1] + Gx1[12]*w11[2] + Gx1[13]*w11[3] + Gx1[14]*w11[4];
+w12[3] += + Gx1[15]*w11[0] + Gx1[16]*w11[1] + Gx1[17]*w11[2] + Gx1[18]*w11[3] + Gx1[19]*w11[4];
+w12[4] += + Gx1[20]*w11[0] + Gx1[21]*w11[1] + Gx1[22]*w11[2] + Gx1[23]*w11[3] + Gx1[24]*w11[4];
+}
+
+void acado_expansionStep( real_t* const Gx1, real_t* const Gu1, real_t* const U1, real_t* const w11, real_t* const w12 )
+{
+w12[0] += + Gx1[0]*w11[0] + Gx1[1]*w11[1] + Gx1[2]*w11[2] + Gx1[3]*w11[3] + Gx1[4]*w11[4];
+w12[1] += + Gx1[5]*w11[0] + Gx1[6]*w11[1] + Gx1[7]*w11[2] + Gx1[8]*w11[3] + Gx1[9]*w11[4];
+w12[2] += + Gx1[10]*w11[0] + Gx1[11]*w11[1] + Gx1[12]*w11[2] + Gx1[13]*w11[3] + Gx1[14]*w11[4];
+w12[3] += + Gx1[15]*w11[0] + Gx1[16]*w11[1] + Gx1[17]*w11[2] + Gx1[18]*w11[3] + Gx1[19]*w11[4];
+w12[4] += + Gx1[20]*w11[0] + Gx1[21]*w11[1] + Gx1[22]*w11[2] + Gx1[23]*w11[3] + Gx1[24]*w11[4];
+w12[0] += + Gu1[0]*U1[0] + Gu1[1]*U1[1];
+w12[1] += + Gu1[2]*U1[0] + Gu1[3]*U1[1];
+w12[2] += + Gu1[4]*U1[0] + Gu1[5]*U1[1];
+w12[3] += + Gu1[6]*U1[0] + Gu1[7]*U1[1];
+w12[4] += + Gu1[8]*U1[0] + Gu1[9]*U1[1];
+}
+
+void acado_copyHTH( int iRow, int iCol )
+{
+acadoWorkspace.H[(iRow * 80) + (iCol * 2)] = acadoWorkspace.H[(iCol * 80) + (iRow * 2)];
+acadoWorkspace.H[(iRow * 80) + (iCol * 2 + 1)] = acadoWorkspace.H[(iCol * 80 + 40) + (iRow * 2)];
+acadoWorkspace.H[(iRow * 80 + 40) + (iCol * 2)] = acadoWorkspace.H[(iCol * 80) + (iRow * 2 + 1)];
+acadoWorkspace.H[(iRow * 80 + 40) + (iCol * 2 + 1)] = acadoWorkspace.H[(iCol * 80 + 40) + (iRow * 2 + 1)];
+}
+
+void acado_multRDy( real_t* const R2, real_t* const Dy1, real_t* const RDy1 )
+{
+RDy1[0] = + R2[0]*Dy1[0] + R2[1]*Dy1[1] + R2[2]*Dy1[2] + R2[3]*Dy1[3] + R2[4]*Dy1[4] + R2[5]*Dy1[5] + R2[6]*Dy1[6] + R2[7]*Dy1[7];
+RDy1[1] = + R2[8]*Dy1[0] + R2[9]*Dy1[1] + R2[10]*Dy1[2] + R2[11]*Dy1[3] + R2[12]*Dy1[4] + R2[13]*Dy1[5] + R2[14]*Dy1[6] + R2[15]*Dy1[7];
+}
+
+void acado_multQDy( real_t* const Q2, real_t* const Dy1, real_t* const QDy1 )
+{
+QDy1[0] = + Q2[0]*Dy1[0] + Q2[1]*Dy1[1] + Q2[2]*Dy1[2] + Q2[3]*Dy1[3] + Q2[4]*Dy1[4] + Q2[5]*Dy1[5] + Q2[6]*Dy1[6] + Q2[7]*Dy1[7];
+QDy1[1] = + Q2[8]*Dy1[0] + Q2[9]*Dy1[1] + Q2[10]*Dy1[2] + Q2[11]*Dy1[3] + Q2[12]*Dy1[4] + Q2[13]*Dy1[5] + Q2[14]*Dy1[6] + Q2[15]*Dy1[7];
+QDy1[2] = + Q2[16]*Dy1[0] + Q2[17]*Dy1[1] + Q2[18]*Dy1[2] + Q2[19]*Dy1[3] + Q2[20]*Dy1[4] + Q2[21]*Dy1[5] + Q2[22]*Dy1[6] + Q2[23]*Dy1[7];
+QDy1[3] = + Q2[24]*Dy1[0] + Q2[25]*Dy1[1] + Q2[26]*Dy1[2] + Q2[27]*Dy1[3] + Q2[28]*Dy1[4] + Q2[29]*Dy1[5] + Q2[30]*Dy1[6] + Q2[31]*Dy1[7];
+QDy1[4] = + Q2[32]*Dy1[0] + Q2[33]*Dy1[1] + Q2[34]*Dy1[2] + Q2[35]*Dy1[3] + Q2[36]*Dy1[4] + Q2[37]*Dy1[5] + Q2[38]*Dy1[6] + Q2[39]*Dy1[7];
+}
+
+void acado_multHxE( real_t* const Hx, real_t* const E, int row, int col )
+{
+acadoWorkspace.A[(row * 400 + 1600) + (col * 2)] = + Hx[0]*E[0] + Hx[1]*E[2] + Hx[2]*E[4] + Hx[3]*E[6] + Hx[4]*E[8];
+acadoWorkspace.A[(row * 400 + 1600) + (col * 2 + 1)] = + Hx[0]*E[1] + Hx[1]*E[3] + Hx[2]*E[5] + Hx[3]*E[7] + Hx[4]*E[9];
+acadoWorkspace.A[(row * 400 + 1640) + (col * 2)] = + Hx[5]*E[0] + Hx[6]*E[2] + Hx[7]*E[4] + Hx[8]*E[6] + Hx[9]*E[8];
+acadoWorkspace.A[(row * 400 + 1640) + (col * 2 + 1)] = + Hx[5]*E[1] + Hx[6]*E[3] + Hx[7]*E[5] + Hx[8]*E[7] + Hx[9]*E[9];
+acadoWorkspace.A[(row * 400 + 1680) + (col * 2)] = + Hx[10]*E[0] + Hx[11]*E[2] + Hx[12]*E[4] + Hx[13]*E[6] + Hx[14]*E[8];
+acadoWorkspace.A[(row * 400 + 1680) + (col * 2 + 1)] = + Hx[10]*E[1] + Hx[11]*E[3] + Hx[12]*E[5] + Hx[13]*E[7] + Hx[14]*E[9];
+acadoWorkspace.A[(row * 400 + 1720) + (col * 2)] = + Hx[15]*E[0] + Hx[16]*E[2] + Hx[17]*E[4] + Hx[18]*E[6] + Hx[19]*E[8];
+acadoWorkspace.A[(row * 400 + 1720) + (col * 2 + 1)] = + Hx[15]*E[1] + Hx[16]*E[3] + Hx[17]*E[5] + Hx[18]*E[7] + Hx[19]*E[9];
+acadoWorkspace.A[(row * 400 + 1760) + (col * 2)] = + Hx[20]*E[0] + Hx[21]*E[2] + Hx[22]*E[4] + Hx[23]*E[6] + Hx[24]*E[8];
+acadoWorkspace.A[(row * 400 + 1760) + (col * 2 + 1)] = + Hx[20]*E[1] + Hx[21]*E[3] + Hx[22]*E[5] + Hx[23]*E[7] + Hx[24]*E[9];
+acadoWorkspace.A[(row * 400 + 1800) + (col * 2)] = + Hx[25]*E[0] + Hx[26]*E[2] + Hx[27]*E[4] + Hx[28]*E[6] + Hx[29]*E[8];
+acadoWorkspace.A[(row * 400 + 1800) + (col * 2 + 1)] = + Hx[25]*E[1] + Hx[26]*E[3] + Hx[27]*E[5] + Hx[28]*E[7] + Hx[29]*E[9];
+acadoWorkspace.A[(row * 400 + 1840) + (col * 2)] = + Hx[30]*E[0] + Hx[31]*E[2] + Hx[32]*E[4] + Hx[33]*E[6] + Hx[34]*E[8];
+acadoWorkspace.A[(row * 400 + 1840) + (col * 2 + 1)] = + Hx[30]*E[1] + Hx[31]*E[3] + Hx[32]*E[5] + Hx[33]*E[7] + Hx[34]*E[9];
+acadoWorkspace.A[(row * 400 + 1880) + (col * 2)] = + Hx[35]*E[0] + Hx[36]*E[2] + Hx[37]*E[4] + Hx[38]*E[6] + Hx[39]*E[8];
+acadoWorkspace.A[(row * 400 + 1880) + (col * 2 + 1)] = + Hx[35]*E[1] + Hx[36]*E[3] + Hx[37]*E[5] + Hx[38]*E[7] + Hx[39]*E[9];
+acadoWorkspace.A[(row * 400 + 1920) + (col * 2)] = + Hx[40]*E[0] + Hx[41]*E[2] + Hx[42]*E[4] + Hx[43]*E[6] + Hx[44]*E[8];
+acadoWorkspace.A[(row * 400 + 1920) + (col * 2 + 1)] = + Hx[40]*E[1] + Hx[41]*E[3] + Hx[42]*E[5] + Hx[43]*E[7] + Hx[44]*E[9];
+acadoWorkspace.A[(row * 400 + 1960) + (col * 2)] = + Hx[45]*E[0] + Hx[46]*E[2] + Hx[47]*E[4] + Hx[48]*E[6] + Hx[49]*E[8];
+acadoWorkspace.A[(row * 400 + 1960) + (col * 2 + 1)] = + Hx[45]*E[1] + Hx[46]*E[3] + Hx[47]*E[5] + Hx[48]*E[7] + Hx[49]*E[9];
+}
+
+void acado_macHxd( real_t* const Hx, real_t* const tmpd, real_t* const lbA, real_t* const ubA )
+{
+acadoWorkspace.evHxd[0] = + Hx[0]*tmpd[0] + Hx[1]*tmpd[1] + Hx[2]*tmpd[2] + Hx[3]*tmpd[3] + Hx[4]*tmpd[4];
+acadoWorkspace.evHxd[1] = + Hx[5]*tmpd[0] + Hx[6]*tmpd[1] + Hx[7]*tmpd[2] + Hx[8]*tmpd[3] + Hx[9]*tmpd[4];
+acadoWorkspace.evHxd[2] = + Hx[10]*tmpd[0] + Hx[11]*tmpd[1] + Hx[12]*tmpd[2] + Hx[13]*tmpd[3] + Hx[14]*tmpd[4];
+acadoWorkspace.evHxd[3] = + Hx[15]*tmpd[0] + Hx[16]*tmpd[1] + Hx[17]*tmpd[2] + Hx[18]*tmpd[3] + Hx[19]*tmpd[4];
+acadoWorkspace.evHxd[4] = + Hx[20]*tmpd[0] + Hx[21]*tmpd[1] + Hx[22]*tmpd[2] + Hx[23]*tmpd[3] + Hx[24]*tmpd[4];
+acadoWorkspace.evHxd[5] = + Hx[25]*tmpd[0] + Hx[26]*tmpd[1] + Hx[27]*tmpd[2] + Hx[28]*tmpd[3] + Hx[29]*tmpd[4];
+acadoWorkspace.evHxd[6] = + Hx[30]*tmpd[0] + Hx[31]*tmpd[1] + Hx[32]*tmpd[2] + Hx[33]*tmpd[3] + Hx[34]*tmpd[4];
+acadoWorkspace.evHxd[7] = + Hx[35]*tmpd[0] + Hx[36]*tmpd[1] + Hx[37]*tmpd[2] + Hx[38]*tmpd[3] + Hx[39]*tmpd[4];
+acadoWorkspace.evHxd[8] = + Hx[40]*tmpd[0] + Hx[41]*tmpd[1] + Hx[42]*tmpd[2] + Hx[43]*tmpd[3] + Hx[44]*tmpd[4];
+acadoWorkspace.evHxd[9] = + Hx[45]*tmpd[0] + Hx[46]*tmpd[1] + Hx[47]*tmpd[2] + Hx[48]*tmpd[3] + Hx[49]*tmpd[4];
+lbA[0] -= acadoWorkspace.evHxd[0];
+lbA[1] -= acadoWorkspace.evHxd[1];
+lbA[2] -= acadoWorkspace.evHxd[2];
+lbA[3] -= acadoWorkspace.evHxd[3];
+lbA[4] -= acadoWorkspace.evHxd[4];
+lbA[5] -= acadoWorkspace.evHxd[5];
+lbA[6] -= acadoWorkspace.evHxd[6];
+lbA[7] -= acadoWorkspace.evHxd[7];
+lbA[8] -= acadoWorkspace.evHxd[8];
+lbA[9] -= acadoWorkspace.evHxd[9];
+ubA[0] -= acadoWorkspace.evHxd[0];
+ubA[1] -= acadoWorkspace.evHxd[1];
+ubA[2] -= acadoWorkspace.evHxd[2];
+ubA[3] -= acadoWorkspace.evHxd[3];
+ubA[4] -= acadoWorkspace.evHxd[4];
+ubA[5] -= acadoWorkspace.evHxd[5];
+ubA[6] -= acadoWorkspace.evHxd[6];
+ubA[7] -= acadoWorkspace.evHxd[7];
+ubA[8] -= acadoWorkspace.evHxd[8];
+ubA[9] -= acadoWorkspace.evHxd[9];
+}
+
+void acado_condensePrep(  )
+{
+int lRun1;
+int lRun2;
+int lRun3;
+int lRun4;
+int lRun5;
+/** Row vector of size: 40 */
+static const int xBoundIndices[ 40 ] = 
+{ 8, 9, 13, 14, 18, 19, 23, 24, 28, 29, 33, 34, 38, 39, 43, 44, 48, 49, 53, 54, 58, 59, 63, 64, 68, 69, 73, 74, 78, 79, 83, 84, 88, 89, 93, 94, 98, 99, 103, 104 };
+acado_moveGxT( acadoWorkspace.evGx, acadoWorkspace.C );
+acado_multGxGx( &(acadoWorkspace.evGx[ 25 ]), acadoWorkspace.C, &(acadoWorkspace.C[ 25 ]) );
+acado_multGxGx( &(acadoWorkspace.evGx[ 50 ]), &(acadoWorkspace.C[ 25 ]), &(acadoWorkspace.C[ 50 ]) );
+acado_multGxGx( &(acadoWorkspace.evGx[ 75 ]), &(acadoWorkspace.C[ 50 ]), &(acadoWorkspace.C[ 75 ]) );
+acado_multGxGx( &(acadoWorkspace.evGx[ 100 ]), &(acadoWorkspace.C[ 75 ]), &(acadoWorkspace.C[ 100 ]) );
+acado_multGxGx( &(acadoWorkspace.evGx[ 125 ]), &(acadoWorkspace.C[ 100 ]), &(acadoWorkspace.C[ 125 ]) );
+acado_multGxGx( &(acadoWorkspace.evGx[ 150 ]), &(acadoWorkspace.C[ 125 ]), &(acadoWorkspace.C[ 150 ]) );
+acado_multGxGx( &(acadoWorkspace.evGx[ 175 ]), &(acadoWorkspace.C[ 150 ]), &(acadoWorkspace.C[ 175 ]) );
+acado_multGxGx( &(acadoWorkspace.evGx[ 200 ]), &(acadoWorkspace.C[ 175 ]), &(acadoWorkspace.C[ 200 ]) );
+acado_multGxGx( &(acadoWorkspace.evGx[ 225 ]), &(acadoWorkspace.C[ 200 ]), &(acadoWorkspace.C[ 225 ]) );
+acado_multGxGx( &(acadoWorkspace.evGx[ 250 ]), &(acadoWorkspace.C[ 225 ]), &(acadoWorkspace.C[ 250 ]) );
+acado_multGxGx( &(acadoWorkspace.evGx[ 275 ]), &(acadoWorkspace.C[ 250 ]), &(acadoWorkspace.C[ 275 ]) );
+acado_multGxGx( &(acadoWorkspace.evGx[ 300 ]), &(acadoWorkspace.C[ 275 ]), &(acadoWorkspace.C[ 300 ]) );
+acado_multGxGx( &(acadoWorkspace.evGx[ 325 ]), &(acadoWorkspace.C[ 300 ]), &(acadoWorkspace.C[ 325 ]) );
+acado_multGxGx( &(acadoWorkspace.evGx[ 350 ]), &(acadoWorkspace.C[ 325 ]), &(acadoWorkspace.C[ 350 ]) );
+acado_multGxGx( &(acadoWorkspace.evGx[ 375 ]), &(acadoWorkspace.C[ 350 ]), &(acadoWorkspace.C[ 375 ]) );
+acado_multGxGx( &(acadoWorkspace.evGx[ 400 ]), &(acadoWorkspace.C[ 375 ]), &(acadoWorkspace.C[ 400 ]) );
+acado_multGxGx( &(acadoWorkspace.evGx[ 425 ]), &(acadoWorkspace.C[ 400 ]), &(acadoWorkspace.C[ 425 ]) );
+acado_multGxGx( &(acadoWorkspace.evGx[ 450 ]), &(acadoWorkspace.C[ 425 ]), &(acadoWorkspace.C[ 450 ]) );
+acado_multGxGx( &(acadoWorkspace.evGx[ 475 ]), &(acadoWorkspace.C[ 450 ]), &(acadoWorkspace.C[ 475 ]) );
+for (lRun2 = 0; lRun2 < 20; ++lRun2)
+{
+lRun3 = ((lRun2) * (lRun2 * -1 + 41)) / (2);
+acado_moveGuE( &(acadoWorkspace.evGu[ lRun2 * 10 ]), &(acadoWorkspace.E[ lRun3 * 10 ]) );
+for (lRun1 = 1; lRun1 < lRun2 * -1 + 20; ++lRun1)
+{
+acado_multGxGu( &(acadoWorkspace.evGx[ ((((lRun2) + (lRun1)) * (5)) * (5)) + (0) ]), &(acadoWorkspace.E[ (((((lRun3) + (lRun1)) - (1)) * (5)) * (2)) + (0) ]), &(acadoWorkspace.E[ ((((lRun3) + (lRun1)) * (5)) * (2)) + (0) ]) );
+}
+
+acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ ((((((lRun3) - (lRun2)) + (20)) - (1)) * (5)) * (2)) + (0) ]), acadoWorkspace.W1 );
+for (lRun1 = 19; lRun2 < lRun1; --lRun1)
+{
+acado_multBTW1( &(acadoWorkspace.evGu[ lRun1 * 10 ]), acadoWorkspace.W1, lRun1, lRun2 );
+acado_multGxTGu( &(acadoWorkspace.evGx[ lRun1 * 25 ]), acadoWorkspace.W1, acadoWorkspace.W2 );
+acado_multQEW2( &(acadoWorkspace.Q1[ lRun1 * 25 ]), &(acadoWorkspace.E[ ((((((lRun3) + (lRun1)) - (lRun2)) - (1)) * (5)) * (2)) + (0) ]), acadoWorkspace.W2, acadoWorkspace.W1 );
+}
+acado_multBTW1_R1( &(acadoWorkspace.R1[ lRun2 * 4 ]), &(acadoWorkspace.evGu[ lRun2 * 10 ]), acadoWorkspace.W1, lRun2 );
+}
+
+acado_copyHTH( 0, 1 );
+acado_copyHTH( 0, 2 );
+acado_copyHTH( 1, 2 );
+acado_copyHTH( 0, 3 );
+acado_copyHTH( 1, 3 );
+acado_copyHTH( 2, 3 );
+acado_copyHTH( 0, 4 );
+acado_copyHTH( 1, 4 );
+acado_copyHTH( 2, 4 );
+acado_copyHTH( 3, 4 );
+acado_copyHTH( 0, 5 );
+acado_copyHTH( 1, 5 );
+acado_copyHTH( 2, 5 );
+acado_copyHTH( 3, 5 );
+acado_copyHTH( 4, 5 );
+acado_copyHTH( 0, 6 );
+acado_copyHTH( 1, 6 );
+acado_copyHTH( 2, 6 );
+acado_copyHTH( 3, 6 );
+acado_copyHTH( 4, 6 );
+acado_copyHTH( 5, 6 );
+acado_copyHTH( 0, 7 );
+acado_copyHTH( 1, 7 );
+acado_copyHTH( 2, 7 );
+acado_copyHTH( 3, 7 );
+acado_copyHTH( 4, 7 );
+acado_copyHTH( 5, 7 );
+acado_copyHTH( 6, 7 );
+acado_copyHTH( 0, 8 );
+acado_copyHTH( 1, 8 );
+acado_copyHTH( 2, 8 );
+acado_copyHTH( 3, 8 );
+acado_copyHTH( 4, 8 );
+acado_copyHTH( 5, 8 );
+acado_copyHTH( 6, 8 );
+acado_copyHTH( 7, 8 );
+acado_copyHTH( 0, 9 );
+acado_copyHTH( 1, 9 );
+acado_copyHTH( 2, 9 );
+acado_copyHTH( 3, 9 );
+acado_copyHTH( 4, 9 );
+acado_copyHTH( 5, 9 );
+acado_copyHTH( 6, 9 );
+acado_copyHTH( 7, 9 );
+acado_copyHTH( 8, 9 );
+acado_copyHTH( 0, 10 );
+acado_copyHTH( 1, 10 );
+acado_copyHTH( 2, 10 );
+acado_copyHTH( 3, 10 );
+acado_copyHTH( 4, 10 );
+acado_copyHTH( 5, 10 );
+acado_copyHTH( 6, 10 );
+acado_copyHTH( 7, 10 );
+acado_copyHTH( 8, 10 );
+acado_copyHTH( 9, 10 );
+acado_copyHTH( 0, 11 );
+acado_copyHTH( 1, 11 );
+acado_copyHTH( 2, 11 );
+acado_copyHTH( 3, 11 );
+acado_copyHTH( 4, 11 );
+acado_copyHTH( 5, 11 );
+acado_copyHTH( 6, 11 );
+acado_copyHTH( 7, 11 );
+acado_copyHTH( 8, 11 );
+acado_copyHTH( 9, 11 );
+acado_copyHTH( 10, 11 );
+acado_copyHTH( 0, 12 );
+acado_copyHTH( 1, 12 );
+acado_copyHTH( 2, 12 );
+acado_copyHTH( 3, 12 );
+acado_copyHTH( 4, 12 );
+acado_copyHTH( 5, 12 );
+acado_copyHTH( 6, 12 );
+acado_copyHTH( 7, 12 );
+acado_copyHTH( 8, 12 );
+acado_copyHTH( 9, 12 );
+acado_copyHTH( 10, 12 );
+acado_copyHTH( 11, 12 );
+acado_copyHTH( 0, 13 );
+acado_copyHTH( 1, 13 );
+acado_copyHTH( 2, 13 );
+acado_copyHTH( 3, 13 );
+acado_copyHTH( 4, 13 );
+acado_copyHTH( 5, 13 );
+acado_copyHTH( 6, 13 );
+acado_copyHTH( 7, 13 );
+acado_copyHTH( 8, 13 );
+acado_copyHTH( 9, 13 );
+acado_copyHTH( 10, 13 );
+acado_copyHTH( 11, 13 );
+acado_copyHTH( 12, 13 );
+acado_copyHTH( 0, 14 );
+acado_copyHTH( 1, 14 );
+acado_copyHTH( 2, 14 );
+acado_copyHTH( 3, 14 );
+acado_copyHTH( 4, 14 );
+acado_copyHTH( 5, 14 );
+acado_copyHTH( 6, 14 );
+acado_copyHTH( 7, 14 );
+acado_copyHTH( 8, 14 );
+acado_copyHTH( 9, 14 );
+acado_copyHTH( 10, 14 );
+acado_copyHTH( 11, 14 );
+acado_copyHTH( 12, 14 );
+acado_copyHTH( 13, 14 );
+acado_copyHTH( 0, 15 );
+acado_copyHTH( 1, 15 );
+acado_copyHTH( 2, 15 );
+acado_copyHTH( 3, 15 );
+acado_copyHTH( 4, 15 );
+acado_copyHTH( 5, 15 );
+acado_copyHTH( 6, 15 );
+acado_copyHTH( 7, 15 );
+acado_copyHTH( 8, 15 );
+acado_copyHTH( 9, 15 );
+acado_copyHTH( 10, 15 );
+acado_copyHTH( 11, 15 );
+acado_copyHTH( 12, 15 );
+acado_copyHTH( 13, 15 );
+acado_copyHTH( 14, 15 );
+acado_copyHTH( 0, 16 );
+acado_copyHTH( 1, 16 );
+acado_copyHTH( 2, 16 );
+acado_copyHTH( 3, 16 );
+acado_copyHTH( 4, 16 );
+acado_copyHTH( 5, 16 );
+acado_copyHTH( 6, 16 );
+acado_copyHTH( 7, 16 );
+acado_copyHTH( 8, 16 );
+acado_copyHTH( 9, 16 );
+acado_copyHTH( 10, 16 );
+acado_copyHTH( 11, 16 );
+acado_copyHTH( 12, 16 );
+acado_copyHTH( 13, 16 );
+acado_copyHTH( 14, 16 );
+acado_copyHTH( 15, 16 );
+acado_copyHTH( 0, 17 );
+acado_copyHTH( 1, 17 );
+acado_copyHTH( 2, 17 );
+acado_copyHTH( 3, 17 );
+acado_copyHTH( 4, 17 );
+acado_copyHTH( 5, 17 );
+acado_copyHTH( 6, 17 );
+acado_copyHTH( 7, 17 );
+acado_copyHTH( 8, 17 );
+acado_copyHTH( 9, 17 );
+acado_copyHTH( 10, 17 );
+acado_copyHTH( 11, 17 );
+acado_copyHTH( 12, 17 );
+acado_copyHTH( 13, 17 );
+acado_copyHTH( 14, 17 );
+acado_copyHTH( 15, 17 );
+acado_copyHTH( 16, 17 );
+acado_copyHTH( 0, 18 );
+acado_copyHTH( 1, 18 );
+acado_copyHTH( 2, 18 );
+acado_copyHTH( 3, 18 );
+acado_copyHTH( 4, 18 );
+acado_copyHTH( 5, 18 );
+acado_copyHTH( 6, 18 );
+acado_copyHTH( 7, 18 );
+acado_copyHTH( 8, 18 );
+acado_copyHTH( 9, 18 );
+acado_copyHTH( 10, 18 );
+acado_copyHTH( 11, 18 );
+acado_copyHTH( 12, 18 );
+acado_copyHTH( 13, 18 );
+acado_copyHTH( 14, 18 );
+acado_copyHTH( 15, 18 );
+acado_copyHTH( 16, 18 );
+acado_copyHTH( 17, 18 );
+acado_copyHTH( 0, 19 );
+acado_copyHTH( 1, 19 );
+acado_copyHTH( 2, 19 );
+acado_copyHTH( 3, 19 );
+acado_copyHTH( 4, 19 );
+acado_copyHTH( 5, 19 );
+acado_copyHTH( 6, 19 );
+acado_copyHTH( 7, 19 );
+acado_copyHTH( 8, 19 );
+acado_copyHTH( 9, 19 );
+acado_copyHTH( 10, 19 );
+acado_copyHTH( 11, 19 );
+acado_copyHTH( 12, 19 );
+acado_copyHTH( 13, 19 );
+acado_copyHTH( 14, 19 );
+acado_copyHTH( 15, 19 );
+acado_copyHTH( 16, 19 );
+acado_copyHTH( 17, 19 );
+acado_copyHTH( 18, 19 );
+
+acadoWorkspace.sbar[5] = acadoWorkspace.d[0];
+acadoWorkspace.sbar[6] = acadoWorkspace.d[1];
+acadoWorkspace.sbar[7] = acadoWorkspace.d[2];
+acadoWorkspace.sbar[8] = acadoWorkspace.d[3];
+acadoWorkspace.sbar[9] = acadoWorkspace.d[4];
+acadoWorkspace.sbar[10] = acadoWorkspace.d[5];
+acadoWorkspace.sbar[11] = acadoWorkspace.d[6];
+acadoWorkspace.sbar[12] = acadoWorkspace.d[7];
+acadoWorkspace.sbar[13] = acadoWorkspace.d[8];
+acadoWorkspace.sbar[14] = acadoWorkspace.d[9];
+acadoWorkspace.sbar[15] = acadoWorkspace.d[10];
+acadoWorkspace.sbar[16] = acadoWorkspace.d[11];
+acadoWorkspace.sbar[17] = acadoWorkspace.d[12];
+acadoWorkspace.sbar[18] = acadoWorkspace.d[13];
+acadoWorkspace.sbar[19] = acadoWorkspace.d[14];
+acadoWorkspace.sbar[20] = acadoWorkspace.d[15];
+acadoWorkspace.sbar[21] = acadoWorkspace.d[16];
+acadoWorkspace.sbar[22] = acadoWorkspace.d[17];
+acadoWorkspace.sbar[23] = acadoWorkspace.d[18];
+acadoWorkspace.sbar[24] = acadoWorkspace.d[19];
+acadoWorkspace.sbar[25] = acadoWorkspace.d[20];
+acadoWorkspace.sbar[26] = acadoWorkspace.d[21];
+acadoWorkspace.sbar[27] = acadoWorkspace.d[22];
+acadoWorkspace.sbar[28] = acadoWorkspace.d[23];
+acadoWorkspace.sbar[29] = acadoWorkspace.d[24];
+acadoWorkspace.sbar[30] = acadoWorkspace.d[25];
+acadoWorkspace.sbar[31] = acadoWorkspace.d[26];
+acadoWorkspace.sbar[32] = acadoWorkspace.d[27];
+acadoWorkspace.sbar[33] = acadoWorkspace.d[28];
+acadoWorkspace.sbar[34] = acadoWorkspace.d[29];
+acadoWorkspace.sbar[35] = acadoWorkspace.d[30];
+acadoWorkspace.sbar[36] = acadoWorkspace.d[31];
+acadoWorkspace.sbar[37] = acadoWorkspace.d[32];
+acadoWorkspace.sbar[38] = acadoWorkspace.d[33];
+acadoWorkspace.sbar[39] = acadoWorkspace.d[34];
+acadoWorkspace.sbar[40] = acadoWorkspace.d[35];
+acadoWorkspace.sbar[41] = acadoWorkspace.d[36];
+acadoWorkspace.sbar[42] = acadoWorkspace.d[37];
+acadoWorkspace.sbar[43] = acadoWorkspace.d[38];
+acadoWorkspace.sbar[44] = acadoWorkspace.d[39];
+acadoWorkspace.sbar[45] = acadoWorkspace.d[40];
+acadoWorkspace.sbar[46] = acadoWorkspace.d[41];
+acadoWorkspace.sbar[47] = acadoWorkspace.d[42];
+acadoWorkspace.sbar[48] = acadoWorkspace.d[43];
+acadoWorkspace.sbar[49] = acadoWorkspace.d[44];
+acadoWorkspace.sbar[50] = acadoWorkspace.d[45];
+acadoWorkspace.sbar[51] = acadoWorkspace.d[46];
+acadoWorkspace.sbar[52] = acadoWorkspace.d[47];
+acadoWorkspace.sbar[53] = acadoWorkspace.d[48];
+acadoWorkspace.sbar[54] = acadoWorkspace.d[49];
+acadoWorkspace.sbar[55] = acadoWorkspace.d[50];
+acadoWorkspace.sbar[56] = acadoWorkspace.d[51];
+acadoWorkspace.sbar[57] = acadoWorkspace.d[52];
+acadoWorkspace.sbar[58] = acadoWorkspace.d[53];
+acadoWorkspace.sbar[59] = acadoWorkspace.d[54];
+acadoWorkspace.sbar[60] = acadoWorkspace.d[55];
+acadoWorkspace.sbar[61] = acadoWorkspace.d[56];
+acadoWorkspace.sbar[62] = acadoWorkspace.d[57];
+acadoWorkspace.sbar[63] = acadoWorkspace.d[58];
+acadoWorkspace.sbar[64] = acadoWorkspace.d[59];
+acadoWorkspace.sbar[65] = acadoWorkspace.d[60];
+acadoWorkspace.sbar[66] = acadoWorkspace.d[61];
+acadoWorkspace.sbar[67] = acadoWorkspace.d[62];
+acadoWorkspace.sbar[68] = acadoWorkspace.d[63];
+acadoWorkspace.sbar[69] = acadoWorkspace.d[64];
+acadoWorkspace.sbar[70] = acadoWorkspace.d[65];
+acadoWorkspace.sbar[71] = acadoWorkspace.d[66];
+acadoWorkspace.sbar[72] = acadoWorkspace.d[67];
+acadoWorkspace.sbar[73] = acadoWorkspace.d[68];
+acadoWorkspace.sbar[74] = acadoWorkspace.d[69];
+acadoWorkspace.sbar[75] = acadoWorkspace.d[70];
+acadoWorkspace.sbar[76] = acadoWorkspace.d[71];
+acadoWorkspace.sbar[77] = acadoWorkspace.d[72];
+acadoWorkspace.sbar[78] = acadoWorkspace.d[73];
+acadoWorkspace.sbar[79] = acadoWorkspace.d[74];
+acadoWorkspace.sbar[80] = acadoWorkspace.d[75];
+acadoWorkspace.sbar[81] = acadoWorkspace.d[76];
+acadoWorkspace.sbar[82] = acadoWorkspace.d[77];
+acadoWorkspace.sbar[83] = acadoWorkspace.d[78];
+acadoWorkspace.sbar[84] = acadoWorkspace.d[79];
+acadoWorkspace.sbar[85] = acadoWorkspace.d[80];
+acadoWorkspace.sbar[86] = acadoWorkspace.d[81];
+acadoWorkspace.sbar[87] = acadoWorkspace.d[82];
+acadoWorkspace.sbar[88] = acadoWorkspace.d[83];
+acadoWorkspace.sbar[89] = acadoWorkspace.d[84];
+acadoWorkspace.sbar[90] = acadoWorkspace.d[85];
+acadoWorkspace.sbar[91] = acadoWorkspace.d[86];
+acadoWorkspace.sbar[92] = acadoWorkspace.d[87];
+acadoWorkspace.sbar[93] = acadoWorkspace.d[88];
+acadoWorkspace.sbar[94] = acadoWorkspace.d[89];
+acadoWorkspace.sbar[95] = acadoWorkspace.d[90];
+acadoWorkspace.sbar[96] = acadoWorkspace.d[91];
+acadoWorkspace.sbar[97] = acadoWorkspace.d[92];
+acadoWorkspace.sbar[98] = acadoWorkspace.d[93];
+acadoWorkspace.sbar[99] = acadoWorkspace.d[94];
+acadoWorkspace.sbar[100] = acadoWorkspace.d[95];
+acadoWorkspace.sbar[101] = acadoWorkspace.d[96];
+acadoWorkspace.sbar[102] = acadoWorkspace.d[97];
+acadoWorkspace.sbar[103] = acadoWorkspace.d[98];
+acadoWorkspace.sbar[104] = acadoWorkspace.d[99];
+
+for (lRun1 = 0; lRun1 < 40; ++lRun1)
+{
+lRun3 = xBoundIndices[ lRun1 ] - 5;
+lRun4 = ((lRun3) / (5)) + (1);
+for (lRun2 = 0; lRun2 < lRun4; ++lRun2)
+{
+lRun5 = ((((((lRun2) * (lRun2 * -1 + 39)) / (2)) + (lRun4)) - (1)) * (5)) + ((lRun3) % (5));
+acadoWorkspace.A[(lRun1 * 40) + (lRun2 * 2)] = acadoWorkspace.E[lRun5 * 2];
+acadoWorkspace.A[(lRun1 * 40) + (lRun2 * 2 + 1)] = acadoWorkspace.E[lRun5 * 2 + 1];
+}
+}
+
+for (lRun1 = 0; lRun1 < 20; ++lRun1)
+{
+acadoWorkspace.conValueIn[0] = acadoVariables.x[lRun1 * 5];
+acadoWorkspace.conValueIn[1] = acadoVariables.x[lRun1 * 5 + 1];
+acadoWorkspace.conValueIn[2] = acadoVariables.x[lRun1 * 5 + 2];
+acadoWorkspace.conValueIn[3] = acadoVariables.x[lRun1 * 5 + 3];
+acadoWorkspace.conValueIn[4] = acadoVariables.x[lRun1 * 5 + 4];
+acadoWorkspace.conValueIn[5] = acadoVariables.u[lRun1 * 2];
+acadoWorkspace.conValueIn[6] = acadoVariables.u[lRun1 * 2 + 1];
+acadoWorkspace.conValueIn[7] = acadoVariables.od[lRun1 * 20];
+acadoWorkspace.conValueIn[8] = acadoVariables.od[lRun1 * 20 + 1];
+acadoWorkspace.conValueIn[9] = acadoVariables.od[lRun1 * 20 + 2];
+acadoWorkspace.conValueIn[10] = acadoVariables.od[lRun1 * 20 + 3];
+acadoWorkspace.conValueIn[11] = acadoVariables.od[lRun1 * 20 + 4];
+acadoWorkspace.conValueIn[12] = acadoVariables.od[lRun1 * 20 + 5];
+acadoWorkspace.conValueIn[13] = acadoVariables.od[lRun1 * 20 + 6];
+acadoWorkspace.conValueIn[14] = acadoVariables.od[lRun1 * 20 + 7];
+acadoWorkspace.conValueIn[15] = acadoVariables.od[lRun1 * 20 + 8];
+acadoWorkspace.conValueIn[16] = acadoVariables.od[lRun1 * 20 + 9];
+acadoWorkspace.conValueIn[17] = acadoVariables.od[lRun1 * 20 + 10];
+acadoWorkspace.conValueIn[18] = acadoVariables.od[lRun1 * 20 + 11];
+acadoWorkspace.conValueIn[19] = acadoVariables.od[lRun1 * 20 + 12];
+acadoWorkspace.conValueIn[20] = acadoVariables.od[lRun1 * 20 + 13];
+acadoWorkspace.conValueIn[21] = acadoVariables.od[lRun1 * 20 + 14];
+acadoWorkspace.conValueIn[22] = acadoVariables.od[lRun1 * 20 + 15];
+acadoWorkspace.conValueIn[23] = acadoVariables.od[lRun1 * 20 + 16];
+acadoWorkspace.conValueIn[24] = acadoVariables.od[lRun1 * 20 + 17];
+acadoWorkspace.conValueIn[25] = acadoVariables.od[lRun1 * 20 + 18];
+acadoWorkspace.conValueIn[26] = acadoVariables.od[lRun1 * 20 + 19];
+acado_evaluatePathConstraints( acadoWorkspace.conValueIn, acadoWorkspace.conValueOut );
+acadoWorkspace.evH[lRun1 * 10] = acadoWorkspace.conValueOut[0];
+acadoWorkspace.evH[lRun1 * 10 + 1] = acadoWorkspace.conValueOut[1];
+acadoWorkspace.evH[lRun1 * 10 + 2] = acadoWorkspace.conValueOut[2];
+acadoWorkspace.evH[lRun1 * 10 + 3] = acadoWorkspace.conValueOut[3];
+acadoWorkspace.evH[lRun1 * 10 + 4] = acadoWorkspace.conValueOut[4];
+acadoWorkspace.evH[lRun1 * 10 + 5] = acadoWorkspace.conValueOut[5];
+acadoWorkspace.evH[lRun1 * 10 + 6] = acadoWorkspace.conValueOut[6];
+acadoWorkspace.evH[lRun1 * 10 + 7] = acadoWorkspace.conValueOut[7];
+acadoWorkspace.evH[lRun1 * 10 + 8] = acadoWorkspace.conValueOut[8];
+acadoWorkspace.evH[lRun1 * 10 + 9] = acadoWorkspace.conValueOut[9];
+
+acadoWorkspace.evHx[lRun1 * 50] = acadoWorkspace.conValueOut[10];
+acadoWorkspace.evHx[lRun1 * 50 + 1] = acadoWorkspace.conValueOut[11];
+acadoWorkspace.evHx[lRun1 * 50 + 2] = acadoWorkspace.conValueOut[12];
+acadoWorkspace.evHx[lRun1 * 50 + 3] = acadoWorkspace.conValueOut[13];
+acadoWorkspace.evHx[lRun1 * 50 + 4] = acadoWorkspace.conValueOut[14];
+acadoWorkspace.evHx[lRun1 * 50 + 5] = acadoWorkspace.conValueOut[15];
+acadoWorkspace.evHx[lRun1 * 50 + 6] = acadoWorkspace.conValueOut[16];
+acadoWorkspace.evHx[lRun1 * 50 + 7] = acadoWorkspace.conValueOut[17];
+acadoWorkspace.evHx[lRun1 * 50 + 8] = acadoWorkspace.conValueOut[18];
+acadoWorkspace.evHx[lRun1 * 50 + 9] = acadoWorkspace.conValueOut[19];
+acadoWorkspace.evHx[lRun1 * 50 + 10] = acadoWorkspace.conValueOut[20];
+acadoWorkspace.evHx[lRun1 * 50 + 11] = acadoWorkspace.conValueOut[21];
+acadoWorkspace.evHx[lRun1 * 50 + 12] = acadoWorkspace.conValueOut[22];
+acadoWorkspace.evHx[lRun1 * 50 + 13] = acadoWorkspace.conValueOut[23];
+acadoWorkspace.evHx[lRun1 * 50 + 14] = acadoWorkspace.conValueOut[24];
+acadoWorkspace.evHx[lRun1 * 50 + 15] = acadoWorkspace.conValueOut[25];
+acadoWorkspace.evHx[lRun1 * 50 + 16] = acadoWorkspace.conValueOut[26];
+acadoWorkspace.evHx[lRun1 * 50 + 17] = acadoWorkspace.conValueOut[27];
+acadoWorkspace.evHx[lRun1 * 50 + 18] = acadoWorkspace.conValueOut[28];
+acadoWorkspace.evHx[lRun1 * 50 + 19] = acadoWorkspace.conValueOut[29];
+acadoWorkspace.evHx[lRun1 * 50 + 20] = acadoWorkspace.conValueOut[30];
+acadoWorkspace.evHx[lRun1 * 50 + 21] = acadoWorkspace.conValueOut[31];
+acadoWorkspace.evHx[lRun1 * 50 + 22] = acadoWorkspace.conValueOut[32];
+acadoWorkspace.evHx[lRun1 * 50 + 23] = acadoWorkspace.conValueOut[33];
+acadoWorkspace.evHx[lRun1 * 50 + 24] = acadoWorkspace.conValueOut[34];
+acadoWorkspace.evHx[lRun1 * 50 + 25] = acadoWorkspace.conValueOut[35];
+acadoWorkspace.evHx[lRun1 * 50 + 26] = acadoWorkspace.conValueOut[36];
+acadoWorkspace.evHx[lRun1 * 50 + 27] = acadoWorkspace.conValueOut[37];
+acadoWorkspace.evHx[lRun1 * 50 + 28] = acadoWorkspace.conValueOut[38];
+acadoWorkspace.evHx[lRun1 * 50 + 29] = acadoWorkspace.conValueOut[39];
+acadoWorkspace.evHx[lRun1 * 50 + 30] = acadoWorkspace.conValueOut[40];
+acadoWorkspace.evHx[lRun1 * 50 + 31] = acadoWorkspace.conValueOut[41];
+acadoWorkspace.evHx[lRun1 * 50 + 32] = acadoWorkspace.conValueOut[42];
+acadoWorkspace.evHx[lRun1 * 50 + 33] = acadoWorkspace.conValueOut[43];
+acadoWorkspace.evHx[lRun1 * 50 + 34] = acadoWorkspace.conValueOut[44];
+acadoWorkspace.evHx[lRun1 * 50 + 35] = acadoWorkspace.conValueOut[45];
+acadoWorkspace.evHx[lRun1 * 50 + 36] = acadoWorkspace.conValueOut[46];
+acadoWorkspace.evHx[lRun1 * 50 + 37] = acadoWorkspace.conValueOut[47];
+acadoWorkspace.evHx[lRun1 * 50 + 38] = acadoWorkspace.conValueOut[48];
+acadoWorkspace.evHx[lRun1 * 50 + 39] = acadoWorkspace.conValueOut[49];
+acadoWorkspace.evHx[lRun1 * 50 + 40] = acadoWorkspace.conValueOut[50];
+acadoWorkspace.evHx[lRun1 * 50 + 41] = acadoWorkspace.conValueOut[51];
+acadoWorkspace.evHx[lRun1 * 50 + 42] = acadoWorkspace.conValueOut[52];
+acadoWorkspace.evHx[lRun1 * 50 + 43] = acadoWorkspace.conValueOut[53];
+acadoWorkspace.evHx[lRun1 * 50 + 44] = acadoWorkspace.conValueOut[54];
+acadoWorkspace.evHx[lRun1 * 50 + 45] = acadoWorkspace.conValueOut[55];
+acadoWorkspace.evHx[lRun1 * 50 + 46] = acadoWorkspace.conValueOut[56];
+acadoWorkspace.evHx[lRun1 * 50 + 47] = acadoWorkspace.conValueOut[57];
+acadoWorkspace.evHx[lRun1 * 50 + 48] = acadoWorkspace.conValueOut[58];
+acadoWorkspace.evHx[lRun1 * 50 + 49] = acadoWorkspace.conValueOut[59];
+acadoWorkspace.evHu[lRun1 * 20] = acadoWorkspace.conValueOut[60];
+acadoWorkspace.evHu[lRun1 * 20 + 1] = acadoWorkspace.conValueOut[61];
+acadoWorkspace.evHu[lRun1 * 20 + 2] = acadoWorkspace.conValueOut[62];
+acadoWorkspace.evHu[lRun1 * 20 + 3] = acadoWorkspace.conValueOut[63];
+acadoWorkspace.evHu[lRun1 * 20 + 4] = acadoWorkspace.conValueOut[64];
+acadoWorkspace.evHu[lRun1 * 20 + 5] = acadoWorkspace.conValueOut[65];
+acadoWorkspace.evHu[lRun1 * 20 + 6] = acadoWorkspace.conValueOut[66];
+acadoWorkspace.evHu[lRun1 * 20 + 7] = acadoWorkspace.conValueOut[67];
+acadoWorkspace.evHu[lRun1 * 20 + 8] = acadoWorkspace.conValueOut[68];
+acadoWorkspace.evHu[lRun1 * 20 + 9] = acadoWorkspace.conValueOut[69];
+acadoWorkspace.evHu[lRun1 * 20 + 10] = acadoWorkspace.conValueOut[70];
+acadoWorkspace.evHu[lRun1 * 20 + 11] = acadoWorkspace.conValueOut[71];
+acadoWorkspace.evHu[lRun1 * 20 + 12] = acadoWorkspace.conValueOut[72];
+acadoWorkspace.evHu[lRun1 * 20 + 13] = acadoWorkspace.conValueOut[73];
+acadoWorkspace.evHu[lRun1 * 20 + 14] = acadoWorkspace.conValueOut[74];
+acadoWorkspace.evHu[lRun1 * 20 + 15] = acadoWorkspace.conValueOut[75];
+acadoWorkspace.evHu[lRun1 * 20 + 16] = acadoWorkspace.conValueOut[76];
+acadoWorkspace.evHu[lRun1 * 20 + 17] = acadoWorkspace.conValueOut[77];
+acadoWorkspace.evHu[lRun1 * 20 + 18] = acadoWorkspace.conValueOut[78];
+acadoWorkspace.evHu[lRun1 * 20 + 19] = acadoWorkspace.conValueOut[79];
+}
+
+
+
+acado_multHxE( &(acadoWorkspace.evHx[ 50 ]), acadoWorkspace.E, 1, 0 );
+acado_multHxE( &(acadoWorkspace.evHx[ 100 ]), &(acadoWorkspace.E[ 10 ]), 2, 0 );
+acado_multHxE( &(acadoWorkspace.evHx[ 100 ]), &(acadoWorkspace.E[ 200 ]), 2, 1 );
+acado_multHxE( &(acadoWorkspace.evHx[ 150 ]), &(acadoWorkspace.E[ 20 ]), 3, 0 );
+acado_multHxE( &(acadoWorkspace.evHx[ 150 ]), &(acadoWorkspace.E[ 210 ]), 3, 1 );
+acado_multHxE( &(acadoWorkspace.evHx[ 150 ]), &(acadoWorkspace.E[ 390 ]), 3, 2 );
+acado_multHxE( &(acadoWorkspace.evHx[ 200 ]), &(acadoWorkspace.E[ 30 ]), 4, 0 );
+acado_multHxE( &(acadoWorkspace.evHx[ 200 ]), &(acadoWorkspace.E[ 220 ]), 4, 1 );
+acado_multHxE( &(acadoWorkspace.evHx[ 200 ]), &(acadoWorkspace.E[ 400 ]), 4, 2 );
+acado_multHxE( &(acadoWorkspace.evHx[ 200 ]), &(acadoWorkspace.E[ 570 ]), 4, 3 );
+acado_multHxE( &(acadoWorkspace.evHx[ 250 ]), &(acadoWorkspace.E[ 40 ]), 5, 0 );
+acado_multHxE( &(acadoWorkspace.evHx[ 250 ]), &(acadoWorkspace.E[ 230 ]), 5, 1 );
+acado_multHxE( &(acadoWorkspace.evHx[ 250 ]), &(acadoWorkspace.E[ 410 ]), 5, 2 );
+acado_multHxE( &(acadoWorkspace.evHx[ 250 ]), &(acadoWorkspace.E[ 580 ]), 5, 3 );
+acado_multHxE( &(acadoWorkspace.evHx[ 250 ]), &(acadoWorkspace.E[ 740 ]), 5, 4 );
+acado_multHxE( &(acadoWorkspace.evHx[ 300 ]), &(acadoWorkspace.E[ 50 ]), 6, 0 );
+acado_multHxE( &(acadoWorkspace.evHx[ 300 ]), &(acadoWorkspace.E[ 240 ]), 6, 1 );
+acado_multHxE( &(acadoWorkspace.evHx[ 300 ]), &(acadoWorkspace.E[ 420 ]), 6, 2 );
+acado_multHxE( &(acadoWorkspace.evHx[ 300 ]), &(acadoWorkspace.E[ 590 ]), 6, 3 );
+acado_multHxE( &(acadoWorkspace.evHx[ 300 ]), &(acadoWorkspace.E[ 750 ]), 6, 4 );
+acado_multHxE( &(acadoWorkspace.evHx[ 300 ]), &(acadoWorkspace.E[ 900 ]), 6, 5 );
+acado_multHxE( &(acadoWorkspace.evHx[ 350 ]), &(acadoWorkspace.E[ 60 ]), 7, 0 );
+acado_multHxE( &(acadoWorkspace.evHx[ 350 ]), &(acadoWorkspace.E[ 250 ]), 7, 1 );
+acado_multHxE( &(acadoWorkspace.evHx[ 350 ]), &(acadoWorkspace.E[ 430 ]), 7, 2 );
+acado_multHxE( &(acadoWorkspace.evHx[ 350 ]), &(acadoWorkspace.E[ 600 ]), 7, 3 );
+acado_multHxE( &(acadoWorkspace.evHx[ 350 ]), &(acadoWorkspace.E[ 760 ]), 7, 4 );
+acado_multHxE( &(acadoWorkspace.evHx[ 350 ]), &(acadoWorkspace.E[ 910 ]), 7, 5 );
+acado_multHxE( &(acadoWorkspace.evHx[ 350 ]), &(acadoWorkspace.E[ 1050 ]), 7, 6 );
+acado_multHxE( &(acadoWorkspace.evHx[ 400 ]), &(acadoWorkspace.E[ 70 ]), 8, 0 );
+acado_multHxE( &(acadoWorkspace.evHx[ 400 ]), &(acadoWorkspace.E[ 260 ]), 8, 1 );
+acado_multHxE( &(acadoWorkspace.evHx[ 400 ]), &(acadoWorkspace.E[ 440 ]), 8, 2 );
+acado_multHxE( &(acadoWorkspace.evHx[ 400 ]), &(acadoWorkspace.E[ 610 ]), 8, 3 );
+acado_multHxE( &(acadoWorkspace.evHx[ 400 ]), &(acadoWorkspace.E[ 770 ]), 8, 4 );
+acado_multHxE( &(acadoWorkspace.evHx[ 400 ]), &(acadoWorkspace.E[ 920 ]), 8, 5 );
+acado_multHxE( &(acadoWorkspace.evHx[ 400 ]), &(acadoWorkspace.E[ 1060 ]), 8, 6 );
+acado_multHxE( &(acadoWorkspace.evHx[ 400 ]), &(acadoWorkspace.E[ 1190 ]), 8, 7 );
+acado_multHxE( &(acadoWorkspace.evHx[ 450 ]), &(acadoWorkspace.E[ 80 ]), 9, 0 );
+acado_multHxE( &(acadoWorkspace.evHx[ 450 ]), &(acadoWorkspace.E[ 270 ]), 9, 1 );
+acado_multHxE( &(acadoWorkspace.evHx[ 450 ]), &(acadoWorkspace.E[ 450 ]), 9, 2 );
+acado_multHxE( &(acadoWorkspace.evHx[ 450 ]), &(acadoWorkspace.E[ 620 ]), 9, 3 );
+acado_multHxE( &(acadoWorkspace.evHx[ 450 ]), &(acadoWorkspace.E[ 780 ]), 9, 4 );
+acado_multHxE( &(acadoWorkspace.evHx[ 450 ]), &(acadoWorkspace.E[ 930 ]), 9, 5 );
+acado_multHxE( &(acadoWorkspace.evHx[ 450 ]), &(acadoWorkspace.E[ 1070 ]), 9, 6 );
+acado_multHxE( &(acadoWorkspace.evHx[ 450 ]), &(acadoWorkspace.E[ 1200 ]), 9, 7 );
+acado_multHxE( &(acadoWorkspace.evHx[ 450 ]), &(acadoWorkspace.E[ 1320 ]), 9, 8 );
+acado_multHxE( &(acadoWorkspace.evHx[ 500 ]), &(acadoWorkspace.E[ 90 ]), 10, 0 );
+acado_multHxE( &(acadoWorkspace.evHx[ 500 ]), &(acadoWorkspace.E[ 280 ]), 10, 1 );
+acado_multHxE( &(acadoWorkspace.evHx[ 500 ]), &(acadoWorkspace.E[ 460 ]), 10, 2 );
+acado_multHxE( &(acadoWorkspace.evHx[ 500 ]), &(acadoWorkspace.E[ 630 ]), 10, 3 );
+acado_multHxE( &(acadoWorkspace.evHx[ 500 ]), &(acadoWorkspace.E[ 790 ]), 10, 4 );
+acado_multHxE( &(acadoWorkspace.evHx[ 500 ]), &(acadoWorkspace.E[ 940 ]), 10, 5 );
+acado_multHxE( &(acadoWorkspace.evHx[ 500 ]), &(acadoWorkspace.E[ 1080 ]), 10, 6 );
+acado_multHxE( &(acadoWorkspace.evHx[ 500 ]), &(acadoWorkspace.E[ 1210 ]), 10, 7 );
+acado_multHxE( &(acadoWorkspace.evHx[ 500 ]), &(acadoWorkspace.E[ 1330 ]), 10, 8 );
+acado_multHxE( &(acadoWorkspace.evHx[ 500 ]), &(acadoWorkspace.E[ 1440 ]), 10, 9 );
+acado_multHxE( &(acadoWorkspace.evHx[ 550 ]), &(acadoWorkspace.E[ 100 ]), 11, 0 );
+acado_multHxE( &(acadoWorkspace.evHx[ 550 ]), &(acadoWorkspace.E[ 290 ]), 11, 1 );
+acado_multHxE( &(acadoWorkspace.evHx[ 550 ]), &(acadoWorkspace.E[ 470 ]), 11, 2 );
+acado_multHxE( &(acadoWorkspace.evHx[ 550 ]), &(acadoWorkspace.E[ 640 ]), 11, 3 );
+acado_multHxE( &(acadoWorkspace.evHx[ 550 ]), &(acadoWorkspace.E[ 800 ]), 11, 4 );
+acado_multHxE( &(acadoWorkspace.evHx[ 550 ]), &(acadoWorkspace.E[ 950 ]), 11, 5 );
+acado_multHxE( &(acadoWorkspace.evHx[ 550 ]), &(acadoWorkspace.E[ 1090 ]), 11, 6 );
+acado_multHxE( &(acadoWorkspace.evHx[ 550 ]), &(acadoWorkspace.E[ 1220 ]), 11, 7 );
+acado_multHxE( &(acadoWorkspace.evHx[ 550 ]), &(acadoWorkspace.E[ 1340 ]), 11, 8 );
+acado_multHxE( &(acadoWorkspace.evHx[ 550 ]), &(acadoWorkspace.E[ 1450 ]), 11, 9 );
+acado_multHxE( &(acadoWorkspace.evHx[ 550 ]), &(acadoWorkspace.E[ 1550 ]), 11, 10 );
+acado_multHxE( &(acadoWorkspace.evHx[ 600 ]), &(acadoWorkspace.E[ 110 ]), 12, 0 );
+acado_multHxE( &(acadoWorkspace.evHx[ 600 ]), &(acadoWorkspace.E[ 300 ]), 12, 1 );
+acado_multHxE( &(acadoWorkspace.evHx[ 600 ]), &(acadoWorkspace.E[ 480 ]), 12, 2 );
+acado_multHxE( &(acadoWorkspace.evHx[ 600 ]), &(acadoWorkspace.E[ 650 ]), 12, 3 );
+acado_multHxE( &(acadoWorkspace.evHx[ 600 ]), &(acadoWorkspace.E[ 810 ]), 12, 4 );
+acado_multHxE( &(acadoWorkspace.evHx[ 600 ]), &(acadoWorkspace.E[ 960 ]), 12, 5 );
+acado_multHxE( &(acadoWorkspace.evHx[ 600 ]), &(acadoWorkspace.E[ 1100 ]), 12, 6 );
+acado_multHxE( &(acadoWorkspace.evHx[ 600 ]), &(acadoWorkspace.E[ 1230 ]), 12, 7 );
+acado_multHxE( &(acadoWorkspace.evHx[ 600 ]), &(acadoWorkspace.E[ 1350 ]), 12, 8 );
+acado_multHxE( &(acadoWorkspace.evHx[ 600 ]), &(acadoWorkspace.E[ 1460 ]), 12, 9 );
+acado_multHxE( &(acadoWorkspace.evHx[ 600 ]), &(acadoWorkspace.E[ 1560 ]), 12, 10 );
+acado_multHxE( &(acadoWorkspace.evHx[ 600 ]), &(acadoWorkspace.E[ 1650 ]), 12, 11 );
+acado_multHxE( &(acadoWorkspace.evHx[ 650 ]), &(acadoWorkspace.E[ 120 ]), 13, 0 );
+acado_multHxE( &(acadoWorkspace.evHx[ 650 ]), &(acadoWorkspace.E[ 310 ]), 13, 1 );
+acado_multHxE( &(acadoWorkspace.evHx[ 650 ]), &(acadoWorkspace.E[ 490 ]), 13, 2 );
+acado_multHxE( &(acadoWorkspace.evHx[ 650 ]), &(acadoWorkspace.E[ 660 ]), 13, 3 );
+acado_multHxE( &(acadoWorkspace.evHx[ 650 ]), &(acadoWorkspace.E[ 820 ]), 13, 4 );
+acado_multHxE( &(acadoWorkspace.evHx[ 650 ]), &(acadoWorkspace.E[ 970 ]), 13, 5 );
+acado_multHxE( &(acadoWorkspace.evHx[ 650 ]), &(acadoWorkspace.E[ 1110 ]), 13, 6 );
+acado_multHxE( &(acadoWorkspace.evHx[ 650 ]), &(acadoWorkspace.E[ 1240 ]), 13, 7 );
+acado_multHxE( &(acadoWorkspace.evHx[ 650 ]), &(acadoWorkspace.E[ 1360 ]), 13, 8 );
+acado_multHxE( &(acadoWorkspace.evHx[ 650 ]), &(acadoWorkspace.E[ 1470 ]), 13, 9 );
+acado_multHxE( &(acadoWorkspace.evHx[ 650 ]), &(acadoWorkspace.E[ 1570 ]), 13, 10 );
+acado_multHxE( &(acadoWorkspace.evHx[ 650 ]), &(acadoWorkspace.E[ 1660 ]), 13, 11 );
+acado_multHxE( &(acadoWorkspace.evHx[ 650 ]), &(acadoWorkspace.E[ 1740 ]), 13, 12 );
+acado_multHxE( &(acadoWorkspace.evHx[ 700 ]), &(acadoWorkspace.E[ 130 ]), 14, 0 );
+acado_multHxE( &(acadoWorkspace.evHx[ 700 ]), &(acadoWorkspace.E[ 320 ]), 14, 1 );
+acado_multHxE( &(acadoWorkspace.evHx[ 700 ]), &(acadoWorkspace.E[ 500 ]), 14, 2 );
+acado_multHxE( &(acadoWorkspace.evHx[ 700 ]), &(acadoWorkspace.E[ 670 ]), 14, 3 );
+acado_multHxE( &(acadoWorkspace.evHx[ 700 ]), &(acadoWorkspace.E[ 830 ]), 14, 4 );
+acado_multHxE( &(acadoWorkspace.evHx[ 700 ]), &(acadoWorkspace.E[ 980 ]), 14, 5 );
+acado_multHxE( &(acadoWorkspace.evHx[ 700 ]), &(acadoWorkspace.E[ 1120 ]), 14, 6 );
+acado_multHxE( &(acadoWorkspace.evHx[ 700 ]), &(acadoWorkspace.E[ 1250 ]), 14, 7 );
+acado_multHxE( &(acadoWorkspace.evHx[ 700 ]), &(acadoWorkspace.E[ 1370 ]), 14, 8 );
+acado_multHxE( &(acadoWorkspace.evHx[ 700 ]), &(acadoWorkspace.E[ 1480 ]), 14, 9 );
+acado_multHxE( &(acadoWorkspace.evHx[ 700 ]), &(acadoWorkspace.E[ 1580 ]), 14, 10 );
+acado_multHxE( &(acadoWorkspace.evHx[ 700 ]), &(acadoWorkspace.E[ 1670 ]), 14, 11 );
+acado_multHxE( &(acadoWorkspace.evHx[ 700 ]), &(acadoWorkspace.E[ 1750 ]), 14, 12 );
+acado_multHxE( &(acadoWorkspace.evHx[ 700 ]), &(acadoWorkspace.E[ 1820 ]), 14, 13 );
+acado_multHxE( &(acadoWorkspace.evHx[ 750 ]), &(acadoWorkspace.E[ 140 ]), 15, 0 );
+acado_multHxE( &(acadoWorkspace.evHx[ 750 ]), &(acadoWorkspace.E[ 330 ]), 15, 1 );
+acado_multHxE( &(acadoWorkspace.evHx[ 750 ]), &(acadoWorkspace.E[ 510 ]), 15, 2 );
+acado_multHxE( &(acadoWorkspace.evHx[ 750 ]), &(acadoWorkspace.E[ 680 ]), 15, 3 );
+acado_multHxE( &(acadoWorkspace.evHx[ 750 ]), &(acadoWorkspace.E[ 840 ]), 15, 4 );
+acado_multHxE( &(acadoWorkspace.evHx[ 750 ]), &(acadoWorkspace.E[ 990 ]), 15, 5 );
+acado_multHxE( &(acadoWorkspace.evHx[ 750 ]), &(acadoWorkspace.E[ 1130 ]), 15, 6 );
+acado_multHxE( &(acadoWorkspace.evHx[ 750 ]), &(acadoWorkspace.E[ 1260 ]), 15, 7 );
+acado_multHxE( &(acadoWorkspace.evHx[ 750 ]), &(acadoWorkspace.E[ 1380 ]), 15, 8 );
+acado_multHxE( &(acadoWorkspace.evHx[ 750 ]), &(acadoWorkspace.E[ 1490 ]), 15, 9 );
+acado_multHxE( &(acadoWorkspace.evHx[ 750 ]), &(acadoWorkspace.E[ 1590 ]), 15, 10 );
+acado_multHxE( &(acadoWorkspace.evHx[ 750 ]), &(acadoWorkspace.E[ 1680 ]), 15, 11 );
+acado_multHxE( &(acadoWorkspace.evHx[ 750 ]), &(acadoWorkspace.E[ 1760 ]), 15, 12 );
+acado_multHxE( &(acadoWorkspace.evHx[ 750 ]), &(acadoWorkspace.E[ 1830 ]), 15, 13 );
+acado_multHxE( &(acadoWorkspace.evHx[ 750 ]), &(acadoWorkspace.E[ 1890 ]), 15, 14 );
+acado_multHxE( &(acadoWorkspace.evHx[ 800 ]), &(acadoWorkspace.E[ 150 ]), 16, 0 );
+acado_multHxE( &(acadoWorkspace.evHx[ 800 ]), &(acadoWorkspace.E[ 340 ]), 16, 1 );
+acado_multHxE( &(acadoWorkspace.evHx[ 800 ]), &(acadoWorkspace.E[ 520 ]), 16, 2 );
+acado_multHxE( &(acadoWorkspace.evHx[ 800 ]), &(acadoWorkspace.E[ 690 ]), 16, 3 );
+acado_multHxE( &(acadoWorkspace.evHx[ 800 ]), &(acadoWorkspace.E[ 850 ]), 16, 4 );
+acado_multHxE( &(acadoWorkspace.evHx[ 800 ]), &(acadoWorkspace.E[ 1000 ]), 16, 5 );
+acado_multHxE( &(acadoWorkspace.evHx[ 800 ]), &(acadoWorkspace.E[ 1140 ]), 16, 6 );
+acado_multHxE( &(acadoWorkspace.evHx[ 800 ]), &(acadoWorkspace.E[ 1270 ]), 16, 7 );
+acado_multHxE( &(acadoWorkspace.evHx[ 800 ]), &(acadoWorkspace.E[ 1390 ]), 16, 8 );
+acado_multHxE( &(acadoWorkspace.evHx[ 800 ]), &(acadoWorkspace.E[ 1500 ]), 16, 9 );
+acado_multHxE( &(acadoWorkspace.evHx[ 800 ]), &(acadoWorkspace.E[ 1600 ]), 16, 10 );
+acado_multHxE( &(acadoWorkspace.evHx[ 800 ]), &(acadoWorkspace.E[ 1690 ]), 16, 11 );
+acado_multHxE( &(acadoWorkspace.evHx[ 800 ]), &(acadoWorkspace.E[ 1770 ]), 16, 12 );
+acado_multHxE( &(acadoWorkspace.evHx[ 800 ]), &(acadoWorkspace.E[ 1840 ]), 16, 13 );
+acado_multHxE( &(acadoWorkspace.evHx[ 800 ]), &(acadoWorkspace.E[ 1900 ]), 16, 14 );
+acado_multHxE( &(acadoWorkspace.evHx[ 800 ]), &(acadoWorkspace.E[ 1950 ]), 16, 15 );
+acado_multHxE( &(acadoWorkspace.evHx[ 850 ]), &(acadoWorkspace.E[ 160 ]), 17, 0 );
+acado_multHxE( &(acadoWorkspace.evHx[ 850 ]), &(acadoWorkspace.E[ 350 ]), 17, 1 );
+acado_multHxE( &(acadoWorkspace.evHx[ 850 ]), &(acadoWorkspace.E[ 530 ]), 17, 2 );
+acado_multHxE( &(acadoWorkspace.evHx[ 850 ]), &(acadoWorkspace.E[ 700 ]), 17, 3 );
+acado_multHxE( &(acadoWorkspace.evHx[ 850 ]), &(acadoWorkspace.E[ 860 ]), 17, 4 );
+acado_multHxE( &(acadoWorkspace.evHx[ 850 ]), &(acadoWorkspace.E[ 1010 ]), 17, 5 );
+acado_multHxE( &(acadoWorkspace.evHx[ 850 ]), &(acadoWorkspace.E[ 1150 ]), 17, 6 );
+acado_multHxE( &(acadoWorkspace.evHx[ 850 ]), &(acadoWorkspace.E[ 1280 ]), 17, 7 );
+acado_multHxE( &(acadoWorkspace.evHx[ 850 ]), &(acadoWorkspace.E[ 1400 ]), 17, 8 );
+acado_multHxE( &(acadoWorkspace.evHx[ 850 ]), &(acadoWorkspace.E[ 1510 ]), 17, 9 );
+acado_multHxE( &(acadoWorkspace.evHx[ 850 ]), &(acadoWorkspace.E[ 1610 ]), 17, 10 );
+acado_multHxE( &(acadoWorkspace.evHx[ 850 ]), &(acadoWorkspace.E[ 1700 ]), 17, 11 );
+acado_multHxE( &(acadoWorkspace.evHx[ 850 ]), &(acadoWorkspace.E[ 1780 ]), 17, 12 );
+acado_multHxE( &(acadoWorkspace.evHx[ 850 ]), &(acadoWorkspace.E[ 1850 ]), 17, 13 );
+acado_multHxE( &(acadoWorkspace.evHx[ 850 ]), &(acadoWorkspace.E[ 1910 ]), 17, 14 );
+acado_multHxE( &(acadoWorkspace.evHx[ 850 ]), &(acadoWorkspace.E[ 1960 ]), 17, 15 );
+acado_multHxE( &(acadoWorkspace.evHx[ 850 ]), &(acadoWorkspace.E[ 2000 ]), 17, 16 );
+acado_multHxE( &(acadoWorkspace.evHx[ 900 ]), &(acadoWorkspace.E[ 170 ]), 18, 0 );
+acado_multHxE( &(acadoWorkspace.evHx[ 900 ]), &(acadoWorkspace.E[ 360 ]), 18, 1 );
+acado_multHxE( &(acadoWorkspace.evHx[ 900 ]), &(acadoWorkspace.E[ 540 ]), 18, 2 );
+acado_multHxE( &(acadoWorkspace.evHx[ 900 ]), &(acadoWorkspace.E[ 710 ]), 18, 3 );
+acado_multHxE( &(acadoWorkspace.evHx[ 900 ]), &(acadoWorkspace.E[ 870 ]), 18, 4 );
+acado_multHxE( &(acadoWorkspace.evHx[ 900 ]), &(acadoWorkspace.E[ 1020 ]), 18, 5 );
+acado_multHxE( &(acadoWorkspace.evHx[ 900 ]), &(acadoWorkspace.E[ 1160 ]), 18, 6 );
+acado_multHxE( &(acadoWorkspace.evHx[ 900 ]), &(acadoWorkspace.E[ 1290 ]), 18, 7 );
+acado_multHxE( &(acadoWorkspace.evHx[ 900 ]), &(acadoWorkspace.E[ 1410 ]), 18, 8 );
+acado_multHxE( &(acadoWorkspace.evHx[ 900 ]), &(acadoWorkspace.E[ 1520 ]), 18, 9 );
+acado_multHxE( &(acadoWorkspace.evHx[ 900 ]), &(acadoWorkspace.E[ 1620 ]), 18, 10 );
+acado_multHxE( &(acadoWorkspace.evHx[ 900 ]), &(acadoWorkspace.E[ 1710 ]), 18, 11 );
+acado_multHxE( &(acadoWorkspace.evHx[ 900 ]), &(acadoWorkspace.E[ 1790 ]), 18, 12 );
+acado_multHxE( &(acadoWorkspace.evHx[ 900 ]), &(acadoWorkspace.E[ 1860 ]), 18, 13 );
+acado_multHxE( &(acadoWorkspace.evHx[ 900 ]), &(acadoWorkspace.E[ 1920 ]), 18, 14 );
+acado_multHxE( &(acadoWorkspace.evHx[ 900 ]), &(acadoWorkspace.E[ 1970 ]), 18, 15 );
+acado_multHxE( &(acadoWorkspace.evHx[ 900 ]), &(acadoWorkspace.E[ 2010 ]), 18, 16 );
+acado_multHxE( &(acadoWorkspace.evHx[ 900 ]), &(acadoWorkspace.E[ 2040 ]), 18, 17 );
+acado_multHxE( &(acadoWorkspace.evHx[ 950 ]), &(acadoWorkspace.E[ 180 ]), 19, 0 );
+acado_multHxE( &(acadoWorkspace.evHx[ 950 ]), &(acadoWorkspace.E[ 370 ]), 19, 1 );
+acado_multHxE( &(acadoWorkspace.evHx[ 950 ]), &(acadoWorkspace.E[ 550 ]), 19, 2 );
+acado_multHxE( &(acadoWorkspace.evHx[ 950 ]), &(acadoWorkspace.E[ 720 ]), 19, 3 );
+acado_multHxE( &(acadoWorkspace.evHx[ 950 ]), &(acadoWorkspace.E[ 880 ]), 19, 4 );
+acado_multHxE( &(acadoWorkspace.evHx[ 950 ]), &(acadoWorkspace.E[ 1030 ]), 19, 5 );
+acado_multHxE( &(acadoWorkspace.evHx[ 950 ]), &(acadoWorkspace.E[ 1170 ]), 19, 6 );
+acado_multHxE( &(acadoWorkspace.evHx[ 950 ]), &(acadoWorkspace.E[ 1300 ]), 19, 7 );
+acado_multHxE( &(acadoWorkspace.evHx[ 950 ]), &(acadoWorkspace.E[ 1420 ]), 19, 8 );
+acado_multHxE( &(acadoWorkspace.evHx[ 950 ]), &(acadoWorkspace.E[ 1530 ]), 19, 9 );
+acado_multHxE( &(acadoWorkspace.evHx[ 950 ]), &(acadoWorkspace.E[ 1630 ]), 19, 10 );
+acado_multHxE( &(acadoWorkspace.evHx[ 950 ]), &(acadoWorkspace.E[ 1720 ]), 19, 11 );
+acado_multHxE( &(acadoWorkspace.evHx[ 950 ]), &(acadoWorkspace.E[ 1800 ]), 19, 12 );
+acado_multHxE( &(acadoWorkspace.evHx[ 950 ]), &(acadoWorkspace.E[ 1870 ]), 19, 13 );
+acado_multHxE( &(acadoWorkspace.evHx[ 950 ]), &(acadoWorkspace.E[ 1930 ]), 19, 14 );
+acado_multHxE( &(acadoWorkspace.evHx[ 950 ]), &(acadoWorkspace.E[ 1980 ]), 19, 15 );
+acado_multHxE( &(acadoWorkspace.evHx[ 950 ]), &(acadoWorkspace.E[ 2020 ]), 19, 16 );
+acado_multHxE( &(acadoWorkspace.evHx[ 950 ]), &(acadoWorkspace.E[ 2050 ]), 19, 17 );
+acado_multHxE( &(acadoWorkspace.evHx[ 950 ]), &(acadoWorkspace.E[ 2070 ]), 19, 18 );
+
+acadoWorkspace.A[1600] = acadoWorkspace.evHu[0];
+acadoWorkspace.A[1601] = acadoWorkspace.evHu[1];
+acadoWorkspace.A[1640] = acadoWorkspace.evHu[2];
+acadoWorkspace.A[1641] = acadoWorkspace.evHu[3];
+acadoWorkspace.A[1680] = acadoWorkspace.evHu[4];
+acadoWorkspace.A[1681] = acadoWorkspace.evHu[5];
+acadoWorkspace.A[1720] = acadoWorkspace.evHu[6];
+acadoWorkspace.A[1721] = acadoWorkspace.evHu[7];
+acadoWorkspace.A[1760] = acadoWorkspace.evHu[8];
+acadoWorkspace.A[1761] = acadoWorkspace.evHu[9];
+acadoWorkspace.A[1800] = acadoWorkspace.evHu[10];
+acadoWorkspace.A[1801] = acadoWorkspace.evHu[11];
+acadoWorkspace.A[1840] = acadoWorkspace.evHu[12];
+acadoWorkspace.A[1841] = acadoWorkspace.evHu[13];
+acadoWorkspace.A[1880] = acadoWorkspace.evHu[14];
+acadoWorkspace.A[1881] = acadoWorkspace.evHu[15];
+acadoWorkspace.A[1920] = acadoWorkspace.evHu[16];
+acadoWorkspace.A[1921] = acadoWorkspace.evHu[17];
+acadoWorkspace.A[1960] = acadoWorkspace.evHu[18];
+acadoWorkspace.A[1961] = acadoWorkspace.evHu[19];
+acadoWorkspace.A[2002] = acadoWorkspace.evHu[20];
+acadoWorkspace.A[2003] = acadoWorkspace.evHu[21];
+acadoWorkspace.A[2042] = acadoWorkspace.evHu[22];
+acadoWorkspace.A[2043] = acadoWorkspace.evHu[23];
+acadoWorkspace.A[2082] = acadoWorkspace.evHu[24];
+acadoWorkspace.A[2083] = acadoWorkspace.evHu[25];
+acadoWorkspace.A[2122] = acadoWorkspace.evHu[26];
+acadoWorkspace.A[2123] = acadoWorkspace.evHu[27];
+acadoWorkspace.A[2162] = acadoWorkspace.evHu[28];
+acadoWorkspace.A[2163] = acadoWorkspace.evHu[29];
+acadoWorkspace.A[2202] = acadoWorkspace.evHu[30];
+acadoWorkspace.A[2203] = acadoWorkspace.evHu[31];
+acadoWorkspace.A[2242] = acadoWorkspace.evHu[32];
+acadoWorkspace.A[2243] = acadoWorkspace.evHu[33];
+acadoWorkspace.A[2282] = acadoWorkspace.evHu[34];
+acadoWorkspace.A[2283] = acadoWorkspace.evHu[35];
+acadoWorkspace.A[2322] = acadoWorkspace.evHu[36];
+acadoWorkspace.A[2323] = acadoWorkspace.evHu[37];
+acadoWorkspace.A[2362] = acadoWorkspace.evHu[38];
+acadoWorkspace.A[2363] = acadoWorkspace.evHu[39];
+acadoWorkspace.A[2404] = acadoWorkspace.evHu[40];
+acadoWorkspace.A[2405] = acadoWorkspace.evHu[41];
+acadoWorkspace.A[2444] = acadoWorkspace.evHu[42];
+acadoWorkspace.A[2445] = acadoWorkspace.evHu[43];
+acadoWorkspace.A[2484] = acadoWorkspace.evHu[44];
+acadoWorkspace.A[2485] = acadoWorkspace.evHu[45];
+acadoWorkspace.A[2524] = acadoWorkspace.evHu[46];
+acadoWorkspace.A[2525] = acadoWorkspace.evHu[47];
+acadoWorkspace.A[2564] = acadoWorkspace.evHu[48];
+acadoWorkspace.A[2565] = acadoWorkspace.evHu[49];
+acadoWorkspace.A[2604] = acadoWorkspace.evHu[50];
+acadoWorkspace.A[2605] = acadoWorkspace.evHu[51];
+acadoWorkspace.A[2644] = acadoWorkspace.evHu[52];
+acadoWorkspace.A[2645] = acadoWorkspace.evHu[53];
+acadoWorkspace.A[2684] = acadoWorkspace.evHu[54];
+acadoWorkspace.A[2685] = acadoWorkspace.evHu[55];
+acadoWorkspace.A[2724] = acadoWorkspace.evHu[56];
+acadoWorkspace.A[2725] = acadoWorkspace.evHu[57];
+acadoWorkspace.A[2764] = acadoWorkspace.evHu[58];
+acadoWorkspace.A[2765] = acadoWorkspace.evHu[59];
+acadoWorkspace.A[2806] = acadoWorkspace.evHu[60];
+acadoWorkspace.A[2807] = acadoWorkspace.evHu[61];
+acadoWorkspace.A[2846] = acadoWorkspace.evHu[62];
+acadoWorkspace.A[2847] = acadoWorkspace.evHu[63];
+acadoWorkspace.A[2886] = acadoWorkspace.evHu[64];
+acadoWorkspace.A[2887] = acadoWorkspace.evHu[65];
+acadoWorkspace.A[2926] = acadoWorkspace.evHu[66];
+acadoWorkspace.A[2927] = acadoWorkspace.evHu[67];
+acadoWorkspace.A[2966] = acadoWorkspace.evHu[68];
+acadoWorkspace.A[2967] = acadoWorkspace.evHu[69];
+acadoWorkspace.A[3006] = acadoWorkspace.evHu[70];
+acadoWorkspace.A[3007] = acadoWorkspace.evHu[71];
+acadoWorkspace.A[3046] = acadoWorkspace.evHu[72];
+acadoWorkspace.A[3047] = acadoWorkspace.evHu[73];
+acadoWorkspace.A[3086] = acadoWorkspace.evHu[74];
+acadoWorkspace.A[3087] = acadoWorkspace.evHu[75];
+acadoWorkspace.A[3126] = acadoWorkspace.evHu[76];
+acadoWorkspace.A[3127] = acadoWorkspace.evHu[77];
+acadoWorkspace.A[3166] = acadoWorkspace.evHu[78];
+acadoWorkspace.A[3167] = acadoWorkspace.evHu[79];
+acadoWorkspace.A[3208] = acadoWorkspace.evHu[80];
+acadoWorkspace.A[3209] = acadoWorkspace.evHu[81];
+acadoWorkspace.A[3248] = acadoWorkspace.evHu[82];
+acadoWorkspace.A[3249] = acadoWorkspace.evHu[83];
+acadoWorkspace.A[3288] = acadoWorkspace.evHu[84];
+acadoWorkspace.A[3289] = acadoWorkspace.evHu[85];
+acadoWorkspace.A[3328] = acadoWorkspace.evHu[86];
+acadoWorkspace.A[3329] = acadoWorkspace.evHu[87];
+acadoWorkspace.A[3368] = acadoWorkspace.evHu[88];
+acadoWorkspace.A[3369] = acadoWorkspace.evHu[89];
+acadoWorkspace.A[3408] = acadoWorkspace.evHu[90];
+acadoWorkspace.A[3409] = acadoWorkspace.evHu[91];
+acadoWorkspace.A[3448] = acadoWorkspace.evHu[92];
+acadoWorkspace.A[3449] = acadoWorkspace.evHu[93];
+acadoWorkspace.A[3488] = acadoWorkspace.evHu[94];
+acadoWorkspace.A[3489] = acadoWorkspace.evHu[95];
+acadoWorkspace.A[3528] = acadoWorkspace.evHu[96];
+acadoWorkspace.A[3529] = acadoWorkspace.evHu[97];
+acadoWorkspace.A[3568] = acadoWorkspace.evHu[98];
+acadoWorkspace.A[3569] = acadoWorkspace.evHu[99];
+acadoWorkspace.A[3610] = acadoWorkspace.evHu[100];
+acadoWorkspace.A[3611] = acadoWorkspace.evHu[101];
+acadoWorkspace.A[3650] = acadoWorkspace.evHu[102];
+acadoWorkspace.A[3651] = acadoWorkspace.evHu[103];
+acadoWorkspace.A[3690] = acadoWorkspace.evHu[104];
+acadoWorkspace.A[3691] = acadoWorkspace.evHu[105];
+acadoWorkspace.A[3730] = acadoWorkspace.evHu[106];
+acadoWorkspace.A[3731] = acadoWorkspace.evHu[107];
+acadoWorkspace.A[3770] = acadoWorkspace.evHu[108];
+acadoWorkspace.A[3771] = acadoWorkspace.evHu[109];
+acadoWorkspace.A[3810] = acadoWorkspace.evHu[110];
+acadoWorkspace.A[3811] = acadoWorkspace.evHu[111];
+acadoWorkspace.A[3850] = acadoWorkspace.evHu[112];
+acadoWorkspace.A[3851] = acadoWorkspace.evHu[113];
+acadoWorkspace.A[3890] = acadoWorkspace.evHu[114];
+acadoWorkspace.A[3891] = acadoWorkspace.evHu[115];
+acadoWorkspace.A[3930] = acadoWorkspace.evHu[116];
+acadoWorkspace.A[3931] = acadoWorkspace.evHu[117];
+acadoWorkspace.A[3970] = acadoWorkspace.evHu[118];
+acadoWorkspace.A[3971] = acadoWorkspace.evHu[119];
+acadoWorkspace.A[4012] = acadoWorkspace.evHu[120];
+acadoWorkspace.A[4013] = acadoWorkspace.evHu[121];
+acadoWorkspace.A[4052] = acadoWorkspace.evHu[122];
+acadoWorkspace.A[4053] = acadoWorkspace.evHu[123];
+acadoWorkspace.A[4092] = acadoWorkspace.evHu[124];
+acadoWorkspace.A[4093] = acadoWorkspace.evHu[125];
+acadoWorkspace.A[4132] = acadoWorkspace.evHu[126];
+acadoWorkspace.A[4133] = acadoWorkspace.evHu[127];
+acadoWorkspace.A[4172] = acadoWorkspace.evHu[128];
+acadoWorkspace.A[4173] = acadoWorkspace.evHu[129];
+acadoWorkspace.A[4212] = acadoWorkspace.evHu[130];
+acadoWorkspace.A[4213] = acadoWorkspace.evHu[131];
+acadoWorkspace.A[4252] = acadoWorkspace.evHu[132];
+acadoWorkspace.A[4253] = acadoWorkspace.evHu[133];
+acadoWorkspace.A[4292] = acadoWorkspace.evHu[134];
+acadoWorkspace.A[4293] = acadoWorkspace.evHu[135];
+acadoWorkspace.A[4332] = acadoWorkspace.evHu[136];
+acadoWorkspace.A[4333] = acadoWorkspace.evHu[137];
+acadoWorkspace.A[4372] = acadoWorkspace.evHu[138];
+acadoWorkspace.A[4373] = acadoWorkspace.evHu[139];
+acadoWorkspace.A[4414] = acadoWorkspace.evHu[140];
+acadoWorkspace.A[4415] = acadoWorkspace.evHu[141];
+acadoWorkspace.A[4454] = acadoWorkspace.evHu[142];
+acadoWorkspace.A[4455] = acadoWorkspace.evHu[143];
+acadoWorkspace.A[4494] = acadoWorkspace.evHu[144];
+acadoWorkspace.A[4495] = acadoWorkspace.evHu[145];
+acadoWorkspace.A[4534] = acadoWorkspace.evHu[146];
+acadoWorkspace.A[4535] = acadoWorkspace.evHu[147];
+acadoWorkspace.A[4574] = acadoWorkspace.evHu[148];
+acadoWorkspace.A[4575] = acadoWorkspace.evHu[149];
+acadoWorkspace.A[4614] = acadoWorkspace.evHu[150];
+acadoWorkspace.A[4615] = acadoWorkspace.evHu[151];
+acadoWorkspace.A[4654] = acadoWorkspace.evHu[152];
+acadoWorkspace.A[4655] = acadoWorkspace.evHu[153];
+acadoWorkspace.A[4694] = acadoWorkspace.evHu[154];
+acadoWorkspace.A[4695] = acadoWorkspace.evHu[155];
+acadoWorkspace.A[4734] = acadoWorkspace.evHu[156];
+acadoWorkspace.A[4735] = acadoWorkspace.evHu[157];
+acadoWorkspace.A[4774] = acadoWorkspace.evHu[158];
+acadoWorkspace.A[4775] = acadoWorkspace.evHu[159];
+acadoWorkspace.A[4816] = acadoWorkspace.evHu[160];
+acadoWorkspace.A[4817] = acadoWorkspace.evHu[161];
+acadoWorkspace.A[4856] = acadoWorkspace.evHu[162];
+acadoWorkspace.A[4857] = acadoWorkspace.evHu[163];
+acadoWorkspace.A[4896] = acadoWorkspace.evHu[164];
+acadoWorkspace.A[4897] = acadoWorkspace.evHu[165];
+acadoWorkspace.A[4936] = acadoWorkspace.evHu[166];
+acadoWorkspace.A[4937] = acadoWorkspace.evHu[167];
+acadoWorkspace.A[4976] = acadoWorkspace.evHu[168];
+acadoWorkspace.A[4977] = acadoWorkspace.evHu[169];
+acadoWorkspace.A[5016] = acadoWorkspace.evHu[170];
+acadoWorkspace.A[5017] = acadoWorkspace.evHu[171];
+acadoWorkspace.A[5056] = acadoWorkspace.evHu[172];
+acadoWorkspace.A[5057] = acadoWorkspace.evHu[173];
+acadoWorkspace.A[5096] = acadoWorkspace.evHu[174];
+acadoWorkspace.A[5097] = acadoWorkspace.evHu[175];
+acadoWorkspace.A[5136] = acadoWorkspace.evHu[176];
+acadoWorkspace.A[5137] = acadoWorkspace.evHu[177];
+acadoWorkspace.A[5176] = acadoWorkspace.evHu[178];
+acadoWorkspace.A[5177] = acadoWorkspace.evHu[179];
+acadoWorkspace.A[5218] = acadoWorkspace.evHu[180];
+acadoWorkspace.A[5219] = acadoWorkspace.evHu[181];
+acadoWorkspace.A[5258] = acadoWorkspace.evHu[182];
+acadoWorkspace.A[5259] = acadoWorkspace.evHu[183];
+acadoWorkspace.A[5298] = acadoWorkspace.evHu[184];
+acadoWorkspace.A[5299] = acadoWorkspace.evHu[185];
+acadoWorkspace.A[5338] = acadoWorkspace.evHu[186];
+acadoWorkspace.A[5339] = acadoWorkspace.evHu[187];
+acadoWorkspace.A[5378] = acadoWorkspace.evHu[188];
+acadoWorkspace.A[5379] = acadoWorkspace.evHu[189];
+acadoWorkspace.A[5418] = acadoWorkspace.evHu[190];
+acadoWorkspace.A[5419] = acadoWorkspace.evHu[191];
+acadoWorkspace.A[5458] = acadoWorkspace.evHu[192];
+acadoWorkspace.A[5459] = acadoWorkspace.evHu[193];
+acadoWorkspace.A[5498] = acadoWorkspace.evHu[194];
+acadoWorkspace.A[5499] = acadoWorkspace.evHu[195];
+acadoWorkspace.A[5538] = acadoWorkspace.evHu[196];
+acadoWorkspace.A[5539] = acadoWorkspace.evHu[197];
+acadoWorkspace.A[5578] = acadoWorkspace.evHu[198];
+acadoWorkspace.A[5579] = acadoWorkspace.evHu[199];
+acadoWorkspace.A[5620] = acadoWorkspace.evHu[200];
+acadoWorkspace.A[5621] = acadoWorkspace.evHu[201];
+acadoWorkspace.A[5660] = acadoWorkspace.evHu[202];
+acadoWorkspace.A[5661] = acadoWorkspace.evHu[203];
+acadoWorkspace.A[5700] = acadoWorkspace.evHu[204];
+acadoWorkspace.A[5701] = acadoWorkspace.evHu[205];
+acadoWorkspace.A[5740] = acadoWorkspace.evHu[206];
+acadoWorkspace.A[5741] = acadoWorkspace.evHu[207];
+acadoWorkspace.A[5780] = acadoWorkspace.evHu[208];
+acadoWorkspace.A[5781] = acadoWorkspace.evHu[209];
+acadoWorkspace.A[5820] = acadoWorkspace.evHu[210];
+acadoWorkspace.A[5821] = acadoWorkspace.evHu[211];
+acadoWorkspace.A[5860] = acadoWorkspace.evHu[212];
+acadoWorkspace.A[5861] = acadoWorkspace.evHu[213];
+acadoWorkspace.A[5900] = acadoWorkspace.evHu[214];
+acadoWorkspace.A[5901] = acadoWorkspace.evHu[215];
+acadoWorkspace.A[5940] = acadoWorkspace.evHu[216];
+acadoWorkspace.A[5941] = acadoWorkspace.evHu[217];
+acadoWorkspace.A[5980] = acadoWorkspace.evHu[218];
+acadoWorkspace.A[5981] = acadoWorkspace.evHu[219];
+acadoWorkspace.A[6022] = acadoWorkspace.evHu[220];
+acadoWorkspace.A[6023] = acadoWorkspace.evHu[221];
+acadoWorkspace.A[6062] = acadoWorkspace.evHu[222];
+acadoWorkspace.A[6063] = acadoWorkspace.evHu[223];
+acadoWorkspace.A[6102] = acadoWorkspace.evHu[224];
+acadoWorkspace.A[6103] = acadoWorkspace.evHu[225];
+acadoWorkspace.A[6142] = acadoWorkspace.evHu[226];
+acadoWorkspace.A[6143] = acadoWorkspace.evHu[227];
+acadoWorkspace.A[6182] = acadoWorkspace.evHu[228];
+acadoWorkspace.A[6183] = acadoWorkspace.evHu[229];
+acadoWorkspace.A[6222] = acadoWorkspace.evHu[230];
+acadoWorkspace.A[6223] = acadoWorkspace.evHu[231];
+acadoWorkspace.A[6262] = acadoWorkspace.evHu[232];
+acadoWorkspace.A[6263] = acadoWorkspace.evHu[233];
+acadoWorkspace.A[6302] = acadoWorkspace.evHu[234];
+acadoWorkspace.A[6303] = acadoWorkspace.evHu[235];
+acadoWorkspace.A[6342] = acadoWorkspace.evHu[236];
+acadoWorkspace.A[6343] = acadoWorkspace.evHu[237];
+acadoWorkspace.A[6382] = acadoWorkspace.evHu[238];
+acadoWorkspace.A[6383] = acadoWorkspace.evHu[239];
+acadoWorkspace.A[6424] = acadoWorkspace.evHu[240];
+acadoWorkspace.A[6425] = acadoWorkspace.evHu[241];
+acadoWorkspace.A[6464] = acadoWorkspace.evHu[242];
+acadoWorkspace.A[6465] = acadoWorkspace.evHu[243];
+acadoWorkspace.A[6504] = acadoWorkspace.evHu[244];
+acadoWorkspace.A[6505] = acadoWorkspace.evHu[245];
+acadoWorkspace.A[6544] = acadoWorkspace.evHu[246];
+acadoWorkspace.A[6545] = acadoWorkspace.evHu[247];
+acadoWorkspace.A[6584] = acadoWorkspace.evHu[248];
+acadoWorkspace.A[6585] = acadoWorkspace.evHu[249];
+acadoWorkspace.A[6624] = acadoWorkspace.evHu[250];
+acadoWorkspace.A[6625] = acadoWorkspace.evHu[251];
+acadoWorkspace.A[6664] = acadoWorkspace.evHu[252];
+acadoWorkspace.A[6665] = acadoWorkspace.evHu[253];
+acadoWorkspace.A[6704] = acadoWorkspace.evHu[254];
+acadoWorkspace.A[6705] = acadoWorkspace.evHu[255];
+acadoWorkspace.A[6744] = acadoWorkspace.evHu[256];
+acadoWorkspace.A[6745] = acadoWorkspace.evHu[257];
+acadoWorkspace.A[6784] = acadoWorkspace.evHu[258];
+acadoWorkspace.A[6785] = acadoWorkspace.evHu[259];
+acadoWorkspace.A[6826] = acadoWorkspace.evHu[260];
+acadoWorkspace.A[6827] = acadoWorkspace.evHu[261];
+acadoWorkspace.A[6866] = acadoWorkspace.evHu[262];
+acadoWorkspace.A[6867] = acadoWorkspace.evHu[263];
+acadoWorkspace.A[6906] = acadoWorkspace.evHu[264];
+acadoWorkspace.A[6907] = acadoWorkspace.evHu[265];
+acadoWorkspace.A[6946] = acadoWorkspace.evHu[266];
+acadoWorkspace.A[6947] = acadoWorkspace.evHu[267];
+acadoWorkspace.A[6986] = acadoWorkspace.evHu[268];
+acadoWorkspace.A[6987] = acadoWorkspace.evHu[269];
+acadoWorkspace.A[7026] = acadoWorkspace.evHu[270];
+acadoWorkspace.A[7027] = acadoWorkspace.evHu[271];
+acadoWorkspace.A[7066] = acadoWorkspace.evHu[272];
+acadoWorkspace.A[7067] = acadoWorkspace.evHu[273];
+acadoWorkspace.A[7106] = acadoWorkspace.evHu[274];
+acadoWorkspace.A[7107] = acadoWorkspace.evHu[275];
+acadoWorkspace.A[7146] = acadoWorkspace.evHu[276];
+acadoWorkspace.A[7147] = acadoWorkspace.evHu[277];
+acadoWorkspace.A[7186] = acadoWorkspace.evHu[278];
+acadoWorkspace.A[7187] = acadoWorkspace.evHu[279];
+acadoWorkspace.A[7228] = acadoWorkspace.evHu[280];
+acadoWorkspace.A[7229] = acadoWorkspace.evHu[281];
+acadoWorkspace.A[7268] = acadoWorkspace.evHu[282];
+acadoWorkspace.A[7269] = acadoWorkspace.evHu[283];
+acadoWorkspace.A[7308] = acadoWorkspace.evHu[284];
+acadoWorkspace.A[7309] = acadoWorkspace.evHu[285];
+acadoWorkspace.A[7348] = acadoWorkspace.evHu[286];
+acadoWorkspace.A[7349] = acadoWorkspace.evHu[287];
+acadoWorkspace.A[7388] = acadoWorkspace.evHu[288];
+acadoWorkspace.A[7389] = acadoWorkspace.evHu[289];
+acadoWorkspace.A[7428] = acadoWorkspace.evHu[290];
+acadoWorkspace.A[7429] = acadoWorkspace.evHu[291];
+acadoWorkspace.A[7468] = acadoWorkspace.evHu[292];
+acadoWorkspace.A[7469] = acadoWorkspace.evHu[293];
+acadoWorkspace.A[7508] = acadoWorkspace.evHu[294];
+acadoWorkspace.A[7509] = acadoWorkspace.evHu[295];
+acadoWorkspace.A[7548] = acadoWorkspace.evHu[296];
+acadoWorkspace.A[7549] = acadoWorkspace.evHu[297];
+acadoWorkspace.A[7588] = acadoWorkspace.evHu[298];
+acadoWorkspace.A[7589] = acadoWorkspace.evHu[299];
+acadoWorkspace.A[7630] = acadoWorkspace.evHu[300];
+acadoWorkspace.A[7631] = acadoWorkspace.evHu[301];
+acadoWorkspace.A[7670] = acadoWorkspace.evHu[302];
+acadoWorkspace.A[7671] = acadoWorkspace.evHu[303];
+acadoWorkspace.A[7710] = acadoWorkspace.evHu[304];
+acadoWorkspace.A[7711] = acadoWorkspace.evHu[305];
+acadoWorkspace.A[7750] = acadoWorkspace.evHu[306];
+acadoWorkspace.A[7751] = acadoWorkspace.evHu[307];
+acadoWorkspace.A[7790] = acadoWorkspace.evHu[308];
+acadoWorkspace.A[7791] = acadoWorkspace.evHu[309];
+acadoWorkspace.A[7830] = acadoWorkspace.evHu[310];
+acadoWorkspace.A[7831] = acadoWorkspace.evHu[311];
+acadoWorkspace.A[7870] = acadoWorkspace.evHu[312];
+acadoWorkspace.A[7871] = acadoWorkspace.evHu[313];
+acadoWorkspace.A[7910] = acadoWorkspace.evHu[314];
+acadoWorkspace.A[7911] = acadoWorkspace.evHu[315];
+acadoWorkspace.A[7950] = acadoWorkspace.evHu[316];
+acadoWorkspace.A[7951] = acadoWorkspace.evHu[317];
+acadoWorkspace.A[7990] = acadoWorkspace.evHu[318];
+acadoWorkspace.A[7991] = acadoWorkspace.evHu[319];
+acadoWorkspace.A[8032] = acadoWorkspace.evHu[320];
+acadoWorkspace.A[8033] = acadoWorkspace.evHu[321];
+acadoWorkspace.A[8072] = acadoWorkspace.evHu[322];
+acadoWorkspace.A[8073] = acadoWorkspace.evHu[323];
+acadoWorkspace.A[8112] = acadoWorkspace.evHu[324];
+acadoWorkspace.A[8113] = acadoWorkspace.evHu[325];
+acadoWorkspace.A[8152] = acadoWorkspace.evHu[326];
+acadoWorkspace.A[8153] = acadoWorkspace.evHu[327];
+acadoWorkspace.A[8192] = acadoWorkspace.evHu[328];
+acadoWorkspace.A[8193] = acadoWorkspace.evHu[329];
+acadoWorkspace.A[8232] = acadoWorkspace.evHu[330];
+acadoWorkspace.A[8233] = acadoWorkspace.evHu[331];
+acadoWorkspace.A[8272] = acadoWorkspace.evHu[332];
+acadoWorkspace.A[8273] = acadoWorkspace.evHu[333];
+acadoWorkspace.A[8312] = acadoWorkspace.evHu[334];
+acadoWorkspace.A[8313] = acadoWorkspace.evHu[335];
+acadoWorkspace.A[8352] = acadoWorkspace.evHu[336];
+acadoWorkspace.A[8353] = acadoWorkspace.evHu[337];
+acadoWorkspace.A[8392] = acadoWorkspace.evHu[338];
+acadoWorkspace.A[8393] = acadoWorkspace.evHu[339];
+acadoWorkspace.A[8434] = acadoWorkspace.evHu[340];
+acadoWorkspace.A[8435] = acadoWorkspace.evHu[341];
+acadoWorkspace.A[8474] = acadoWorkspace.evHu[342];
+acadoWorkspace.A[8475] = acadoWorkspace.evHu[343];
+acadoWorkspace.A[8514] = acadoWorkspace.evHu[344];
+acadoWorkspace.A[8515] = acadoWorkspace.evHu[345];
+acadoWorkspace.A[8554] = acadoWorkspace.evHu[346];
+acadoWorkspace.A[8555] = acadoWorkspace.evHu[347];
+acadoWorkspace.A[8594] = acadoWorkspace.evHu[348];
+acadoWorkspace.A[8595] = acadoWorkspace.evHu[349];
+acadoWorkspace.A[8634] = acadoWorkspace.evHu[350];
+acadoWorkspace.A[8635] = acadoWorkspace.evHu[351];
+acadoWorkspace.A[8674] = acadoWorkspace.evHu[352];
+acadoWorkspace.A[8675] = acadoWorkspace.evHu[353];
+acadoWorkspace.A[8714] = acadoWorkspace.evHu[354];
+acadoWorkspace.A[8715] = acadoWorkspace.evHu[355];
+acadoWorkspace.A[8754] = acadoWorkspace.evHu[356];
+acadoWorkspace.A[8755] = acadoWorkspace.evHu[357];
+acadoWorkspace.A[8794] = acadoWorkspace.evHu[358];
+acadoWorkspace.A[8795] = acadoWorkspace.evHu[359];
+acadoWorkspace.A[8836] = acadoWorkspace.evHu[360];
+acadoWorkspace.A[8837] = acadoWorkspace.evHu[361];
+acadoWorkspace.A[8876] = acadoWorkspace.evHu[362];
+acadoWorkspace.A[8877] = acadoWorkspace.evHu[363];
+acadoWorkspace.A[8916] = acadoWorkspace.evHu[364];
+acadoWorkspace.A[8917] = acadoWorkspace.evHu[365];
+acadoWorkspace.A[8956] = acadoWorkspace.evHu[366];
+acadoWorkspace.A[8957] = acadoWorkspace.evHu[367];
+acadoWorkspace.A[8996] = acadoWorkspace.evHu[368];
+acadoWorkspace.A[8997] = acadoWorkspace.evHu[369];
+acadoWorkspace.A[9036] = acadoWorkspace.evHu[370];
+acadoWorkspace.A[9037] = acadoWorkspace.evHu[371];
+acadoWorkspace.A[9076] = acadoWorkspace.evHu[372];
+acadoWorkspace.A[9077] = acadoWorkspace.evHu[373];
+acadoWorkspace.A[9116] = acadoWorkspace.evHu[374];
+acadoWorkspace.A[9117] = acadoWorkspace.evHu[375];
+acadoWorkspace.A[9156] = acadoWorkspace.evHu[376];
+acadoWorkspace.A[9157] = acadoWorkspace.evHu[377];
+acadoWorkspace.A[9196] = acadoWorkspace.evHu[378];
+acadoWorkspace.A[9197] = acadoWorkspace.evHu[379];
+acadoWorkspace.A[9238] = acadoWorkspace.evHu[380];
+acadoWorkspace.A[9239] = acadoWorkspace.evHu[381];
+acadoWorkspace.A[9278] = acadoWorkspace.evHu[382];
+acadoWorkspace.A[9279] = acadoWorkspace.evHu[383];
+acadoWorkspace.A[9318] = acadoWorkspace.evHu[384];
+acadoWorkspace.A[9319] = acadoWorkspace.evHu[385];
+acadoWorkspace.A[9358] = acadoWorkspace.evHu[386];
+acadoWorkspace.A[9359] = acadoWorkspace.evHu[387];
+acadoWorkspace.A[9398] = acadoWorkspace.evHu[388];
+acadoWorkspace.A[9399] = acadoWorkspace.evHu[389];
+acadoWorkspace.A[9438] = acadoWorkspace.evHu[390];
+acadoWorkspace.A[9439] = acadoWorkspace.evHu[391];
+acadoWorkspace.A[9478] = acadoWorkspace.evHu[392];
+acadoWorkspace.A[9479] = acadoWorkspace.evHu[393];
+acadoWorkspace.A[9518] = acadoWorkspace.evHu[394];
+acadoWorkspace.A[9519] = acadoWorkspace.evHu[395];
+acadoWorkspace.A[9558] = acadoWorkspace.evHu[396];
+acadoWorkspace.A[9559] = acadoWorkspace.evHu[397];
+acadoWorkspace.A[9598] = acadoWorkspace.evHu[398];
+acadoWorkspace.A[9599] = acadoWorkspace.evHu[399];
+acadoWorkspace.lbA[40] = acadoVariables.lbAValues[40] - acadoWorkspace.evH[0];
+acadoWorkspace.lbA[41] = acadoVariables.lbAValues[41] - acadoWorkspace.evH[1];
+acadoWorkspace.lbA[42] = acadoVariables.lbAValues[42] - acadoWorkspace.evH[2];
+acadoWorkspace.lbA[43] = acadoVariables.lbAValues[43] - acadoWorkspace.evH[3];
+acadoWorkspace.lbA[44] = acadoVariables.lbAValues[44] - acadoWorkspace.evH[4];
+acadoWorkspace.lbA[45] = acadoVariables.lbAValues[45] - acadoWorkspace.evH[5];
+acadoWorkspace.lbA[46] = acadoVariables.lbAValues[46] - acadoWorkspace.evH[6];
+acadoWorkspace.lbA[47] = acadoVariables.lbAValues[47] - acadoWorkspace.evH[7];
+acadoWorkspace.lbA[48] = acadoVariables.lbAValues[48] - acadoWorkspace.evH[8];
+acadoWorkspace.lbA[49] = acadoVariables.lbAValues[49] - acadoWorkspace.evH[9];
+acadoWorkspace.lbA[50] = acadoVariables.lbAValues[50] - acadoWorkspace.evH[10];
+acadoWorkspace.lbA[51] = acadoVariables.lbAValues[51] - acadoWorkspace.evH[11];
+acadoWorkspace.lbA[52] = acadoVariables.lbAValues[52] - acadoWorkspace.evH[12];
+acadoWorkspace.lbA[53] = acadoVariables.lbAValues[53] - acadoWorkspace.evH[13];
+acadoWorkspace.lbA[54] = acadoVariables.lbAValues[54] - acadoWorkspace.evH[14];
+acadoWorkspace.lbA[55] = acadoVariables.lbAValues[55] - acadoWorkspace.evH[15];
+acadoWorkspace.lbA[56] = acadoVariables.lbAValues[56] - acadoWorkspace.evH[16];
+acadoWorkspace.lbA[57] = acadoVariables.lbAValues[57] - acadoWorkspace.evH[17];
+acadoWorkspace.lbA[58] = acadoVariables.lbAValues[58] - acadoWorkspace.evH[18];
+acadoWorkspace.lbA[59] = acadoVariables.lbAValues[59] - acadoWorkspace.evH[19];
+acadoWorkspace.lbA[60] = acadoVariables.lbAValues[60] - acadoWorkspace.evH[20];
+acadoWorkspace.lbA[61] = acadoVariables.lbAValues[61] - acadoWorkspace.evH[21];
+acadoWorkspace.lbA[62] = acadoVariables.lbAValues[62] - acadoWorkspace.evH[22];
+acadoWorkspace.lbA[63] = acadoVariables.lbAValues[63] - acadoWorkspace.evH[23];
+acadoWorkspace.lbA[64] = acadoVariables.lbAValues[64] - acadoWorkspace.evH[24];
+acadoWorkspace.lbA[65] = acadoVariables.lbAValues[65] - acadoWorkspace.evH[25];
+acadoWorkspace.lbA[66] = acadoVariables.lbAValues[66] - acadoWorkspace.evH[26];
+acadoWorkspace.lbA[67] = acadoVariables.lbAValues[67] - acadoWorkspace.evH[27];
+acadoWorkspace.lbA[68] = acadoVariables.lbAValues[68] - acadoWorkspace.evH[28];
+acadoWorkspace.lbA[69] = acadoVariables.lbAValues[69] - acadoWorkspace.evH[29];
+acadoWorkspace.lbA[70] = acadoVariables.lbAValues[70] - acadoWorkspace.evH[30];
+acadoWorkspace.lbA[71] = acadoVariables.lbAValues[71] - acadoWorkspace.evH[31];
+acadoWorkspace.lbA[72] = acadoVariables.lbAValues[72] - acadoWorkspace.evH[32];
+acadoWorkspace.lbA[73] = acadoVariables.lbAValues[73] - acadoWorkspace.evH[33];
+acadoWorkspace.lbA[74] = acadoVariables.lbAValues[74] - acadoWorkspace.evH[34];
+acadoWorkspace.lbA[75] = acadoVariables.lbAValues[75] - acadoWorkspace.evH[35];
+acadoWorkspace.lbA[76] = acadoVariables.lbAValues[76] - acadoWorkspace.evH[36];
+acadoWorkspace.lbA[77] = acadoVariables.lbAValues[77] - acadoWorkspace.evH[37];
+acadoWorkspace.lbA[78] = acadoVariables.lbAValues[78] - acadoWorkspace.evH[38];
+acadoWorkspace.lbA[79] = acadoVariables.lbAValues[79] - acadoWorkspace.evH[39];
+acadoWorkspace.lbA[80] = acadoVariables.lbAValues[80] - acadoWorkspace.evH[40];
+acadoWorkspace.lbA[81] = acadoVariables.lbAValues[81] - acadoWorkspace.evH[41];
+acadoWorkspace.lbA[82] = acadoVariables.lbAValues[82] - acadoWorkspace.evH[42];
+acadoWorkspace.lbA[83] = acadoVariables.lbAValues[83] - acadoWorkspace.evH[43];
+acadoWorkspace.lbA[84] = acadoVariables.lbAValues[84] - acadoWorkspace.evH[44];
+acadoWorkspace.lbA[85] = acadoVariables.lbAValues[85] - acadoWorkspace.evH[45];
+acadoWorkspace.lbA[86] = acadoVariables.lbAValues[86] - acadoWorkspace.evH[46];
+acadoWorkspace.lbA[87] = acadoVariables.lbAValues[87] - acadoWorkspace.evH[47];
+acadoWorkspace.lbA[88] = acadoVariables.lbAValues[88] - acadoWorkspace.evH[48];
+acadoWorkspace.lbA[89] = acadoVariables.lbAValues[89] - acadoWorkspace.evH[49];
+acadoWorkspace.lbA[90] = acadoVariables.lbAValues[90] - acadoWorkspace.evH[50];
+acadoWorkspace.lbA[91] = acadoVariables.lbAValues[91] - acadoWorkspace.evH[51];
+acadoWorkspace.lbA[92] = acadoVariables.lbAValues[92] - acadoWorkspace.evH[52];
+acadoWorkspace.lbA[93] = acadoVariables.lbAValues[93] - acadoWorkspace.evH[53];
+acadoWorkspace.lbA[94] = acadoVariables.lbAValues[94] - acadoWorkspace.evH[54];
+acadoWorkspace.lbA[95] = acadoVariables.lbAValues[95] - acadoWorkspace.evH[55];
+acadoWorkspace.lbA[96] = acadoVariables.lbAValues[96] - acadoWorkspace.evH[56];
+acadoWorkspace.lbA[97] = acadoVariables.lbAValues[97] - acadoWorkspace.evH[57];
+acadoWorkspace.lbA[98] = acadoVariables.lbAValues[98] - acadoWorkspace.evH[58];
+acadoWorkspace.lbA[99] = acadoVariables.lbAValues[99] - acadoWorkspace.evH[59];
+acadoWorkspace.lbA[100] = acadoVariables.lbAValues[100] - acadoWorkspace.evH[60];
+acadoWorkspace.lbA[101] = acadoVariables.lbAValues[101] - acadoWorkspace.evH[61];
+acadoWorkspace.lbA[102] = acadoVariables.lbAValues[102] - acadoWorkspace.evH[62];
+acadoWorkspace.lbA[103] = acadoVariables.lbAValues[103] - acadoWorkspace.evH[63];
+acadoWorkspace.lbA[104] = acadoVariables.lbAValues[104] - acadoWorkspace.evH[64];
+acadoWorkspace.lbA[105] = acadoVariables.lbAValues[105] - acadoWorkspace.evH[65];
+acadoWorkspace.lbA[106] = acadoVariables.lbAValues[106] - acadoWorkspace.evH[66];
+acadoWorkspace.lbA[107] = acadoVariables.lbAValues[107] - acadoWorkspace.evH[67];
+acadoWorkspace.lbA[108] = acadoVariables.lbAValues[108] - acadoWorkspace.evH[68];
+acadoWorkspace.lbA[109] = acadoVariables.lbAValues[109] - acadoWorkspace.evH[69];
+acadoWorkspace.lbA[110] = acadoVariables.lbAValues[110] - acadoWorkspace.evH[70];
+acadoWorkspace.lbA[111] = acadoVariables.lbAValues[111] - acadoWorkspace.evH[71];
+acadoWorkspace.lbA[112] = acadoVariables.lbAValues[112] - acadoWorkspace.evH[72];
+acadoWorkspace.lbA[113] = acadoVariables.lbAValues[113] - acadoWorkspace.evH[73];
+acadoWorkspace.lbA[114] = acadoVariables.lbAValues[114] - acadoWorkspace.evH[74];
+acadoWorkspace.lbA[115] = acadoVariables.lbAValues[115] - acadoWorkspace.evH[75];
+acadoWorkspace.lbA[116] = acadoVariables.lbAValues[116] - acadoWorkspace.evH[76];
+acadoWorkspace.lbA[117] = acadoVariables.lbAValues[117] - acadoWorkspace.evH[77];
+acadoWorkspace.lbA[118] = acadoVariables.lbAValues[118] - acadoWorkspace.evH[78];
+acadoWorkspace.lbA[119] = acadoVariables.lbAValues[119] - acadoWorkspace.evH[79];
+acadoWorkspace.lbA[120] = acadoVariables.lbAValues[120] - acadoWorkspace.evH[80];
+acadoWorkspace.lbA[121] = acadoVariables.lbAValues[121] - acadoWorkspace.evH[81];
+acadoWorkspace.lbA[122] = acadoVariables.lbAValues[122] - acadoWorkspace.evH[82];
+acadoWorkspace.lbA[123] = acadoVariables.lbAValues[123] - acadoWorkspace.evH[83];
+acadoWorkspace.lbA[124] = acadoVariables.lbAValues[124] - acadoWorkspace.evH[84];
+acadoWorkspace.lbA[125] = acadoVariables.lbAValues[125] - acadoWorkspace.evH[85];
+acadoWorkspace.lbA[126] = acadoVariables.lbAValues[126] - acadoWorkspace.evH[86];
+acadoWorkspace.lbA[127] = acadoVariables.lbAValues[127] - acadoWorkspace.evH[87];
+acadoWorkspace.lbA[128] = acadoVariables.lbAValues[128] - acadoWorkspace.evH[88];
+acadoWorkspace.lbA[129] = acadoVariables.lbAValues[129] - acadoWorkspace.evH[89];
+acadoWorkspace.lbA[130] = acadoVariables.lbAValues[130] - acadoWorkspace.evH[90];
+acadoWorkspace.lbA[131] = acadoVariables.lbAValues[131] - acadoWorkspace.evH[91];
+acadoWorkspace.lbA[132] = acadoVariables.lbAValues[132] - acadoWorkspace.evH[92];
+acadoWorkspace.lbA[133] = acadoVariables.lbAValues[133] - acadoWorkspace.evH[93];
+acadoWorkspace.lbA[134] = acadoVariables.lbAValues[134] - acadoWorkspace.evH[94];
+acadoWorkspace.lbA[135] = acadoVariables.lbAValues[135] - acadoWorkspace.evH[95];
+acadoWorkspace.lbA[136] = acadoVariables.lbAValues[136] - acadoWorkspace.evH[96];
+acadoWorkspace.lbA[137] = acadoVariables.lbAValues[137] - acadoWorkspace.evH[97];
+acadoWorkspace.lbA[138] = acadoVariables.lbAValues[138] - acadoWorkspace.evH[98];
+acadoWorkspace.lbA[139] = acadoVariables.lbAValues[139] - acadoWorkspace.evH[99];
+acadoWorkspace.lbA[140] = acadoVariables.lbAValues[140] - acadoWorkspace.evH[100];
+acadoWorkspace.lbA[141] = acadoVariables.lbAValues[141] - acadoWorkspace.evH[101];
+acadoWorkspace.lbA[142] = acadoVariables.lbAValues[142] - acadoWorkspace.evH[102];
+acadoWorkspace.lbA[143] = acadoVariables.lbAValues[143] - acadoWorkspace.evH[103];
+acadoWorkspace.lbA[144] = acadoVariables.lbAValues[144] - acadoWorkspace.evH[104];
+acadoWorkspace.lbA[145] = acadoVariables.lbAValues[145] - acadoWorkspace.evH[105];
+acadoWorkspace.lbA[146] = acadoVariables.lbAValues[146] - acadoWorkspace.evH[106];
+acadoWorkspace.lbA[147] = acadoVariables.lbAValues[147] - acadoWorkspace.evH[107];
+acadoWorkspace.lbA[148] = acadoVariables.lbAValues[148] - acadoWorkspace.evH[108];
+acadoWorkspace.lbA[149] = acadoVariables.lbAValues[149] - acadoWorkspace.evH[109];
+acadoWorkspace.lbA[150] = acadoVariables.lbAValues[150] - acadoWorkspace.evH[110];
+acadoWorkspace.lbA[151] = acadoVariables.lbAValues[151] - acadoWorkspace.evH[111];
+acadoWorkspace.lbA[152] = acadoVariables.lbAValues[152] - acadoWorkspace.evH[112];
+acadoWorkspace.lbA[153] = acadoVariables.lbAValues[153] - acadoWorkspace.evH[113];
+acadoWorkspace.lbA[154] = acadoVariables.lbAValues[154] - acadoWorkspace.evH[114];
+acadoWorkspace.lbA[155] = acadoVariables.lbAValues[155] - acadoWorkspace.evH[115];
+acadoWorkspace.lbA[156] = acadoVariables.lbAValues[156] - acadoWorkspace.evH[116];
+acadoWorkspace.lbA[157] = acadoVariables.lbAValues[157] - acadoWorkspace.evH[117];
+acadoWorkspace.lbA[158] = acadoVariables.lbAValues[158] - acadoWorkspace.evH[118];
+acadoWorkspace.lbA[159] = acadoVariables.lbAValues[159] - acadoWorkspace.evH[119];
+acadoWorkspace.lbA[160] = acadoVariables.lbAValues[160] - acadoWorkspace.evH[120];
+acadoWorkspace.lbA[161] = acadoVariables.lbAValues[161] - acadoWorkspace.evH[121];
+acadoWorkspace.lbA[162] = acadoVariables.lbAValues[162] - acadoWorkspace.evH[122];
+acadoWorkspace.lbA[163] = acadoVariables.lbAValues[163] - acadoWorkspace.evH[123];
+acadoWorkspace.lbA[164] = acadoVariables.lbAValues[164] - acadoWorkspace.evH[124];
+acadoWorkspace.lbA[165] = acadoVariables.lbAValues[165] - acadoWorkspace.evH[125];
+acadoWorkspace.lbA[166] = acadoVariables.lbAValues[166] - acadoWorkspace.evH[126];
+acadoWorkspace.lbA[167] = acadoVariables.lbAValues[167] - acadoWorkspace.evH[127];
+acadoWorkspace.lbA[168] = acadoVariables.lbAValues[168] - acadoWorkspace.evH[128];
+acadoWorkspace.lbA[169] = acadoVariables.lbAValues[169] - acadoWorkspace.evH[129];
+acadoWorkspace.lbA[170] = acadoVariables.lbAValues[170] - acadoWorkspace.evH[130];
+acadoWorkspace.lbA[171] = acadoVariables.lbAValues[171] - acadoWorkspace.evH[131];
+acadoWorkspace.lbA[172] = acadoVariables.lbAValues[172] - acadoWorkspace.evH[132];
+acadoWorkspace.lbA[173] = acadoVariables.lbAValues[173] - acadoWorkspace.evH[133];
+acadoWorkspace.lbA[174] = acadoVariables.lbAValues[174] - acadoWorkspace.evH[134];
+acadoWorkspace.lbA[175] = acadoVariables.lbAValues[175] - acadoWorkspace.evH[135];
+acadoWorkspace.lbA[176] = acadoVariables.lbAValues[176] - acadoWorkspace.evH[136];
+acadoWorkspace.lbA[177] = acadoVariables.lbAValues[177] - acadoWorkspace.evH[137];
+acadoWorkspace.lbA[178] = acadoVariables.lbAValues[178] - acadoWorkspace.evH[138];
+acadoWorkspace.lbA[179] = acadoVariables.lbAValues[179] - acadoWorkspace.evH[139];
+acadoWorkspace.lbA[180] = acadoVariables.lbAValues[180] - acadoWorkspace.evH[140];
+acadoWorkspace.lbA[181] = acadoVariables.lbAValues[181] - acadoWorkspace.evH[141];
+acadoWorkspace.lbA[182] = acadoVariables.lbAValues[182] - acadoWorkspace.evH[142];
+acadoWorkspace.lbA[183] = acadoVariables.lbAValues[183] - acadoWorkspace.evH[143];
+acadoWorkspace.lbA[184] = acadoVariables.lbAValues[184] - acadoWorkspace.evH[144];
+acadoWorkspace.lbA[185] = acadoVariables.lbAValues[185] - acadoWorkspace.evH[145];
+acadoWorkspace.lbA[186] = acadoVariables.lbAValues[186] - acadoWorkspace.evH[146];
+acadoWorkspace.lbA[187] = acadoVariables.lbAValues[187] - acadoWorkspace.evH[147];
+acadoWorkspace.lbA[188] = acadoVariables.lbAValues[188] - acadoWorkspace.evH[148];
+acadoWorkspace.lbA[189] = acadoVariables.lbAValues[189] - acadoWorkspace.evH[149];
+acadoWorkspace.lbA[190] = acadoVariables.lbAValues[190] - acadoWorkspace.evH[150];
+acadoWorkspace.lbA[191] = acadoVariables.lbAValues[191] - acadoWorkspace.evH[151];
+acadoWorkspace.lbA[192] = acadoVariables.lbAValues[192] - acadoWorkspace.evH[152];
+acadoWorkspace.lbA[193] = acadoVariables.lbAValues[193] - acadoWorkspace.evH[153];
+acadoWorkspace.lbA[194] = acadoVariables.lbAValues[194] - acadoWorkspace.evH[154];
+acadoWorkspace.lbA[195] = acadoVariables.lbAValues[195] - acadoWorkspace.evH[155];
+acadoWorkspace.lbA[196] = acadoVariables.lbAValues[196] - acadoWorkspace.evH[156];
+acadoWorkspace.lbA[197] = acadoVariables.lbAValues[197] - acadoWorkspace.evH[157];
+acadoWorkspace.lbA[198] = acadoVariables.lbAValues[198] - acadoWorkspace.evH[158];
+acadoWorkspace.lbA[199] = acadoVariables.lbAValues[199] - acadoWorkspace.evH[159];
+acadoWorkspace.lbA[200] = acadoVariables.lbAValues[200] - acadoWorkspace.evH[160];
+acadoWorkspace.lbA[201] = acadoVariables.lbAValues[201] - acadoWorkspace.evH[161];
+acadoWorkspace.lbA[202] = acadoVariables.lbAValues[202] - acadoWorkspace.evH[162];
+acadoWorkspace.lbA[203] = acadoVariables.lbAValues[203] - acadoWorkspace.evH[163];
+acadoWorkspace.lbA[204] = acadoVariables.lbAValues[204] - acadoWorkspace.evH[164];
+acadoWorkspace.lbA[205] = acadoVariables.lbAValues[205] - acadoWorkspace.evH[165];
+acadoWorkspace.lbA[206] = acadoVariables.lbAValues[206] - acadoWorkspace.evH[166];
+acadoWorkspace.lbA[207] = acadoVariables.lbAValues[207] - acadoWorkspace.evH[167];
+acadoWorkspace.lbA[208] = acadoVariables.lbAValues[208] - acadoWorkspace.evH[168];
+acadoWorkspace.lbA[209] = acadoVariables.lbAValues[209] - acadoWorkspace.evH[169];
+acadoWorkspace.lbA[210] = acadoVariables.lbAValues[210] - acadoWorkspace.evH[170];
+acadoWorkspace.lbA[211] = acadoVariables.lbAValues[211] - acadoWorkspace.evH[171];
+acadoWorkspace.lbA[212] = acadoVariables.lbAValues[212] - acadoWorkspace.evH[172];
+acadoWorkspace.lbA[213] = acadoVariables.lbAValues[213] - acadoWorkspace.evH[173];
+acadoWorkspace.lbA[214] = acadoVariables.lbAValues[214] - acadoWorkspace.evH[174];
+acadoWorkspace.lbA[215] = acadoVariables.lbAValues[215] - acadoWorkspace.evH[175];
+acadoWorkspace.lbA[216] = acadoVariables.lbAValues[216] - acadoWorkspace.evH[176];
+acadoWorkspace.lbA[217] = acadoVariables.lbAValues[217] - acadoWorkspace.evH[177];
+acadoWorkspace.lbA[218] = acadoVariables.lbAValues[218] - acadoWorkspace.evH[178];
+acadoWorkspace.lbA[219] = acadoVariables.lbAValues[219] - acadoWorkspace.evH[179];
+acadoWorkspace.lbA[220] = acadoVariables.lbAValues[220] - acadoWorkspace.evH[180];
+acadoWorkspace.lbA[221] = acadoVariables.lbAValues[221] - acadoWorkspace.evH[181];
+acadoWorkspace.lbA[222] = acadoVariables.lbAValues[222] - acadoWorkspace.evH[182];
+acadoWorkspace.lbA[223] = acadoVariables.lbAValues[223] - acadoWorkspace.evH[183];
+acadoWorkspace.lbA[224] = acadoVariables.lbAValues[224] - acadoWorkspace.evH[184];
+acadoWorkspace.lbA[225] = acadoVariables.lbAValues[225] - acadoWorkspace.evH[185];
+acadoWorkspace.lbA[226] = acadoVariables.lbAValues[226] - acadoWorkspace.evH[186];
+acadoWorkspace.lbA[227] = acadoVariables.lbAValues[227] - acadoWorkspace.evH[187];
+acadoWorkspace.lbA[228] = acadoVariables.lbAValues[228] - acadoWorkspace.evH[188];
+acadoWorkspace.lbA[229] = acadoVariables.lbAValues[229] - acadoWorkspace.evH[189];
+acadoWorkspace.lbA[230] = acadoVariables.lbAValues[230] - acadoWorkspace.evH[190];
+acadoWorkspace.lbA[231] = acadoVariables.lbAValues[231] - acadoWorkspace.evH[191];
+acadoWorkspace.lbA[232] = acadoVariables.lbAValues[232] - acadoWorkspace.evH[192];
+acadoWorkspace.lbA[233] = acadoVariables.lbAValues[233] - acadoWorkspace.evH[193];
+acadoWorkspace.lbA[234] = acadoVariables.lbAValues[234] - acadoWorkspace.evH[194];
+acadoWorkspace.lbA[235] = acadoVariables.lbAValues[235] - acadoWorkspace.evH[195];
+acadoWorkspace.lbA[236] = acadoVariables.lbAValues[236] - acadoWorkspace.evH[196];
+acadoWorkspace.lbA[237] = acadoVariables.lbAValues[237] - acadoWorkspace.evH[197];
+acadoWorkspace.lbA[238] = acadoVariables.lbAValues[238] - acadoWorkspace.evH[198];
+acadoWorkspace.lbA[239] = acadoVariables.lbAValues[239] - acadoWorkspace.evH[199];
+
+acadoWorkspace.ubA[40] = acadoVariables.ubAValues[40] - acadoWorkspace.evH[0];
+acadoWorkspace.ubA[41] = acadoVariables.ubAValues[41] - acadoWorkspace.evH[1];
+acadoWorkspace.ubA[42] = acadoVariables.ubAValues[42] - acadoWorkspace.evH[2];
+acadoWorkspace.ubA[43] = acadoVariables.ubAValues[43] - acadoWorkspace.evH[3];
+acadoWorkspace.ubA[44] = acadoVariables.ubAValues[44] - acadoWorkspace.evH[4];
+acadoWorkspace.ubA[45] = acadoVariables.ubAValues[45] - acadoWorkspace.evH[5];
+acadoWorkspace.ubA[46] = acadoVariables.ubAValues[46] - acadoWorkspace.evH[6];
+acadoWorkspace.ubA[47] = acadoVariables.ubAValues[47] - acadoWorkspace.evH[7];
+acadoWorkspace.ubA[48] = acadoVariables.ubAValues[48] - acadoWorkspace.evH[8];
+acadoWorkspace.ubA[49] = acadoVariables.ubAValues[49] - acadoWorkspace.evH[9];
+acadoWorkspace.ubA[50] = acadoVariables.ubAValues[50] - acadoWorkspace.evH[10];
+acadoWorkspace.ubA[51] = acadoVariables.ubAValues[51] - acadoWorkspace.evH[11];
+acadoWorkspace.ubA[52] = acadoVariables.ubAValues[52] - acadoWorkspace.evH[12];
+acadoWorkspace.ubA[53] = acadoVariables.ubAValues[53] - acadoWorkspace.evH[13];
+acadoWorkspace.ubA[54] = acadoVariables.ubAValues[54] - acadoWorkspace.evH[14];
+acadoWorkspace.ubA[55] = acadoVariables.ubAValues[55] - acadoWorkspace.evH[15];
+acadoWorkspace.ubA[56] = acadoVariables.ubAValues[56] - acadoWorkspace.evH[16];
+acadoWorkspace.ubA[57] = acadoVariables.ubAValues[57] - acadoWorkspace.evH[17];
+acadoWorkspace.ubA[58] = acadoVariables.ubAValues[58] - acadoWorkspace.evH[18];
+acadoWorkspace.ubA[59] = acadoVariables.ubAValues[59] - acadoWorkspace.evH[19];
+acadoWorkspace.ubA[60] = acadoVariables.ubAValues[60] - acadoWorkspace.evH[20];
+acadoWorkspace.ubA[61] = acadoVariables.ubAValues[61] - acadoWorkspace.evH[21];
+acadoWorkspace.ubA[62] = acadoVariables.ubAValues[62] - acadoWorkspace.evH[22];
+acadoWorkspace.ubA[63] = acadoVariables.ubAValues[63] - acadoWorkspace.evH[23];
+acadoWorkspace.ubA[64] = acadoVariables.ubAValues[64] - acadoWorkspace.evH[24];
+acadoWorkspace.ubA[65] = acadoVariables.ubAValues[65] - acadoWorkspace.evH[25];
+acadoWorkspace.ubA[66] = acadoVariables.ubAValues[66] - acadoWorkspace.evH[26];
+acadoWorkspace.ubA[67] = acadoVariables.ubAValues[67] - acadoWorkspace.evH[27];
+acadoWorkspace.ubA[68] = acadoVariables.ubAValues[68] - acadoWorkspace.evH[28];
+acadoWorkspace.ubA[69] = acadoVariables.ubAValues[69] - acadoWorkspace.evH[29];
+acadoWorkspace.ubA[70] = acadoVariables.ubAValues[70] - acadoWorkspace.evH[30];
+acadoWorkspace.ubA[71] = acadoVariables.ubAValues[71] - acadoWorkspace.evH[31];
+acadoWorkspace.ubA[72] = acadoVariables.ubAValues[72] - acadoWorkspace.evH[32];
+acadoWorkspace.ubA[73] = acadoVariables.ubAValues[73] - acadoWorkspace.evH[33];
+acadoWorkspace.ubA[74] = acadoVariables.ubAValues[74] - acadoWorkspace.evH[34];
+acadoWorkspace.ubA[75] = acadoVariables.ubAValues[75] - acadoWorkspace.evH[35];
+acadoWorkspace.ubA[76] = acadoVariables.ubAValues[76] - acadoWorkspace.evH[36];
+acadoWorkspace.ubA[77] = acadoVariables.ubAValues[77] - acadoWorkspace.evH[37];
+acadoWorkspace.ubA[78] = acadoVariables.ubAValues[78] - acadoWorkspace.evH[38];
+acadoWorkspace.ubA[79] = acadoVariables.ubAValues[79] - acadoWorkspace.evH[39];
+acadoWorkspace.ubA[80] = acadoVariables.ubAValues[80] - acadoWorkspace.evH[40];
+acadoWorkspace.ubA[81] = acadoVariables.ubAValues[81] - acadoWorkspace.evH[41];
+acadoWorkspace.ubA[82] = acadoVariables.ubAValues[82] - acadoWorkspace.evH[42];
+acadoWorkspace.ubA[83] = acadoVariables.ubAValues[83] - acadoWorkspace.evH[43];
+acadoWorkspace.ubA[84] = acadoVariables.ubAValues[84] - acadoWorkspace.evH[44];
+acadoWorkspace.ubA[85] = acadoVariables.ubAValues[85] - acadoWorkspace.evH[45];
+acadoWorkspace.ubA[86] = acadoVariables.ubAValues[86] - acadoWorkspace.evH[46];
+acadoWorkspace.ubA[87] = acadoVariables.ubAValues[87] - acadoWorkspace.evH[47];
+acadoWorkspace.ubA[88] = acadoVariables.ubAValues[88] - acadoWorkspace.evH[48];
+acadoWorkspace.ubA[89] = acadoVariables.ubAValues[89] - acadoWorkspace.evH[49];
+acadoWorkspace.ubA[90] = acadoVariables.ubAValues[90] - acadoWorkspace.evH[50];
+acadoWorkspace.ubA[91] = acadoVariables.ubAValues[91] - acadoWorkspace.evH[51];
+acadoWorkspace.ubA[92] = acadoVariables.ubAValues[92] - acadoWorkspace.evH[52];
+acadoWorkspace.ubA[93] = acadoVariables.ubAValues[93] - acadoWorkspace.evH[53];
+acadoWorkspace.ubA[94] = acadoVariables.ubAValues[94] - acadoWorkspace.evH[54];
+acadoWorkspace.ubA[95] = acadoVariables.ubAValues[95] - acadoWorkspace.evH[55];
+acadoWorkspace.ubA[96] = acadoVariables.ubAValues[96] - acadoWorkspace.evH[56];
+acadoWorkspace.ubA[97] = acadoVariables.ubAValues[97] - acadoWorkspace.evH[57];
+acadoWorkspace.ubA[98] = acadoVariables.ubAValues[98] - acadoWorkspace.evH[58];
+acadoWorkspace.ubA[99] = acadoVariables.ubAValues[99] - acadoWorkspace.evH[59];
+acadoWorkspace.ubA[100] = acadoVariables.ubAValues[100] - acadoWorkspace.evH[60];
+acadoWorkspace.ubA[101] = acadoVariables.ubAValues[101] - acadoWorkspace.evH[61];
+acadoWorkspace.ubA[102] = acadoVariables.ubAValues[102] - acadoWorkspace.evH[62];
+acadoWorkspace.ubA[103] = acadoVariables.ubAValues[103] - acadoWorkspace.evH[63];
+acadoWorkspace.ubA[104] = acadoVariables.ubAValues[104] - acadoWorkspace.evH[64];
+acadoWorkspace.ubA[105] = acadoVariables.ubAValues[105] - acadoWorkspace.evH[65];
+acadoWorkspace.ubA[106] = acadoVariables.ubAValues[106] - acadoWorkspace.evH[66];
+acadoWorkspace.ubA[107] = acadoVariables.ubAValues[107] - acadoWorkspace.evH[67];
+acadoWorkspace.ubA[108] = acadoVariables.ubAValues[108] - acadoWorkspace.evH[68];
+acadoWorkspace.ubA[109] = acadoVariables.ubAValues[109] - acadoWorkspace.evH[69];
+acadoWorkspace.ubA[110] = acadoVariables.ubAValues[110] - acadoWorkspace.evH[70];
+acadoWorkspace.ubA[111] = acadoVariables.ubAValues[111] - acadoWorkspace.evH[71];
+acadoWorkspace.ubA[112] = acadoVariables.ubAValues[112] - acadoWorkspace.evH[72];
+acadoWorkspace.ubA[113] = acadoVariables.ubAValues[113] - acadoWorkspace.evH[73];
+acadoWorkspace.ubA[114] = acadoVariables.ubAValues[114] - acadoWorkspace.evH[74];
+acadoWorkspace.ubA[115] = acadoVariables.ubAValues[115] - acadoWorkspace.evH[75];
+acadoWorkspace.ubA[116] = acadoVariables.ubAValues[116] - acadoWorkspace.evH[76];
+acadoWorkspace.ubA[117] = acadoVariables.ubAValues[117] - acadoWorkspace.evH[77];
+acadoWorkspace.ubA[118] = acadoVariables.ubAValues[118] - acadoWorkspace.evH[78];
+acadoWorkspace.ubA[119] = acadoVariables.ubAValues[119] - acadoWorkspace.evH[79];
+acadoWorkspace.ubA[120] = acadoVariables.ubAValues[120] - acadoWorkspace.evH[80];
+acadoWorkspace.ubA[121] = acadoVariables.ubAValues[121] - acadoWorkspace.evH[81];
+acadoWorkspace.ubA[122] = acadoVariables.ubAValues[122] - acadoWorkspace.evH[82];
+acadoWorkspace.ubA[123] = acadoVariables.ubAValues[123] - acadoWorkspace.evH[83];
+acadoWorkspace.ubA[124] = acadoVariables.ubAValues[124] - acadoWorkspace.evH[84];
+acadoWorkspace.ubA[125] = acadoVariables.ubAValues[125] - acadoWorkspace.evH[85];
+acadoWorkspace.ubA[126] = acadoVariables.ubAValues[126] - acadoWorkspace.evH[86];
+acadoWorkspace.ubA[127] = acadoVariables.ubAValues[127] - acadoWorkspace.evH[87];
+acadoWorkspace.ubA[128] = acadoVariables.ubAValues[128] - acadoWorkspace.evH[88];
+acadoWorkspace.ubA[129] = acadoVariables.ubAValues[129] - acadoWorkspace.evH[89];
+acadoWorkspace.ubA[130] = acadoVariables.ubAValues[130] - acadoWorkspace.evH[90];
+acadoWorkspace.ubA[131] = acadoVariables.ubAValues[131] - acadoWorkspace.evH[91];
+acadoWorkspace.ubA[132] = acadoVariables.ubAValues[132] - acadoWorkspace.evH[92];
+acadoWorkspace.ubA[133] = acadoVariables.ubAValues[133] - acadoWorkspace.evH[93];
+acadoWorkspace.ubA[134] = acadoVariables.ubAValues[134] - acadoWorkspace.evH[94];
+acadoWorkspace.ubA[135] = acadoVariables.ubAValues[135] - acadoWorkspace.evH[95];
+acadoWorkspace.ubA[136] = acadoVariables.ubAValues[136] - acadoWorkspace.evH[96];
+acadoWorkspace.ubA[137] = acadoVariables.ubAValues[137] - acadoWorkspace.evH[97];
+acadoWorkspace.ubA[138] = acadoVariables.ubAValues[138] - acadoWorkspace.evH[98];
+acadoWorkspace.ubA[139] = acadoVariables.ubAValues[139] - acadoWorkspace.evH[99];
+acadoWorkspace.ubA[140] = acadoVariables.ubAValues[140] - acadoWorkspace.evH[100];
+acadoWorkspace.ubA[141] = acadoVariables.ubAValues[141] - acadoWorkspace.evH[101];
+acadoWorkspace.ubA[142] = acadoVariables.ubAValues[142] - acadoWorkspace.evH[102];
+acadoWorkspace.ubA[143] = acadoVariables.ubAValues[143] - acadoWorkspace.evH[103];
+acadoWorkspace.ubA[144] = acadoVariables.ubAValues[144] - acadoWorkspace.evH[104];
+acadoWorkspace.ubA[145] = acadoVariables.ubAValues[145] - acadoWorkspace.evH[105];
+acadoWorkspace.ubA[146] = acadoVariables.ubAValues[146] - acadoWorkspace.evH[106];
+acadoWorkspace.ubA[147] = acadoVariables.ubAValues[147] - acadoWorkspace.evH[107];
+acadoWorkspace.ubA[148] = acadoVariables.ubAValues[148] - acadoWorkspace.evH[108];
+acadoWorkspace.ubA[149] = acadoVariables.ubAValues[149] - acadoWorkspace.evH[109];
+acadoWorkspace.ubA[150] = acadoVariables.ubAValues[150] - acadoWorkspace.evH[110];
+acadoWorkspace.ubA[151] = acadoVariables.ubAValues[151] - acadoWorkspace.evH[111];
+acadoWorkspace.ubA[152] = acadoVariables.ubAValues[152] - acadoWorkspace.evH[112];
+acadoWorkspace.ubA[153] = acadoVariables.ubAValues[153] - acadoWorkspace.evH[113];
+acadoWorkspace.ubA[154] = acadoVariables.ubAValues[154] - acadoWorkspace.evH[114];
+acadoWorkspace.ubA[155] = acadoVariables.ubAValues[155] - acadoWorkspace.evH[115];
+acadoWorkspace.ubA[156] = acadoVariables.ubAValues[156] - acadoWorkspace.evH[116];
+acadoWorkspace.ubA[157] = acadoVariables.ubAValues[157] - acadoWorkspace.evH[117];
+acadoWorkspace.ubA[158] = acadoVariables.ubAValues[158] - acadoWorkspace.evH[118];
+acadoWorkspace.ubA[159] = acadoVariables.ubAValues[159] - acadoWorkspace.evH[119];
+acadoWorkspace.ubA[160] = acadoVariables.ubAValues[160] - acadoWorkspace.evH[120];
+acadoWorkspace.ubA[161] = acadoVariables.ubAValues[161] - acadoWorkspace.evH[121];
+acadoWorkspace.ubA[162] = acadoVariables.ubAValues[162] - acadoWorkspace.evH[122];
+acadoWorkspace.ubA[163] = acadoVariables.ubAValues[163] - acadoWorkspace.evH[123];
+acadoWorkspace.ubA[164] = acadoVariables.ubAValues[164] - acadoWorkspace.evH[124];
+acadoWorkspace.ubA[165] = acadoVariables.ubAValues[165] - acadoWorkspace.evH[125];
+acadoWorkspace.ubA[166] = acadoVariables.ubAValues[166] - acadoWorkspace.evH[126];
+acadoWorkspace.ubA[167] = acadoVariables.ubAValues[167] - acadoWorkspace.evH[127];
+acadoWorkspace.ubA[168] = acadoVariables.ubAValues[168] - acadoWorkspace.evH[128];
+acadoWorkspace.ubA[169] = acadoVariables.ubAValues[169] - acadoWorkspace.evH[129];
+acadoWorkspace.ubA[170] = acadoVariables.ubAValues[170] - acadoWorkspace.evH[130];
+acadoWorkspace.ubA[171] = acadoVariables.ubAValues[171] - acadoWorkspace.evH[131];
+acadoWorkspace.ubA[172] = acadoVariables.ubAValues[172] - acadoWorkspace.evH[132];
+acadoWorkspace.ubA[173] = acadoVariables.ubAValues[173] - acadoWorkspace.evH[133];
+acadoWorkspace.ubA[174] = acadoVariables.ubAValues[174] - acadoWorkspace.evH[134];
+acadoWorkspace.ubA[175] = acadoVariables.ubAValues[175] - acadoWorkspace.evH[135];
+acadoWorkspace.ubA[176] = acadoVariables.ubAValues[176] - acadoWorkspace.evH[136];
+acadoWorkspace.ubA[177] = acadoVariables.ubAValues[177] - acadoWorkspace.evH[137];
+acadoWorkspace.ubA[178] = acadoVariables.ubAValues[178] - acadoWorkspace.evH[138];
+acadoWorkspace.ubA[179] = acadoVariables.ubAValues[179] - acadoWorkspace.evH[139];
+acadoWorkspace.ubA[180] = acadoVariables.ubAValues[180] - acadoWorkspace.evH[140];
+acadoWorkspace.ubA[181] = acadoVariables.ubAValues[181] - acadoWorkspace.evH[141];
+acadoWorkspace.ubA[182] = acadoVariables.ubAValues[182] - acadoWorkspace.evH[142];
+acadoWorkspace.ubA[183] = acadoVariables.ubAValues[183] - acadoWorkspace.evH[143];
+acadoWorkspace.ubA[184] = acadoVariables.ubAValues[184] - acadoWorkspace.evH[144];
+acadoWorkspace.ubA[185] = acadoVariables.ubAValues[185] - acadoWorkspace.evH[145];
+acadoWorkspace.ubA[186] = acadoVariables.ubAValues[186] - acadoWorkspace.evH[146];
+acadoWorkspace.ubA[187] = acadoVariables.ubAValues[187] - acadoWorkspace.evH[147];
+acadoWorkspace.ubA[188] = acadoVariables.ubAValues[188] - acadoWorkspace.evH[148];
+acadoWorkspace.ubA[189] = acadoVariables.ubAValues[189] - acadoWorkspace.evH[149];
+acadoWorkspace.ubA[190] = acadoVariables.ubAValues[190] - acadoWorkspace.evH[150];
+acadoWorkspace.ubA[191] = acadoVariables.ubAValues[191] - acadoWorkspace.evH[151];
+acadoWorkspace.ubA[192] = acadoVariables.ubAValues[192] - acadoWorkspace.evH[152];
+acadoWorkspace.ubA[193] = acadoVariables.ubAValues[193] - acadoWorkspace.evH[153];
+acadoWorkspace.ubA[194] = acadoVariables.ubAValues[194] - acadoWorkspace.evH[154];
+acadoWorkspace.ubA[195] = acadoVariables.ubAValues[195] - acadoWorkspace.evH[155];
+acadoWorkspace.ubA[196] = acadoVariables.ubAValues[196] - acadoWorkspace.evH[156];
+acadoWorkspace.ubA[197] = acadoVariables.ubAValues[197] - acadoWorkspace.evH[157];
+acadoWorkspace.ubA[198] = acadoVariables.ubAValues[198] - acadoWorkspace.evH[158];
+acadoWorkspace.ubA[199] = acadoVariables.ubAValues[199] - acadoWorkspace.evH[159];
+acadoWorkspace.ubA[200] = acadoVariables.ubAValues[200] - acadoWorkspace.evH[160];
+acadoWorkspace.ubA[201] = acadoVariables.ubAValues[201] - acadoWorkspace.evH[161];
+acadoWorkspace.ubA[202] = acadoVariables.ubAValues[202] - acadoWorkspace.evH[162];
+acadoWorkspace.ubA[203] = acadoVariables.ubAValues[203] - acadoWorkspace.evH[163];
+acadoWorkspace.ubA[204] = acadoVariables.ubAValues[204] - acadoWorkspace.evH[164];
+acadoWorkspace.ubA[205] = acadoVariables.ubAValues[205] - acadoWorkspace.evH[165];
+acadoWorkspace.ubA[206] = acadoVariables.ubAValues[206] - acadoWorkspace.evH[166];
+acadoWorkspace.ubA[207] = acadoVariables.ubAValues[207] - acadoWorkspace.evH[167];
+acadoWorkspace.ubA[208] = acadoVariables.ubAValues[208] - acadoWorkspace.evH[168];
+acadoWorkspace.ubA[209] = acadoVariables.ubAValues[209] - acadoWorkspace.evH[169];
+acadoWorkspace.ubA[210] = acadoVariables.ubAValues[210] - acadoWorkspace.evH[170];
+acadoWorkspace.ubA[211] = acadoVariables.ubAValues[211] - acadoWorkspace.evH[171];
+acadoWorkspace.ubA[212] = acadoVariables.ubAValues[212] - acadoWorkspace.evH[172];
+acadoWorkspace.ubA[213] = acadoVariables.ubAValues[213] - acadoWorkspace.evH[173];
+acadoWorkspace.ubA[214] = acadoVariables.ubAValues[214] - acadoWorkspace.evH[174];
+acadoWorkspace.ubA[215] = acadoVariables.ubAValues[215] - acadoWorkspace.evH[175];
+acadoWorkspace.ubA[216] = acadoVariables.ubAValues[216] - acadoWorkspace.evH[176];
+acadoWorkspace.ubA[217] = acadoVariables.ubAValues[217] - acadoWorkspace.evH[177];
+acadoWorkspace.ubA[218] = acadoVariables.ubAValues[218] - acadoWorkspace.evH[178];
+acadoWorkspace.ubA[219] = acadoVariables.ubAValues[219] - acadoWorkspace.evH[179];
+acadoWorkspace.ubA[220] = acadoVariables.ubAValues[220] - acadoWorkspace.evH[180];
+acadoWorkspace.ubA[221] = acadoVariables.ubAValues[221] - acadoWorkspace.evH[181];
+acadoWorkspace.ubA[222] = acadoVariables.ubAValues[222] - acadoWorkspace.evH[182];
+acadoWorkspace.ubA[223] = acadoVariables.ubAValues[223] - acadoWorkspace.evH[183];
+acadoWorkspace.ubA[224] = acadoVariables.ubAValues[224] - acadoWorkspace.evH[184];
+acadoWorkspace.ubA[225] = acadoVariables.ubAValues[225] - acadoWorkspace.evH[185];
+acadoWorkspace.ubA[226] = acadoVariables.ubAValues[226] - acadoWorkspace.evH[186];
+acadoWorkspace.ubA[227] = acadoVariables.ubAValues[227] - acadoWorkspace.evH[187];
+acadoWorkspace.ubA[228] = acadoVariables.ubAValues[228] - acadoWorkspace.evH[188];
+acadoWorkspace.ubA[229] = acadoVariables.ubAValues[229] - acadoWorkspace.evH[189];
+acadoWorkspace.ubA[230] = acadoVariables.ubAValues[230] - acadoWorkspace.evH[190];
+acadoWorkspace.ubA[231] = acadoVariables.ubAValues[231] - acadoWorkspace.evH[191];
+acadoWorkspace.ubA[232] = acadoVariables.ubAValues[232] - acadoWorkspace.evH[192];
+acadoWorkspace.ubA[233] = acadoVariables.ubAValues[233] - acadoWorkspace.evH[193];
+acadoWorkspace.ubA[234] = acadoVariables.ubAValues[234] - acadoWorkspace.evH[194];
+acadoWorkspace.ubA[235] = acadoVariables.ubAValues[235] - acadoWorkspace.evH[195];
+acadoWorkspace.ubA[236] = acadoVariables.ubAValues[236] - acadoWorkspace.evH[196];
+acadoWorkspace.ubA[237] = acadoVariables.ubAValues[237] - acadoWorkspace.evH[197];
+acadoWorkspace.ubA[238] = acadoVariables.ubAValues[238] - acadoWorkspace.evH[198];
+acadoWorkspace.ubA[239] = acadoVariables.ubAValues[239] - acadoWorkspace.evH[199];
+
+}
+
+void acado_condenseFdb(  )
+{
+int lRun1;
+real_t tmp;
+
+acadoWorkspace.Dx0[0] = acadoVariables.x0[0] - acadoVariables.x[0];
+acadoWorkspace.Dx0[1] = acadoVariables.x0[1] - acadoVariables.x[1];
+acadoWorkspace.Dx0[2] = acadoVariables.x0[2] - acadoVariables.x[2];
+acadoWorkspace.Dx0[3] = acadoVariables.x0[3] - acadoVariables.x[3];
+acadoWorkspace.Dx0[4] = acadoVariables.x0[4] - acadoVariables.x[4];
+for (lRun1 = 0; lRun1 < 160; ++lRun1)
+acadoWorkspace.Dy[lRun1] -= acadoVariables.y[lRun1];
+
+acadoWorkspace.DyN[0] -= acadoVariables.yN[0];
+acadoWorkspace.DyN[1] -= acadoVariables.yN[1];
+acadoWorkspace.DyN[2] -= acadoVariables.yN[2];
+acadoWorkspace.DyN[3] -= acadoVariables.yN[3];
+acadoWorkspace.DyN[4] -= acadoVariables.yN[4];
+
+acado_multRDy( acadoWorkspace.R2, acadoWorkspace.Dy, acadoWorkspace.g );
+acado_multRDy( &(acadoWorkspace.R2[ 16 ]), &(acadoWorkspace.Dy[ 8 ]), &(acadoWorkspace.g[ 2 ]) );
+acado_multRDy( &(acadoWorkspace.R2[ 32 ]), &(acadoWorkspace.Dy[ 16 ]), &(acadoWorkspace.g[ 4 ]) );
+acado_multRDy( &(acadoWorkspace.R2[ 48 ]), &(acadoWorkspace.Dy[ 24 ]), &(acadoWorkspace.g[ 6 ]) );
+acado_multRDy( &(acadoWorkspace.R2[ 64 ]), &(acadoWorkspace.Dy[ 32 ]), &(acadoWorkspace.g[ 8 ]) );
+acado_multRDy( &(acadoWorkspace.R2[ 80 ]), &(acadoWorkspace.Dy[ 40 ]), &(acadoWorkspace.g[ 10 ]) );
+acado_multRDy( &(acadoWorkspace.R2[ 96 ]), &(acadoWorkspace.Dy[ 48 ]), &(acadoWorkspace.g[ 12 ]) );
+acado_multRDy( &(acadoWorkspace.R2[ 112 ]), &(acadoWorkspace.Dy[ 56 ]), &(acadoWorkspace.g[ 14 ]) );
+acado_multRDy( &(acadoWorkspace.R2[ 128 ]), &(acadoWorkspace.Dy[ 64 ]), &(acadoWorkspace.g[ 16 ]) );
+acado_multRDy( &(acadoWorkspace.R2[ 144 ]), &(acadoWorkspace.Dy[ 72 ]), &(acadoWorkspace.g[ 18 ]) );
+acado_multRDy( &(acadoWorkspace.R2[ 160 ]), &(acadoWorkspace.Dy[ 80 ]), &(acadoWorkspace.g[ 20 ]) );
+acado_multRDy( &(acadoWorkspace.R2[ 176 ]), &(acadoWorkspace.Dy[ 88 ]), &(acadoWorkspace.g[ 22 ]) );
+acado_multRDy( &(acadoWorkspace.R2[ 192 ]), &(acadoWorkspace.Dy[ 96 ]), &(acadoWorkspace.g[ 24 ]) );
+acado_multRDy( &(acadoWorkspace.R2[ 208 ]), &(acadoWorkspace.Dy[ 104 ]), &(acadoWorkspace.g[ 26 ]) );
+acado_multRDy( &(acadoWorkspace.R2[ 224 ]), &(acadoWorkspace.Dy[ 112 ]), &(acadoWorkspace.g[ 28 ]) );
+acado_multRDy( &(acadoWorkspace.R2[ 240 ]), &(acadoWorkspace.Dy[ 120 ]), &(acadoWorkspace.g[ 30 ]) );
+acado_multRDy( &(acadoWorkspace.R2[ 256 ]), &(acadoWorkspace.Dy[ 128 ]), &(acadoWorkspace.g[ 32 ]) );
+acado_multRDy( &(acadoWorkspace.R2[ 272 ]), &(acadoWorkspace.Dy[ 136 ]), &(acadoWorkspace.g[ 34 ]) );
+acado_multRDy( &(acadoWorkspace.R2[ 288 ]), &(acadoWorkspace.Dy[ 144 ]), &(acadoWorkspace.g[ 36 ]) );
+acado_multRDy( &(acadoWorkspace.R2[ 304 ]), &(acadoWorkspace.Dy[ 152 ]), &(acadoWorkspace.g[ 38 ]) );
+
+acado_multQDy( acadoWorkspace.Q2, acadoWorkspace.Dy, acadoWorkspace.QDy );
+acado_multQDy( &(acadoWorkspace.Q2[ 40 ]), &(acadoWorkspace.Dy[ 8 ]), &(acadoWorkspace.QDy[ 5 ]) );
+acado_multQDy( &(acadoWorkspace.Q2[ 80 ]), &(acadoWorkspace.Dy[ 16 ]), &(acadoWorkspace.QDy[ 10 ]) );
+acado_multQDy( &(acadoWorkspace.Q2[ 120 ]), &(acadoWorkspace.Dy[ 24 ]), &(acadoWorkspace.QDy[ 15 ]) );
+acado_multQDy( &(acadoWorkspace.Q2[ 160 ]), &(acadoWorkspace.Dy[ 32 ]), &(acadoWorkspace.QDy[ 20 ]) );
+acado_multQDy( &(acadoWorkspace.Q2[ 200 ]), &(acadoWorkspace.Dy[ 40 ]), &(acadoWorkspace.QDy[ 25 ]) );
+acado_multQDy( &(acadoWorkspace.Q2[ 240 ]), &(acadoWorkspace.Dy[ 48 ]), &(acadoWorkspace.QDy[ 30 ]) );
+acado_multQDy( &(acadoWorkspace.Q2[ 280 ]), &(acadoWorkspace.Dy[ 56 ]), &(acadoWorkspace.QDy[ 35 ]) );
+acado_multQDy( &(acadoWorkspace.Q2[ 320 ]), &(acadoWorkspace.Dy[ 64 ]), &(acadoWorkspace.QDy[ 40 ]) );
+acado_multQDy( &(acadoWorkspace.Q2[ 360 ]), &(acadoWorkspace.Dy[ 72 ]), &(acadoWorkspace.QDy[ 45 ]) );
+acado_multQDy( &(acadoWorkspace.Q2[ 400 ]), &(acadoWorkspace.Dy[ 80 ]), &(acadoWorkspace.QDy[ 50 ]) );
+acado_multQDy( &(acadoWorkspace.Q2[ 440 ]), &(acadoWorkspace.Dy[ 88 ]), &(acadoWorkspace.QDy[ 55 ]) );
+acado_multQDy( &(acadoWorkspace.Q2[ 480 ]), &(acadoWorkspace.Dy[ 96 ]), &(acadoWorkspace.QDy[ 60 ]) );
+acado_multQDy( &(acadoWorkspace.Q2[ 520 ]), &(acadoWorkspace.Dy[ 104 ]), &(acadoWorkspace.QDy[ 65 ]) );
+acado_multQDy( &(acadoWorkspace.Q2[ 560 ]), &(acadoWorkspace.Dy[ 112 ]), &(acadoWorkspace.QDy[ 70 ]) );
+acado_multQDy( &(acadoWorkspace.Q2[ 600 ]), &(acadoWorkspace.Dy[ 120 ]), &(acadoWorkspace.QDy[ 75 ]) );
+acado_multQDy( &(acadoWorkspace.Q2[ 640 ]), &(acadoWorkspace.Dy[ 128 ]), &(acadoWorkspace.QDy[ 80 ]) );
+acado_multQDy( &(acadoWorkspace.Q2[ 680 ]), &(acadoWorkspace.Dy[ 136 ]), &(acadoWorkspace.QDy[ 85 ]) );
+acado_multQDy( &(acadoWorkspace.Q2[ 720 ]), &(acadoWorkspace.Dy[ 144 ]), &(acadoWorkspace.QDy[ 90 ]) );
+acado_multQDy( &(acadoWorkspace.Q2[ 760 ]), &(acadoWorkspace.Dy[ 152 ]), &(acadoWorkspace.QDy[ 95 ]) );
+
+acadoWorkspace.QDy[100] = + acadoWorkspace.QN2[0]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[1]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[2]*acadoWorkspace.DyN[2] + acadoWorkspace.QN2[3]*acadoWorkspace.DyN[3] + acadoWorkspace.QN2[4]*acadoWorkspace.DyN[4];
+acadoWorkspace.QDy[101] = + acadoWorkspace.QN2[5]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[6]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[7]*acadoWorkspace.DyN[2] + acadoWorkspace.QN2[8]*acadoWorkspace.DyN[3] + acadoWorkspace.QN2[9]*acadoWorkspace.DyN[4];
+acadoWorkspace.QDy[102] = + acadoWorkspace.QN2[10]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[11]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[12]*acadoWorkspace.DyN[2] + acadoWorkspace.QN2[13]*acadoWorkspace.DyN[3] + acadoWorkspace.QN2[14]*acadoWorkspace.DyN[4];
+acadoWorkspace.QDy[103] = + acadoWorkspace.QN2[15]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[16]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[17]*acadoWorkspace.DyN[2] + acadoWorkspace.QN2[18]*acadoWorkspace.DyN[3] + acadoWorkspace.QN2[19]*acadoWorkspace.DyN[4];
+acadoWorkspace.QDy[104] = + acadoWorkspace.QN2[20]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[21]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[22]*acadoWorkspace.DyN[2] + acadoWorkspace.QN2[23]*acadoWorkspace.DyN[3] + acadoWorkspace.QN2[24]*acadoWorkspace.DyN[4];
+
+acadoWorkspace.sbar[0] = acadoWorkspace.Dx0[0];
+acadoWorkspace.sbar[1] = acadoWorkspace.Dx0[1];
+acadoWorkspace.sbar[2] = acadoWorkspace.Dx0[2];
+acadoWorkspace.sbar[3] = acadoWorkspace.Dx0[3];
+acadoWorkspace.sbar[4] = acadoWorkspace.Dx0[4];
+acado_macASbar( acadoWorkspace.evGx, acadoWorkspace.sbar, &(acadoWorkspace.sbar[ 5 ]) );
+acado_macASbar( &(acadoWorkspace.evGx[ 25 ]), &(acadoWorkspace.sbar[ 5 ]), &(acadoWorkspace.sbar[ 10 ]) );
+acado_macASbar( &(acadoWorkspace.evGx[ 50 ]), &(acadoWorkspace.sbar[ 10 ]), &(acadoWorkspace.sbar[ 15 ]) );
+acado_macASbar( &(acadoWorkspace.evGx[ 75 ]), &(acadoWorkspace.sbar[ 15 ]), &(acadoWorkspace.sbar[ 20 ]) );
+acado_macASbar( &(acadoWorkspace.evGx[ 100 ]), &(acadoWorkspace.sbar[ 20 ]), &(acadoWorkspace.sbar[ 25 ]) );
+acado_macASbar( &(acadoWorkspace.evGx[ 125 ]), &(acadoWorkspace.sbar[ 25 ]), &(acadoWorkspace.sbar[ 30 ]) );
+acado_macASbar( &(acadoWorkspace.evGx[ 150 ]), &(acadoWorkspace.sbar[ 30 ]), &(acadoWorkspace.sbar[ 35 ]) );
+acado_macASbar( &(acadoWorkspace.evGx[ 175 ]), &(acadoWorkspace.sbar[ 35 ]), &(acadoWorkspace.sbar[ 40 ]) );
+acado_macASbar( &(acadoWorkspace.evGx[ 200 ]), &(acadoWorkspace.sbar[ 40 ]), &(acadoWorkspace.sbar[ 45 ]) );
+acado_macASbar( &(acadoWorkspace.evGx[ 225 ]), &(acadoWorkspace.sbar[ 45 ]), &(acadoWorkspace.sbar[ 50 ]) );
+acado_macASbar( &(acadoWorkspace.evGx[ 250 ]), &(acadoWorkspace.sbar[ 50 ]), &(acadoWorkspace.sbar[ 55 ]) );
+acado_macASbar( &(acadoWorkspace.evGx[ 275 ]), &(acadoWorkspace.sbar[ 55 ]), &(acadoWorkspace.sbar[ 60 ]) );
+acado_macASbar( &(acadoWorkspace.evGx[ 300 ]), &(acadoWorkspace.sbar[ 60 ]), &(acadoWorkspace.sbar[ 65 ]) );
+acado_macASbar( &(acadoWorkspace.evGx[ 325 ]), &(acadoWorkspace.sbar[ 65 ]), &(acadoWorkspace.sbar[ 70 ]) );
+acado_macASbar( &(acadoWorkspace.evGx[ 350 ]), &(acadoWorkspace.sbar[ 70 ]), &(acadoWorkspace.sbar[ 75 ]) );
+acado_macASbar( &(acadoWorkspace.evGx[ 375 ]), &(acadoWorkspace.sbar[ 75 ]), &(acadoWorkspace.sbar[ 80 ]) );
+acado_macASbar( &(acadoWorkspace.evGx[ 400 ]), &(acadoWorkspace.sbar[ 80 ]), &(acadoWorkspace.sbar[ 85 ]) );
+acado_macASbar( &(acadoWorkspace.evGx[ 425 ]), &(acadoWorkspace.sbar[ 85 ]), &(acadoWorkspace.sbar[ 90 ]) );
+acado_macASbar( &(acadoWorkspace.evGx[ 450 ]), &(acadoWorkspace.sbar[ 90 ]), &(acadoWorkspace.sbar[ 95 ]) );
+acado_macASbar( &(acadoWorkspace.evGx[ 475 ]), &(acadoWorkspace.sbar[ 95 ]), &(acadoWorkspace.sbar[ 100 ]) );
+
+acadoWorkspace.w1[0] = + acadoWorkspace.QN1[0]*acadoWorkspace.sbar[100] + acadoWorkspace.QN1[1]*acadoWorkspace.sbar[101] + acadoWorkspace.QN1[2]*acadoWorkspace.sbar[102] + acadoWorkspace.QN1[3]*acadoWorkspace.sbar[103] + acadoWorkspace.QN1[4]*acadoWorkspace.sbar[104] + acadoWorkspace.QDy[100];
+acadoWorkspace.w1[1] = + acadoWorkspace.QN1[5]*acadoWorkspace.sbar[100] + acadoWorkspace.QN1[6]*acadoWorkspace.sbar[101] + acadoWorkspace.QN1[7]*acadoWorkspace.sbar[102] + acadoWorkspace.QN1[8]*acadoWorkspace.sbar[103] + acadoWorkspace.QN1[9]*acadoWorkspace.sbar[104] + acadoWorkspace.QDy[101];
+acadoWorkspace.w1[2] = + acadoWorkspace.QN1[10]*acadoWorkspace.sbar[100] + acadoWorkspace.QN1[11]*acadoWorkspace.sbar[101] + acadoWorkspace.QN1[12]*acadoWorkspace.sbar[102] + acadoWorkspace.QN1[13]*acadoWorkspace.sbar[103] + acadoWorkspace.QN1[14]*acadoWorkspace.sbar[104] + acadoWorkspace.QDy[102];
+acadoWorkspace.w1[3] = + acadoWorkspace.QN1[15]*acadoWorkspace.sbar[100] + acadoWorkspace.QN1[16]*acadoWorkspace.sbar[101] + acadoWorkspace.QN1[17]*acadoWorkspace.sbar[102] + acadoWorkspace.QN1[18]*acadoWorkspace.sbar[103] + acadoWorkspace.QN1[19]*acadoWorkspace.sbar[104] + acadoWorkspace.QDy[103];
+acadoWorkspace.w1[4] = + acadoWorkspace.QN1[20]*acadoWorkspace.sbar[100] + acadoWorkspace.QN1[21]*acadoWorkspace.sbar[101] + acadoWorkspace.QN1[22]*acadoWorkspace.sbar[102] + acadoWorkspace.QN1[23]*acadoWorkspace.sbar[103] + acadoWorkspace.QN1[24]*acadoWorkspace.sbar[104] + acadoWorkspace.QDy[104];
+acado_macBTw1( &(acadoWorkspace.evGu[ 190 ]), acadoWorkspace.w1, &(acadoWorkspace.g[ 38 ]) );
+acado_macATw1QDy( &(acadoWorkspace.evGx[ 475 ]), acadoWorkspace.w1, &(acadoWorkspace.QDy[ 95 ]), acadoWorkspace.w2 );
+acado_macQSbarW2( &(acadoWorkspace.Q1[ 475 ]), &(acadoWorkspace.sbar[ 95 ]), acadoWorkspace.w2, acadoWorkspace.w1 );
+acado_macBTw1( &(acadoWorkspace.evGu[ 180 ]), acadoWorkspace.w1, &(acadoWorkspace.g[ 36 ]) );
+acado_macATw1QDy( &(acadoWorkspace.evGx[ 450 ]), acadoWorkspace.w1, &(acadoWorkspace.QDy[ 90 ]), acadoWorkspace.w2 );
+acado_macQSbarW2( &(acadoWorkspace.Q1[ 450 ]), &(acadoWorkspace.sbar[ 90 ]), acadoWorkspace.w2, acadoWorkspace.w1 );
+acado_macBTw1( &(acadoWorkspace.evGu[ 170 ]), acadoWorkspace.w1, &(acadoWorkspace.g[ 34 ]) );
+acado_macATw1QDy( &(acadoWorkspace.evGx[ 425 ]), acadoWorkspace.w1, &(acadoWorkspace.QDy[ 85 ]), acadoWorkspace.w2 );
+acado_macQSbarW2( &(acadoWorkspace.Q1[ 425 ]), &(acadoWorkspace.sbar[ 85 ]), acadoWorkspace.w2, acadoWorkspace.w1 );
+acado_macBTw1( &(acadoWorkspace.evGu[ 160 ]), acadoWorkspace.w1, &(acadoWorkspace.g[ 32 ]) );
+acado_macATw1QDy( &(acadoWorkspace.evGx[ 400 ]), acadoWorkspace.w1, &(acadoWorkspace.QDy[ 80 ]), acadoWorkspace.w2 );
+acado_macQSbarW2( &(acadoWorkspace.Q1[ 400 ]), &(acadoWorkspace.sbar[ 80 ]), acadoWorkspace.w2, acadoWorkspace.w1 );
+acado_macBTw1( &(acadoWorkspace.evGu[ 150 ]), acadoWorkspace.w1, &(acadoWorkspace.g[ 30 ]) );
+acado_macATw1QDy( &(acadoWorkspace.evGx[ 375 ]), acadoWorkspace.w1, &(acadoWorkspace.QDy[ 75 ]), acadoWorkspace.w2 );
+acado_macQSbarW2( &(acadoWorkspace.Q1[ 375 ]), &(acadoWorkspace.sbar[ 75 ]), acadoWorkspace.w2, acadoWorkspace.w1 );
+acado_macBTw1( &(acadoWorkspace.evGu[ 140 ]), acadoWorkspace.w1, &(acadoWorkspace.g[ 28 ]) );
+acado_macATw1QDy( &(acadoWorkspace.evGx[ 350 ]), acadoWorkspace.w1, &(acadoWorkspace.QDy[ 70 ]), acadoWorkspace.w2 );
+acado_macQSbarW2( &(acadoWorkspace.Q1[ 350 ]), &(acadoWorkspace.sbar[ 70 ]), acadoWorkspace.w2, acadoWorkspace.w1 );
+acado_macBTw1( &(acadoWorkspace.evGu[ 130 ]), acadoWorkspace.w1, &(acadoWorkspace.g[ 26 ]) );
+acado_macATw1QDy( &(acadoWorkspace.evGx[ 325 ]), acadoWorkspace.w1, &(acadoWorkspace.QDy[ 65 ]), acadoWorkspace.w2 );
+acado_macQSbarW2( &(acadoWorkspace.Q1[ 325 ]), &(acadoWorkspace.sbar[ 65 ]), acadoWorkspace.w2, acadoWorkspace.w1 );
+acado_macBTw1( &(acadoWorkspace.evGu[ 120 ]), acadoWorkspace.w1, &(acadoWorkspace.g[ 24 ]) );
+acado_macATw1QDy( &(acadoWorkspace.evGx[ 300 ]), acadoWorkspace.w1, &(acadoWorkspace.QDy[ 60 ]), acadoWorkspace.w2 );
+acado_macQSbarW2( &(acadoWorkspace.Q1[ 300 ]), &(acadoWorkspace.sbar[ 60 ]), acadoWorkspace.w2, acadoWorkspace.w1 );
+acado_macBTw1( &(acadoWorkspace.evGu[ 110 ]), acadoWorkspace.w1, &(acadoWorkspace.g[ 22 ]) );
+acado_macATw1QDy( &(acadoWorkspace.evGx[ 275 ]), acadoWorkspace.w1, &(acadoWorkspace.QDy[ 55 ]), acadoWorkspace.w2 );
+acado_macQSbarW2( &(acadoWorkspace.Q1[ 275 ]), &(acadoWorkspace.sbar[ 55 ]), acadoWorkspace.w2, acadoWorkspace.w1 );
+acado_macBTw1( &(acadoWorkspace.evGu[ 100 ]), acadoWorkspace.w1, &(acadoWorkspace.g[ 20 ]) );
+acado_macATw1QDy( &(acadoWorkspace.evGx[ 250 ]), acadoWorkspace.w1, &(acadoWorkspace.QDy[ 50 ]), acadoWorkspace.w2 );
+acado_macQSbarW2( &(acadoWorkspace.Q1[ 250 ]), &(acadoWorkspace.sbar[ 50 ]), acadoWorkspace.w2, acadoWorkspace.w1 );
+acado_macBTw1( &(acadoWorkspace.evGu[ 90 ]), acadoWorkspace.w1, &(acadoWorkspace.g[ 18 ]) );
+acado_macATw1QDy( &(acadoWorkspace.evGx[ 225 ]), acadoWorkspace.w1, &(acadoWorkspace.QDy[ 45 ]), acadoWorkspace.w2 );
+acado_macQSbarW2( &(acadoWorkspace.Q1[ 225 ]), &(acadoWorkspace.sbar[ 45 ]), acadoWorkspace.w2, acadoWorkspace.w1 );
+acado_macBTw1( &(acadoWorkspace.evGu[ 80 ]), acadoWorkspace.w1, &(acadoWorkspace.g[ 16 ]) );
+acado_macATw1QDy( &(acadoWorkspace.evGx[ 200 ]), acadoWorkspace.w1, &(acadoWorkspace.QDy[ 40 ]), acadoWorkspace.w2 );
+acado_macQSbarW2( &(acadoWorkspace.Q1[ 200 ]), &(acadoWorkspace.sbar[ 40 ]), acadoWorkspace.w2, acadoWorkspace.w1 );
+acado_macBTw1( &(acadoWorkspace.evGu[ 70 ]), acadoWorkspace.w1, &(acadoWorkspace.g[ 14 ]) );
+acado_macATw1QDy( &(acadoWorkspace.evGx[ 175 ]), acadoWorkspace.w1, &(acadoWorkspace.QDy[ 35 ]), acadoWorkspace.w2 );
+acado_macQSbarW2( &(acadoWorkspace.Q1[ 175 ]), &(acadoWorkspace.sbar[ 35 ]), acadoWorkspace.w2, acadoWorkspace.w1 );
+acado_macBTw1( &(acadoWorkspace.evGu[ 60 ]), acadoWorkspace.w1, &(acadoWorkspace.g[ 12 ]) );
+acado_macATw1QDy( &(acadoWorkspace.evGx[ 150 ]), acadoWorkspace.w1, &(acadoWorkspace.QDy[ 30 ]), acadoWorkspace.w2 );
+acado_macQSbarW2( &(acadoWorkspace.Q1[ 150 ]), &(acadoWorkspace.sbar[ 30 ]), acadoWorkspace.w2, acadoWorkspace.w1 );
+acado_macBTw1( &(acadoWorkspace.evGu[ 50 ]), acadoWorkspace.w1, &(acadoWorkspace.g[ 10 ]) );
+acado_macATw1QDy( &(acadoWorkspace.evGx[ 125 ]), acadoWorkspace.w1, &(acadoWorkspace.QDy[ 25 ]), acadoWorkspace.w2 );
+acado_macQSbarW2( &(acadoWorkspace.Q1[ 125 ]), &(acadoWorkspace.sbar[ 25 ]), acadoWorkspace.w2, acadoWorkspace.w1 );
+acado_macBTw1( &(acadoWorkspace.evGu[ 40 ]), acadoWorkspace.w1, &(acadoWorkspace.g[ 8 ]) );
+acado_macATw1QDy( &(acadoWorkspace.evGx[ 100 ]), acadoWorkspace.w1, &(acadoWorkspace.QDy[ 20 ]), acadoWorkspace.w2 );
+acado_macQSbarW2( &(acadoWorkspace.Q1[ 100 ]), &(acadoWorkspace.sbar[ 20 ]), acadoWorkspace.w2, acadoWorkspace.w1 );
+acado_macBTw1( &(acadoWorkspace.evGu[ 30 ]), acadoWorkspace.w1, &(acadoWorkspace.g[ 6 ]) );
+acado_macATw1QDy( &(acadoWorkspace.evGx[ 75 ]), acadoWorkspace.w1, &(acadoWorkspace.QDy[ 15 ]), acadoWorkspace.w2 );
+acado_macQSbarW2( &(acadoWorkspace.Q1[ 75 ]), &(acadoWorkspace.sbar[ 15 ]), acadoWorkspace.w2, acadoWorkspace.w1 );
+acado_macBTw1( &(acadoWorkspace.evGu[ 20 ]), acadoWorkspace.w1, &(acadoWorkspace.g[ 4 ]) );
+acado_macATw1QDy( &(acadoWorkspace.evGx[ 50 ]), acadoWorkspace.w1, &(acadoWorkspace.QDy[ 10 ]), acadoWorkspace.w2 );
+acado_macQSbarW2( &(acadoWorkspace.Q1[ 50 ]), &(acadoWorkspace.sbar[ 10 ]), acadoWorkspace.w2, acadoWorkspace.w1 );
+acado_macBTw1( &(acadoWorkspace.evGu[ 10 ]), acadoWorkspace.w1, &(acadoWorkspace.g[ 2 ]) );
+acado_macATw1QDy( &(acadoWorkspace.evGx[ 25 ]), acadoWorkspace.w1, &(acadoWorkspace.QDy[ 5 ]), acadoWorkspace.w2 );
+acado_macQSbarW2( &(acadoWorkspace.Q1[ 25 ]), &(acadoWorkspace.sbar[ 5 ]), acadoWorkspace.w2, acadoWorkspace.w1 );
+acado_macBTw1( acadoWorkspace.evGu, acadoWorkspace.w1, acadoWorkspace.g );
+
+acadoWorkspace.lb[0] = acadoVariables.lbValues[0] - acadoVariables.u[0];
+acadoWorkspace.lb[1] = acadoVariables.lbValues[1] - acadoVariables.u[1];
+acadoWorkspace.lb[2] = acadoVariables.lbValues[2] - acadoVariables.u[2];
+acadoWorkspace.lb[3] = acadoVariables.lbValues[3] - acadoVariables.u[3];
+acadoWorkspace.lb[4] = acadoVariables.lbValues[4] - acadoVariables.u[4];
+acadoWorkspace.lb[5] = acadoVariables.lbValues[5] - acadoVariables.u[5];
+acadoWorkspace.lb[6] = acadoVariables.lbValues[6] - acadoVariables.u[6];
+acadoWorkspace.lb[7] = acadoVariables.lbValues[7] - acadoVariables.u[7];
+acadoWorkspace.lb[8] = acadoVariables.lbValues[8] - acadoVariables.u[8];
+acadoWorkspace.lb[9] = acadoVariables.lbValues[9] - acadoVariables.u[9];
+acadoWorkspace.lb[10] = acadoVariables.lbValues[10] - acadoVariables.u[10];
+acadoWorkspace.lb[11] = acadoVariables.lbValues[11] - acadoVariables.u[11];
+acadoWorkspace.lb[12] = acadoVariables.lbValues[12] - acadoVariables.u[12];
+acadoWorkspace.lb[13] = acadoVariables.lbValues[13] - acadoVariables.u[13];
+acadoWorkspace.lb[14] = acadoVariables.lbValues[14] - acadoVariables.u[14];
+acadoWorkspace.lb[15] = acadoVariables.lbValues[15] - acadoVariables.u[15];
+acadoWorkspace.lb[16] = acadoVariables.lbValues[16] - acadoVariables.u[16];
+acadoWorkspace.lb[17] = acadoVariables.lbValues[17] - acadoVariables.u[17];
+acadoWorkspace.lb[18] = acadoVariables.lbValues[18] - acadoVariables.u[18];
+acadoWorkspace.lb[19] = acadoVariables.lbValues[19] - acadoVariables.u[19];
+acadoWorkspace.lb[20] = acadoVariables.lbValues[20] - acadoVariables.u[20];
+acadoWorkspace.lb[21] = acadoVariables.lbValues[21] - acadoVariables.u[21];
+acadoWorkspace.lb[22] = acadoVariables.lbValues[22] - acadoVariables.u[22];
+acadoWorkspace.lb[23] = acadoVariables.lbValues[23] - acadoVariables.u[23];
+acadoWorkspace.lb[24] = acadoVariables.lbValues[24] - acadoVariables.u[24];
+acadoWorkspace.lb[25] = acadoVariables.lbValues[25] - acadoVariables.u[25];
+acadoWorkspace.lb[26] = acadoVariables.lbValues[26] - acadoVariables.u[26];
+acadoWorkspace.lb[27] = acadoVariables.lbValues[27] - acadoVariables.u[27];
+acadoWorkspace.lb[28] = acadoVariables.lbValues[28] - acadoVariables.u[28];
+acadoWorkspace.lb[29] = acadoVariables.lbValues[29] - acadoVariables.u[29];
+acadoWorkspace.lb[30] = acadoVariables.lbValues[30] - acadoVariables.u[30];
+acadoWorkspace.lb[31] = acadoVariables.lbValues[31] - acadoVariables.u[31];
+acadoWorkspace.lb[32] = acadoVariables.lbValues[32] - acadoVariables.u[32];
+acadoWorkspace.lb[33] = acadoVariables.lbValues[33] - acadoVariables.u[33];
+acadoWorkspace.lb[34] = acadoVariables.lbValues[34] - acadoVariables.u[34];
+acadoWorkspace.lb[35] = acadoVariables.lbValues[35] - acadoVariables.u[35];
+acadoWorkspace.lb[36] = acadoVariables.lbValues[36] - acadoVariables.u[36];
+acadoWorkspace.lb[37] = acadoVariables.lbValues[37] - acadoVariables.u[37];
+acadoWorkspace.lb[38] = acadoVariables.lbValues[38] - acadoVariables.u[38];
+acadoWorkspace.lb[39] = acadoVariables.lbValues[39] - acadoVariables.u[39];
+acadoWorkspace.ub[0] = acadoVariables.ubValues[0] - acadoVariables.u[0];
+acadoWorkspace.ub[1] = acadoVariables.ubValues[1] - acadoVariables.u[1];
+acadoWorkspace.ub[2] = acadoVariables.ubValues[2] - acadoVariables.u[2];
+acadoWorkspace.ub[3] = acadoVariables.ubValues[3] - acadoVariables.u[3];
+acadoWorkspace.ub[4] = acadoVariables.ubValues[4] - acadoVariables.u[4];
+acadoWorkspace.ub[5] = acadoVariables.ubValues[5] - acadoVariables.u[5];
+acadoWorkspace.ub[6] = acadoVariables.ubValues[6] - acadoVariables.u[6];
+acadoWorkspace.ub[7] = acadoVariables.ubValues[7] - acadoVariables.u[7];
+acadoWorkspace.ub[8] = acadoVariables.ubValues[8] - acadoVariables.u[8];
+acadoWorkspace.ub[9] = acadoVariables.ubValues[9] - acadoVariables.u[9];
+acadoWorkspace.ub[10] = acadoVariables.ubValues[10] - acadoVariables.u[10];
+acadoWorkspace.ub[11] = acadoVariables.ubValues[11] - acadoVariables.u[11];
+acadoWorkspace.ub[12] = acadoVariables.ubValues[12] - acadoVariables.u[12];
+acadoWorkspace.ub[13] = acadoVariables.ubValues[13] - acadoVariables.u[13];
+acadoWorkspace.ub[14] = acadoVariables.ubValues[14] - acadoVariables.u[14];
+acadoWorkspace.ub[15] = acadoVariables.ubValues[15] - acadoVariables.u[15];
+acadoWorkspace.ub[16] = acadoVariables.ubValues[16] - acadoVariables.u[16];
+acadoWorkspace.ub[17] = acadoVariables.ubValues[17] - acadoVariables.u[17];
+acadoWorkspace.ub[18] = acadoVariables.ubValues[18] - acadoVariables.u[18];
+acadoWorkspace.ub[19] = acadoVariables.ubValues[19] - acadoVariables.u[19];
+acadoWorkspace.ub[20] = acadoVariables.ubValues[20] - acadoVariables.u[20];
+acadoWorkspace.ub[21] = acadoVariables.ubValues[21] - acadoVariables.u[21];
+acadoWorkspace.ub[22] = acadoVariables.ubValues[22] - acadoVariables.u[22];
+acadoWorkspace.ub[23] = acadoVariables.ubValues[23] - acadoVariables.u[23];
+acadoWorkspace.ub[24] = acadoVariables.ubValues[24] - acadoVariables.u[24];
+acadoWorkspace.ub[25] = acadoVariables.ubValues[25] - acadoVariables.u[25];
+acadoWorkspace.ub[26] = acadoVariables.ubValues[26] - acadoVariables.u[26];
+acadoWorkspace.ub[27] = acadoVariables.ubValues[27] - acadoVariables.u[27];
+acadoWorkspace.ub[28] = acadoVariables.ubValues[28] - acadoVariables.u[28];
+acadoWorkspace.ub[29] = acadoVariables.ubValues[29] - acadoVariables.u[29];
+acadoWorkspace.ub[30] = acadoVariables.ubValues[30] - acadoVariables.u[30];
+acadoWorkspace.ub[31] = acadoVariables.ubValues[31] - acadoVariables.u[31];
+acadoWorkspace.ub[32] = acadoVariables.ubValues[32] - acadoVariables.u[32];
+acadoWorkspace.ub[33] = acadoVariables.ubValues[33] - acadoVariables.u[33];
+acadoWorkspace.ub[34] = acadoVariables.ubValues[34] - acadoVariables.u[34];
+acadoWorkspace.ub[35] = acadoVariables.ubValues[35] - acadoVariables.u[35];
+acadoWorkspace.ub[36] = acadoVariables.ubValues[36] - acadoVariables.u[36];
+acadoWorkspace.ub[37] = acadoVariables.ubValues[37] - acadoVariables.u[37];
+acadoWorkspace.ub[38] = acadoVariables.ubValues[38] - acadoVariables.u[38];
+acadoWorkspace.ub[39] = acadoVariables.ubValues[39] - acadoVariables.u[39];
+
+tmp = acadoWorkspace.sbar[8] + acadoVariables.x[8];
+acadoWorkspace.lbA[0] = acadoVariables.lbAValues[0] - tmp;
+acadoWorkspace.ubA[0] = acadoVariables.ubAValues[0] - tmp;
+tmp = acadoWorkspace.sbar[9] + acadoVariables.x[9];
+acadoWorkspace.lbA[1] = acadoVariables.lbAValues[1] - tmp;
+acadoWorkspace.ubA[1] = acadoVariables.ubAValues[1] - tmp;
+tmp = acadoWorkspace.sbar[13] + acadoVariables.x[13];
+acadoWorkspace.lbA[2] = acadoVariables.lbAValues[2] - tmp;
+acadoWorkspace.ubA[2] = acadoVariables.ubAValues[2] - tmp;
+tmp = acadoWorkspace.sbar[14] + acadoVariables.x[14];
+acadoWorkspace.lbA[3] = acadoVariables.lbAValues[3] - tmp;
+acadoWorkspace.ubA[3] = acadoVariables.ubAValues[3] - tmp;
+tmp = acadoWorkspace.sbar[18] + acadoVariables.x[18];
+acadoWorkspace.lbA[4] = acadoVariables.lbAValues[4] - tmp;
+acadoWorkspace.ubA[4] = acadoVariables.ubAValues[4] - tmp;
+tmp = acadoWorkspace.sbar[19] + acadoVariables.x[19];
+acadoWorkspace.lbA[5] = acadoVariables.lbAValues[5] - tmp;
+acadoWorkspace.ubA[5] = acadoVariables.ubAValues[5] - tmp;
+tmp = acadoWorkspace.sbar[23] + acadoVariables.x[23];
+acadoWorkspace.lbA[6] = acadoVariables.lbAValues[6] - tmp;
+acadoWorkspace.ubA[6] = acadoVariables.ubAValues[6] - tmp;
+tmp = acadoWorkspace.sbar[24] + acadoVariables.x[24];
+acadoWorkspace.lbA[7] = acadoVariables.lbAValues[7] - tmp;
+acadoWorkspace.ubA[7] = acadoVariables.ubAValues[7] - tmp;
+tmp = acadoWorkspace.sbar[28] + acadoVariables.x[28];
+acadoWorkspace.lbA[8] = acadoVariables.lbAValues[8] - tmp;
+acadoWorkspace.ubA[8] = acadoVariables.ubAValues[8] - tmp;
+tmp = acadoWorkspace.sbar[29] + acadoVariables.x[29];
+acadoWorkspace.lbA[9] = acadoVariables.lbAValues[9] - tmp;
+acadoWorkspace.ubA[9] = acadoVariables.ubAValues[9] - tmp;
+tmp = acadoWorkspace.sbar[33] + acadoVariables.x[33];
+acadoWorkspace.lbA[10] = acadoVariables.lbAValues[10] - tmp;
+acadoWorkspace.ubA[10] = acadoVariables.ubAValues[10] - tmp;
+tmp = acadoWorkspace.sbar[34] + acadoVariables.x[34];
+acadoWorkspace.lbA[11] = acadoVariables.lbAValues[11] - tmp;
+acadoWorkspace.ubA[11] = acadoVariables.ubAValues[11] - tmp;
+tmp = acadoWorkspace.sbar[38] + acadoVariables.x[38];
+acadoWorkspace.lbA[12] = acadoVariables.lbAValues[12] - tmp;
+acadoWorkspace.ubA[12] = acadoVariables.ubAValues[12] - tmp;
+tmp = acadoWorkspace.sbar[39] + acadoVariables.x[39];
+acadoWorkspace.lbA[13] = acadoVariables.lbAValues[13] - tmp;
+acadoWorkspace.ubA[13] = acadoVariables.ubAValues[13] - tmp;
+tmp = acadoWorkspace.sbar[43] + acadoVariables.x[43];
+acadoWorkspace.lbA[14] = acadoVariables.lbAValues[14] - tmp;
+acadoWorkspace.ubA[14] = acadoVariables.ubAValues[14] - tmp;
+tmp = acadoWorkspace.sbar[44] + acadoVariables.x[44];
+acadoWorkspace.lbA[15] = acadoVariables.lbAValues[15] - tmp;
+acadoWorkspace.ubA[15] = acadoVariables.ubAValues[15] - tmp;
+tmp = acadoWorkspace.sbar[48] + acadoVariables.x[48];
+acadoWorkspace.lbA[16] = acadoVariables.lbAValues[16] - tmp;
+acadoWorkspace.ubA[16] = acadoVariables.ubAValues[16] - tmp;
+tmp = acadoWorkspace.sbar[49] + acadoVariables.x[49];
+acadoWorkspace.lbA[17] = acadoVariables.lbAValues[17] - tmp;
+acadoWorkspace.ubA[17] = acadoVariables.ubAValues[17] - tmp;
+tmp = acadoWorkspace.sbar[53] + acadoVariables.x[53];
+acadoWorkspace.lbA[18] = acadoVariables.lbAValues[18] - tmp;
+acadoWorkspace.ubA[18] = acadoVariables.ubAValues[18] - tmp;
+tmp = acadoWorkspace.sbar[54] + acadoVariables.x[54];
+acadoWorkspace.lbA[19] = acadoVariables.lbAValues[19] - tmp;
+acadoWorkspace.ubA[19] = acadoVariables.ubAValues[19] - tmp;
+tmp = acadoWorkspace.sbar[58] + acadoVariables.x[58];
+acadoWorkspace.lbA[20] = acadoVariables.lbAValues[20] - tmp;
+acadoWorkspace.ubA[20] = acadoVariables.ubAValues[20] - tmp;
+tmp = acadoWorkspace.sbar[59] + acadoVariables.x[59];
+acadoWorkspace.lbA[21] = acadoVariables.lbAValues[21] - tmp;
+acadoWorkspace.ubA[21] = acadoVariables.ubAValues[21] - tmp;
+tmp = acadoWorkspace.sbar[63] + acadoVariables.x[63];
+acadoWorkspace.lbA[22] = acadoVariables.lbAValues[22] - tmp;
+acadoWorkspace.ubA[22] = acadoVariables.ubAValues[22] - tmp;
+tmp = acadoWorkspace.sbar[64] + acadoVariables.x[64];
+acadoWorkspace.lbA[23] = acadoVariables.lbAValues[23] - tmp;
+acadoWorkspace.ubA[23] = acadoVariables.ubAValues[23] - tmp;
+tmp = acadoWorkspace.sbar[68] + acadoVariables.x[68];
+acadoWorkspace.lbA[24] = acadoVariables.lbAValues[24] - tmp;
+acadoWorkspace.ubA[24] = acadoVariables.ubAValues[24] - tmp;
+tmp = acadoWorkspace.sbar[69] + acadoVariables.x[69];
+acadoWorkspace.lbA[25] = acadoVariables.lbAValues[25] - tmp;
+acadoWorkspace.ubA[25] = acadoVariables.ubAValues[25] - tmp;
+tmp = acadoWorkspace.sbar[73] + acadoVariables.x[73];
+acadoWorkspace.lbA[26] = acadoVariables.lbAValues[26] - tmp;
+acadoWorkspace.ubA[26] = acadoVariables.ubAValues[26] - tmp;
+tmp = acadoWorkspace.sbar[74] + acadoVariables.x[74];
+acadoWorkspace.lbA[27] = acadoVariables.lbAValues[27] - tmp;
+acadoWorkspace.ubA[27] = acadoVariables.ubAValues[27] - tmp;
+tmp = acadoWorkspace.sbar[78] + acadoVariables.x[78];
+acadoWorkspace.lbA[28] = acadoVariables.lbAValues[28] - tmp;
+acadoWorkspace.ubA[28] = acadoVariables.ubAValues[28] - tmp;
+tmp = acadoWorkspace.sbar[79] + acadoVariables.x[79];
+acadoWorkspace.lbA[29] = acadoVariables.lbAValues[29] - tmp;
+acadoWorkspace.ubA[29] = acadoVariables.ubAValues[29] - tmp;
+tmp = acadoWorkspace.sbar[83] + acadoVariables.x[83];
+acadoWorkspace.lbA[30] = acadoVariables.lbAValues[30] - tmp;
+acadoWorkspace.ubA[30] = acadoVariables.ubAValues[30] - tmp;
+tmp = acadoWorkspace.sbar[84] + acadoVariables.x[84];
+acadoWorkspace.lbA[31] = acadoVariables.lbAValues[31] - tmp;
+acadoWorkspace.ubA[31] = acadoVariables.ubAValues[31] - tmp;
+tmp = acadoWorkspace.sbar[88] + acadoVariables.x[88];
+acadoWorkspace.lbA[32] = acadoVariables.lbAValues[32] - tmp;
+acadoWorkspace.ubA[32] = acadoVariables.ubAValues[32] - tmp;
+tmp = acadoWorkspace.sbar[89] + acadoVariables.x[89];
+acadoWorkspace.lbA[33] = acadoVariables.lbAValues[33] - tmp;
+acadoWorkspace.ubA[33] = acadoVariables.ubAValues[33] - tmp;
+tmp = acadoWorkspace.sbar[93] + acadoVariables.x[93];
+acadoWorkspace.lbA[34] = acadoVariables.lbAValues[34] - tmp;
+acadoWorkspace.ubA[34] = acadoVariables.ubAValues[34] - tmp;
+tmp = acadoWorkspace.sbar[94] + acadoVariables.x[94];
+acadoWorkspace.lbA[35] = acadoVariables.lbAValues[35] - tmp;
+acadoWorkspace.ubA[35] = acadoVariables.ubAValues[35] - tmp;
+tmp = acadoWorkspace.sbar[98] + acadoVariables.x[98];
+acadoWorkspace.lbA[36] = acadoVariables.lbAValues[36] - tmp;
+acadoWorkspace.ubA[36] = acadoVariables.ubAValues[36] - tmp;
+tmp = acadoWorkspace.sbar[99] + acadoVariables.x[99];
+acadoWorkspace.lbA[37] = acadoVariables.lbAValues[37] - tmp;
+acadoWorkspace.ubA[37] = acadoVariables.ubAValues[37] - tmp;
+tmp = acadoWorkspace.sbar[103] + acadoVariables.x[103];
+acadoWorkspace.lbA[38] = acadoVariables.lbAValues[38] - tmp;
+acadoWorkspace.ubA[38] = acadoVariables.ubAValues[38] - tmp;
+tmp = acadoWorkspace.sbar[104] + acadoVariables.x[104];
+acadoWorkspace.lbA[39] = acadoVariables.lbAValues[39] - tmp;
+acadoWorkspace.ubA[39] = acadoVariables.ubAValues[39] - tmp;
+
+acado_macHxd( acadoWorkspace.evHx, acadoWorkspace.sbar, &(acadoWorkspace.lbA[ 40 ]), &(acadoWorkspace.ubA[ 40 ]) );
+acado_macHxd( &(acadoWorkspace.evHx[ 50 ]), &(acadoWorkspace.sbar[ 5 ]), &(acadoWorkspace.lbA[ 50 ]), &(acadoWorkspace.ubA[ 50 ]) );
+acado_macHxd( &(acadoWorkspace.evHx[ 100 ]), &(acadoWorkspace.sbar[ 10 ]), &(acadoWorkspace.lbA[ 60 ]), &(acadoWorkspace.ubA[ 60 ]) );
+acado_macHxd( &(acadoWorkspace.evHx[ 150 ]), &(acadoWorkspace.sbar[ 15 ]), &(acadoWorkspace.lbA[ 70 ]), &(acadoWorkspace.ubA[ 70 ]) );
+acado_macHxd( &(acadoWorkspace.evHx[ 200 ]), &(acadoWorkspace.sbar[ 20 ]), &(acadoWorkspace.lbA[ 80 ]), &(acadoWorkspace.ubA[ 80 ]) );
+acado_macHxd( &(acadoWorkspace.evHx[ 250 ]), &(acadoWorkspace.sbar[ 25 ]), &(acadoWorkspace.lbA[ 90 ]), &(acadoWorkspace.ubA[ 90 ]) );
+acado_macHxd( &(acadoWorkspace.evHx[ 300 ]), &(acadoWorkspace.sbar[ 30 ]), &(acadoWorkspace.lbA[ 100 ]), &(acadoWorkspace.ubA[ 100 ]) );
+acado_macHxd( &(acadoWorkspace.evHx[ 350 ]), &(acadoWorkspace.sbar[ 35 ]), &(acadoWorkspace.lbA[ 110 ]), &(acadoWorkspace.ubA[ 110 ]) );
+acado_macHxd( &(acadoWorkspace.evHx[ 400 ]), &(acadoWorkspace.sbar[ 40 ]), &(acadoWorkspace.lbA[ 120 ]), &(acadoWorkspace.ubA[ 120 ]) );
+acado_macHxd( &(acadoWorkspace.evHx[ 450 ]), &(acadoWorkspace.sbar[ 45 ]), &(acadoWorkspace.lbA[ 130 ]), &(acadoWorkspace.ubA[ 130 ]) );
+acado_macHxd( &(acadoWorkspace.evHx[ 500 ]), &(acadoWorkspace.sbar[ 50 ]), &(acadoWorkspace.lbA[ 140 ]), &(acadoWorkspace.ubA[ 140 ]) );
+acado_macHxd( &(acadoWorkspace.evHx[ 550 ]), &(acadoWorkspace.sbar[ 55 ]), &(acadoWorkspace.lbA[ 150 ]), &(acadoWorkspace.ubA[ 150 ]) );
+acado_macHxd( &(acadoWorkspace.evHx[ 600 ]), &(acadoWorkspace.sbar[ 60 ]), &(acadoWorkspace.lbA[ 160 ]), &(acadoWorkspace.ubA[ 160 ]) );
+acado_macHxd( &(acadoWorkspace.evHx[ 650 ]), &(acadoWorkspace.sbar[ 65 ]), &(acadoWorkspace.lbA[ 170 ]), &(acadoWorkspace.ubA[ 170 ]) );
+acado_macHxd( &(acadoWorkspace.evHx[ 700 ]), &(acadoWorkspace.sbar[ 70 ]), &(acadoWorkspace.lbA[ 180 ]), &(acadoWorkspace.ubA[ 180 ]) );
+acado_macHxd( &(acadoWorkspace.evHx[ 750 ]), &(acadoWorkspace.sbar[ 75 ]), &(acadoWorkspace.lbA[ 190 ]), &(acadoWorkspace.ubA[ 190 ]) );
+acado_macHxd( &(acadoWorkspace.evHx[ 800 ]), &(acadoWorkspace.sbar[ 80 ]), &(acadoWorkspace.lbA[ 200 ]), &(acadoWorkspace.ubA[ 200 ]) );
+acado_macHxd( &(acadoWorkspace.evHx[ 850 ]), &(acadoWorkspace.sbar[ 85 ]), &(acadoWorkspace.lbA[ 210 ]), &(acadoWorkspace.ubA[ 210 ]) );
+acado_macHxd( &(acadoWorkspace.evHx[ 900 ]), &(acadoWorkspace.sbar[ 90 ]), &(acadoWorkspace.lbA[ 220 ]), &(acadoWorkspace.ubA[ 220 ]) );
+acado_macHxd( &(acadoWorkspace.evHx[ 950 ]), &(acadoWorkspace.sbar[ 95 ]), &(acadoWorkspace.lbA[ 230 ]), &(acadoWorkspace.ubA[ 230 ]) );
+
+}
+
+void acado_expand(  )
+{
+acadoVariables.u[0] += acadoWorkspace.x[0];
+acadoVariables.u[1] += acadoWorkspace.x[1];
+acadoVariables.u[2] += acadoWorkspace.x[2];
+acadoVariables.u[3] += acadoWorkspace.x[3];
+acadoVariables.u[4] += acadoWorkspace.x[4];
+acadoVariables.u[5] += acadoWorkspace.x[5];
+acadoVariables.u[6] += acadoWorkspace.x[6];
+acadoVariables.u[7] += acadoWorkspace.x[7];
+acadoVariables.u[8] += acadoWorkspace.x[8];
+acadoVariables.u[9] += acadoWorkspace.x[9];
+acadoVariables.u[10] += acadoWorkspace.x[10];
+acadoVariables.u[11] += acadoWorkspace.x[11];
+acadoVariables.u[12] += acadoWorkspace.x[12];
+acadoVariables.u[13] += acadoWorkspace.x[13];
+acadoVariables.u[14] += acadoWorkspace.x[14];
+acadoVariables.u[15] += acadoWorkspace.x[15];
+acadoVariables.u[16] += acadoWorkspace.x[16];
+acadoVariables.u[17] += acadoWorkspace.x[17];
+acadoVariables.u[18] += acadoWorkspace.x[18];
+acadoVariables.u[19] += acadoWorkspace.x[19];
+acadoVariables.u[20] += acadoWorkspace.x[20];
+acadoVariables.u[21] += acadoWorkspace.x[21];
+acadoVariables.u[22] += acadoWorkspace.x[22];
+acadoVariables.u[23] += acadoWorkspace.x[23];
+acadoVariables.u[24] += acadoWorkspace.x[24];
+acadoVariables.u[25] += acadoWorkspace.x[25];
+acadoVariables.u[26] += acadoWorkspace.x[26];
+acadoVariables.u[27] += acadoWorkspace.x[27];
+acadoVariables.u[28] += acadoWorkspace.x[28];
+acadoVariables.u[29] += acadoWorkspace.x[29];
+acadoVariables.u[30] += acadoWorkspace.x[30];
+acadoVariables.u[31] += acadoWorkspace.x[31];
+acadoVariables.u[32] += acadoWorkspace.x[32];
+acadoVariables.u[33] += acadoWorkspace.x[33];
+acadoVariables.u[34] += acadoWorkspace.x[34];
+acadoVariables.u[35] += acadoWorkspace.x[35];
+acadoVariables.u[36] += acadoWorkspace.x[36];
+acadoVariables.u[37] += acadoWorkspace.x[37];
+acadoVariables.u[38] += acadoWorkspace.x[38];
+acadoVariables.u[39] += acadoWorkspace.x[39];
+acadoWorkspace.sbar[0] = acadoWorkspace.Dx0[0];
+acadoWorkspace.sbar[1] = acadoWorkspace.Dx0[1];
+acadoWorkspace.sbar[2] = acadoWorkspace.Dx0[2];
+acadoWorkspace.sbar[3] = acadoWorkspace.Dx0[3];
+acadoWorkspace.sbar[4] = acadoWorkspace.Dx0[4];
+acadoWorkspace.sbar[5] = acadoWorkspace.d[0];
+acadoWorkspace.sbar[6] = acadoWorkspace.d[1];
+acadoWorkspace.sbar[7] = acadoWorkspace.d[2];
+acadoWorkspace.sbar[8] = acadoWorkspace.d[3];
+acadoWorkspace.sbar[9] = acadoWorkspace.d[4];
+acadoWorkspace.sbar[10] = acadoWorkspace.d[5];
+acadoWorkspace.sbar[11] = acadoWorkspace.d[6];
+acadoWorkspace.sbar[12] = acadoWorkspace.d[7];
+acadoWorkspace.sbar[13] = acadoWorkspace.d[8];
+acadoWorkspace.sbar[14] = acadoWorkspace.d[9];
+acadoWorkspace.sbar[15] = acadoWorkspace.d[10];
+acadoWorkspace.sbar[16] = acadoWorkspace.d[11];
+acadoWorkspace.sbar[17] = acadoWorkspace.d[12];
+acadoWorkspace.sbar[18] = acadoWorkspace.d[13];
+acadoWorkspace.sbar[19] = acadoWorkspace.d[14];
+acadoWorkspace.sbar[20] = acadoWorkspace.d[15];
+acadoWorkspace.sbar[21] = acadoWorkspace.d[16];
+acadoWorkspace.sbar[22] = acadoWorkspace.d[17];
+acadoWorkspace.sbar[23] = acadoWorkspace.d[18];
+acadoWorkspace.sbar[24] = acadoWorkspace.d[19];
+acadoWorkspace.sbar[25] = acadoWorkspace.d[20];
+acadoWorkspace.sbar[26] = acadoWorkspace.d[21];
+acadoWorkspace.sbar[27] = acadoWorkspace.d[22];
+acadoWorkspace.sbar[28] = acadoWorkspace.d[23];
+acadoWorkspace.sbar[29] = acadoWorkspace.d[24];
+acadoWorkspace.sbar[30] = acadoWorkspace.d[25];
+acadoWorkspace.sbar[31] = acadoWorkspace.d[26];
+acadoWorkspace.sbar[32] = acadoWorkspace.d[27];
+acadoWorkspace.sbar[33] = acadoWorkspace.d[28];
+acadoWorkspace.sbar[34] = acadoWorkspace.d[29];
+acadoWorkspace.sbar[35] = acadoWorkspace.d[30];
+acadoWorkspace.sbar[36] = acadoWorkspace.d[31];
+acadoWorkspace.sbar[37] = acadoWorkspace.d[32];
+acadoWorkspace.sbar[38] = acadoWorkspace.d[33];
+acadoWorkspace.sbar[39] = acadoWorkspace.d[34];
+acadoWorkspace.sbar[40] = acadoWorkspace.d[35];
+acadoWorkspace.sbar[41] = acadoWorkspace.d[36];
+acadoWorkspace.sbar[42] = acadoWorkspace.d[37];
+acadoWorkspace.sbar[43] = acadoWorkspace.d[38];
+acadoWorkspace.sbar[44] = acadoWorkspace.d[39];
+acadoWorkspace.sbar[45] = acadoWorkspace.d[40];
+acadoWorkspace.sbar[46] = acadoWorkspace.d[41];
+acadoWorkspace.sbar[47] = acadoWorkspace.d[42];
+acadoWorkspace.sbar[48] = acadoWorkspace.d[43];
+acadoWorkspace.sbar[49] = acadoWorkspace.d[44];
+acadoWorkspace.sbar[50] = acadoWorkspace.d[45];
+acadoWorkspace.sbar[51] = acadoWorkspace.d[46];
+acadoWorkspace.sbar[52] = acadoWorkspace.d[47];
+acadoWorkspace.sbar[53] = acadoWorkspace.d[48];
+acadoWorkspace.sbar[54] = acadoWorkspace.d[49];
+acadoWorkspace.sbar[55] = acadoWorkspace.d[50];
+acadoWorkspace.sbar[56] = acadoWorkspace.d[51];
+acadoWorkspace.sbar[57] = acadoWorkspace.d[52];
+acadoWorkspace.sbar[58] = acadoWorkspace.d[53];
+acadoWorkspace.sbar[59] = acadoWorkspace.d[54];
+acadoWorkspace.sbar[60] = acadoWorkspace.d[55];
+acadoWorkspace.sbar[61] = acadoWorkspace.d[56];
+acadoWorkspace.sbar[62] = acadoWorkspace.d[57];
+acadoWorkspace.sbar[63] = acadoWorkspace.d[58];
+acadoWorkspace.sbar[64] = acadoWorkspace.d[59];
+acadoWorkspace.sbar[65] = acadoWorkspace.d[60];
+acadoWorkspace.sbar[66] = acadoWorkspace.d[61];
+acadoWorkspace.sbar[67] = acadoWorkspace.d[62];
+acadoWorkspace.sbar[68] = acadoWorkspace.d[63];
+acadoWorkspace.sbar[69] = acadoWorkspace.d[64];
+acadoWorkspace.sbar[70] = acadoWorkspace.d[65];
+acadoWorkspace.sbar[71] = acadoWorkspace.d[66];
+acadoWorkspace.sbar[72] = acadoWorkspace.d[67];
+acadoWorkspace.sbar[73] = acadoWorkspace.d[68];
+acadoWorkspace.sbar[74] = acadoWorkspace.d[69];
+acadoWorkspace.sbar[75] = acadoWorkspace.d[70];
+acadoWorkspace.sbar[76] = acadoWorkspace.d[71];
+acadoWorkspace.sbar[77] = acadoWorkspace.d[72];
+acadoWorkspace.sbar[78] = acadoWorkspace.d[73];
+acadoWorkspace.sbar[79] = acadoWorkspace.d[74];
+acadoWorkspace.sbar[80] = acadoWorkspace.d[75];
+acadoWorkspace.sbar[81] = acadoWorkspace.d[76];
+acadoWorkspace.sbar[82] = acadoWorkspace.d[77];
+acadoWorkspace.sbar[83] = acadoWorkspace.d[78];
+acadoWorkspace.sbar[84] = acadoWorkspace.d[79];
+acadoWorkspace.sbar[85] = acadoWorkspace.d[80];
+acadoWorkspace.sbar[86] = acadoWorkspace.d[81];
+acadoWorkspace.sbar[87] = acadoWorkspace.d[82];
+acadoWorkspace.sbar[88] = acadoWorkspace.d[83];
+acadoWorkspace.sbar[89] = acadoWorkspace.d[84];
+acadoWorkspace.sbar[90] = acadoWorkspace.d[85];
+acadoWorkspace.sbar[91] = acadoWorkspace.d[86];
+acadoWorkspace.sbar[92] = acadoWorkspace.d[87];
+acadoWorkspace.sbar[93] = acadoWorkspace.d[88];
+acadoWorkspace.sbar[94] = acadoWorkspace.d[89];
+acadoWorkspace.sbar[95] = acadoWorkspace.d[90];
+acadoWorkspace.sbar[96] = acadoWorkspace.d[91];
+acadoWorkspace.sbar[97] = acadoWorkspace.d[92];
+acadoWorkspace.sbar[98] = acadoWorkspace.d[93];
+acadoWorkspace.sbar[99] = acadoWorkspace.d[94];
+acadoWorkspace.sbar[100] = acadoWorkspace.d[95];
+acadoWorkspace.sbar[101] = acadoWorkspace.d[96];
+acadoWorkspace.sbar[102] = acadoWorkspace.d[97];
+acadoWorkspace.sbar[103] = acadoWorkspace.d[98];
+acadoWorkspace.sbar[104] = acadoWorkspace.d[99];
+acado_expansionStep( acadoWorkspace.evGx, acadoWorkspace.evGu, acadoWorkspace.x, acadoWorkspace.sbar, &(acadoWorkspace.sbar[ 5 ]) );
+acado_expansionStep( &(acadoWorkspace.evGx[ 25 ]), &(acadoWorkspace.evGu[ 10 ]), &(acadoWorkspace.x[ 2 ]), &(acadoWorkspace.sbar[ 5 ]), &(acadoWorkspace.sbar[ 10 ]) );
+acado_expansionStep( &(acadoWorkspace.evGx[ 50 ]), &(acadoWorkspace.evGu[ 20 ]), &(acadoWorkspace.x[ 4 ]), &(acadoWorkspace.sbar[ 10 ]), &(acadoWorkspace.sbar[ 15 ]) );
+acado_expansionStep( &(acadoWorkspace.evGx[ 75 ]), &(acadoWorkspace.evGu[ 30 ]), &(acadoWorkspace.x[ 6 ]), &(acadoWorkspace.sbar[ 15 ]), &(acadoWorkspace.sbar[ 20 ]) );
+acado_expansionStep( &(acadoWorkspace.evGx[ 100 ]), &(acadoWorkspace.evGu[ 40 ]), &(acadoWorkspace.x[ 8 ]), &(acadoWorkspace.sbar[ 20 ]), &(acadoWorkspace.sbar[ 25 ]) );
+acado_expansionStep( &(acadoWorkspace.evGx[ 125 ]), &(acadoWorkspace.evGu[ 50 ]), &(acadoWorkspace.x[ 10 ]), &(acadoWorkspace.sbar[ 25 ]), &(acadoWorkspace.sbar[ 30 ]) );
+acado_expansionStep( &(acadoWorkspace.evGx[ 150 ]), &(acadoWorkspace.evGu[ 60 ]), &(acadoWorkspace.x[ 12 ]), &(acadoWorkspace.sbar[ 30 ]), &(acadoWorkspace.sbar[ 35 ]) );
+acado_expansionStep( &(acadoWorkspace.evGx[ 175 ]), &(acadoWorkspace.evGu[ 70 ]), &(acadoWorkspace.x[ 14 ]), &(acadoWorkspace.sbar[ 35 ]), &(acadoWorkspace.sbar[ 40 ]) );
+acado_expansionStep( &(acadoWorkspace.evGx[ 200 ]), &(acadoWorkspace.evGu[ 80 ]), &(acadoWorkspace.x[ 16 ]), &(acadoWorkspace.sbar[ 40 ]), &(acadoWorkspace.sbar[ 45 ]) );
+acado_expansionStep( &(acadoWorkspace.evGx[ 225 ]), &(acadoWorkspace.evGu[ 90 ]), &(acadoWorkspace.x[ 18 ]), &(acadoWorkspace.sbar[ 45 ]), &(acadoWorkspace.sbar[ 50 ]) );
+acado_expansionStep( &(acadoWorkspace.evGx[ 250 ]), &(acadoWorkspace.evGu[ 100 ]), &(acadoWorkspace.x[ 20 ]), &(acadoWorkspace.sbar[ 50 ]), &(acadoWorkspace.sbar[ 55 ]) );
+acado_expansionStep( &(acadoWorkspace.evGx[ 275 ]), &(acadoWorkspace.evGu[ 110 ]), &(acadoWorkspace.x[ 22 ]), &(acadoWorkspace.sbar[ 55 ]), &(acadoWorkspace.sbar[ 60 ]) );
+acado_expansionStep( &(acadoWorkspace.evGx[ 300 ]), &(acadoWorkspace.evGu[ 120 ]), &(acadoWorkspace.x[ 24 ]), &(acadoWorkspace.sbar[ 60 ]), &(acadoWorkspace.sbar[ 65 ]) );
+acado_expansionStep( &(acadoWorkspace.evGx[ 325 ]), &(acadoWorkspace.evGu[ 130 ]), &(acadoWorkspace.x[ 26 ]), &(acadoWorkspace.sbar[ 65 ]), &(acadoWorkspace.sbar[ 70 ]) );
+acado_expansionStep( &(acadoWorkspace.evGx[ 350 ]), &(acadoWorkspace.evGu[ 140 ]), &(acadoWorkspace.x[ 28 ]), &(acadoWorkspace.sbar[ 70 ]), &(acadoWorkspace.sbar[ 75 ]) );
+acado_expansionStep( &(acadoWorkspace.evGx[ 375 ]), &(acadoWorkspace.evGu[ 150 ]), &(acadoWorkspace.x[ 30 ]), &(acadoWorkspace.sbar[ 75 ]), &(acadoWorkspace.sbar[ 80 ]) );
+acado_expansionStep( &(acadoWorkspace.evGx[ 400 ]), &(acadoWorkspace.evGu[ 160 ]), &(acadoWorkspace.x[ 32 ]), &(acadoWorkspace.sbar[ 80 ]), &(acadoWorkspace.sbar[ 85 ]) );
+acado_expansionStep( &(acadoWorkspace.evGx[ 425 ]), &(acadoWorkspace.evGu[ 170 ]), &(acadoWorkspace.x[ 34 ]), &(acadoWorkspace.sbar[ 85 ]), &(acadoWorkspace.sbar[ 90 ]) );
+acado_expansionStep( &(acadoWorkspace.evGx[ 450 ]), &(acadoWorkspace.evGu[ 180 ]), &(acadoWorkspace.x[ 36 ]), &(acadoWorkspace.sbar[ 90 ]), &(acadoWorkspace.sbar[ 95 ]) );
+acado_expansionStep( &(acadoWorkspace.evGx[ 475 ]), &(acadoWorkspace.evGu[ 190 ]), &(acadoWorkspace.x[ 38 ]), &(acadoWorkspace.sbar[ 95 ]), &(acadoWorkspace.sbar[ 100 ]) );
+acadoVariables.x[0] += acadoWorkspace.sbar[0];
+acadoVariables.x[1] += acadoWorkspace.sbar[1];
+acadoVariables.x[2] += acadoWorkspace.sbar[2];
+acadoVariables.x[3] += acadoWorkspace.sbar[3];
+acadoVariables.x[4] += acadoWorkspace.sbar[4];
+acadoVariables.x[5] += acadoWorkspace.sbar[5];
+acadoVariables.x[6] += acadoWorkspace.sbar[6];
+acadoVariables.x[7] += acadoWorkspace.sbar[7];
+acadoVariables.x[8] += acadoWorkspace.sbar[8];
+acadoVariables.x[9] += acadoWorkspace.sbar[9];
+acadoVariables.x[10] += acadoWorkspace.sbar[10];
+acadoVariables.x[11] += acadoWorkspace.sbar[11];
+acadoVariables.x[12] += acadoWorkspace.sbar[12];
+acadoVariables.x[13] += acadoWorkspace.sbar[13];
+acadoVariables.x[14] += acadoWorkspace.sbar[14];
+acadoVariables.x[15] += acadoWorkspace.sbar[15];
+acadoVariables.x[16] += acadoWorkspace.sbar[16];
+acadoVariables.x[17] += acadoWorkspace.sbar[17];
+acadoVariables.x[18] += acadoWorkspace.sbar[18];
+acadoVariables.x[19] += acadoWorkspace.sbar[19];
+acadoVariables.x[20] += acadoWorkspace.sbar[20];
+acadoVariables.x[21] += acadoWorkspace.sbar[21];
+acadoVariables.x[22] += acadoWorkspace.sbar[22];
+acadoVariables.x[23] += acadoWorkspace.sbar[23];
+acadoVariables.x[24] += acadoWorkspace.sbar[24];
+acadoVariables.x[25] += acadoWorkspace.sbar[25];
+acadoVariables.x[26] += acadoWorkspace.sbar[26];
+acadoVariables.x[27] += acadoWorkspace.sbar[27];
+acadoVariables.x[28] += acadoWorkspace.sbar[28];
+acadoVariables.x[29] += acadoWorkspace.sbar[29];
+acadoVariables.x[30] += acadoWorkspace.sbar[30];
+acadoVariables.x[31] += acadoWorkspace.sbar[31];
+acadoVariables.x[32] += acadoWorkspace.sbar[32];
+acadoVariables.x[33] += acadoWorkspace.sbar[33];
+acadoVariables.x[34] += acadoWorkspace.sbar[34];
+acadoVariables.x[35] += acadoWorkspace.sbar[35];
+acadoVariables.x[36] += acadoWorkspace.sbar[36];
+acadoVariables.x[37] += acadoWorkspace.sbar[37];
+acadoVariables.x[38] += acadoWorkspace.sbar[38];
+acadoVariables.x[39] += acadoWorkspace.sbar[39];
+acadoVariables.x[40] += acadoWorkspace.sbar[40];
+acadoVariables.x[41] += acadoWorkspace.sbar[41];
+acadoVariables.x[42] += acadoWorkspace.sbar[42];
+acadoVariables.x[43] += acadoWorkspace.sbar[43];
+acadoVariables.x[44] += acadoWorkspace.sbar[44];
+acadoVariables.x[45] += acadoWorkspace.sbar[45];
+acadoVariables.x[46] += acadoWorkspace.sbar[46];
+acadoVariables.x[47] += acadoWorkspace.sbar[47];
+acadoVariables.x[48] += acadoWorkspace.sbar[48];
+acadoVariables.x[49] += acadoWorkspace.sbar[49];
+acadoVariables.x[50] += acadoWorkspace.sbar[50];
+acadoVariables.x[51] += acadoWorkspace.sbar[51];
+acadoVariables.x[52] += acadoWorkspace.sbar[52];
+acadoVariables.x[53] += acadoWorkspace.sbar[53];
+acadoVariables.x[54] += acadoWorkspace.sbar[54];
+acadoVariables.x[55] += acadoWorkspace.sbar[55];
+acadoVariables.x[56] += acadoWorkspace.sbar[56];
+acadoVariables.x[57] += acadoWorkspace.sbar[57];
+acadoVariables.x[58] += acadoWorkspace.sbar[58];
+acadoVariables.x[59] += acadoWorkspace.sbar[59];
+acadoVariables.x[60] += acadoWorkspace.sbar[60];
+acadoVariables.x[61] += acadoWorkspace.sbar[61];
+acadoVariables.x[62] += acadoWorkspace.sbar[62];
+acadoVariables.x[63] += acadoWorkspace.sbar[63];
+acadoVariables.x[64] += acadoWorkspace.sbar[64];
+acadoVariables.x[65] += acadoWorkspace.sbar[65];
+acadoVariables.x[66] += acadoWorkspace.sbar[66];
+acadoVariables.x[67] += acadoWorkspace.sbar[67];
+acadoVariables.x[68] += acadoWorkspace.sbar[68];
+acadoVariables.x[69] += acadoWorkspace.sbar[69];
+acadoVariables.x[70] += acadoWorkspace.sbar[70];
+acadoVariables.x[71] += acadoWorkspace.sbar[71];
+acadoVariables.x[72] += acadoWorkspace.sbar[72];
+acadoVariables.x[73] += acadoWorkspace.sbar[73];
+acadoVariables.x[74] += acadoWorkspace.sbar[74];
+acadoVariables.x[75] += acadoWorkspace.sbar[75];
+acadoVariables.x[76] += acadoWorkspace.sbar[76];
+acadoVariables.x[77] += acadoWorkspace.sbar[77];
+acadoVariables.x[78] += acadoWorkspace.sbar[78];
+acadoVariables.x[79] += acadoWorkspace.sbar[79];
+acadoVariables.x[80] += acadoWorkspace.sbar[80];
+acadoVariables.x[81] += acadoWorkspace.sbar[81];
+acadoVariables.x[82] += acadoWorkspace.sbar[82];
+acadoVariables.x[83] += acadoWorkspace.sbar[83];
+acadoVariables.x[84] += acadoWorkspace.sbar[84];
+acadoVariables.x[85] += acadoWorkspace.sbar[85];
+acadoVariables.x[86] += acadoWorkspace.sbar[86];
+acadoVariables.x[87] += acadoWorkspace.sbar[87];
+acadoVariables.x[88] += acadoWorkspace.sbar[88];
+acadoVariables.x[89] += acadoWorkspace.sbar[89];
+acadoVariables.x[90] += acadoWorkspace.sbar[90];
+acadoVariables.x[91] += acadoWorkspace.sbar[91];
+acadoVariables.x[92] += acadoWorkspace.sbar[92];
+acadoVariables.x[93] += acadoWorkspace.sbar[93];
+acadoVariables.x[94] += acadoWorkspace.sbar[94];
+acadoVariables.x[95] += acadoWorkspace.sbar[95];
+acadoVariables.x[96] += acadoWorkspace.sbar[96];
+acadoVariables.x[97] += acadoWorkspace.sbar[97];
+acadoVariables.x[98] += acadoWorkspace.sbar[98];
+acadoVariables.x[99] += acadoWorkspace.sbar[99];
+acadoVariables.x[100] += acadoWorkspace.sbar[100];
+acadoVariables.x[101] += acadoWorkspace.sbar[101];
+acadoVariables.x[102] += acadoWorkspace.sbar[102];
+acadoVariables.x[103] += acadoWorkspace.sbar[103];
+acadoVariables.x[104] += acadoWorkspace.sbar[104];
+}
+
+int acado_preparationStep(  )
+{
+int ret;
+
+ret = acado_modelSimulation();
+acado_evaluateObjective(  );
+acado_condensePrep(  );
+return ret;
+}
+
+int acado_feedbackStep(  )
+{
+int tmp;
+
+acado_condenseFdb(  );
+
+tmp = acado_solve( );
+
+acado_expand(  );
+return tmp;
+}
+
+int acado_initializeSolver(  )
+{
+int ret;
+
+/* This is a function which must be called once before any other function call! */
+
+
+ret = 0;
+
+memset(&acadoWorkspace, 0, sizeof( acadoWorkspace ));
+acadoVariables.lbValues[0] = -3.0000000000000000e+00;
+acadoVariables.lbValues[1] = -3.0000000000000000e+00;
+acadoVariables.lbValues[2] = -3.0000000000000000e+00;
+acadoVariables.lbValues[3] = -3.0000000000000000e+00;
+acadoVariables.lbValues[4] = -3.0000000000000000e+00;
+acadoVariables.lbValues[5] = -3.0000000000000000e+00;
+acadoVariables.lbValues[6] = -3.0000000000000000e+00;
+acadoVariables.lbValues[7] = -3.0000000000000000e+00;
+acadoVariables.lbValues[8] = -3.0000000000000000e+00;
+acadoVariables.lbValues[9] = -3.0000000000000000e+00;
+acadoVariables.lbValues[10] = -3.0000000000000000e+00;
+acadoVariables.lbValues[11] = -3.0000000000000000e+00;
+acadoVariables.lbValues[12] = -3.0000000000000000e+00;
+acadoVariables.lbValues[13] = -3.0000000000000000e+00;
+acadoVariables.lbValues[14] = -3.0000000000000000e+00;
+acadoVariables.lbValues[15] = -3.0000000000000000e+00;
+acadoVariables.lbValues[16] = -3.0000000000000000e+00;
+acadoVariables.lbValues[17] = -3.0000000000000000e+00;
+acadoVariables.lbValues[18] = -3.0000000000000000e+00;
+acadoVariables.lbValues[19] = -3.0000000000000000e+00;
+acadoVariables.lbValues[20] = -3.0000000000000000e+00;
+acadoVariables.lbValues[21] = -3.0000000000000000e+00;
+acadoVariables.lbValues[22] = -3.0000000000000000e+00;
+acadoVariables.lbValues[23] = -3.0000000000000000e+00;
+acadoVariables.lbValues[24] = -3.0000000000000000e+00;
+acadoVariables.lbValues[25] = -3.0000000000000000e+00;
+acadoVariables.lbValues[26] = -3.0000000000000000e+00;
+acadoVariables.lbValues[27] = -3.0000000000000000e+00;
+acadoVariables.lbValues[28] = -3.0000000000000000e+00;
+acadoVariables.lbValues[29] = -3.0000000000000000e+00;
+acadoVariables.lbValues[30] = -3.0000000000000000e+00;
+acadoVariables.lbValues[31] = -3.0000000000000000e+00;
+acadoVariables.lbValues[32] = -3.0000000000000000e+00;
+acadoVariables.lbValues[33] = -3.0000000000000000e+00;
+acadoVariables.lbValues[34] = -3.0000000000000000e+00;
+acadoVariables.lbValues[35] = -3.0000000000000000e+00;
+acadoVariables.lbValues[36] = -3.0000000000000000e+00;
+acadoVariables.lbValues[37] = -3.0000000000000000e+00;
+acadoVariables.lbValues[38] = -3.0000000000000000e+00;
+acadoVariables.lbValues[39] = -3.0000000000000000e+00;
+acadoVariables.ubValues[0] = 3.0000000000000000e+00;
+acadoVariables.ubValues[1] = 3.0000000000000000e+00;
+acadoVariables.ubValues[2] = 3.0000000000000000e+00;
+acadoVariables.ubValues[3] = 3.0000000000000000e+00;
+acadoVariables.ubValues[4] = 3.0000000000000000e+00;
+acadoVariables.ubValues[5] = 3.0000000000000000e+00;
+acadoVariables.ubValues[6] = 3.0000000000000000e+00;
+acadoVariables.ubValues[7] = 3.0000000000000000e+00;
+acadoVariables.ubValues[8] = 3.0000000000000000e+00;
+acadoVariables.ubValues[9] = 3.0000000000000000e+00;
+acadoVariables.ubValues[10] = 3.0000000000000000e+00;
+acadoVariables.ubValues[11] = 3.0000000000000000e+00;
+acadoVariables.ubValues[12] = 3.0000000000000000e+00;
+acadoVariables.ubValues[13] = 3.0000000000000000e+00;
+acadoVariables.ubValues[14] = 3.0000000000000000e+00;
+acadoVariables.ubValues[15] = 3.0000000000000000e+00;
+acadoVariables.ubValues[16] = 3.0000000000000000e+00;
+acadoVariables.ubValues[17] = 3.0000000000000000e+00;
+acadoVariables.ubValues[18] = 3.0000000000000000e+00;
+acadoVariables.ubValues[19] = 3.0000000000000000e+00;
+acadoVariables.ubValues[20] = 3.0000000000000000e+00;
+acadoVariables.ubValues[21] = 3.0000000000000000e+00;
+acadoVariables.ubValues[22] = 3.0000000000000000e+00;
+acadoVariables.ubValues[23] = 3.0000000000000000e+00;
+acadoVariables.ubValues[24] = 3.0000000000000000e+00;
+acadoVariables.ubValues[25] = 3.0000000000000000e+00;
+acadoVariables.ubValues[26] = 3.0000000000000000e+00;
+acadoVariables.ubValues[27] = 3.0000000000000000e+00;
+acadoVariables.ubValues[28] = 3.0000000000000000e+00;
+acadoVariables.ubValues[29] = 3.0000000000000000e+00;
+acadoVariables.ubValues[30] = 3.0000000000000000e+00;
+acadoVariables.ubValues[31] = 3.0000000000000000e+00;
+acadoVariables.ubValues[32] = 3.0000000000000000e+00;
+acadoVariables.ubValues[33] = 3.0000000000000000e+00;
+acadoVariables.ubValues[34] = 3.0000000000000000e+00;
+acadoVariables.ubValues[35] = 3.0000000000000000e+00;
+acadoVariables.ubValues[36] = 3.0000000000000000e+00;
+acadoVariables.ubValues[37] = 3.0000000000000000e+00;
+acadoVariables.ubValues[38] = 3.0000000000000000e+00;
+acadoVariables.ubValues[39] = 3.0000000000000000e+00;
+acadoVariables.lbAValues[0] = -1.0000000000000000e+00;
+acadoVariables.lbAValues[1] = -3.0000000000000000e+00;
+acadoVariables.lbAValues[2] = -1.0000000000000000e+00;
+acadoVariables.lbAValues[3] = -3.0000000000000000e+00;
+acadoVariables.lbAValues[4] = -1.0000000000000000e+00;
+acadoVariables.lbAValues[5] = -3.0000000000000000e+00;
+acadoVariables.lbAValues[6] = -1.0000000000000000e+00;
+acadoVariables.lbAValues[7] = -3.0000000000000000e+00;
+acadoVariables.lbAValues[8] = -1.0000000000000000e+00;
+acadoVariables.lbAValues[9] = -3.0000000000000000e+00;
+acadoVariables.lbAValues[10] = -1.0000000000000000e+00;
+acadoVariables.lbAValues[11] = -3.0000000000000000e+00;
+acadoVariables.lbAValues[12] = -1.0000000000000000e+00;
+acadoVariables.lbAValues[13] = -3.0000000000000000e+00;
+acadoVariables.lbAValues[14] = -1.0000000000000000e+00;
+acadoVariables.lbAValues[15] = -3.0000000000000000e+00;
+acadoVariables.lbAValues[16] = -1.0000000000000000e+00;
+acadoVariables.lbAValues[17] = -3.0000000000000000e+00;
+acadoVariables.lbAValues[18] = -1.0000000000000000e+00;
+acadoVariables.lbAValues[19] = -3.0000000000000000e+00;
+acadoVariables.lbAValues[20] = -1.0000000000000000e+00;
+acadoVariables.lbAValues[21] = -3.0000000000000000e+00;
+acadoVariables.lbAValues[22] = -1.0000000000000000e+00;
+acadoVariables.lbAValues[23] = -3.0000000000000000e+00;
+acadoVariables.lbAValues[24] = -1.0000000000000000e+00;
+acadoVariables.lbAValues[25] = -3.0000000000000000e+00;
+acadoVariables.lbAValues[26] = -1.0000000000000000e+00;
+acadoVariables.lbAValues[27] = -3.0000000000000000e+00;
+acadoVariables.lbAValues[28] = -1.0000000000000000e+00;
+acadoVariables.lbAValues[29] = -3.0000000000000000e+00;
+acadoVariables.lbAValues[30] = -1.0000000000000000e+00;
+acadoVariables.lbAValues[31] = -3.0000000000000000e+00;
+acadoVariables.lbAValues[32] = -1.0000000000000000e+00;
+acadoVariables.lbAValues[33] = -3.0000000000000000e+00;
+acadoVariables.lbAValues[34] = -1.0000000000000000e+00;
+acadoVariables.lbAValues[35] = -3.0000000000000000e+00;
+acadoVariables.lbAValues[36] = -1.0000000000000000e+00;
+acadoVariables.lbAValues[37] = -3.0000000000000000e+00;
+acadoVariables.lbAValues[38] = -1.0000000000000000e+00;
+acadoVariables.lbAValues[39] = -3.0000000000000000e+00;
+acadoVariables.lbAValues[40] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[41] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[42] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[43] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[44] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[45] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[46] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[47] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[48] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[49] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[50] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[51] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[52] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[53] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[54] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[55] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[56] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[57] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[58] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[59] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[60] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[61] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[62] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[63] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[64] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[65] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[66] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[67] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[68] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[69] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[70] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[71] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[72] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[73] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[74] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[75] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[76] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[77] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[78] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[79] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[80] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[81] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[82] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[83] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[84] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[85] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[86] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[87] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[88] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[89] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[90] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[91] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[92] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[93] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[94] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[95] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[96] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[97] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[98] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[99] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[100] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[101] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[102] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[103] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[104] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[105] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[106] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[107] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[108] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[109] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[110] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[111] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[112] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[113] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[114] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[115] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[116] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[117] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[118] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[119] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[120] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[121] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[122] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[123] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[124] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[125] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[126] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[127] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[128] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[129] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[130] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[131] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[132] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[133] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[134] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[135] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[136] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[137] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[138] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[139] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[140] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[141] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[142] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[143] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[144] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[145] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[146] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[147] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[148] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[149] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[150] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[151] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[152] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[153] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[154] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[155] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[156] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[157] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[158] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[159] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[160] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[161] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[162] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[163] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[164] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[165] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[166] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[167] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[168] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[169] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[170] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[171] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[172] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[173] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[174] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[175] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[176] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[177] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[178] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[179] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[180] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[181] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[182] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[183] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[184] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[185] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[186] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[187] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[188] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[189] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[190] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[191] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[192] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[193] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[194] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[195] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[196] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[197] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[198] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[199] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[200] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[201] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[202] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[203] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[204] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[205] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[206] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[207] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[208] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[209] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[210] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[211] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[212] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[213] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[214] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[215] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[216] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[217] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[218] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[219] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[220] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[221] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[222] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[223] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[224] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[225] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[226] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[227] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[228] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[229] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[230] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[231] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[232] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[233] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[234] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[235] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[236] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[237] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[238] = 1.0000000000000000e+00;
+acadoVariables.lbAValues[239] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[0] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[1] = 3.0000000000000000e+00;
+acadoVariables.ubAValues[2] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[3] = 3.0000000000000000e+00;
+acadoVariables.ubAValues[4] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[5] = 3.0000000000000000e+00;
+acadoVariables.ubAValues[6] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[7] = 3.0000000000000000e+00;
+acadoVariables.ubAValues[8] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[9] = 3.0000000000000000e+00;
+acadoVariables.ubAValues[10] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[11] = 3.0000000000000000e+00;
+acadoVariables.ubAValues[12] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[13] = 3.0000000000000000e+00;
+acadoVariables.ubAValues[14] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[15] = 3.0000000000000000e+00;
+acadoVariables.ubAValues[16] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[17] = 3.0000000000000000e+00;
+acadoVariables.ubAValues[18] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[19] = 3.0000000000000000e+00;
+acadoVariables.ubAValues[20] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[21] = 3.0000000000000000e+00;
+acadoVariables.ubAValues[22] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[23] = 3.0000000000000000e+00;
+acadoVariables.ubAValues[24] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[25] = 3.0000000000000000e+00;
+acadoVariables.ubAValues[26] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[27] = 3.0000000000000000e+00;
+acadoVariables.ubAValues[28] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[29] = 3.0000000000000000e+00;
+acadoVariables.ubAValues[30] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[31] = 3.0000000000000000e+00;
+acadoVariables.ubAValues[32] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[33] = 3.0000000000000000e+00;
+acadoVariables.ubAValues[34] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[35] = 3.0000000000000000e+00;
+acadoVariables.ubAValues[36] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[37] = 3.0000000000000000e+00;
+acadoVariables.ubAValues[38] = 1.0000000000000000e+00;
+acadoVariables.ubAValues[39] = 3.0000000000000000e+00;
+acadoVariables.ubAValues[40] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[41] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[42] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[43] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[44] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[45] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[46] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[47] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[48] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[49] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[50] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[51] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[52] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[53] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[54] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[55] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[56] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[57] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[58] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[59] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[60] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[61] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[62] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[63] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[64] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[65] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[66] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[67] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[68] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[69] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[70] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[71] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[72] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[73] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[74] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[75] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[76] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[77] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[78] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[79] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[80] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[81] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[82] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[83] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[84] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[85] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[86] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[87] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[88] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[89] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[90] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[91] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[92] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[93] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[94] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[95] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[96] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[97] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[98] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[99] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[100] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[101] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[102] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[103] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[104] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[105] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[106] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[107] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[108] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[109] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[110] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[111] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[112] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[113] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[114] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[115] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[116] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[117] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[118] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[119] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[120] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[121] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[122] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[123] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[124] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[125] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[126] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[127] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[128] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[129] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[130] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[131] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[132] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[133] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[134] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[135] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[136] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[137] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[138] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[139] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[140] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[141] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[142] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[143] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[144] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[145] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[146] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[147] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[148] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[149] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[150] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[151] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[152] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[153] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[154] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[155] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[156] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[157] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[158] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[159] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[160] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[161] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[162] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[163] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[164] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[165] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[166] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[167] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[168] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[169] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[170] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[171] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[172] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[173] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[174] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[175] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[176] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[177] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[178] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[179] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[180] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[181] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[182] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[183] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[184] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[185] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[186] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[187] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[188] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[189] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[190] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[191] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[192] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[193] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[194] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[195] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[196] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[197] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[198] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[199] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[200] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[201] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[202] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[203] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[204] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[205] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[206] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[207] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[208] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[209] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[210] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[211] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[212] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[213] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[214] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[215] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[216] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[217] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[218] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[219] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[220] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[221] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[222] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[223] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[224] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[225] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[226] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[227] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[228] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[229] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[230] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[231] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[232] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[233] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[234] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[235] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[236] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[237] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[238] = 1.0000000000000000e+12;
+acadoVariables.ubAValues[239] = 1.0000000000000000e+12;
+return ret;
+}
+
+void acado_initializeNodesByForwardSimulation(  )
+{
+int index;
+for (index = 0; index < 20; ++index)
+{
+state[0] = acadoVariables.x[index * 5];
+state[1] = acadoVariables.x[index * 5 + 1];
+state[2] = acadoVariables.x[index * 5 + 2];
+state[3] = acadoVariables.x[index * 5 + 3];
+state[4] = acadoVariables.x[index * 5 + 4];
+state[40] = acadoVariables.u[index * 2];
+state[41] = acadoVariables.u[index * 2 + 1];
+state[42] = acadoVariables.od[index * 20];
+state[43] = acadoVariables.od[index * 20 + 1];
+state[44] = acadoVariables.od[index * 20 + 2];
+state[45] = acadoVariables.od[index * 20 + 3];
+state[46] = acadoVariables.od[index * 20 + 4];
+state[47] = acadoVariables.od[index * 20 + 5];
+state[48] = acadoVariables.od[index * 20 + 6];
+state[49] = acadoVariables.od[index * 20 + 7];
+state[50] = acadoVariables.od[index * 20 + 8];
+state[51] = acadoVariables.od[index * 20 + 9];
+state[52] = acadoVariables.od[index * 20 + 10];
+state[53] = acadoVariables.od[index * 20 + 11];
+state[54] = acadoVariables.od[index * 20 + 12];
+state[55] = acadoVariables.od[index * 20 + 13];
+state[56] = acadoVariables.od[index * 20 + 14];
+state[57] = acadoVariables.od[index * 20 + 15];
+state[58] = acadoVariables.od[index * 20 + 16];
+state[59] = acadoVariables.od[index * 20 + 17];
+state[60] = acadoVariables.od[index * 20 + 18];
+state[61] = acadoVariables.od[index * 20 + 19];
+
+acado_integrate(state, index == 0);
+
+acadoVariables.x[index * 5 + 5] = state[0];
+acadoVariables.x[index * 5 + 6] = state[1];
+acadoVariables.x[index * 5 + 7] = state[2];
+acadoVariables.x[index * 5 + 8] = state[3];
+acadoVariables.x[index * 5 + 9] = state[4];
+}
+}
+
+void acado_shiftStates( int strategy, real_t* const xEnd, real_t* const uEnd )
+{
+int index;
+for (index = 0; index < 20; ++index)
+{
+acadoVariables.x[index * 5] = acadoVariables.x[index * 5 + 5];
+acadoVariables.x[index * 5 + 1] = acadoVariables.x[index * 5 + 6];
+acadoVariables.x[index * 5 + 2] = acadoVariables.x[index * 5 + 7];
+acadoVariables.x[index * 5 + 3] = acadoVariables.x[index * 5 + 8];
+acadoVariables.x[index * 5 + 4] = acadoVariables.x[index * 5 + 9];
+}
+
+if (strategy == 1 && xEnd != 0)
+{
+acadoVariables.x[100] = xEnd[0];
+acadoVariables.x[101] = xEnd[1];
+acadoVariables.x[102] = xEnd[2];
+acadoVariables.x[103] = xEnd[3];
+acadoVariables.x[104] = xEnd[4];
+}
+else if (strategy == 2) 
+{
+state[0] = acadoVariables.x[100];
+state[1] = acadoVariables.x[101];
+state[2] = acadoVariables.x[102];
+state[3] = acadoVariables.x[103];
+state[4] = acadoVariables.x[104];
+if (uEnd != 0)
+{
+state[40] = uEnd[0];
+state[41] = uEnd[1];
+}
+else
+{
+state[40] = acadoVariables.u[38];
+state[41] = acadoVariables.u[39];
+}
+state[42] = acadoVariables.od[400];
+state[43] = acadoVariables.od[401];
+state[44] = acadoVariables.od[402];
+state[45] = acadoVariables.od[403];
+state[46] = acadoVariables.od[404];
+state[47] = acadoVariables.od[405];
+state[48] = acadoVariables.od[406];
+state[49] = acadoVariables.od[407];
+state[50] = acadoVariables.od[408];
+state[51] = acadoVariables.od[409];
+state[52] = acadoVariables.od[410];
+state[53] = acadoVariables.od[411];
+state[54] = acadoVariables.od[412];
+state[55] = acadoVariables.od[413];
+state[56] = acadoVariables.od[414];
+state[57] = acadoVariables.od[415];
+state[58] = acadoVariables.od[416];
+state[59] = acadoVariables.od[417];
+state[60] = acadoVariables.od[418];
+state[61] = acadoVariables.od[419];
+
+acado_integrate(state, 1);
+
+acadoVariables.x[100] = state[0];
+acadoVariables.x[101] = state[1];
+acadoVariables.x[102] = state[2];
+acadoVariables.x[103] = state[3];
+acadoVariables.x[104] = state[4];
+}
+}
+
+void acado_shiftControls( real_t* const uEnd )
+{
+int index;
+for (index = 0; index < 19; ++index)
+{
+acadoVariables.u[index * 2] = acadoVariables.u[index * 2 + 2];
+acadoVariables.u[index * 2 + 1] = acadoVariables.u[index * 2 + 3];
+}
+
+if (uEnd != 0)
+{
+acadoVariables.u[38] = uEnd[0];
+acadoVariables.u[39] = uEnd[1];
+}
+}
+
+real_t acado_getKKT(  )
+{
+real_t kkt;
+
+int index;
+real_t prd;
+
+kkt = + acadoWorkspace.g[0]*acadoWorkspace.x[0] + acadoWorkspace.g[1]*acadoWorkspace.x[1] + acadoWorkspace.g[2]*acadoWorkspace.x[2] + acadoWorkspace.g[3]*acadoWorkspace.x[3] + acadoWorkspace.g[4]*acadoWorkspace.x[4] + acadoWorkspace.g[5]*acadoWorkspace.x[5] + acadoWorkspace.g[6]*acadoWorkspace.x[6] + acadoWorkspace.g[7]*acadoWorkspace.x[7] + acadoWorkspace.g[8]*acadoWorkspace.x[8] + acadoWorkspace.g[9]*acadoWorkspace.x[9] + acadoWorkspace.g[10]*acadoWorkspace.x[10] + acadoWorkspace.g[11]*acadoWorkspace.x[11] + acadoWorkspace.g[12]*acadoWorkspace.x[12] + acadoWorkspace.g[13]*acadoWorkspace.x[13] + acadoWorkspace.g[14]*acadoWorkspace.x[14] + acadoWorkspace.g[15]*acadoWorkspace.x[15] + acadoWorkspace.g[16]*acadoWorkspace.x[16] + acadoWorkspace.g[17]*acadoWorkspace.x[17] + acadoWorkspace.g[18]*acadoWorkspace.x[18] + acadoWorkspace.g[19]*acadoWorkspace.x[19] + acadoWorkspace.g[20]*acadoWorkspace.x[20] + acadoWorkspace.g[21]*acadoWorkspace.x[21] + acadoWorkspace.g[22]*acadoWorkspace.x[22] + acadoWorkspace.g[23]*acadoWorkspace.x[23] + acadoWorkspace.g[24]*acadoWorkspace.x[24] + acadoWorkspace.g[25]*acadoWorkspace.x[25] + acadoWorkspace.g[26]*acadoWorkspace.x[26] + acadoWorkspace.g[27]*acadoWorkspace.x[27] + acadoWorkspace.g[28]*acadoWorkspace.x[28] + acadoWorkspace.g[29]*acadoWorkspace.x[29] + acadoWorkspace.g[30]*acadoWorkspace.x[30] + acadoWorkspace.g[31]*acadoWorkspace.x[31] + acadoWorkspace.g[32]*acadoWorkspace.x[32] + acadoWorkspace.g[33]*acadoWorkspace.x[33] + acadoWorkspace.g[34]*acadoWorkspace.x[34] + acadoWorkspace.g[35]*acadoWorkspace.x[35] + acadoWorkspace.g[36]*acadoWorkspace.x[36] + acadoWorkspace.g[37]*acadoWorkspace.x[37] + acadoWorkspace.g[38]*acadoWorkspace.x[38] + acadoWorkspace.g[39]*acadoWorkspace.x[39];
+kkt = fabs( kkt );
+for (index = 0; index < 40; ++index)
+{
+prd = acadoWorkspace.y[index];
+if (prd > 1e-12)
+kkt += fabs(acadoWorkspace.lb[index] * prd);
+else if (prd < -1e-12)
+kkt += fabs(acadoWorkspace.ub[index] * prd);
+}
+for (index = 0; index < 240; ++index)
+{
+prd = acadoWorkspace.y[index + 40];
+if (prd > 1e-12)
+kkt += fabs(acadoWorkspace.lbA[index] * prd);
+else if (prd < -1e-12)
+kkt += fabs(acadoWorkspace.ubA[index] * prd);
+}
+return kkt;
+}
+
+real_t acado_getObjective(  )
+{
+real_t objVal;
+
+int lRun1;
+/** Row vector of size: 8 */
+real_t tmpDy[ 8 ];
+
+/** Row vector of size: 5 */
+real_t tmpDyN[ 5 ];
+
+for (lRun1 = 0; lRun1 < 20; ++lRun1)
+{
+acadoWorkspace.objValueIn[0] = acadoVariables.x[lRun1 * 5];
+acadoWorkspace.objValueIn[1] = acadoVariables.x[lRun1 * 5 + 1];
+acadoWorkspace.objValueIn[2] = acadoVariables.x[lRun1 * 5 + 2];
+acadoWorkspace.objValueIn[3] = acadoVariables.x[lRun1 * 5 + 3];
+acadoWorkspace.objValueIn[4] = acadoVariables.x[lRun1 * 5 + 4];
+acadoWorkspace.objValueIn[5] = acadoVariables.u[lRun1 * 2];
+acadoWorkspace.objValueIn[6] = acadoVariables.u[lRun1 * 2 + 1];
+acadoWorkspace.objValueIn[7] = acadoVariables.od[lRun1 * 20];
+acadoWorkspace.objValueIn[8] = acadoVariables.od[lRun1 * 20 + 1];
+acadoWorkspace.objValueIn[9] = acadoVariables.od[lRun1 * 20 + 2];
+acadoWorkspace.objValueIn[10] = acadoVariables.od[lRun1 * 20 + 3];
+acadoWorkspace.objValueIn[11] = acadoVariables.od[lRun1 * 20 + 4];
+acadoWorkspace.objValueIn[12] = acadoVariables.od[lRun1 * 20 + 5];
+acadoWorkspace.objValueIn[13] = acadoVariables.od[lRun1 * 20 + 6];
+acadoWorkspace.objValueIn[14] = acadoVariables.od[lRun1 * 20 + 7];
+acadoWorkspace.objValueIn[15] = acadoVariables.od[lRun1 * 20 + 8];
+acadoWorkspace.objValueIn[16] = acadoVariables.od[lRun1 * 20 + 9];
+acadoWorkspace.objValueIn[17] = acadoVariables.od[lRun1 * 20 + 10];
+acadoWorkspace.objValueIn[18] = acadoVariables.od[lRun1 * 20 + 11];
+acadoWorkspace.objValueIn[19] = acadoVariables.od[lRun1 * 20 + 12];
+acadoWorkspace.objValueIn[20] = acadoVariables.od[lRun1 * 20 + 13];
+acadoWorkspace.objValueIn[21] = acadoVariables.od[lRun1 * 20 + 14];
+acadoWorkspace.objValueIn[22] = acadoVariables.od[lRun1 * 20 + 15];
+acadoWorkspace.objValueIn[23] = acadoVariables.od[lRun1 * 20 + 16];
+acadoWorkspace.objValueIn[24] = acadoVariables.od[lRun1 * 20 + 17];
+acadoWorkspace.objValueIn[25] = acadoVariables.od[lRun1 * 20 + 18];
+acadoWorkspace.objValueIn[26] = acadoVariables.od[lRun1 * 20 + 19];
+
+acado_evaluateLSQ( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut );
+acadoWorkspace.Dy[lRun1 * 8] = acadoWorkspace.objValueOut[0] - acadoVariables.y[lRun1 * 8];
+acadoWorkspace.Dy[lRun1 * 8 + 1] = acadoWorkspace.objValueOut[1] - acadoVariables.y[lRun1 * 8 + 1];
+acadoWorkspace.Dy[lRun1 * 8 + 2] = acadoWorkspace.objValueOut[2] - acadoVariables.y[lRun1 * 8 + 2];
+acadoWorkspace.Dy[lRun1 * 8 + 3] = acadoWorkspace.objValueOut[3] - acadoVariables.y[lRun1 * 8 + 3];
+acadoWorkspace.Dy[lRun1 * 8 + 4] = acadoWorkspace.objValueOut[4] - acadoVariables.y[lRun1 * 8 + 4];
+acadoWorkspace.Dy[lRun1 * 8 + 5] = acadoWorkspace.objValueOut[5] - acadoVariables.y[lRun1 * 8 + 5];
+acadoWorkspace.Dy[lRun1 * 8 + 6] = acadoWorkspace.objValueOut[6] - acadoVariables.y[lRun1 * 8 + 6];
+acadoWorkspace.Dy[lRun1 * 8 + 7] = acadoWorkspace.objValueOut[7] - acadoVariables.y[lRun1 * 8 + 7];
+}
+acadoWorkspace.objValueIn[0] = acadoVariables.x[100];
+acadoWorkspace.objValueIn[1] = acadoVariables.x[101];
+acadoWorkspace.objValueIn[2] = acadoVariables.x[102];
+acadoWorkspace.objValueIn[3] = acadoVariables.x[103];
+acadoWorkspace.objValueIn[4] = acadoVariables.x[104];
+acadoWorkspace.objValueIn[5] = acadoVariables.od[400];
+acadoWorkspace.objValueIn[6] = acadoVariables.od[401];
+acadoWorkspace.objValueIn[7] = acadoVariables.od[402];
+acadoWorkspace.objValueIn[8] = acadoVariables.od[403];
+acadoWorkspace.objValueIn[9] = acadoVariables.od[404];
+acadoWorkspace.objValueIn[10] = acadoVariables.od[405];
+acadoWorkspace.objValueIn[11] = acadoVariables.od[406];
+acadoWorkspace.objValueIn[12] = acadoVariables.od[407];
+acadoWorkspace.objValueIn[13] = acadoVariables.od[408];
+acadoWorkspace.objValueIn[14] = acadoVariables.od[409];
+acadoWorkspace.objValueIn[15] = acadoVariables.od[410];
+acadoWorkspace.objValueIn[16] = acadoVariables.od[411];
+acadoWorkspace.objValueIn[17] = acadoVariables.od[412];
+acadoWorkspace.objValueIn[18] = acadoVariables.od[413];
+acadoWorkspace.objValueIn[19] = acadoVariables.od[414];
+acadoWorkspace.objValueIn[20] = acadoVariables.od[415];
+acadoWorkspace.objValueIn[21] = acadoVariables.od[416];
+acadoWorkspace.objValueIn[22] = acadoVariables.od[417];
+acadoWorkspace.objValueIn[23] = acadoVariables.od[418];
+acadoWorkspace.objValueIn[24] = acadoVariables.od[419];
+acado_evaluateLSQEndTerm( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut );
+acadoWorkspace.DyN[0] = acadoWorkspace.objValueOut[0] - acadoVariables.yN[0];
+acadoWorkspace.DyN[1] = acadoWorkspace.objValueOut[1] - acadoVariables.yN[1];
+acadoWorkspace.DyN[2] = acadoWorkspace.objValueOut[2] - acadoVariables.yN[2];
+acadoWorkspace.DyN[3] = acadoWorkspace.objValueOut[3] - acadoVariables.yN[3];
+acadoWorkspace.DyN[4] = acadoWorkspace.objValueOut[4] - acadoVariables.yN[4];
+objVal = 0.0000000000000000e+00;
+for (lRun1 = 0; lRun1 < 20; ++lRun1)
+{
+tmpDy[0] = + acadoWorkspace.Dy[lRun1 * 8]*acadoVariables.W[lRun1 * 64] + acadoWorkspace.Dy[lRun1 * 8 + 1]*acadoVariables.W[lRun1 * 64 + 8] + acadoWorkspace.Dy[lRun1 * 8 + 2]*acadoVariables.W[lRun1 * 64 + 16] + acadoWorkspace.Dy[lRun1 * 8 + 3]*acadoVariables.W[lRun1 * 64 + 24] + acadoWorkspace.Dy[lRun1 * 8 + 4]*acadoVariables.W[lRun1 * 64 + 32] + acadoWorkspace.Dy[lRun1 * 8 + 5]*acadoVariables.W[lRun1 * 64 + 40] + acadoWorkspace.Dy[lRun1 * 8 + 6]*acadoVariables.W[lRun1 * 64 + 48] + acadoWorkspace.Dy[lRun1 * 8 + 7]*acadoVariables.W[lRun1 * 64 + 56];
+tmpDy[1] = + acadoWorkspace.Dy[lRun1 * 8]*acadoVariables.W[lRun1 * 64 + 1] + acadoWorkspace.Dy[lRun1 * 8 + 1]*acadoVariables.W[lRun1 * 64 + 9] + acadoWorkspace.Dy[lRun1 * 8 + 2]*acadoVariables.W[lRun1 * 64 + 17] + acadoWorkspace.Dy[lRun1 * 8 + 3]*acadoVariables.W[lRun1 * 64 + 25] + acadoWorkspace.Dy[lRun1 * 8 + 4]*acadoVariables.W[lRun1 * 64 + 33] + acadoWorkspace.Dy[lRun1 * 8 + 5]*acadoVariables.W[lRun1 * 64 + 41] + acadoWorkspace.Dy[lRun1 * 8 + 6]*acadoVariables.W[lRun1 * 64 + 49] + acadoWorkspace.Dy[lRun1 * 8 + 7]*acadoVariables.W[lRun1 * 64 + 57];
+tmpDy[2] = + acadoWorkspace.Dy[lRun1 * 8]*acadoVariables.W[lRun1 * 64 + 2] + acadoWorkspace.Dy[lRun1 * 8 + 1]*acadoVariables.W[lRun1 * 64 + 10] + acadoWorkspace.Dy[lRun1 * 8 + 2]*acadoVariables.W[lRun1 * 64 + 18] + acadoWorkspace.Dy[lRun1 * 8 + 3]*acadoVariables.W[lRun1 * 64 + 26] + acadoWorkspace.Dy[lRun1 * 8 + 4]*acadoVariables.W[lRun1 * 64 + 34] + acadoWorkspace.Dy[lRun1 * 8 + 5]*acadoVariables.W[lRun1 * 64 + 42] + acadoWorkspace.Dy[lRun1 * 8 + 6]*acadoVariables.W[lRun1 * 64 + 50] + acadoWorkspace.Dy[lRun1 * 8 + 7]*acadoVariables.W[lRun1 * 64 + 58];
+tmpDy[3] = + acadoWorkspace.Dy[lRun1 * 8]*acadoVariables.W[lRun1 * 64 + 3] + acadoWorkspace.Dy[lRun1 * 8 + 1]*acadoVariables.W[lRun1 * 64 + 11] + acadoWorkspace.Dy[lRun1 * 8 + 2]*acadoVariables.W[lRun1 * 64 + 19] + acadoWorkspace.Dy[lRun1 * 8 + 3]*acadoVariables.W[lRun1 * 64 + 27] + acadoWorkspace.Dy[lRun1 * 8 + 4]*acadoVariables.W[lRun1 * 64 + 35] + acadoWorkspace.Dy[lRun1 * 8 + 5]*acadoVariables.W[lRun1 * 64 + 43] + acadoWorkspace.Dy[lRun1 * 8 + 6]*acadoVariables.W[lRun1 * 64 + 51] + acadoWorkspace.Dy[lRun1 * 8 + 7]*acadoVariables.W[lRun1 * 64 + 59];
+tmpDy[4] = + acadoWorkspace.Dy[lRun1 * 8]*acadoVariables.W[lRun1 * 64 + 4] + acadoWorkspace.Dy[lRun1 * 8 + 1]*acadoVariables.W[lRun1 * 64 + 12] + acadoWorkspace.Dy[lRun1 * 8 + 2]*acadoVariables.W[lRun1 * 64 + 20] + acadoWorkspace.Dy[lRun1 * 8 + 3]*acadoVariables.W[lRun1 * 64 + 28] + acadoWorkspace.Dy[lRun1 * 8 + 4]*acadoVariables.W[lRun1 * 64 + 36] + acadoWorkspace.Dy[lRun1 * 8 + 5]*acadoVariables.W[lRun1 * 64 + 44] + acadoWorkspace.Dy[lRun1 * 8 + 6]*acadoVariables.W[lRun1 * 64 + 52] + acadoWorkspace.Dy[lRun1 * 8 + 7]*acadoVariables.W[lRun1 * 64 + 60];
+tmpDy[5] = + acadoWorkspace.Dy[lRun1 * 8]*acadoVariables.W[lRun1 * 64 + 5] + acadoWorkspace.Dy[lRun1 * 8 + 1]*acadoVariables.W[lRun1 * 64 + 13] + acadoWorkspace.Dy[lRun1 * 8 + 2]*acadoVariables.W[lRun1 * 64 + 21] + acadoWorkspace.Dy[lRun1 * 8 + 3]*acadoVariables.W[lRun1 * 64 + 29] + acadoWorkspace.Dy[lRun1 * 8 + 4]*acadoVariables.W[lRun1 * 64 + 37] + acadoWorkspace.Dy[lRun1 * 8 + 5]*acadoVariables.W[lRun1 * 64 + 45] + acadoWorkspace.Dy[lRun1 * 8 + 6]*acadoVariables.W[lRun1 * 64 + 53] + acadoWorkspace.Dy[lRun1 * 8 + 7]*acadoVariables.W[lRun1 * 64 + 61];
+tmpDy[6] = + acadoWorkspace.Dy[lRun1 * 8]*acadoVariables.W[lRun1 * 64 + 6] + acadoWorkspace.Dy[lRun1 * 8 + 1]*acadoVariables.W[lRun1 * 64 + 14] + acadoWorkspace.Dy[lRun1 * 8 + 2]*acadoVariables.W[lRun1 * 64 + 22] + acadoWorkspace.Dy[lRun1 * 8 + 3]*acadoVariables.W[lRun1 * 64 + 30] + acadoWorkspace.Dy[lRun1 * 8 + 4]*acadoVariables.W[lRun1 * 64 + 38] + acadoWorkspace.Dy[lRun1 * 8 + 5]*acadoVariables.W[lRun1 * 64 + 46] + acadoWorkspace.Dy[lRun1 * 8 + 6]*acadoVariables.W[lRun1 * 64 + 54] + acadoWorkspace.Dy[lRun1 * 8 + 7]*acadoVariables.W[lRun1 * 64 + 62];
+tmpDy[7] = + acadoWorkspace.Dy[lRun1 * 8]*acadoVariables.W[lRun1 * 64 + 7] + acadoWorkspace.Dy[lRun1 * 8 + 1]*acadoVariables.W[lRun1 * 64 + 15] + acadoWorkspace.Dy[lRun1 * 8 + 2]*acadoVariables.W[lRun1 * 64 + 23] + acadoWorkspace.Dy[lRun1 * 8 + 3]*acadoVariables.W[lRun1 * 64 + 31] + acadoWorkspace.Dy[lRun1 * 8 + 4]*acadoVariables.W[lRun1 * 64 + 39] + acadoWorkspace.Dy[lRun1 * 8 + 5]*acadoVariables.W[lRun1 * 64 + 47] + acadoWorkspace.Dy[lRun1 * 8 + 6]*acadoVariables.W[lRun1 * 64 + 55] + acadoWorkspace.Dy[lRun1 * 8 + 7]*acadoVariables.W[lRun1 * 64 + 63];
+objVal += + acadoWorkspace.Dy[lRun1 * 8]*tmpDy[0] + acadoWorkspace.Dy[lRun1 * 8 + 1]*tmpDy[1] + acadoWorkspace.Dy[lRun1 * 8 + 2]*tmpDy[2] + acadoWorkspace.Dy[lRun1 * 8 + 3]*tmpDy[3] + acadoWorkspace.Dy[lRun1 * 8 + 4]*tmpDy[4] + acadoWorkspace.Dy[lRun1 * 8 + 5]*tmpDy[5] + acadoWorkspace.Dy[lRun1 * 8 + 6]*tmpDy[6] + acadoWorkspace.Dy[lRun1 * 8 + 7]*tmpDy[7];
+}
+
+tmpDyN[0] = + acadoWorkspace.DyN[0]*acadoVariables.WN[0];
+tmpDyN[1] = + acadoWorkspace.DyN[1]*acadoVariables.WN[6];
+tmpDyN[2] = + acadoWorkspace.DyN[2]*acadoVariables.WN[12];
+tmpDyN[3] = + acadoWorkspace.DyN[3]*acadoVariables.WN[18];
+tmpDyN[4] = + acadoWorkspace.DyN[4]*acadoVariables.WN[24];
+objVal += + acadoWorkspace.DyN[0]*tmpDyN[0] + acadoWorkspace.DyN[1]*tmpDyN[1] + acadoWorkspace.DyN[2]*tmpDyN[2] + acadoWorkspace.DyN[3]*tmpDyN[3] + acadoWorkspace.DyN[4]*tmpDyN[4];
+
+objVal *= 0.5;
+return objVal;
+}
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/acado_solver_mex.c b/mav_control_rw/mav_nonlinear_mpc/solver/acado_solver_mex.c
new file mode 100644
index 0000000000000000000000000000000000000000..bdd6778bd7e4f77a3ebfb9ff1f535ef1e9c7163f
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/acado_solver_mex.c
@@ -0,0 +1,539 @@
+/*
+ *    This file was auto-generated using the ACADO Toolkit.
+ *    
+ *    While ACADO Toolkit is free software released under the terms of
+ *    the GNU Lesser General Public License (LGPL), the generated code
+ *    as such remains the property of the user who used ACADO Toolkit
+ *    to generate this code. In particular, user dependent data of the code
+ *    do not inherit the GNU LGPL license. On the other hand, parts of the
+ *    generated code that are a direct copy of source code from the
+ *    ACADO Toolkit or the software tools it is based on, remain, as derived
+ *    work, automatically covered by the LGPL license.
+ *    
+ *    ACADO Toolkit is distributed in the hope that it will be useful,
+ *    but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ *    
+ */
+
+
+/*
+input
+{
+	control: optional
+		0: init once, and run preparation and feedback; default behaviour
+		1: initialize
+		2: preparation
+		3: feedback
+		4: shift
+	x
+	u
+	od
+	y
+	yN
+	W
+	WN
+	x0: depends on the type of an OCP
+	xAC: optional
+	SAC: optional
+	shifting: optional
+	{
+		strategy:
+			1: use xEnd
+			2: integrate
+		xEnd
+		uEnd
+	}
+	initialization: optional
+		1: initialize by a forward simulation
+		else: do nothing
+}
+
+output
+{
+	x
+	u
+	xAC: optional
+	SAC: optional
+	info
+	{
+		status
+		cpuTime
+		kktValue
+		objValue
+		nIterations: works only for qpOASES
+	}	
+}
+*/
+
+/** MEX interface for the ACADO OCP solver
+ *
+ *  \author Milan Vukov, milan.vukov@esat.kuleuven.be
+ *
+ *  Credits: Alexander Domahidi (ETHZ), Janick Frasch (KUL, OVGU)
+ *
+ */
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <stdarg.h>
+
+#include "mex.h"
+#include "acado_common.h"
+#include "acado_auxiliary_functions.h"
+
+#define FREE( mem ) { if( mem ) { mxFree( mem ); mem = NULL; } }
+
+/* Define number of outputs */
+#define NOO 3
+
+#if ACADO_NXA > 0
+#define NOO_2 NOO + 1
+#else
+#define NOO_2 NOO
+#endif
+
+#if ACADO_USE_ARRIVAL_COST == 1
+#define NOO_3 NOO_2 + 2
+#else
+#define NOO_3 NOO_2
+#endif
+
+#if ACADO_COMPUTE_COVARIANCE_MATRIX == 1
+#define NOO_4 NOO_3 + 1
+#else
+#define NOO_4 NOO_3
+#endif
+
+/** Instance of the user data structure. */
+ACADOvariables acadoVariables;
+/** Instance of the private workspace structure. */
+ACADOworkspace acadoWorkspace;
+
+#if ACADO_QP_SOLVER == ACADO_FORCES
+#include "forces.h"
+extern forces_info acadoForces_info;
+#elif ACADO_QP_SOLVER == ACADO_QPDUNES
+#include <qpDUNES.h>
+extern qpData_t    qpData;
+#endif
+
+/** A bit more advanced printing function. */
+void mexErrMsgTxtAdv(	char* string,
+						...
+						)
+{
+	static char buffer[ 128 ];
+	
+	va_list printArgs;
+	va_start(printArgs, string);
+	
+	vsprintf(buffer, string, printArgs);
+	va_end( printArgs );
+
+	mexErrMsgTxt( buffer );
+}
+
+/** A simple helper function. */
+void printMatrix(	const char* name,
+					real_t* mat,
+					unsigned nRows,
+					unsigned nCols
+					)
+{
+    unsigned r, c;
+    mexPrintf("%s: \n", name);
+    for (r = 0; r < nRows; ++r)
+    {
+        for(c = 0; c < nCols; ++c)
+            mexPrintf("\t%f", mat[r * nCols + c]);
+        mexPrintf("\n");
+    }
+}
+
+/** A function for copying data from MATLAB to C array. */
+int getArray(	const unsigned mandatory,
+				const mxArray* source,
+				const int index,
+				const char* name,
+				real_t* destination,
+				const unsigned nRows,
+				const unsigned nCols
+				)
+{
+	mxArray* mxPtr = mxGetField(source, index, name);
+	unsigned i, j;
+	double* dPtr;
+	
+	if (mxPtr == NULL)
+	{
+		if ( !mandatory )
+			return -1;
+		else
+			mexErrMsgTxtAdv("Field %s not found.", name);
+	}
+
+    if ( !mxIsDouble( mxPtr ) )
+		mexErrMsgTxtAdv("Field %s must be an array of doubles.", name);
+
+    if (mxGetM( mxPtr ) != nRows || mxGetN( mxPtr ) != nCols )
+		mexErrMsgTxtAdv("Field %s must be of size: %d x %d.", name, nRows, nCols);
+
+	dPtr = mxGetPr( mxPtr );
+	
+	if (destination == NULL)
+		destination = (real_t*)mxCalloc(nRows * nCols, sizeof( real_t ));
+
+	if (nRows == 1 && nCols == 1)
+		*destination = *dPtr;
+	else
+		for (i = 0; i < nRows; ++i)
+			for (j = 0; j < nCols; ++j)
+				destination[i * nCols + j] = (real_t)dPtr[j * nRows + i];
+			
+	return 0;
+}
+
+void setArray( 	mxArray* destination,
+				const int index,
+				const char* name,
+				real_t* source,
+				const unsigned nRows,
+				const unsigned nCols
+				)
+{
+	mxArray* mxPtr = mxCreateDoubleMatrix(nRows, nCols, mxREAL);
+	double* dPtr = mxGetPr( mxPtr );
+	unsigned i, j;
+	
+	if (nRows == 1 && nCols == 1)
+		*dPtr = *source;
+	else
+		for (i = 0; i < nRows; ++i)
+			for(j = 0; j < nCols; ++j)
+				dPtr[j * nRows + i] = (double)source[i * nCols + j];
+
+	mxSetField(destination, index, name, mxPtr);
+}
+
+/** The MEX interface function. */
+void mexFunction(	int nlhs,
+					mxArray *plhs[],
+					int nrhs,
+					const mxArray *prhs[]
+					)
+{
+	static unsigned initialized = 0;
+	unsigned ctrl;
+	int ctrlIndex;
+	unsigned strategy;
+	unsigned initType;
+	real_t* xEnd = NULL;
+	real_t* uEnd = NULL;
+	const mxArray* src = prhs[ 0 ];
+	
+	const char *infoNames[ 5 ] = {"status", "cpuTime", "kktValue", "objValue", "nIterations"};
+	mxArray* info;
+	double status, cpuTime, kktValue, objValue;
+	double tmp[ 1 ];
+	mxArray* shPtr;
+	acado_timer tmr;
+	double nIterations = 0;
+	
+	const char *outNames[ NOO_4 ];
+	outNames[ 0 ] = "info";
+	outNames[ 1 ] = "x";
+	outNames[ 2 ] = "u";
+#if ACADO_NXA
+	outNames[ NOO ] = "z";
+#endif	
+		
+#if ACADO_USE_ARRIVAL_COST == 1
+	outNames[ NOO_2 ] = "xAC";
+	outNames[NOO_2  + 1] = "SAC";
+#endif
+#if ACADO_COMPUTE_COVARIANCE_MATRIX == 1
+	outNames[ NOO_3 ] = "sigmaN";
+#endif
+	
+	if (nrhs != 1)
+		mexErrMsgTxt(
+			"This function requires exactly one input: a structure with parameters.");
+			
+	if (nlhs != 1)
+		mexErrMsgTxt(
+			"This function returns one output.");
+			
+	if( !mxIsStruct( src ) )
+		mexErrMsgTxt("The function argument must be a structure.");
+	
+	/* Get the control flag. */
+	if (getArray(0, src, 0, "control", tmp, 1, 1) == 0)
+		ctrl = (unsigned)tmp[ 0 ];
+	else
+		ctrl = 0;
+		
+	/* Get the initialization flag. */
+	if (getArray(0, src, 0, "initialization", tmp, 1, 1) == 0)
+		initType = (unsigned)tmp[ 0 ];
+	else
+		initType = 0;
+		
+	/* Copy MATLAB arrays to C arrays. */
+	getArray(1, src, 0, "x", acadoVariables.x, ACADO_N + 1, ACADO_NX);
+	getArray(1, src, 0, "u", acadoVariables.u, ACADO_N, ACADO_NU);
+	
+#if ACADO_NXA	
+	getArray(1, src, 0, "z", acadoVariables.z, ACADO_N, ACADO_NXA);
+#endif	
+	
+#if ACADO_NOD
+	getArray(1, src, 0, "od", acadoVariables.od, ACADO_N + 1, ACADO_NOD);
+#endif
+	
+	getArray(1, src, 0, "y", acadoVariables.y, ACADO_N, ACADO_NY);
+	
+#if ACADO_NYN
+	getArray(1, src, 0, "yN", acadoVariables.yN, 1, ACADO_NYN);
+#endif /* ACADO_NYN */
+
+#if ACADO_INITIAL_STATE_FIXED
+	getArray(1, src, 0, "x0", acadoVariables.x0, 1, ACADO_NX);
+#endif /* ACADO_INITIAL_STATE_FIXED */
+
+#if ACADO_WEIGHTING_MATRICES_TYPE == 1
+	getArray(1, src, 0, "W", acadoVariables.W, ACADO_NY, ACADO_NY);
+	getArray(1, src, 0, "WN", acadoVariables.WN, ACADO_NYN, ACADO_NYN);
+#elif ACADO_WEIGHTING_MATRICES_TYPE == 2
+	getArray(1, src, 0, "W", acadoVariables.W, ACADO_N * ACADO_NY, ACADO_NY);
+	getArray(1, src, 0, "WN", acadoVariables.WN, ACADO_NYN, ACADO_NYN);
+#endif /* ACADO_WEIGHTING_MATRICES_TYPE */
+
+
+#if (ACADO_HARDCODED_CONSTRAINT_VALUES == 0)
+	if (!initialized)
+	{
+		acado_initializeSolver();
+	}
+#endif
+
+#if (ACADO_HARDCODED_CONSTRAINT_VALUES == 0) && ( (ACADO_QP_SOLVER == ACADO_QPOASES) || (ACADO_QP_SOLVER == ACADO_QPOASES3) )
+	/* Bounds */
+#if ACADO_INITIAL_STATE_FIXED == 1
+	getArray(1, src, 0, "lbValues", acadoVariables.lbValues, ACADO_N * ACADO_NU, 1);
+	getArray(1, src, 0, "ubValues", acadoVariables.ubValues, ACADO_N * ACADO_NU, 1);
+#else
+	getArray(1, src, 0, "lbValues", acadoVariables.lbValues, ACADO_NX + ACADO_N * ACADO_NU, 1);
+	getArray(1, src, 0, "ubValues", acadoVariables.ubValues, ACADO_NX + ACADO_N * ACADO_NU, 1);
+#endif /* ACADO_INITIAL_STATE_FIXED == 0 */
+
+#if QPOASES_NCMAX > 0
+	/* Affine constraints */
+	getArray(1, src, 0, "lbAValues", acadoVariables.lbAValues, QPOASES_NCMAX, 1);
+	getArray(1, src, 0, "ubAValues", acadoVariables.ubAValues, QPOASES_NCMAX, 1);
+#endif /* QPOASES_NCMAX > 0 */
+
+#elif (ACADO_HARDCODED_CONSTRAINT_VALUES == 0) && (ACADO_QP_SOLVER == ACADO_FORCES) && !ACADO_BLOCK_CONDENSING
+	/* Bounds */
+	#if (ACADO_QP_NLB > 0)
+	getArray(1, src, 0, "lbValues", acadoVariables.lbValues, ACADO_QP_NLB, 1);
+	#endif
+	#if (ACADO_QP_NUB > 0)
+	getArray(1, src, 0, "ubValues", acadoVariables.ubValues, ACADO_QP_NUB, 1);
+	#endif
+
+#elif (ACADO_HARDCODED_CONSTRAINT_VALUES == 0) && (ACADO_QP_SOLVER == ACADO_QPDUNES) && !ACADO_BLOCK_CONDENSING
+	/* Bounds */
+	getArray(1, src, 0, "lbValues", acadoVariables.lbValues, ACADO_QP_NV, 1);
+	getArray(1, src, 0, "ubValues", acadoVariables.ubValues, ACADO_QP_NV, 1);
+	
+#elif (ACADO_HARDCODED_CONSTRAINT_VALUES == 0) && ACADO_BLOCK_CONDENSING
+	/* Bounds */
+	getArray(1, src, 0, "lbValues", acadoVariables.lbValues, ACADO_QP_NV, 1);
+	getArray(1, src, 0, "ubValues", acadoVariables.ubValues, ACADO_QP_NV, 1);
+	#if (ACADO_QP_NCA > 0)
+	/* Affine bounds */
+	getArray(1, src, 0, "lbAValues", acadoVariables.lbAValues, ACADO_QP_NCA, 1);
+	getArray(1, src, 0, "ubAValues", acadoVariables.ubAValues, ACADO_QP_NCA, 1);
+	#endif
+#endif
+
+#if ACADO_USE_ARRIVAL_COST == 1
+	getArray(1, src, 0, "xAC", acadoVariables.xAC, ACADO_NX, 1);
+	getArray(1, src, 0, "SAC", acadoVariables.SAC, ACADO_NX, ACADO_NX);
+    getArray(1, src, 0, "WL",  acadoVariables.WL,  ACADO_NX, ACADO_NX);
+#endif
+
+	/* Shifting strategy */
+	shPtr = mxGetField(src, 0, "shifting");
+	if (shPtr != NULL)
+	{
+		if( !mxIsStruct( shPtr ) )
+			mexErrMsgTxt("Field \"shifting\" must be defined with a structure.");
+		
+		/* Get the shifting strategy flag */
+		getArray(1, shPtr, 0, "strategy", tmp, 1, 1);
+		strategy = (unsigned)tmp[ 0 ];
+		
+		if (strategy > 2)
+			mexErrMsgTxt("Valid options for the shifting strategy are 1 or 2.");
+	
+		getArray(0, shPtr, 0, "xEnd", xEnd, ACADO_NX, 1);
+		getArray(0, shPtr, 0, "uEnd", uEnd, ACADO_NU, 1);
+	}
+	else
+		strategy = 0;
+		
+	acado_tic( &tmr );
+	
+	/* Call solver */
+	switch ( ctrl )
+	{
+		case 0:
+			/* Simple operational mode. Run one RTI with optional shifting. */
+			
+			if ( !initialized )
+			{
+				memset(&acadoWorkspace, 0, sizeof( acadoWorkspace ));
+			
+#if ACADO_HARDCODED_CONSTRAINT_VALUES == 1
+				acado_initializeSolver();
+#endif /* ACADO_HARDCODED_CONSTRAINT_VALUES == 1 */
+				
+				if (initType == 1)
+				{
+					acado_initializeNodesByForwardSimulation();
+				}
+				
+#if ACADO_USE_ARRIVAL_COST == 1 
+                acado_updateArrivalCost( 1 );
+#endif /* ACADO_USE_ARRIVAL_COST == 1 */
+				
+				initialized = 1;
+			}
+			else if (strategy == 1 || strategy == 2)
+			{
+#if ACADO_USE_ARRIVAL_COST == 1 
+                acado_updateArrivalCost( 0 );
+#endif /* ACADO_USE_ARRIVAL_COST == 1 */
+				
+				acado_shiftStates(strategy, xEnd, uEnd);
+				acado_shiftControls(uEnd);
+			}
+			
+			acado_preparationStep();
+			
+			status = (double)acado_feedbackStep();
+			
+			kktValue = acado_getKKT();
+			objValue = acado_getObjective();
+
+#if ( (ACADO_QP_SOLVER == ACADO_QPOASES) || (ACADO_QP_SOLVER == ACADO_QPOASES3) )
+			nIterations = (double)acado_getNWSR();
+#elif ACADO_QP_SOLVER == ACADO_FORCES
+			nIterations = acadoForces_info.it;
+#elif ACADO_QP_SOLVER == ACADO_QPDUNES
+			nIterations = qpData.log.numIter;
+#endif /* ACADO_QP_SOLVER */
+			
+			break;
+		
+		case 1:
+			/* Initialize */
+			
+			memset(&acadoWorkspace, 0, sizeof( acadoWorkspace ));
+			
+			acado_initializeSolver();
+				
+			if (initType == 1)
+			{
+				acado_initializeNodesByForwardSimulation();
+			}
+			
+#if ACADO_USE_ARRIVAL_COST == 1 
+			acado_updateArrivalCost( 1 );
+#endif /* ACADO_USE_ARRIVAL_COST == 1 */
+
+			initialized = 1;
+			
+			break;
+		
+		case 2:
+			/* Preparation step */
+			
+			acado_preparationStep();
+			
+			break;
+		
+		case 3:
+			/* Feedback step */
+			
+			status = (double)acado_feedbackStep();
+			
+			kktValue = acado_getKKT();
+			objValue = acado_getObjective();
+			
+#if ( (ACADO_QP_SOLVER == ACADO_QPOASES) || (ACADO_QP_SOLVER == ACADO_QPOASES3) )
+			nIterations = (double)acado_getNWSR();
+#elif ACADO_QP_SOLVER == ACADO_FORCES
+			nIterations = acadoForces_info.it;
+#endif /* ACADO_QP_SOLVER */
+			
+			break;
+		
+		case 4:
+			/* Shifting */
+			
+#if ACADO_USE_ARRIVAL_COST == 1 
+			acado_updateArrivalCost( 0 );
+#endif /* ACADO_USE_ARRIVAL_COST == 1 */			
+			
+			acado_shiftStates(strategy, xEnd, uEnd);
+			acado_shiftControls( uEnd );
+			
+			break;
+			
+		default:
+			/* Return an error */
+			mexErrMsgTxt("Unknown control code.");
+	}
+	
+	cpuTime = acado_toc( &tmr );
+	
+	/* Prepare return argument */
+	
+	plhs[ 0 ] = mxCreateStructMatrix(1, 1, NOO_4, outNames);
+		
+	setArray(plhs[ 0 ], 0, "x", acadoVariables.x, ACADO_N + 1, ACADO_NX);
+	setArray(plhs[ 0 ], 0, "u", acadoVariables.u, ACADO_N, ACADO_NU);
+#if ACADO_NXA > 0
+	setArray(plhs[ 0 ], 0, "z", acadoVariables.z, ACADO_N, ACADO_NXA);
+#endif	
+		
+#if ACADO_USE_ARRIVAL_COST == 1
+	setArray(plhs[ 0 ], 0, "xAC", acadoVariables.xAC, ACADO_NX, 1);
+	setArray(plhs[ 0 ], 0, "SAC", acadoVariables.SAC, ACADO_NX, ACADO_NX);
+#endif /* ACADO_USE_ARRIVAL_COST */
+
+#if ACADO_COMPUTE_COVARIANCE_MATRIX == 1
+	setArray(plhs[ 0 ], 0, "sigmaN", acadoVariables.sigmaN, ACADO_NX, ACADO_NX);
+#endif /* ACADO_COMPUTE_COVARIANCE_MATRIX */
+
+	/* Create the info structure. */
+	info = mxCreateStructMatrix(1, 1, 5, infoNames);
+		
+	setArray(info, 0, "status", &status, 1, 1);
+	setArray(info, 0, "cpuTime", &cpuTime, 1, 1);
+	setArray(info, 0, "kktValue", &kktValue, 1, 1);
+	setArray(info, 0, "objValue", &objValue, 1, 1);
+#if ( (ACADO_QP_SOLVER == ACADO_QPOASES) || (ACADO_QP_SOLVER == ACADO_QPOASES3) )
+	setArray(info, 0, "nIterations", &nIterations, 1, 1);
+#endif /* ( (ACADO_QP_SOLVER == ACADO_QPOASES) || (ACADO_QP_SOLVER == ACADO_QPOASES3) ) */
+		
+	mxSetField(plhs[ 0 ], 0, "info", info);
+	
+	/* Cleanup of the allocated memory */
+	FREE( xEnd );
+	FREE( uEnd );
+}
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/.rosinstall b/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/.rosinstall
new file mode 100644
index 0000000000000000000000000000000000000000..0da04c9b02fcc3f87fdab4510e0bf70b3c02eee7
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/.rosinstall
@@ -0,0 +1,2 @@
+- setup-file:
+    local-name: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/setup.sh
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/_setup_util.py b/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/_setup_util.py
new file mode 100644
index 0000000000000000000000000000000000000000..cb721f76776998339077c845951ad674ed972969
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/_setup_util.py
@@ -0,0 +1,304 @@
+#!/usr/bin/python3
+# -*- coding: utf-8 -*-
+
+# Software License Agreement (BSD License)
+#
+# Copyright (c) 2012, Willow Garage, Inc.
+# All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+#  * Redistributions of source code must retain the above copyright
+#    notice, this list of conditions and the following disclaimer.
+#  * Redistributions in binary form must reproduce the above
+#    copyright notice, this list of conditions and the following
+#    disclaimer in the documentation and/or other materials provided
+#    with the distribution.
+#  * Neither the name of Willow Garage, Inc. nor the names of its
+#    contributors may be used to endorse or promote products derived
+#    from this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+
+"""This file generates shell code for the setup.SHELL scripts to set environment variables."""
+
+from __future__ import print_function
+
+import argparse
+import copy
+import errno
+import os
+import platform
+import sys
+
+CATKIN_MARKER_FILE = '.catkin'
+
+system = platform.system()
+IS_DARWIN = (system == 'Darwin')
+IS_WINDOWS = (system == 'Windows')
+
+PATH_TO_ADD_SUFFIX = ['bin']
+if IS_WINDOWS:
+    # while catkin recommends putting dll's into bin, 3rd party packages often put dll's into lib
+    # since Windows finds dll's via the PATH variable, prepend it with path to lib
+    PATH_TO_ADD_SUFFIX.extend([['lib', os.path.join('lib', 'x86_64-linux-gnu')]])
+
+# subfolder of workspace prepended to CMAKE_PREFIX_PATH
+ENV_VAR_SUBFOLDERS = {
+    'CMAKE_PREFIX_PATH': '',
+    'LD_LIBRARY_PATH' if not IS_DARWIN else 'DYLD_LIBRARY_PATH': ['lib', os.path.join('lib', 'x86_64-linux-gnu')],
+    'PATH': PATH_TO_ADD_SUFFIX,
+    'PKG_CONFIG_PATH': [os.path.join('lib', 'pkgconfig'), os.path.join('lib', 'x86_64-linux-gnu', 'pkgconfig')],
+    'PYTHONPATH': 'lib/python3/dist-packages',
+}
+
+
+def rollback_env_variables(environ, env_var_subfolders):
+    """
+    Generate shell code to reset environment variables.
+
+    by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH.
+    This does not cover modifications performed by environment hooks.
+    """
+    lines = []
+    unmodified_environ = copy.copy(environ)
+    for key in sorted(env_var_subfolders.keys()):
+        subfolders = env_var_subfolders[key]
+        if not isinstance(subfolders, list):
+            subfolders = [subfolders]
+        value = _rollback_env_variable(unmodified_environ, key, subfolders)
+        if value is not None:
+            environ[key] = value
+            lines.append(assignment(key, value))
+    if lines:
+        lines.insert(0, comment('reset environment variables by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH'))
+    return lines
+
+
+def _rollback_env_variable(environ, name, subfolders):
+    """
+    For each catkin workspace in CMAKE_PREFIX_PATH remove the first entry from env[NAME] matching workspace + subfolder.
+
+    :param subfolders: list of str '' or subfoldername that may start with '/'
+    :returns: the updated value of the environment variable.
+    """
+    value = environ[name] if name in environ else ''
+    env_paths = [path for path in value.split(os.pathsep) if path]
+    value_modified = False
+    for subfolder in subfolders:
+        if subfolder:
+            if subfolder.startswith(os.path.sep) or (os.path.altsep and subfolder.startswith(os.path.altsep)):
+                subfolder = subfolder[1:]
+            if subfolder.endswith(os.path.sep) or (os.path.altsep and subfolder.endswith(os.path.altsep)):
+                subfolder = subfolder[:-1]
+        for ws_path in _get_workspaces(environ, include_fuerte=True, include_non_existing=True):
+            path_to_find = os.path.join(ws_path, subfolder) if subfolder else ws_path
+            path_to_remove = None
+            for env_path in env_paths:
+                env_path_clean = env_path[:-1] if env_path and env_path[-1] in [os.path.sep, os.path.altsep] else env_path
+                if env_path_clean == path_to_find:
+                    path_to_remove = env_path
+                    break
+            if path_to_remove:
+                env_paths.remove(path_to_remove)
+                value_modified = True
+    new_value = os.pathsep.join(env_paths)
+    return new_value if value_modified else None
+
+
+def _get_workspaces(environ, include_fuerte=False, include_non_existing=False):
+    """
+    Based on CMAKE_PREFIX_PATH return all catkin workspaces.
+
+    :param include_fuerte: The flag if paths starting with '/opt/ros/fuerte' should be considered workspaces, ``bool``
+    """
+    # get all cmake prefix paths
+    env_name = 'CMAKE_PREFIX_PATH'
+    value = environ[env_name] if env_name in environ else ''
+    paths = [path for path in value.split(os.pathsep) if path]
+    # remove non-workspace paths
+    workspaces = [path for path in paths if os.path.isfile(os.path.join(path, CATKIN_MARKER_FILE)) or (include_fuerte and path.startswith('/opt/ros/fuerte')) or (include_non_existing and not os.path.exists(path))]
+    return workspaces
+
+
+def prepend_env_variables(environ, env_var_subfolders, workspaces):
+    """Generate shell code to prepend environment variables for the all workspaces."""
+    lines = []
+    lines.append(comment('prepend folders of workspaces to environment variables'))
+
+    paths = [path for path in workspaces.split(os.pathsep) if path]
+
+    prefix = _prefix_env_variable(environ, 'CMAKE_PREFIX_PATH', paths, '')
+    lines.append(prepend(environ, 'CMAKE_PREFIX_PATH', prefix))
+
+    for key in sorted(key for key in env_var_subfolders.keys() if key != 'CMAKE_PREFIX_PATH'):
+        subfolder = env_var_subfolders[key]
+        prefix = _prefix_env_variable(environ, key, paths, subfolder)
+        lines.append(prepend(environ, key, prefix))
+    return lines
+
+
+def _prefix_env_variable(environ, name, paths, subfolders):
+    """
+    Return the prefix to prepend to the environment variable NAME.
+
+    Adding any path in NEW_PATHS_STR without creating duplicate or empty items.
+    """
+    value = environ[name] if name in environ else ''
+    environ_paths = [path for path in value.split(os.pathsep) if path]
+    checked_paths = []
+    for path in paths:
+        if not isinstance(subfolders, list):
+            subfolders = [subfolders]
+        for subfolder in subfolders:
+            path_tmp = path
+            if subfolder:
+                path_tmp = os.path.join(path_tmp, subfolder)
+            # skip nonexistent paths
+            if not os.path.exists(path_tmp):
+                continue
+            # exclude any path already in env and any path we already added
+            if path_tmp not in environ_paths and path_tmp not in checked_paths:
+                checked_paths.append(path_tmp)
+    prefix_str = os.pathsep.join(checked_paths)
+    if prefix_str != '' and environ_paths:
+        prefix_str += os.pathsep
+    return prefix_str
+
+
+def assignment(key, value):
+    if not IS_WINDOWS:
+        return 'export %s="%s"' % (key, value)
+    else:
+        return 'set %s=%s' % (key, value)
+
+
+def comment(msg):
+    if not IS_WINDOWS:
+        return '# %s' % msg
+    else:
+        return 'REM %s' % msg
+
+
+def prepend(environ, key, prefix):
+    if key not in environ or not environ[key]:
+        return assignment(key, prefix)
+    if not IS_WINDOWS:
+        return 'export %s="%s$%s"' % (key, prefix, key)
+    else:
+        return 'set %s=%s%%%s%%' % (key, prefix, key)
+
+
+def find_env_hooks(environ, cmake_prefix_path):
+    """Generate shell code with found environment hooks for the all workspaces."""
+    lines = []
+    lines.append(comment('found environment hooks in workspaces'))
+
+    generic_env_hooks = []
+    generic_env_hooks_workspace = []
+    specific_env_hooks = []
+    specific_env_hooks_workspace = []
+    generic_env_hooks_by_filename = {}
+    specific_env_hooks_by_filename = {}
+    generic_env_hook_ext = 'bat' if IS_WINDOWS else 'sh'
+    specific_env_hook_ext = environ['CATKIN_SHELL'] if not IS_WINDOWS and 'CATKIN_SHELL' in environ and environ['CATKIN_SHELL'] else None
+    # remove non-workspace paths
+    workspaces = [path for path in cmake_prefix_path.split(os.pathsep) if path and os.path.isfile(os.path.join(path, CATKIN_MARKER_FILE))]
+    for workspace in reversed(workspaces):
+        env_hook_dir = os.path.join(workspace, 'etc', 'catkin', 'profile.d')
+        if os.path.isdir(env_hook_dir):
+            for filename in sorted(os.listdir(env_hook_dir)):
+                if filename.endswith('.%s' % generic_env_hook_ext):
+                    # remove previous env hook with same name if present
+                    if filename in generic_env_hooks_by_filename:
+                        i = generic_env_hooks.index(generic_env_hooks_by_filename[filename])
+                        generic_env_hooks.pop(i)
+                        generic_env_hooks_workspace.pop(i)
+                    # append env hook
+                    generic_env_hooks.append(os.path.join(env_hook_dir, filename))
+                    generic_env_hooks_workspace.append(workspace)
+                    generic_env_hooks_by_filename[filename] = generic_env_hooks[-1]
+                elif specific_env_hook_ext is not None and filename.endswith('.%s' % specific_env_hook_ext):
+                    # remove previous env hook with same name if present
+                    if filename in specific_env_hooks_by_filename:
+                        i = specific_env_hooks.index(specific_env_hooks_by_filename[filename])
+                        specific_env_hooks.pop(i)
+                        specific_env_hooks_workspace.pop(i)
+                    # append env hook
+                    specific_env_hooks.append(os.path.join(env_hook_dir, filename))
+                    specific_env_hooks_workspace.append(workspace)
+                    specific_env_hooks_by_filename[filename] = specific_env_hooks[-1]
+    env_hooks = generic_env_hooks + specific_env_hooks
+    env_hooks_workspace = generic_env_hooks_workspace + specific_env_hooks_workspace
+    count = len(env_hooks)
+    lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_COUNT', count))
+    for i in range(count):
+        lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d' % i, env_hooks[i]))
+        lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d_WORKSPACE' % i, env_hooks_workspace[i]))
+    return lines
+
+
+def _parse_arguments(args=None):
+    parser = argparse.ArgumentParser(description='Generates code blocks for the setup.SHELL script.')
+    parser.add_argument('--extend', action='store_true', help='Skip unsetting previous environment variables to extend context')
+    parser.add_argument('--local', action='store_true', help='Only consider this prefix path and ignore other prefix path in the environment')
+    return parser.parse_known_args(args=args)[0]
+
+
+if __name__ == '__main__':
+    try:
+        try:
+            args = _parse_arguments()
+        except Exception as e:
+            print(e, file=sys.stderr)
+            sys.exit(1)
+
+        if not args.local:
+            # environment at generation time
+            CMAKE_PREFIX_PATH = r'/home/simhe502/catkin_ws/devel;/opt/ros/noetic'.split(';')
+        else:
+            # don't consider any other prefix path than this one
+            CMAKE_PREFIX_PATH = []
+        # prepend current workspace if not already part of CPP
+        base_path = os.path.dirname(__file__)
+        # CMAKE_PREFIX_PATH uses forward slash on all platforms, but __file__ is platform dependent
+        # base_path on Windows contains backward slashes, need to be converted to forward slashes before comparison
+        if os.path.sep != '/':
+            base_path = base_path.replace(os.path.sep, '/')
+
+        if base_path not in CMAKE_PREFIX_PATH:
+            CMAKE_PREFIX_PATH.insert(0, base_path)
+        CMAKE_PREFIX_PATH = os.pathsep.join(CMAKE_PREFIX_PATH)
+
+        environ = dict(os.environ)
+        lines = []
+        if not args.extend:
+            lines += rollback_env_variables(environ, ENV_VAR_SUBFOLDERS)
+        lines += prepend_env_variables(environ, ENV_VAR_SUBFOLDERS, CMAKE_PREFIX_PATH)
+        lines += find_env_hooks(environ, CMAKE_PREFIX_PATH)
+        print('\n'.join(lines))
+
+        # need to explicitly flush the output
+        sys.stdout.flush()
+    except IOError as e:
+        # and catch potential "broken pipe" if stdout is not writable
+        # which can happen when piping the output to a file but the disk is full
+        if e.errno == errno.EPIPE:
+            print(e, file=sys.stderr)
+            sys.exit(2)
+        raise
+
+    sys.exit(0)
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/env.sh b/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/env.sh
new file mode 100644
index 0000000000000000000000000000000000000000..8aa9d244ae9475039027a5f25a8d41a46174cddf
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/env.sh
@@ -0,0 +1,16 @@
+#!/usr/bin/env sh
+# generated from catkin/cmake/templates/env.sh.in
+
+if [ $# -eq 0 ] ; then
+  /bin/echo "Usage: env.sh COMMANDS"
+  /bin/echo "Calling env.sh without arguments is not supported anymore. Instead spawn a subshell and source a setup file manually."
+  exit 1
+fi
+
+# ensure to not use different shell type which was set before
+CATKIN_SHELL=sh
+
+# source setup.sh from same directory as this file
+_CATKIN_SETUP_DIR=$(cd "`dirname "$0"`" > /dev/null && pwd)
+. "$_CATKIN_SETUP_DIR/setup.sh"
+exec "$@"
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/local_setup.bash b/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/local_setup.bash
new file mode 100644
index 0000000000000000000000000000000000000000..7da0d973d481c97d4aba63ab3a070fdc192dc3f8
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/local_setup.bash
@@ -0,0 +1,8 @@
+#!/usr/bin/env bash
+# generated from catkin/cmake/templates/local_setup.bash.in
+
+CATKIN_SHELL=bash
+
+# source setup.sh from same directory as this file
+_CATKIN_SETUP_DIR=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null && pwd)
+. "$_CATKIN_SETUP_DIR/setup.sh" --extend --local
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/local_setup.sh b/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/local_setup.sh
new file mode 100644
index 0000000000000000000000000000000000000000..644075365eab616dfdd29c936fd19e6837aeadfd
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/local_setup.sh
@@ -0,0 +1,9 @@
+#!/usr/bin/env sh
+# generated from catkin/cmake/template/local_setup.sh.in
+
+# since this file is sourced either use the provided _CATKIN_SETUP_DIR
+# or fall back to the destination set at configure time
+: ${_CATKIN_SETUP_DIR:=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel}
+CATKIN_SETUP_UTIL_ARGS="--extend --local"
+. "$_CATKIN_SETUP_DIR/setup.sh"
+unset CATKIN_SETUP_UTIL_ARGS
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/local_setup.zsh b/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/local_setup.zsh
new file mode 100644
index 0000000000000000000000000000000000000000..e692accfd3341ef2f575dec1c83d843bd786107f
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/local_setup.zsh
@@ -0,0 +1,8 @@
+#!/usr/bin/env zsh
+# generated from catkin/cmake/templates/local_setup.zsh.in
+
+CATKIN_SHELL=zsh
+
+# source setup.sh from same directory as this file
+_CATKIN_SETUP_DIR=$(builtin cd -q "`dirname "$0"`" > /dev/null && pwd)
+emulate -R zsh -c 'source "$_CATKIN_SETUP_DIR/setup.sh" --extend --local'
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/setup.bash b/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/setup.bash
new file mode 100644
index 0000000000000000000000000000000000000000..ff47af8f30bcc54efd5892530c84c4159250d4a3
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/setup.bash
@@ -0,0 +1,8 @@
+#!/usr/bin/env bash
+# generated from catkin/cmake/templates/setup.bash.in
+
+CATKIN_SHELL=bash
+
+# source setup.sh from same directory as this file
+_CATKIN_SETUP_DIR=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null && pwd)
+. "$_CATKIN_SETUP_DIR/setup.sh"
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/setup.sh b/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/setup.sh
new file mode 100644
index 0000000000000000000000000000000000000000..56b4712095b16c26f031ad40842535a7f2d49b50
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/setup.sh
@@ -0,0 +1,96 @@
+#!/usr/bin/env sh
+# generated from catkin/cmake/template/setup.sh.in
+
+# Sets various environment variables and sources additional environment hooks.
+# It tries it's best to undo changes from a previously sourced setup file before.
+# Supported command line options:
+# --extend: skips the undoing of changes from a previously sourced setup file
+# --local: only considers this workspace but not the chained ones
+# In plain sh shell which doesn't support arguments for sourced scripts you can
+# set the environment variable `CATKIN_SETUP_UTIL_ARGS=--extend/--local` instead.
+
+# since this file is sourced either use the provided _CATKIN_SETUP_DIR
+# or fall back to the destination set at configure time
+: ${_CATKIN_SETUP_DIR:=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel}
+_SETUP_UTIL="$_CATKIN_SETUP_DIR/_setup_util.py"
+unset _CATKIN_SETUP_DIR
+
+if [ ! -f "$_SETUP_UTIL" ]; then
+  echo "Missing Python script: $_SETUP_UTIL"
+  return 22
+fi
+
+# detect if running on Darwin platform
+_UNAME=`uname -s`
+_IS_DARWIN=0
+if [ "$_UNAME" = "Darwin" ]; then
+  _IS_DARWIN=1
+fi
+unset _UNAME
+
+# make sure to export all environment variables
+export CMAKE_PREFIX_PATH
+if [ $_IS_DARWIN -eq 0 ]; then
+  export LD_LIBRARY_PATH
+else
+  export DYLD_LIBRARY_PATH
+fi
+unset _IS_DARWIN
+export PATH
+export PKG_CONFIG_PATH
+export PYTHONPATH
+
+# remember type of shell if not already set
+if [ -z "$CATKIN_SHELL" ]; then
+  CATKIN_SHELL=sh
+fi
+
+# invoke Python script to generate necessary exports of environment variables
+# use TMPDIR if it exists, otherwise fall back to /tmp
+if [ -d "${TMPDIR:-}" ]; then
+  _TMPDIR="${TMPDIR}"
+else
+  _TMPDIR=/tmp
+fi
+_SETUP_TMP=`mktemp "${_TMPDIR}/setup.sh.XXXXXXXXXX"`
+unset _TMPDIR
+if [ $? -ne 0 -o ! -f "$_SETUP_TMP" ]; then
+  echo "Could not create temporary file: $_SETUP_TMP"
+  return 1
+fi
+CATKIN_SHELL=$CATKIN_SHELL "$_SETUP_UTIL" $@ ${CATKIN_SETUP_UTIL_ARGS:-} >> "$_SETUP_TMP"
+_RC=$?
+if [ $_RC -ne 0 ]; then
+  if [ $_RC -eq 2 ]; then
+    echo "Could not write the output of '$_SETUP_UTIL' to temporary file '$_SETUP_TMP': may be the disk if full?"
+  else
+    echo "Failed to run '\"$_SETUP_UTIL\" $@': return code $_RC"
+  fi
+  unset _RC
+  unset _SETUP_UTIL
+  rm -f "$_SETUP_TMP"
+  unset _SETUP_TMP
+  return 1
+fi
+unset _RC
+unset _SETUP_UTIL
+. "$_SETUP_TMP"
+rm -f "$_SETUP_TMP"
+unset _SETUP_TMP
+
+# source all environment hooks
+_i=0
+while [ $_i -lt $_CATKIN_ENVIRONMENT_HOOKS_COUNT ]; do
+  eval _envfile=\$_CATKIN_ENVIRONMENT_HOOKS_$_i
+  unset _CATKIN_ENVIRONMENT_HOOKS_$_i
+  eval _envfile_workspace=\$_CATKIN_ENVIRONMENT_HOOKS_${_i}_WORKSPACE
+  unset _CATKIN_ENVIRONMENT_HOOKS_${_i}_WORKSPACE
+  # set workspace for environment hook
+  CATKIN_ENV_HOOK_WORKSPACE=$_envfile_workspace
+  . "$_envfile"
+  unset CATKIN_ENV_HOOK_WORKSPACE
+  _i=$((_i + 1))
+done
+unset _i
+
+unset _CATKIN_ENVIRONMENT_HOOKS_COUNT
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/setup.zsh b/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/setup.zsh
new file mode 100644
index 0000000000000000000000000000000000000000..9f780b741031d8037b90514441a80f9fed39d02b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/atomic_configure/setup.zsh
@@ -0,0 +1,8 @@
+#!/usr/bin/env zsh
+# generated from catkin/cmake/templates/setup.zsh.in
+
+CATKIN_SHELL=zsh
+
+# source setup.sh from same directory as this file
+_CATKIN_SETUP_DIR=$(builtin cd -q "`dirname "$0"`" > /dev/null && pwd)
+emulate -R zsh -c 'source "$_CATKIN_SETUP_DIR/setup.sh"'
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin/catkin_generated/version/package.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/catkin/catkin_generated/version/package.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..c37e28756c61fb9711966eb99be84d269c33f9be
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin/catkin_generated/version/package.cmake
@@ -0,0 +1,24 @@
+set(_CATKIN_CURRENT_PACKAGE "catkin")
+set(catkin_VERSION "0.8.10")
+set(catkin_MAINTAINER "Michael Carroll <michael@openrobotics.org>, Tully Foote <tfoote@openrobotics.org>")
+set(catkin_PACKAGE_FORMAT "3")
+set(catkin_BUILD_DEPENDS "python-argparse" "python-catkin-pkg" "python3-catkin-pkg" "python-empy" "python3-empy")
+set(catkin_BUILD_DEPENDS_python-catkin-pkg_VERSION_GT "0.4.3")
+set(catkin_BUILD_DEPENDS_python3-catkin-pkg_VERSION_GT "0.4.3")
+set(catkin_BUILD_EXPORT_DEPENDS "google-mock" "gtest" "python-nose" "python3-nose" "python-argparse" "python-catkin-pkg" "python3-catkin-pkg" "python-empy" "python3-empy")
+set(catkin_BUILD_EXPORT_DEPENDS_python-catkin-pkg_VERSION_GT "0.4.3")
+set(catkin_BUILD_EXPORT_DEPENDS_python3-catkin-pkg_VERSION_GT "0.4.3")
+set(catkin_BUILDTOOL_DEPENDS "cmake" "python-setuptools" "python3-setuptools")
+set(catkin_BUILDTOOL_EXPORT_DEPENDS "cmake" "python3-setuptools")
+set(catkin_EXEC_DEPENDS "python-argparse" "python-catkin-pkg" "python3-catkin-pkg" "python-empy" "python3-empy")
+set(catkin_EXEC_DEPENDS_python-catkin-pkg_VERSION_GT "0.4.3")
+set(catkin_EXEC_DEPENDS_python3-catkin-pkg_VERSION_GT "0.4.3")
+set(catkin_RUN_DEPENDS "python-argparse" "python-catkin-pkg" "python3-catkin-pkg" "python-empy" "python3-empy" "google-mock" "gtest" "python-nose" "python3-nose")
+set(catkin_RUN_DEPENDS_python-catkin-pkg_VERSION_GT "0.4.3")
+set(catkin_RUN_DEPENDS_python3-catkin-pkg_VERSION_GT "0.4.3")
+set(catkin_TEST_DEPENDS "python-mock" "python3-mock" "python-nose" "python3-nose")
+set(catkin_DOC_DEPENDS )
+set(catkin_URL_WEBSITE "http://wiki.ros.org/catkin")
+set(catkin_URL_BUGTRACKER "https://github.com/ros/catkin/issues")
+set(catkin_URL_REPOSITORY "https://github.com/ros/catkin")
+set(catkin_DEPRECATED "")
\ No newline at end of file
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/env_cached.sh b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/env_cached.sh
new file mode 100644
index 0000000000000000000000000000000000000000..d6be91db5c97c428f17b165713d3f9a077c78786
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/env_cached.sh
@@ -0,0 +1,16 @@
+#!/usr/bin/env sh
+# generated from catkin/cmake/templates/env.sh.in
+
+if [ $# -eq 0 ] ; then
+  /bin/echo "Usage: env.sh COMMANDS"
+  /bin/echo "Calling env.sh without arguments is not supported anymore. Instead spawn a subshell and source a setup file manually."
+  exit 1
+fi
+
+# ensure to not use different shell type which was set before
+CATKIN_SHELL=sh
+
+# source setup_cached.sh from same directory as this file
+_CATKIN_SETUP_DIR=$(cd "`dirname "$0"`" > /dev/null && pwd)
+. "$_CATKIN_SETUP_DIR/setup_cached.sh"
+exec "$@"
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/generate_cached_setup.py b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/generate_cached_setup.py
new file mode 100644
index 0000000000000000000000000000000000000000..a46206f0aef76b47988ca600a88753625e2e41bd
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/generate_cached_setup.py
@@ -0,0 +1,30 @@
+# -*- coding: utf-8 -*-
+from __future__ import print_function
+
+import os
+import stat
+import sys
+
+# find the import for catkin's python package - either from source space or from an installed underlay
+if os.path.exists(os.path.join('/opt/ros/noetic/share/catkin/cmake', 'catkinConfig.cmake.in')):
+    sys.path.insert(0, os.path.join('/opt/ros/noetic/share/catkin/cmake', '..', 'python'))
+try:
+    from catkin.environment_cache import generate_environment_script
+except ImportError:
+    # search for catkin package in all workspaces and prepend to path
+    for workspace in '/home/simhe502/catkin_ws/devel;/opt/ros/noetic'.split(';'):
+        python_path = os.path.join(workspace, 'lib/python3/dist-packages')
+        if os.path.isdir(os.path.join(python_path, 'catkin')):
+            sys.path.insert(0, python_path)
+            break
+    from catkin.environment_cache import generate_environment_script
+
+code = generate_environment_script('/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/env.sh')
+
+output_filename = '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/setup_cached.sh'
+with open(output_filename, 'w') as f:
+    # print('Generate script for cached setup "%s"' % output_filename)
+    f.write('\n'.join(code))
+
+mode = os.stat(output_filename).st_mode
+os.chmod(output_filename, mode | stat.S_IXUSR)
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/.rosinstall b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/.rosinstall
new file mode 100644
index 0000000000000000000000000000000000000000..6fb13afde30c0c58db22d5c1c2c468bc35158da8
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/.rosinstall
@@ -0,0 +1,2 @@
+- setup-file:
+    local-name: /usr/local/setup.sh
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/_setup_util.py b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/_setup_util.py
new file mode 100644
index 0000000000000000000000000000000000000000..cb721f76776998339077c845951ad674ed972969
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/_setup_util.py
@@ -0,0 +1,304 @@
+#!/usr/bin/python3
+# -*- coding: utf-8 -*-
+
+# Software License Agreement (BSD License)
+#
+# Copyright (c) 2012, Willow Garage, Inc.
+# All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+#  * Redistributions of source code must retain the above copyright
+#    notice, this list of conditions and the following disclaimer.
+#  * Redistributions in binary form must reproduce the above
+#    copyright notice, this list of conditions and the following
+#    disclaimer in the documentation and/or other materials provided
+#    with the distribution.
+#  * Neither the name of Willow Garage, Inc. nor the names of its
+#    contributors may be used to endorse or promote products derived
+#    from this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+
+"""This file generates shell code for the setup.SHELL scripts to set environment variables."""
+
+from __future__ import print_function
+
+import argparse
+import copy
+import errno
+import os
+import platform
+import sys
+
+CATKIN_MARKER_FILE = '.catkin'
+
+system = platform.system()
+IS_DARWIN = (system == 'Darwin')
+IS_WINDOWS = (system == 'Windows')
+
+PATH_TO_ADD_SUFFIX = ['bin']
+if IS_WINDOWS:
+    # while catkin recommends putting dll's into bin, 3rd party packages often put dll's into lib
+    # since Windows finds dll's via the PATH variable, prepend it with path to lib
+    PATH_TO_ADD_SUFFIX.extend([['lib', os.path.join('lib', 'x86_64-linux-gnu')]])
+
+# subfolder of workspace prepended to CMAKE_PREFIX_PATH
+ENV_VAR_SUBFOLDERS = {
+    'CMAKE_PREFIX_PATH': '',
+    'LD_LIBRARY_PATH' if not IS_DARWIN else 'DYLD_LIBRARY_PATH': ['lib', os.path.join('lib', 'x86_64-linux-gnu')],
+    'PATH': PATH_TO_ADD_SUFFIX,
+    'PKG_CONFIG_PATH': [os.path.join('lib', 'pkgconfig'), os.path.join('lib', 'x86_64-linux-gnu', 'pkgconfig')],
+    'PYTHONPATH': 'lib/python3/dist-packages',
+}
+
+
+def rollback_env_variables(environ, env_var_subfolders):
+    """
+    Generate shell code to reset environment variables.
+
+    by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH.
+    This does not cover modifications performed by environment hooks.
+    """
+    lines = []
+    unmodified_environ = copy.copy(environ)
+    for key in sorted(env_var_subfolders.keys()):
+        subfolders = env_var_subfolders[key]
+        if not isinstance(subfolders, list):
+            subfolders = [subfolders]
+        value = _rollback_env_variable(unmodified_environ, key, subfolders)
+        if value is not None:
+            environ[key] = value
+            lines.append(assignment(key, value))
+    if lines:
+        lines.insert(0, comment('reset environment variables by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH'))
+    return lines
+
+
+def _rollback_env_variable(environ, name, subfolders):
+    """
+    For each catkin workspace in CMAKE_PREFIX_PATH remove the first entry from env[NAME] matching workspace + subfolder.
+
+    :param subfolders: list of str '' or subfoldername that may start with '/'
+    :returns: the updated value of the environment variable.
+    """
+    value = environ[name] if name in environ else ''
+    env_paths = [path for path in value.split(os.pathsep) if path]
+    value_modified = False
+    for subfolder in subfolders:
+        if subfolder:
+            if subfolder.startswith(os.path.sep) or (os.path.altsep and subfolder.startswith(os.path.altsep)):
+                subfolder = subfolder[1:]
+            if subfolder.endswith(os.path.sep) or (os.path.altsep and subfolder.endswith(os.path.altsep)):
+                subfolder = subfolder[:-1]
+        for ws_path in _get_workspaces(environ, include_fuerte=True, include_non_existing=True):
+            path_to_find = os.path.join(ws_path, subfolder) if subfolder else ws_path
+            path_to_remove = None
+            for env_path in env_paths:
+                env_path_clean = env_path[:-1] if env_path and env_path[-1] in [os.path.sep, os.path.altsep] else env_path
+                if env_path_clean == path_to_find:
+                    path_to_remove = env_path
+                    break
+            if path_to_remove:
+                env_paths.remove(path_to_remove)
+                value_modified = True
+    new_value = os.pathsep.join(env_paths)
+    return new_value if value_modified else None
+
+
+def _get_workspaces(environ, include_fuerte=False, include_non_existing=False):
+    """
+    Based on CMAKE_PREFIX_PATH return all catkin workspaces.
+
+    :param include_fuerte: The flag if paths starting with '/opt/ros/fuerte' should be considered workspaces, ``bool``
+    """
+    # get all cmake prefix paths
+    env_name = 'CMAKE_PREFIX_PATH'
+    value = environ[env_name] if env_name in environ else ''
+    paths = [path for path in value.split(os.pathsep) if path]
+    # remove non-workspace paths
+    workspaces = [path for path in paths if os.path.isfile(os.path.join(path, CATKIN_MARKER_FILE)) or (include_fuerte and path.startswith('/opt/ros/fuerte')) or (include_non_existing and not os.path.exists(path))]
+    return workspaces
+
+
+def prepend_env_variables(environ, env_var_subfolders, workspaces):
+    """Generate shell code to prepend environment variables for the all workspaces."""
+    lines = []
+    lines.append(comment('prepend folders of workspaces to environment variables'))
+
+    paths = [path for path in workspaces.split(os.pathsep) if path]
+
+    prefix = _prefix_env_variable(environ, 'CMAKE_PREFIX_PATH', paths, '')
+    lines.append(prepend(environ, 'CMAKE_PREFIX_PATH', prefix))
+
+    for key in sorted(key for key in env_var_subfolders.keys() if key != 'CMAKE_PREFIX_PATH'):
+        subfolder = env_var_subfolders[key]
+        prefix = _prefix_env_variable(environ, key, paths, subfolder)
+        lines.append(prepend(environ, key, prefix))
+    return lines
+
+
+def _prefix_env_variable(environ, name, paths, subfolders):
+    """
+    Return the prefix to prepend to the environment variable NAME.
+
+    Adding any path in NEW_PATHS_STR without creating duplicate or empty items.
+    """
+    value = environ[name] if name in environ else ''
+    environ_paths = [path for path in value.split(os.pathsep) if path]
+    checked_paths = []
+    for path in paths:
+        if not isinstance(subfolders, list):
+            subfolders = [subfolders]
+        for subfolder in subfolders:
+            path_tmp = path
+            if subfolder:
+                path_tmp = os.path.join(path_tmp, subfolder)
+            # skip nonexistent paths
+            if not os.path.exists(path_tmp):
+                continue
+            # exclude any path already in env and any path we already added
+            if path_tmp not in environ_paths and path_tmp not in checked_paths:
+                checked_paths.append(path_tmp)
+    prefix_str = os.pathsep.join(checked_paths)
+    if prefix_str != '' and environ_paths:
+        prefix_str += os.pathsep
+    return prefix_str
+
+
+def assignment(key, value):
+    if not IS_WINDOWS:
+        return 'export %s="%s"' % (key, value)
+    else:
+        return 'set %s=%s' % (key, value)
+
+
+def comment(msg):
+    if not IS_WINDOWS:
+        return '# %s' % msg
+    else:
+        return 'REM %s' % msg
+
+
+def prepend(environ, key, prefix):
+    if key not in environ or not environ[key]:
+        return assignment(key, prefix)
+    if not IS_WINDOWS:
+        return 'export %s="%s$%s"' % (key, prefix, key)
+    else:
+        return 'set %s=%s%%%s%%' % (key, prefix, key)
+
+
+def find_env_hooks(environ, cmake_prefix_path):
+    """Generate shell code with found environment hooks for the all workspaces."""
+    lines = []
+    lines.append(comment('found environment hooks in workspaces'))
+
+    generic_env_hooks = []
+    generic_env_hooks_workspace = []
+    specific_env_hooks = []
+    specific_env_hooks_workspace = []
+    generic_env_hooks_by_filename = {}
+    specific_env_hooks_by_filename = {}
+    generic_env_hook_ext = 'bat' if IS_WINDOWS else 'sh'
+    specific_env_hook_ext = environ['CATKIN_SHELL'] if not IS_WINDOWS and 'CATKIN_SHELL' in environ and environ['CATKIN_SHELL'] else None
+    # remove non-workspace paths
+    workspaces = [path for path in cmake_prefix_path.split(os.pathsep) if path and os.path.isfile(os.path.join(path, CATKIN_MARKER_FILE))]
+    for workspace in reversed(workspaces):
+        env_hook_dir = os.path.join(workspace, 'etc', 'catkin', 'profile.d')
+        if os.path.isdir(env_hook_dir):
+            for filename in sorted(os.listdir(env_hook_dir)):
+                if filename.endswith('.%s' % generic_env_hook_ext):
+                    # remove previous env hook with same name if present
+                    if filename in generic_env_hooks_by_filename:
+                        i = generic_env_hooks.index(generic_env_hooks_by_filename[filename])
+                        generic_env_hooks.pop(i)
+                        generic_env_hooks_workspace.pop(i)
+                    # append env hook
+                    generic_env_hooks.append(os.path.join(env_hook_dir, filename))
+                    generic_env_hooks_workspace.append(workspace)
+                    generic_env_hooks_by_filename[filename] = generic_env_hooks[-1]
+                elif specific_env_hook_ext is not None and filename.endswith('.%s' % specific_env_hook_ext):
+                    # remove previous env hook with same name if present
+                    if filename in specific_env_hooks_by_filename:
+                        i = specific_env_hooks.index(specific_env_hooks_by_filename[filename])
+                        specific_env_hooks.pop(i)
+                        specific_env_hooks_workspace.pop(i)
+                    # append env hook
+                    specific_env_hooks.append(os.path.join(env_hook_dir, filename))
+                    specific_env_hooks_workspace.append(workspace)
+                    specific_env_hooks_by_filename[filename] = specific_env_hooks[-1]
+    env_hooks = generic_env_hooks + specific_env_hooks
+    env_hooks_workspace = generic_env_hooks_workspace + specific_env_hooks_workspace
+    count = len(env_hooks)
+    lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_COUNT', count))
+    for i in range(count):
+        lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d' % i, env_hooks[i]))
+        lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d_WORKSPACE' % i, env_hooks_workspace[i]))
+    return lines
+
+
+def _parse_arguments(args=None):
+    parser = argparse.ArgumentParser(description='Generates code blocks for the setup.SHELL script.')
+    parser.add_argument('--extend', action='store_true', help='Skip unsetting previous environment variables to extend context')
+    parser.add_argument('--local', action='store_true', help='Only consider this prefix path and ignore other prefix path in the environment')
+    return parser.parse_known_args(args=args)[0]
+
+
+if __name__ == '__main__':
+    try:
+        try:
+            args = _parse_arguments()
+        except Exception as e:
+            print(e, file=sys.stderr)
+            sys.exit(1)
+
+        if not args.local:
+            # environment at generation time
+            CMAKE_PREFIX_PATH = r'/home/simhe502/catkin_ws/devel;/opt/ros/noetic'.split(';')
+        else:
+            # don't consider any other prefix path than this one
+            CMAKE_PREFIX_PATH = []
+        # prepend current workspace if not already part of CPP
+        base_path = os.path.dirname(__file__)
+        # CMAKE_PREFIX_PATH uses forward slash on all platforms, but __file__ is platform dependent
+        # base_path on Windows contains backward slashes, need to be converted to forward slashes before comparison
+        if os.path.sep != '/':
+            base_path = base_path.replace(os.path.sep, '/')
+
+        if base_path not in CMAKE_PREFIX_PATH:
+            CMAKE_PREFIX_PATH.insert(0, base_path)
+        CMAKE_PREFIX_PATH = os.pathsep.join(CMAKE_PREFIX_PATH)
+
+        environ = dict(os.environ)
+        lines = []
+        if not args.extend:
+            lines += rollback_env_variables(environ, ENV_VAR_SUBFOLDERS)
+        lines += prepend_env_variables(environ, ENV_VAR_SUBFOLDERS, CMAKE_PREFIX_PATH)
+        lines += find_env_hooks(environ, CMAKE_PREFIX_PATH)
+        print('\n'.join(lines))
+
+        # need to explicitly flush the output
+        sys.stdout.flush()
+    except IOError as e:
+        # and catch potential "broken pipe" if stdout is not writable
+        # which can happen when piping the output to a file but the disk is full
+        if e.errno == errno.EPIPE:
+            print(e, file=sys.stderr)
+            sys.exit(2)
+        raise
+
+    sys.exit(0)
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/env.sh b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/env.sh
new file mode 100644
index 0000000000000000000000000000000000000000..8aa9d244ae9475039027a5f25a8d41a46174cddf
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/env.sh
@@ -0,0 +1,16 @@
+#!/usr/bin/env sh
+# generated from catkin/cmake/templates/env.sh.in
+
+if [ $# -eq 0 ] ; then
+  /bin/echo "Usage: env.sh COMMANDS"
+  /bin/echo "Calling env.sh without arguments is not supported anymore. Instead spawn a subshell and source a setup file manually."
+  exit 1
+fi
+
+# ensure to not use different shell type which was set before
+CATKIN_SHELL=sh
+
+# source setup.sh from same directory as this file
+_CATKIN_SETUP_DIR=$(cd "`dirname "$0"`" > /dev/null && pwd)
+. "$_CATKIN_SETUP_DIR/setup.sh"
+exec "$@"
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/local_setup.bash b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/local_setup.bash
new file mode 100644
index 0000000000000000000000000000000000000000..7da0d973d481c97d4aba63ab3a070fdc192dc3f8
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/local_setup.bash
@@ -0,0 +1,8 @@
+#!/usr/bin/env bash
+# generated from catkin/cmake/templates/local_setup.bash.in
+
+CATKIN_SHELL=bash
+
+# source setup.sh from same directory as this file
+_CATKIN_SETUP_DIR=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null && pwd)
+. "$_CATKIN_SETUP_DIR/setup.sh" --extend --local
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/local_setup.sh b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/local_setup.sh
new file mode 100644
index 0000000000000000000000000000000000000000..f0210983067ffe62a2a191f4d3931ca1b4d9aa7a
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/local_setup.sh
@@ -0,0 +1,9 @@
+#!/usr/bin/env sh
+# generated from catkin/cmake/template/local_setup.sh.in
+
+# since this file is sourced either use the provided _CATKIN_SETUP_DIR
+# or fall back to the destination set at configure time
+: ${_CATKIN_SETUP_DIR:=/usr/local}
+CATKIN_SETUP_UTIL_ARGS="--extend --local"
+. "$_CATKIN_SETUP_DIR/setup.sh"
+unset CATKIN_SETUP_UTIL_ARGS
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/local_setup.zsh b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/local_setup.zsh
new file mode 100644
index 0000000000000000000000000000000000000000..e692accfd3341ef2f575dec1c83d843bd786107f
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/local_setup.zsh
@@ -0,0 +1,8 @@
+#!/usr/bin/env zsh
+# generated from catkin/cmake/templates/local_setup.zsh.in
+
+CATKIN_SHELL=zsh
+
+# source setup.sh from same directory as this file
+_CATKIN_SETUP_DIR=$(builtin cd -q "`dirname "$0"`" > /dev/null && pwd)
+emulate -R zsh -c 'source "$_CATKIN_SETUP_DIR/setup.sh" --extend --local'
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/mav_nonlinear_mpc.pc b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/mav_nonlinear_mpc.pc
new file mode 100644
index 0000000000000000000000000000000000000000..62867ae366798a77d99cbafe66297a3df7ed353d
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/mav_nonlinear_mpc.pc
@@ -0,0 +1,8 @@
+prefix=/usr/local
+
+Name: mav_nonlinear_mpc
+Description: Description of mav_nonlinear_mpc
+Version: 1.0.0
+Cflags: -I${prefix}/include
+Libs: -L${prefix}/lib -lmav_nonlinear_mpc_lib
+Requires: std_msgs cmake_modules roscpp dynamic_reconfigure tf
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/mav_nonlinear_mpcConfig-version.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/mav_nonlinear_mpcConfig-version.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..de35aa22a9bd546ca9e0b4e63357adc254d83544
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/mav_nonlinear_mpcConfig-version.cmake
@@ -0,0 +1,14 @@
+# generated from catkin/cmake/template/pkgConfig-version.cmake.in
+set(PACKAGE_VERSION "1.0.0")
+
+set(PACKAGE_VERSION_EXACT False)
+set(PACKAGE_VERSION_COMPATIBLE False)
+
+if("${PACKAGE_FIND_VERSION}" VERSION_EQUAL "${PACKAGE_VERSION}")
+  set(PACKAGE_VERSION_EXACT True)
+  set(PACKAGE_VERSION_COMPATIBLE True)
+endif()
+
+if("${PACKAGE_FIND_VERSION}" VERSION_LESS "${PACKAGE_VERSION}")
+  set(PACKAGE_VERSION_COMPATIBLE True)
+endif()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/mav_nonlinear_mpcConfig.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/mav_nonlinear_mpcConfig.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..a8675b9a5fb9054b076fc6b7c88dc49adc96016a
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/mav_nonlinear_mpcConfig.cmake
@@ -0,0 +1,223 @@
+# generated from catkin/cmake/template/pkgConfig.cmake.in
+
+# append elements to a list and remove existing duplicates from the list
+# copied from catkin/cmake/list_append_deduplicate.cmake to keep pkgConfig
+# self contained
+macro(_list_append_deduplicate listname)
+  if(NOT "${ARGN}" STREQUAL "")
+    if(${listname})
+      list(REMOVE_ITEM ${listname} ${ARGN})
+    endif()
+    list(APPEND ${listname} ${ARGN})
+  endif()
+endmacro()
+
+# append elements to a list if they are not already in the list
+# copied from catkin/cmake/list_append_unique.cmake to keep pkgConfig
+# self contained
+macro(_list_append_unique listname)
+  foreach(_item ${ARGN})
+    list(FIND ${listname} ${_item} _index)
+    if(_index EQUAL -1)
+      list(APPEND ${listname} ${_item})
+    endif()
+  endforeach()
+endmacro()
+
+# pack a list of libraries with optional build configuration keywords
+# copied from catkin/cmake/catkin_libraries.cmake to keep pkgConfig
+# self contained
+macro(_pack_libraries_with_build_configuration VAR)
+  set(${VAR} "")
+  set(_argn ${ARGN})
+  list(LENGTH _argn _count)
+  set(_index 0)
+  while(${_index} LESS ${_count})
+    list(GET _argn ${_index} lib)
+    if("${lib}" MATCHES "^(debug|optimized|general)$")
+      math(EXPR _index "${_index} + 1")
+      if(${_index} EQUAL ${_count})
+        message(FATAL_ERROR "_pack_libraries_with_build_configuration() the list of libraries '${ARGN}' ends with '${lib}' which is a build configuration keyword and must be followed by a library")
+      endif()
+      list(GET _argn ${_index} library)
+      list(APPEND ${VAR} "${lib}${CATKIN_BUILD_CONFIGURATION_KEYWORD_SEPARATOR}${library}")
+    else()
+      list(APPEND ${VAR} "${lib}")
+    endif()
+    math(EXPR _index "${_index} + 1")
+  endwhile()
+endmacro()
+
+# unpack a list of libraries with optional build configuration keyword prefixes
+# copied from catkin/cmake/catkin_libraries.cmake to keep pkgConfig
+# self contained
+macro(_unpack_libraries_with_build_configuration VAR)
+  set(${VAR} "")
+  foreach(lib ${ARGN})
+    string(REGEX REPLACE "^(debug|optimized|general)${CATKIN_BUILD_CONFIGURATION_KEYWORD_SEPARATOR}(.+)$" "\\1;\\2" lib "${lib}")
+    list(APPEND ${VAR} "${lib}")
+  endforeach()
+endmacro()
+
+
+if(mav_nonlinear_mpc_CONFIG_INCLUDED)
+  return()
+endif()
+set(mav_nonlinear_mpc_CONFIG_INCLUDED TRUE)
+
+# set variables for source/devel/install prefixes
+if("FALSE" STREQUAL "TRUE")
+  set(mav_nonlinear_mpc_SOURCE_PREFIX /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc)
+  set(mav_nonlinear_mpc_DEVEL_PREFIX /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel)
+  set(mav_nonlinear_mpc_INSTALL_PREFIX "")
+  set(mav_nonlinear_mpc_PREFIX ${mav_nonlinear_mpc_DEVEL_PREFIX})
+else()
+  set(mav_nonlinear_mpc_SOURCE_PREFIX "")
+  set(mav_nonlinear_mpc_DEVEL_PREFIX "")
+  set(mav_nonlinear_mpc_INSTALL_PREFIX /usr/local)
+  set(mav_nonlinear_mpc_PREFIX ${mav_nonlinear_mpc_INSTALL_PREFIX})
+endif()
+
+# warn when using a deprecated package
+if(NOT "" STREQUAL "")
+  set(_msg "WARNING: package 'mav_nonlinear_mpc' is deprecated")
+  # append custom deprecation text if available
+  if(NOT "" STREQUAL "TRUE")
+    set(_msg "${_msg} ()")
+  endif()
+  message("${_msg}")
+endif()
+
+# flag project as catkin-based to distinguish if a find_package()-ed project is a catkin project
+set(mav_nonlinear_mpc_FOUND_CATKIN_PROJECT TRUE)
+
+if(NOT "include " STREQUAL " ")
+  set(mav_nonlinear_mpc_INCLUDE_DIRS "")
+  set(_include_dirs "include")
+  if(NOT " " STREQUAL " ")
+    set(_report "Check the issue tracker '' and consider creating a ticket if the problem has not been reported yet.")
+  elseif(NOT " " STREQUAL " ")
+    set(_report "Check the website '' for information and consider reporting the problem.")
+  else()
+    set(_report "Report the problem to the maintainer 'Mina Kamel <mina.kamel@mavt.ethz.com>' and request to fix the problem.")
+  endif()
+  foreach(idir ${_include_dirs})
+    if(IS_ABSOLUTE ${idir} AND IS_DIRECTORY ${idir})
+      set(include ${idir})
+    elseif("${idir} " STREQUAL "include ")
+      get_filename_component(include "${mav_nonlinear_mpc_DIR}/../../../include" ABSOLUTE)
+      if(NOT IS_DIRECTORY ${include})
+        message(FATAL_ERROR "Project 'mav_nonlinear_mpc' specifies '${idir}' as an include dir, which is not found.  It does not exist in '${include}'.  ${_report}")
+      endif()
+    else()
+      message(FATAL_ERROR "Project 'mav_nonlinear_mpc' specifies '${idir}' as an include dir, which is not found.  It does neither exist as an absolute directory nor in '\${prefix}/${idir}'.  ${_report}")
+    endif()
+    _list_append_unique(mav_nonlinear_mpc_INCLUDE_DIRS ${include})
+  endforeach()
+endif()
+
+set(libraries "mav_nonlinear_mpc_lib")
+foreach(library ${libraries})
+  # keep build configuration keywords, target names and absolute libraries as-is
+  if("${library}" MATCHES "^(debug|optimized|general)$")
+    list(APPEND mav_nonlinear_mpc_LIBRARIES ${library})
+  elseif(${library} MATCHES "^-l")
+    list(APPEND mav_nonlinear_mpc_LIBRARIES ${library})
+  elseif(${library} MATCHES "^-")
+    # This is a linker flag/option (like -pthread)
+    # There's no standard variable for these, so create an interface library to hold it
+    if(NOT mav_nonlinear_mpc_NUM_DUMMY_TARGETS)
+      set(mav_nonlinear_mpc_NUM_DUMMY_TARGETS 0)
+    endif()
+    # Make sure the target name is unique
+    set(interface_target_name "catkin::mav_nonlinear_mpc::wrapped-linker-option${mav_nonlinear_mpc_NUM_DUMMY_TARGETS}")
+    while(TARGET "${interface_target_name}")
+      math(EXPR mav_nonlinear_mpc_NUM_DUMMY_TARGETS "${mav_nonlinear_mpc_NUM_DUMMY_TARGETS}+1")
+      set(interface_target_name "catkin::mav_nonlinear_mpc::wrapped-linker-option${mav_nonlinear_mpc_NUM_DUMMY_TARGETS}")
+    endwhile()
+    add_library("${interface_target_name}" INTERFACE IMPORTED)
+    if("${CMAKE_VERSION}" VERSION_LESS "3.13.0")
+      set_property(
+        TARGET
+        "${interface_target_name}"
+        APPEND PROPERTY
+        INTERFACE_LINK_LIBRARIES "${library}")
+    else()
+      target_link_options("${interface_target_name}" INTERFACE "${library}")
+    endif()
+    list(APPEND mav_nonlinear_mpc_LIBRARIES "${interface_target_name}")
+  elseif(TARGET ${library})
+    list(APPEND mav_nonlinear_mpc_LIBRARIES ${library})
+  elseif(IS_ABSOLUTE ${library})
+    list(APPEND mav_nonlinear_mpc_LIBRARIES ${library})
+  else()
+    set(lib_path "")
+    set(lib "${library}-NOTFOUND")
+    # since the path where the library is found is returned we have to iterate over the paths manually
+    foreach(path /usr/local/lib;/home/simhe502/catkin_ws/devel/lib;/opt/ros/noetic/lib)
+      find_library(lib ${library}
+        PATHS ${path}
+        NO_DEFAULT_PATH NO_CMAKE_FIND_ROOT_PATH)
+      if(lib)
+        set(lib_path ${path})
+        break()
+      endif()
+    endforeach()
+    if(lib)
+      _list_append_unique(mav_nonlinear_mpc_LIBRARY_DIRS ${lib_path})
+      list(APPEND mav_nonlinear_mpc_LIBRARIES ${lib})
+    else()
+      # as a fall back for non-catkin libraries try to search globally
+      find_library(lib ${library})
+      if(NOT lib)
+        message(FATAL_ERROR "Project '${PROJECT_NAME}' tried to find library '${library}'.  The library is neither a target nor built/installed properly.  Did you compile project 'mav_nonlinear_mpc'?  Did you find_package() it before the subdirectory containing its code is included?")
+      endif()
+      list(APPEND mav_nonlinear_mpc_LIBRARIES ${lib})
+    endif()
+  endif()
+endforeach()
+
+set(mav_nonlinear_mpc_EXPORTED_TARGETS "mav_nonlinear_mpc_gencfg")
+# create dummy targets for exported code generation targets to make life of users easier
+foreach(t ${mav_nonlinear_mpc_EXPORTED_TARGETS})
+  if(NOT TARGET ${t})
+    add_custom_target(${t})
+  endif()
+endforeach()
+
+set(depends "std_msgs;cmake_modules;roscpp;dynamic_reconfigure;tf")
+foreach(depend ${depends})
+  string(REPLACE " " ";" depend_list ${depend})
+  # the package name of the dependency must be kept in a unique variable so that it is not overwritten in recursive calls
+  list(GET depend_list 0 mav_nonlinear_mpc_dep)
+  list(LENGTH depend_list count)
+  if(${count} EQUAL 1)
+    # simple dependencies must only be find_package()-ed once
+    if(NOT ${mav_nonlinear_mpc_dep}_FOUND)
+      find_package(${mav_nonlinear_mpc_dep} REQUIRED NO_MODULE)
+    endif()
+  else()
+    # dependencies with components must be find_package()-ed again
+    list(REMOVE_AT depend_list 0)
+    find_package(${mav_nonlinear_mpc_dep} REQUIRED NO_MODULE ${depend_list})
+  endif()
+  _list_append_unique(mav_nonlinear_mpc_INCLUDE_DIRS ${${mav_nonlinear_mpc_dep}_INCLUDE_DIRS})
+
+  # merge build configuration keywords with library names to correctly deduplicate
+  _pack_libraries_with_build_configuration(mav_nonlinear_mpc_LIBRARIES ${mav_nonlinear_mpc_LIBRARIES})
+  _pack_libraries_with_build_configuration(_libraries ${${mav_nonlinear_mpc_dep}_LIBRARIES})
+  _list_append_deduplicate(mav_nonlinear_mpc_LIBRARIES ${_libraries})
+  # undo build configuration keyword merging after deduplication
+  _unpack_libraries_with_build_configuration(mav_nonlinear_mpc_LIBRARIES ${mav_nonlinear_mpc_LIBRARIES})
+
+  _list_append_unique(mav_nonlinear_mpc_LIBRARY_DIRS ${${mav_nonlinear_mpc_dep}_LIBRARY_DIRS})
+  _list_append_deduplicate(mav_nonlinear_mpc_EXPORTED_TARGETS ${${mav_nonlinear_mpc_dep}_EXPORTED_TARGETS})
+endforeach()
+
+set(pkg_cfg_extras "")
+foreach(extra ${pkg_cfg_extras})
+  if(NOT IS_ABSOLUTE ${extra})
+    set(extra ${mav_nonlinear_mpc_DIR}/${extra})
+  endif()
+  include(${extra})
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/setup.bash b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/setup.bash
new file mode 100644
index 0000000000000000000000000000000000000000..ff47af8f30bcc54efd5892530c84c4159250d4a3
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/setup.bash
@@ -0,0 +1,8 @@
+#!/usr/bin/env bash
+# generated from catkin/cmake/templates/setup.bash.in
+
+CATKIN_SHELL=bash
+
+# source setup.sh from same directory as this file
+_CATKIN_SETUP_DIR=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null && pwd)
+. "$_CATKIN_SETUP_DIR/setup.sh"
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/setup.sh b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/setup.sh
new file mode 100644
index 0000000000000000000000000000000000000000..b5a330e01f0471057c8e58d73213b86ee0c1c4d1
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/setup.sh
@@ -0,0 +1,96 @@
+#!/usr/bin/env sh
+# generated from catkin/cmake/template/setup.sh.in
+
+# Sets various environment variables and sources additional environment hooks.
+# It tries it's best to undo changes from a previously sourced setup file before.
+# Supported command line options:
+# --extend: skips the undoing of changes from a previously sourced setup file
+# --local: only considers this workspace but not the chained ones
+# In plain sh shell which doesn't support arguments for sourced scripts you can
+# set the environment variable `CATKIN_SETUP_UTIL_ARGS=--extend/--local` instead.
+
+# since this file is sourced either use the provided _CATKIN_SETUP_DIR
+# or fall back to the destination set at configure time
+: ${_CATKIN_SETUP_DIR:=/usr/local}
+_SETUP_UTIL="$_CATKIN_SETUP_DIR/_setup_util.py"
+unset _CATKIN_SETUP_DIR
+
+if [ ! -f "$_SETUP_UTIL" ]; then
+  echo "Missing Python script: $_SETUP_UTIL"
+  return 22
+fi
+
+# detect if running on Darwin platform
+_UNAME=`uname -s`
+_IS_DARWIN=0
+if [ "$_UNAME" = "Darwin" ]; then
+  _IS_DARWIN=1
+fi
+unset _UNAME
+
+# make sure to export all environment variables
+export CMAKE_PREFIX_PATH
+if [ $_IS_DARWIN -eq 0 ]; then
+  export LD_LIBRARY_PATH
+else
+  export DYLD_LIBRARY_PATH
+fi
+unset _IS_DARWIN
+export PATH
+export PKG_CONFIG_PATH
+export PYTHONPATH
+
+# remember type of shell if not already set
+if [ -z "$CATKIN_SHELL" ]; then
+  CATKIN_SHELL=sh
+fi
+
+# invoke Python script to generate necessary exports of environment variables
+# use TMPDIR if it exists, otherwise fall back to /tmp
+if [ -d "${TMPDIR:-}" ]; then
+  _TMPDIR="${TMPDIR}"
+else
+  _TMPDIR=/tmp
+fi
+_SETUP_TMP=`mktemp "${_TMPDIR}/setup.sh.XXXXXXXXXX"`
+unset _TMPDIR
+if [ $? -ne 0 -o ! -f "$_SETUP_TMP" ]; then
+  echo "Could not create temporary file: $_SETUP_TMP"
+  return 1
+fi
+CATKIN_SHELL=$CATKIN_SHELL "$_SETUP_UTIL" $@ ${CATKIN_SETUP_UTIL_ARGS:-} >> "$_SETUP_TMP"
+_RC=$?
+if [ $_RC -ne 0 ]; then
+  if [ $_RC -eq 2 ]; then
+    echo "Could not write the output of '$_SETUP_UTIL' to temporary file '$_SETUP_TMP': may be the disk if full?"
+  else
+    echo "Failed to run '\"$_SETUP_UTIL\" $@': return code $_RC"
+  fi
+  unset _RC
+  unset _SETUP_UTIL
+  rm -f "$_SETUP_TMP"
+  unset _SETUP_TMP
+  return 1
+fi
+unset _RC
+unset _SETUP_UTIL
+. "$_SETUP_TMP"
+rm -f "$_SETUP_TMP"
+unset _SETUP_TMP
+
+# source all environment hooks
+_i=0
+while [ $_i -lt $_CATKIN_ENVIRONMENT_HOOKS_COUNT ]; do
+  eval _envfile=\$_CATKIN_ENVIRONMENT_HOOKS_$_i
+  unset _CATKIN_ENVIRONMENT_HOOKS_$_i
+  eval _envfile_workspace=\$_CATKIN_ENVIRONMENT_HOOKS_${_i}_WORKSPACE
+  unset _CATKIN_ENVIRONMENT_HOOKS_${_i}_WORKSPACE
+  # set workspace for environment hook
+  CATKIN_ENV_HOOK_WORKSPACE=$_envfile_workspace
+  . "$_envfile"
+  unset CATKIN_ENV_HOOK_WORKSPACE
+  _i=$((_i + 1))
+done
+unset _i
+
+unset _CATKIN_ENVIRONMENT_HOOKS_COUNT
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/setup.zsh b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/setup.zsh
new file mode 100644
index 0000000000000000000000000000000000000000..9f780b741031d8037b90514441a80f9fed39d02b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/setup.zsh
@@ -0,0 +1,8 @@
+#!/usr/bin/env zsh
+# generated from catkin/cmake/templates/setup.zsh.in
+
+CATKIN_SHELL=zsh
+
+# source setup.sh from same directory as this file
+_CATKIN_SETUP_DIR=$(builtin cd -q "`dirname "$0"`" > /dev/null && pwd)
+emulate -R zsh -c 'source "$_CATKIN_SETUP_DIR/setup.sh"'
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/ordered_paths.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/ordered_paths.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..454cf032904240b2e79e6bdc0768b45d514f015f
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/ordered_paths.cmake
@@ -0,0 +1 @@
+set(ORDERED_PATHS "/opt/ros/noetic/lib")
\ No newline at end of file
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/package.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/package.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..76e62598e4736e5981a0b9f54035dafd212d74a0
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/package.cmake
@@ -0,0 +1,16 @@
+set(_CATKIN_CURRENT_PACKAGE "mav_nonlinear_mpc")
+set(mav_nonlinear_mpc_VERSION "1.0.0")
+set(mav_nonlinear_mpc_MAINTAINER "Mina Kamel <mina.kamel@mavt.ethz.com>")
+set(mav_nonlinear_mpc_PACKAGE_FORMAT "2")
+set(mav_nonlinear_mpc_BUILD_DEPENDS "std_msgs" "cmake_modules" "roscpp" "dynamic_reconfigure" "tf")
+set(mav_nonlinear_mpc_BUILD_EXPORT_DEPENDS "std_msgs" "cmake_modules" "roscpp" "dynamic_reconfigure" "tf")
+set(mav_nonlinear_mpc_BUILDTOOL_DEPENDS "catkin" "catkin_simple")
+set(mav_nonlinear_mpc_BUILDTOOL_EXPORT_DEPENDS )
+set(mav_nonlinear_mpc_EXEC_DEPENDS "std_msgs" "cmake_modules" "roscpp" "dynamic_reconfigure" "tf")
+set(mav_nonlinear_mpc_RUN_DEPENDS "std_msgs" "cmake_modules" "roscpp" "dynamic_reconfigure" "tf")
+set(mav_nonlinear_mpc_TEST_DEPENDS )
+set(mav_nonlinear_mpc_DOC_DEPENDS )
+set(mav_nonlinear_mpc_URL_WEBSITE "")
+set(mav_nonlinear_mpc_URL_BUGTRACKER "")
+set(mav_nonlinear_mpc_URL_REPOSITORY "")
+set(mav_nonlinear_mpc_DEPRECATED "")
\ No newline at end of file
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/pkg.develspace.context.pc.py b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/pkg.develspace.context.pc.py
new file mode 100644
index 0000000000000000000000000000000000000000..5f84b4458b13664d9bf9f0ee4accbb04398db6e8
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/pkg.develspace.context.pc.py
@@ -0,0 +1,8 @@
+# generated from catkin/cmake/template/pkg.context.pc.in
+CATKIN_PACKAGE_PREFIX = ""
+PROJECT_PKG_CONFIG_INCLUDE_DIRS = "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/include;/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/include".split(';') if "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/include;/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/include" != "" else []
+PROJECT_CATKIN_DEPENDS = "std_msgs;cmake_modules;roscpp;dynamic_reconfigure;tf".replace(';', ' ')
+PKG_CONFIG_LIBRARIES_WITH_PREFIX = "-lmav_nonlinear_mpc_lib".split(';') if "-lmav_nonlinear_mpc_lib" != "" else []
+PROJECT_NAME = "mav_nonlinear_mpc"
+PROJECT_SPACE_DIR = "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel"
+PROJECT_VERSION = "1.0.0"
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/pkg.installspace.context.pc.py b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/pkg.installspace.context.pc.py
new file mode 100644
index 0000000000000000000000000000000000000000..5934b20afae58f2bba354896854be0fd1876dc1e
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/pkg.installspace.context.pc.py
@@ -0,0 +1,8 @@
+# generated from catkin/cmake/template/pkg.context.pc.in
+CATKIN_PACKAGE_PREFIX = ""
+PROJECT_PKG_CONFIG_INCLUDE_DIRS = "${prefix}/include".split(';') if "${prefix}/include" != "" else []
+PROJECT_CATKIN_DEPENDS = "std_msgs;cmake_modules;roscpp;dynamic_reconfigure;tf".replace(';', ' ')
+PKG_CONFIG_LIBRARIES_WITH_PREFIX = "-lmav_nonlinear_mpc_lib".split(';') if "-lmav_nonlinear_mpc_lib" != "" else []
+PROJECT_NAME = "mav_nonlinear_mpc"
+PROJECT_SPACE_DIR = "/usr/local"
+PROJECT_VERSION = "1.0.0"
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/setup_cached.sh b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/setup_cached.sh
new file mode 100644
index 0000000000000000000000000000000000000000..eb1797e9d7cd426b2b2ecde81f52c292e2902f79
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/setup_cached.sh
@@ -0,0 +1,15 @@
+#!/usr/bin/env sh
+# generated from catkin/python/catkin/environment_cache.py
+
+# based on a snapshot of the environment before and after calling the setup script
+# it emulates the modifications of the setup script without recurring computations
+
+# new environment variables
+
+# modified environment variables
+export CMAKE_PREFIX_PATH="/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel:$CMAKE_PREFIX_PATH"
+export LD_LIBRARY_PATH="/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib:$LD_LIBRARY_PATH"
+export PKG_CONFIG_PATH="/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/pkgconfig:$PKG_CONFIG_PATH"
+export PYTHONPATH="/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/python3/dist-packages:$PYTHONPATH"
+export ROSLISP_PACKAGE_DIRECTORIES="/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/share/common-lisp:$ROSLISP_PACKAGE_DIRECTORIES"
+export ROS_PACKAGE_PATH="/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc:$ROS_PACKAGE_PATH"
\ No newline at end of file
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/stamps/mav_nonlinear_mpc/_setup_util.py.stamp b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/stamps/mav_nonlinear_mpc/_setup_util.py.stamp
new file mode 100644
index 0000000000000000000000000000000000000000..cb721f76776998339077c845951ad674ed972969
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/stamps/mav_nonlinear_mpc/_setup_util.py.stamp
@@ -0,0 +1,304 @@
+#!/usr/bin/python3
+# -*- coding: utf-8 -*-
+
+# Software License Agreement (BSD License)
+#
+# Copyright (c) 2012, Willow Garage, Inc.
+# All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+#  * Redistributions of source code must retain the above copyright
+#    notice, this list of conditions and the following disclaimer.
+#  * Redistributions in binary form must reproduce the above
+#    copyright notice, this list of conditions and the following
+#    disclaimer in the documentation and/or other materials provided
+#    with the distribution.
+#  * Neither the name of Willow Garage, Inc. nor the names of its
+#    contributors may be used to endorse or promote products derived
+#    from this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+
+"""This file generates shell code for the setup.SHELL scripts to set environment variables."""
+
+from __future__ import print_function
+
+import argparse
+import copy
+import errno
+import os
+import platform
+import sys
+
+CATKIN_MARKER_FILE = '.catkin'
+
+system = platform.system()
+IS_DARWIN = (system == 'Darwin')
+IS_WINDOWS = (system == 'Windows')
+
+PATH_TO_ADD_SUFFIX = ['bin']
+if IS_WINDOWS:
+    # while catkin recommends putting dll's into bin, 3rd party packages often put dll's into lib
+    # since Windows finds dll's via the PATH variable, prepend it with path to lib
+    PATH_TO_ADD_SUFFIX.extend([['lib', os.path.join('lib', 'x86_64-linux-gnu')]])
+
+# subfolder of workspace prepended to CMAKE_PREFIX_PATH
+ENV_VAR_SUBFOLDERS = {
+    'CMAKE_PREFIX_PATH': '',
+    'LD_LIBRARY_PATH' if not IS_DARWIN else 'DYLD_LIBRARY_PATH': ['lib', os.path.join('lib', 'x86_64-linux-gnu')],
+    'PATH': PATH_TO_ADD_SUFFIX,
+    'PKG_CONFIG_PATH': [os.path.join('lib', 'pkgconfig'), os.path.join('lib', 'x86_64-linux-gnu', 'pkgconfig')],
+    'PYTHONPATH': 'lib/python3/dist-packages',
+}
+
+
+def rollback_env_variables(environ, env_var_subfolders):
+    """
+    Generate shell code to reset environment variables.
+
+    by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH.
+    This does not cover modifications performed by environment hooks.
+    """
+    lines = []
+    unmodified_environ = copy.copy(environ)
+    for key in sorted(env_var_subfolders.keys()):
+        subfolders = env_var_subfolders[key]
+        if not isinstance(subfolders, list):
+            subfolders = [subfolders]
+        value = _rollback_env_variable(unmodified_environ, key, subfolders)
+        if value is not None:
+            environ[key] = value
+            lines.append(assignment(key, value))
+    if lines:
+        lines.insert(0, comment('reset environment variables by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH'))
+    return lines
+
+
+def _rollback_env_variable(environ, name, subfolders):
+    """
+    For each catkin workspace in CMAKE_PREFIX_PATH remove the first entry from env[NAME] matching workspace + subfolder.
+
+    :param subfolders: list of str '' or subfoldername that may start with '/'
+    :returns: the updated value of the environment variable.
+    """
+    value = environ[name] if name in environ else ''
+    env_paths = [path for path in value.split(os.pathsep) if path]
+    value_modified = False
+    for subfolder in subfolders:
+        if subfolder:
+            if subfolder.startswith(os.path.sep) or (os.path.altsep and subfolder.startswith(os.path.altsep)):
+                subfolder = subfolder[1:]
+            if subfolder.endswith(os.path.sep) or (os.path.altsep and subfolder.endswith(os.path.altsep)):
+                subfolder = subfolder[:-1]
+        for ws_path in _get_workspaces(environ, include_fuerte=True, include_non_existing=True):
+            path_to_find = os.path.join(ws_path, subfolder) if subfolder else ws_path
+            path_to_remove = None
+            for env_path in env_paths:
+                env_path_clean = env_path[:-1] if env_path and env_path[-1] in [os.path.sep, os.path.altsep] else env_path
+                if env_path_clean == path_to_find:
+                    path_to_remove = env_path
+                    break
+            if path_to_remove:
+                env_paths.remove(path_to_remove)
+                value_modified = True
+    new_value = os.pathsep.join(env_paths)
+    return new_value if value_modified else None
+
+
+def _get_workspaces(environ, include_fuerte=False, include_non_existing=False):
+    """
+    Based on CMAKE_PREFIX_PATH return all catkin workspaces.
+
+    :param include_fuerte: The flag if paths starting with '/opt/ros/fuerte' should be considered workspaces, ``bool``
+    """
+    # get all cmake prefix paths
+    env_name = 'CMAKE_PREFIX_PATH'
+    value = environ[env_name] if env_name in environ else ''
+    paths = [path for path in value.split(os.pathsep) if path]
+    # remove non-workspace paths
+    workspaces = [path for path in paths if os.path.isfile(os.path.join(path, CATKIN_MARKER_FILE)) or (include_fuerte and path.startswith('/opt/ros/fuerte')) or (include_non_existing and not os.path.exists(path))]
+    return workspaces
+
+
+def prepend_env_variables(environ, env_var_subfolders, workspaces):
+    """Generate shell code to prepend environment variables for the all workspaces."""
+    lines = []
+    lines.append(comment('prepend folders of workspaces to environment variables'))
+
+    paths = [path for path in workspaces.split(os.pathsep) if path]
+
+    prefix = _prefix_env_variable(environ, 'CMAKE_PREFIX_PATH', paths, '')
+    lines.append(prepend(environ, 'CMAKE_PREFIX_PATH', prefix))
+
+    for key in sorted(key for key in env_var_subfolders.keys() if key != 'CMAKE_PREFIX_PATH'):
+        subfolder = env_var_subfolders[key]
+        prefix = _prefix_env_variable(environ, key, paths, subfolder)
+        lines.append(prepend(environ, key, prefix))
+    return lines
+
+
+def _prefix_env_variable(environ, name, paths, subfolders):
+    """
+    Return the prefix to prepend to the environment variable NAME.
+
+    Adding any path in NEW_PATHS_STR without creating duplicate or empty items.
+    """
+    value = environ[name] if name in environ else ''
+    environ_paths = [path for path in value.split(os.pathsep) if path]
+    checked_paths = []
+    for path in paths:
+        if not isinstance(subfolders, list):
+            subfolders = [subfolders]
+        for subfolder in subfolders:
+            path_tmp = path
+            if subfolder:
+                path_tmp = os.path.join(path_tmp, subfolder)
+            # skip nonexistent paths
+            if not os.path.exists(path_tmp):
+                continue
+            # exclude any path already in env and any path we already added
+            if path_tmp not in environ_paths and path_tmp not in checked_paths:
+                checked_paths.append(path_tmp)
+    prefix_str = os.pathsep.join(checked_paths)
+    if prefix_str != '' and environ_paths:
+        prefix_str += os.pathsep
+    return prefix_str
+
+
+def assignment(key, value):
+    if not IS_WINDOWS:
+        return 'export %s="%s"' % (key, value)
+    else:
+        return 'set %s=%s' % (key, value)
+
+
+def comment(msg):
+    if not IS_WINDOWS:
+        return '# %s' % msg
+    else:
+        return 'REM %s' % msg
+
+
+def prepend(environ, key, prefix):
+    if key not in environ or not environ[key]:
+        return assignment(key, prefix)
+    if not IS_WINDOWS:
+        return 'export %s="%s$%s"' % (key, prefix, key)
+    else:
+        return 'set %s=%s%%%s%%' % (key, prefix, key)
+
+
+def find_env_hooks(environ, cmake_prefix_path):
+    """Generate shell code with found environment hooks for the all workspaces."""
+    lines = []
+    lines.append(comment('found environment hooks in workspaces'))
+
+    generic_env_hooks = []
+    generic_env_hooks_workspace = []
+    specific_env_hooks = []
+    specific_env_hooks_workspace = []
+    generic_env_hooks_by_filename = {}
+    specific_env_hooks_by_filename = {}
+    generic_env_hook_ext = 'bat' if IS_WINDOWS else 'sh'
+    specific_env_hook_ext = environ['CATKIN_SHELL'] if not IS_WINDOWS and 'CATKIN_SHELL' in environ and environ['CATKIN_SHELL'] else None
+    # remove non-workspace paths
+    workspaces = [path for path in cmake_prefix_path.split(os.pathsep) if path and os.path.isfile(os.path.join(path, CATKIN_MARKER_FILE))]
+    for workspace in reversed(workspaces):
+        env_hook_dir = os.path.join(workspace, 'etc', 'catkin', 'profile.d')
+        if os.path.isdir(env_hook_dir):
+            for filename in sorted(os.listdir(env_hook_dir)):
+                if filename.endswith('.%s' % generic_env_hook_ext):
+                    # remove previous env hook with same name if present
+                    if filename in generic_env_hooks_by_filename:
+                        i = generic_env_hooks.index(generic_env_hooks_by_filename[filename])
+                        generic_env_hooks.pop(i)
+                        generic_env_hooks_workspace.pop(i)
+                    # append env hook
+                    generic_env_hooks.append(os.path.join(env_hook_dir, filename))
+                    generic_env_hooks_workspace.append(workspace)
+                    generic_env_hooks_by_filename[filename] = generic_env_hooks[-1]
+                elif specific_env_hook_ext is not None and filename.endswith('.%s' % specific_env_hook_ext):
+                    # remove previous env hook with same name if present
+                    if filename in specific_env_hooks_by_filename:
+                        i = specific_env_hooks.index(specific_env_hooks_by_filename[filename])
+                        specific_env_hooks.pop(i)
+                        specific_env_hooks_workspace.pop(i)
+                    # append env hook
+                    specific_env_hooks.append(os.path.join(env_hook_dir, filename))
+                    specific_env_hooks_workspace.append(workspace)
+                    specific_env_hooks_by_filename[filename] = specific_env_hooks[-1]
+    env_hooks = generic_env_hooks + specific_env_hooks
+    env_hooks_workspace = generic_env_hooks_workspace + specific_env_hooks_workspace
+    count = len(env_hooks)
+    lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_COUNT', count))
+    for i in range(count):
+        lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d' % i, env_hooks[i]))
+        lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d_WORKSPACE' % i, env_hooks_workspace[i]))
+    return lines
+
+
+def _parse_arguments(args=None):
+    parser = argparse.ArgumentParser(description='Generates code blocks for the setup.SHELL script.')
+    parser.add_argument('--extend', action='store_true', help='Skip unsetting previous environment variables to extend context')
+    parser.add_argument('--local', action='store_true', help='Only consider this prefix path and ignore other prefix path in the environment')
+    return parser.parse_known_args(args=args)[0]
+
+
+if __name__ == '__main__':
+    try:
+        try:
+            args = _parse_arguments()
+        except Exception as e:
+            print(e, file=sys.stderr)
+            sys.exit(1)
+
+        if not args.local:
+            # environment at generation time
+            CMAKE_PREFIX_PATH = r'/home/simhe502/catkin_ws/devel;/opt/ros/noetic'.split(';')
+        else:
+            # don't consider any other prefix path than this one
+            CMAKE_PREFIX_PATH = []
+        # prepend current workspace if not already part of CPP
+        base_path = os.path.dirname(__file__)
+        # CMAKE_PREFIX_PATH uses forward slash on all platforms, but __file__ is platform dependent
+        # base_path on Windows contains backward slashes, need to be converted to forward slashes before comparison
+        if os.path.sep != '/':
+            base_path = base_path.replace(os.path.sep, '/')
+
+        if base_path not in CMAKE_PREFIX_PATH:
+            CMAKE_PREFIX_PATH.insert(0, base_path)
+        CMAKE_PREFIX_PATH = os.pathsep.join(CMAKE_PREFIX_PATH)
+
+        environ = dict(os.environ)
+        lines = []
+        if not args.extend:
+            lines += rollback_env_variables(environ, ENV_VAR_SUBFOLDERS)
+        lines += prepend_env_variables(environ, ENV_VAR_SUBFOLDERS, CMAKE_PREFIX_PATH)
+        lines += find_env_hooks(environ, CMAKE_PREFIX_PATH)
+        print('\n'.join(lines))
+
+        # need to explicitly flush the output
+        sys.stdout.flush()
+    except IOError as e:
+        # and catch potential "broken pipe" if stdout is not writable
+        # which can happen when piping the output to a file but the disk is full
+        if e.errno == errno.EPIPE:
+            print(e, file=sys.stderr)
+            sys.exit(2)
+        raise
+
+    sys.exit(0)
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/stamps/mav_nonlinear_mpc/interrogate_setup_dot_py.py.stamp b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/stamps/mav_nonlinear_mpc/interrogate_setup_dot_py.py.stamp
new file mode 100644
index 0000000000000000000000000000000000000000..5e25fbf8a722c2eec099e7f19f8a67c184b33d4a
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/stamps/mav_nonlinear_mpc/interrogate_setup_dot_py.py.stamp
@@ -0,0 +1,255 @@
+# Software License Agreement (BSD License)
+#
+# Copyright (c) 2012, Willow Garage, Inc.
+# All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+#  * Redistributions of source code must retain the above copyright
+#    notice, this list of conditions and the following disclaimer.
+#  * Redistributions in binary form must reproduce the above
+#    copyright notice, this list of conditions and the following
+#    disclaimer in the documentation and/or other materials provided
+#    with the distribution.
+#  * Neither the name of Willow Garage, Inc. nor the names of its
+#    contributors may be used to endorse or promote products derived
+#    from this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+
+from __future__ import print_function
+
+import os
+import runpy
+import sys
+from argparse import ArgumentParser
+
+setup_modules = []
+
+try:
+    import distutils.core
+    setup_modules.append(distutils.core)
+except ImportError:
+    pass
+
+try:
+    import setuptools
+    setup_modules.append(setuptools)
+except ImportError:
+    pass
+
+assert setup_modules, 'Must have distutils or setuptools installed'
+
+
+def _get_locations(pkgs, package_dir):
+    """
+    Based on setuptools logic and the package_dir dict, builds a dict of location roots for each pkg in pkgs.
+
+    See http://docs.python.org/distutils/setupscript.html
+
+    :returns: a dict {pkgname: root} for each pkgname in pkgs (and each of their parents)
+    """
+    # package_dir contains a dict {package_name: relativepath}
+    # Example {'': 'src', 'foo': 'lib', 'bar': 'lib2'}
+    #
+    # '' means where to look for any package unless a parent package
+    # is listed so package bar.pot is expected at lib2/bar/pot,
+    # whereas package sup.dee is expected at src/sup/dee
+    #
+    # if package_dir does not state anything about a package,
+    # setuptool expects the package folder to be in the root of the
+    # project
+    locations = {}
+    allprefix = package_dir.get('', '')
+    for pkg in pkgs:
+        parent_location = None
+        splits = pkg.split('.')
+        # we iterate over compound name from parent to child
+        # so once we found parent, children just append to their parent
+        for key_len in range(len(splits)):
+            key = '.'.join(splits[:key_len + 1])
+            if key not in locations:
+                if key in package_dir:
+                    locations[key] = package_dir[key]
+                elif parent_location is not None:
+                    locations[key] = os.path.join(parent_location, splits[key_len])
+                else:
+                    locations[key] = os.path.join(allprefix, key)
+            parent_location = locations[key]
+    return locations
+
+
+def generate_cmake_file(package_name, version, scripts, package_dir, pkgs, modules, setup_module=None):
+    """
+    Generate lines to add to a cmake file which will set variables.
+
+    :param version: str, format 'int.int.int'
+    :param scripts: [list of str]: relative paths to scripts
+    :param package_dir: {modulename: path}
+    :param pkgs: [list of str] python_packages declared in catkin package
+    :param modules: [list of str] python modules
+    :param setup_module: str, setuptools or distutils
+    """
+    prefix = '%s_SETUP_PY' % package_name
+    result = []
+    if setup_module:
+        result.append(r'set(%s_SETUP_MODULE "%s")' % (prefix, setup_module))
+    result.append(r'set(%s_VERSION "%s")' % (prefix, version))
+    result.append(r'set(%s_SCRIPTS "%s")' % (prefix, ';'.join(scripts)))
+
+    # Remove packages with '.' separators.
+    #
+    # setuptools allows specifying submodules in other folders than
+    # their parent
+    #
+    # The symlink approach of catkin does not work with such submodules.
+    # In the common case, this does not matter as the submodule is
+    # within the containing module.  We verify this assumption, and if
+    # it passes, we remove submodule packages.
+    locations = _get_locations(pkgs, package_dir)
+    for pkgname, location in locations.items():
+        if '.' not in pkgname:
+            continue
+        splits = pkgname.split('.')
+        # hack: ignore write-combining setup.py files for msg and srv files
+        if splits[1] in ['msg', 'srv']:
+            continue
+        # check every child has the same root folder as its parent
+        root_name = splits[0]
+        root_location = location
+        for _ in range(len(splits) - 1):
+            root_location = os.path.dirname(root_location)
+        if root_location != locations[root_name]:
+            raise RuntimeError(
+                'catkin_export_python does not support setup.py files that combine across multiple directories: %s in %s, %s in %s' % (pkgname, location, root_name, locations[root_name]))
+
+    # If checks pass, remove all submodules
+    pkgs = [p for p in pkgs if '.' not in p]
+
+    resolved_pkgs = []
+    for pkg in pkgs:
+        resolved_pkgs += [locations[pkg]]
+
+    result.append(r'set(%s_PACKAGES "%s")' % (prefix, ';'.join(pkgs)))
+    result.append(r'set(%s_PACKAGE_DIRS "%s")' % (prefix, ';'.join(resolved_pkgs).replace('\\', '/')))
+
+    # skip modules which collide with package names
+    filtered_modules = []
+    for modname in modules:
+        splits = modname.split('.')
+        # check all parents too
+        equals_package = [('.'.join(splits[:-i]) in locations) for i in range(len(splits))]
+        if any(equals_package):
+            continue
+        filtered_modules.append(modname)
+    module_locations = _get_locations(filtered_modules, package_dir)
+
+    result.append(r'set(%s_MODULES "%s")' % (prefix, ';'.join(['%s.py' % m.replace('.', '/') for m in filtered_modules])))
+    result.append(r'set(%s_MODULE_DIRS "%s")' % (prefix, ';'.join([module_locations[m] for m in filtered_modules]).replace('\\', '/')))
+
+    return result
+
+
+def _create_mock_setup_function(setup_module, package_name, outfile):
+    """
+    Create a function to call instead of distutils.core.setup or setuptools.setup.
+
+    It just captures some args and writes them into a file that can be used from cmake.
+
+    :param package_name: name of the package
+    :param outfile: filename that cmake will use afterwards
+    :returns: a function to replace disutils.core.setup and setuptools.setup
+    """
+
+    def setup(*args, **kwargs):
+        """Check kwargs and write a scriptfile."""
+        if 'version' not in kwargs:
+            sys.stderr.write("\n*** Unable to find 'version' in setup.py of %s\n" % package_name)
+            raise RuntimeError('version not found in setup.py')
+        version = kwargs['version']
+        package_dir = kwargs.get('package_dir', {})
+
+        pkgs = kwargs.get('packages', [])
+        scripts = kwargs.get('scripts', [])
+        modules = kwargs.get('py_modules', [])
+
+        unsupported_args = [
+            'entry_points',
+            'exclude_package_data',
+            'ext_modules ',
+            'ext_package',
+            'include_package_data',
+            'namespace_packages',
+            'setup_requires',
+            'use_2to3',
+            'zip_safe']
+        used_unsupported_args = [arg for arg in unsupported_args if arg in kwargs]
+        if used_unsupported_args:
+            sys.stderr.write('*** Arguments %s to setup() not supported in catkin devel space in setup.py of %s\n' % (used_unsupported_args, package_name))
+
+        result = generate_cmake_file(package_name=package_name,
+                                     version=version,
+                                     scripts=scripts,
+                                     package_dir=package_dir,
+                                     pkgs=pkgs,
+                                     modules=modules,
+                                     setup_module=setup_module)
+        with open(outfile, 'w') as out:
+            out.write('\n'.join(result))
+
+    return setup
+
+
+def main():
+    """Script main, parses arguments and invokes Dummy.setup indirectly."""
+    parser = ArgumentParser(description='Utility to read setup.py values from cmake macros. Creates a file with CMake set commands setting variables.')
+    parser.add_argument('package_name', help='Name of catkin package')
+    parser.add_argument('setupfile_path', help='Full path to setup.py')
+    parser.add_argument('outfile', help='Where to write result to')
+
+    args = parser.parse_args()
+
+    # print("%s" % sys.argv)
+    # PACKAGE_NAME = sys.argv[1]
+    # OUTFILE = sys.argv[3]
+    # print("Interrogating setup.py for package %s into %s " % (PACKAGE_NAME, OUTFILE),
+    #      file=sys.stderr)
+
+    # print("executing %s" % args.setupfile_path)
+
+    # be sure you're in the directory containing
+    # setup.py so the sys.path manipulation works,
+    # so the import of __version__ works
+    os.chdir(os.path.dirname(os.path.abspath(args.setupfile_path)))
+
+    # patch setup() function of distutils and setuptools for the
+    # context of evaluating setup.py
+    backup_modules = {}
+    try:
+
+        for module in setup_modules:
+            backup_modules[id(module)] = module.setup
+            module.setup = _create_mock_setup_function(
+                setup_module=module.__name__, package_name=args.package_name, outfile=args.outfile)
+
+        runpy.run_path(args.setupfile_path)
+    finally:
+        for module in setup_modules:
+            module.setup = backup_modules[id(module)]
+
+
+if __name__ == '__main__':
+    main()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/stamps/mav_nonlinear_mpc/package.xml.stamp b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/stamps/mav_nonlinear_mpc/package.xml.stamp
new file mode 100644
index 0000000000000000000000000000000000000000..cd6a522887aeea2ea3cf397581b0133e964f38c2
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/stamps/mav_nonlinear_mpc/package.xml.stamp
@@ -0,0 +1,21 @@
+<?xml version="1.0"?>
+<package format="2">
+  <name>mav_nonlinear_mpc</name>
+  <version>1.0.0</version>
+  <description>
+    Nonlinear model predictive controller for trajectory tracking of multirotor system
+  </description>
+
+  <maintainer email="mina.kamel@mavt.ethz.com">Mina Kamel</maintainer>
+
+  <license>BSD</license>
+
+  <buildtool_depend>catkin</buildtool_depend>
+  <buildtool_depend>catkin_simple</buildtool_depend>
+
+  <depend>std_msgs</depend>
+  <depend>cmake_modules</depend>
+  <depend>roscpp</depend>
+  <depend>dynamic_reconfigure</depend>
+  <depend>tf</depend>
+</package>
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/stamps/mav_nonlinear_mpc/pkg.pc.em.stamp b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/stamps/mav_nonlinear_mpc/pkg.pc.em.stamp
new file mode 100644
index 0000000000000000000000000000000000000000..549fb75ce8000c875c316f444238bd1f28dc88c8
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/stamps/mav_nonlinear_mpc/pkg.pc.em.stamp
@@ -0,0 +1,8 @@
+prefix=@PROJECT_SPACE_DIR
+
+Name: @(CATKIN_PACKAGE_PREFIX + PROJECT_NAME)
+Description: Description of @PROJECT_NAME
+Version: @PROJECT_VERSION
+Cflags: @(' '.join(['-I%s' % include for include in PROJECT_PKG_CONFIG_INCLUDE_DIRS]))
+Libs: -L${prefix}/lib @(' '.join(PKG_CONFIG_LIBRARIES_WITH_PREFIX))
+Requires: @(PROJECT_CATKIN_DEPENDS)
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/cmake_install.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/cmake_install.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..00a9cf0a47d7fc446bba3e65b288ada1fa8ab050
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/cmake_install.cmake
@@ -0,0 +1,228 @@
+# Install script for directory: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# Set the install prefix
+if(NOT DEFINED CMAKE_INSTALL_PREFIX)
+  set(CMAKE_INSTALL_PREFIX "/usr/local")
+endif()
+string(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}")
+
+# Set the install configuration name.
+if(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME)
+  if(BUILD_TYPE)
+    string(REGEX REPLACE "^[^A-Za-z0-9_]+" ""
+           CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}")
+  else()
+    set(CMAKE_INSTALL_CONFIG_NAME "Release")
+  endif()
+  message(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"")
+endif()
+
+# Set the component getting installed.
+if(NOT CMAKE_INSTALL_COMPONENT)
+  if(COMPONENT)
+    message(STATUS "Install component: \"${COMPONENT}\"")
+    set(CMAKE_INSTALL_COMPONENT "${COMPONENT}")
+  else()
+    set(CMAKE_INSTALL_COMPONENT)
+  endif()
+endif()
+
+# Install shared libraries without execute permission?
+if(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE)
+  set(CMAKE_INSTALL_SO_NO_EXE "1")
+endif()
+
+# Is this installation the result of a crosscompile?
+if(NOT DEFINED CMAKE_CROSSCOMPILING)
+  set(CMAKE_CROSSCOMPILING "FALSE")
+endif()
+
+if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT)
+  
+      if (NOT EXISTS "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}")
+        file(MAKE_DIRECTORY "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}")
+      endif()
+      if (NOT EXISTS "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/.catkin")
+        file(WRITE "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/.catkin" "")
+      endif()
+endif()
+
+if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT)
+  list(APPEND CMAKE_ABSOLUTE_DESTINATION_FILES
+   "/usr/local/_setup_util.py")
+  if(CMAKE_WARN_ON_ABSOLUTE_INSTALL_DESTINATION)
+    message(WARNING "ABSOLUTE path INSTALL DESTINATION : ${CMAKE_ABSOLUTE_DESTINATION_FILES}")
+  endif()
+  if(CMAKE_ERROR_ON_ABSOLUTE_INSTALL_DESTINATION)
+    message(FATAL_ERROR "ABSOLUTE path INSTALL DESTINATION forbidden (by caller): ${CMAKE_ABSOLUTE_DESTINATION_FILES}")
+  endif()
+file(INSTALL DESTINATION "/usr/local" TYPE PROGRAM FILES "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/_setup_util.py")
+endif()
+
+if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT)
+  list(APPEND CMAKE_ABSOLUTE_DESTINATION_FILES
+   "/usr/local/env.sh")
+  if(CMAKE_WARN_ON_ABSOLUTE_INSTALL_DESTINATION)
+    message(WARNING "ABSOLUTE path INSTALL DESTINATION : ${CMAKE_ABSOLUTE_DESTINATION_FILES}")
+  endif()
+  if(CMAKE_ERROR_ON_ABSOLUTE_INSTALL_DESTINATION)
+    message(FATAL_ERROR "ABSOLUTE path INSTALL DESTINATION forbidden (by caller): ${CMAKE_ABSOLUTE_DESTINATION_FILES}")
+  endif()
+file(INSTALL DESTINATION "/usr/local" TYPE PROGRAM FILES "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/env.sh")
+endif()
+
+if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT)
+  list(APPEND CMAKE_ABSOLUTE_DESTINATION_FILES
+   "/usr/local/setup.bash;/usr/local/local_setup.bash")
+  if(CMAKE_WARN_ON_ABSOLUTE_INSTALL_DESTINATION)
+    message(WARNING "ABSOLUTE path INSTALL DESTINATION : ${CMAKE_ABSOLUTE_DESTINATION_FILES}")
+  endif()
+  if(CMAKE_ERROR_ON_ABSOLUTE_INSTALL_DESTINATION)
+    message(FATAL_ERROR "ABSOLUTE path INSTALL DESTINATION forbidden (by caller): ${CMAKE_ABSOLUTE_DESTINATION_FILES}")
+  endif()
+file(INSTALL DESTINATION "/usr/local" TYPE FILE FILES
+    "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/setup.bash"
+    "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/local_setup.bash"
+    )
+endif()
+
+if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT)
+  list(APPEND CMAKE_ABSOLUTE_DESTINATION_FILES
+   "/usr/local/setup.sh;/usr/local/local_setup.sh")
+  if(CMAKE_WARN_ON_ABSOLUTE_INSTALL_DESTINATION)
+    message(WARNING "ABSOLUTE path INSTALL DESTINATION : ${CMAKE_ABSOLUTE_DESTINATION_FILES}")
+  endif()
+  if(CMAKE_ERROR_ON_ABSOLUTE_INSTALL_DESTINATION)
+    message(FATAL_ERROR "ABSOLUTE path INSTALL DESTINATION forbidden (by caller): ${CMAKE_ABSOLUTE_DESTINATION_FILES}")
+  endif()
+file(INSTALL DESTINATION "/usr/local" TYPE FILE FILES
+    "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/setup.sh"
+    "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/local_setup.sh"
+    )
+endif()
+
+if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT)
+  list(APPEND CMAKE_ABSOLUTE_DESTINATION_FILES
+   "/usr/local/setup.zsh;/usr/local/local_setup.zsh")
+  if(CMAKE_WARN_ON_ABSOLUTE_INSTALL_DESTINATION)
+    message(WARNING "ABSOLUTE path INSTALL DESTINATION : ${CMAKE_ABSOLUTE_DESTINATION_FILES}")
+  endif()
+  if(CMAKE_ERROR_ON_ABSOLUTE_INSTALL_DESTINATION)
+    message(FATAL_ERROR "ABSOLUTE path INSTALL DESTINATION forbidden (by caller): ${CMAKE_ABSOLUTE_DESTINATION_FILES}")
+  endif()
+file(INSTALL DESTINATION "/usr/local" TYPE FILE FILES
+    "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/setup.zsh"
+    "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/local_setup.zsh"
+    )
+endif()
+
+if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT)
+  list(APPEND CMAKE_ABSOLUTE_DESTINATION_FILES
+   "/usr/local/.rosinstall")
+  if(CMAKE_WARN_ON_ABSOLUTE_INSTALL_DESTINATION)
+    message(WARNING "ABSOLUTE path INSTALL DESTINATION : ${CMAKE_ABSOLUTE_DESTINATION_FILES}")
+  endif()
+  if(CMAKE_ERROR_ON_ABSOLUTE_INSTALL_DESTINATION)
+    message(FATAL_ERROR "ABSOLUTE path INSTALL DESTINATION forbidden (by caller): ${CMAKE_ABSOLUTE_DESTINATION_FILES}")
+  endif()
+file(INSTALL DESTINATION "/usr/local" TYPE FILE FILES "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/.rosinstall")
+endif()
+
+if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT)
+  file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/include/mav_nonlinear_mpc" TYPE FILE FILES "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h")
+endif()
+
+if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT)
+  file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/lib/python3/dist-packages/mav_nonlinear_mpc" TYPE FILE FILES "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/python3/dist-packages/mav_nonlinear_mpc/__init__.py")
+endif()
+
+if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT)
+  execute_process(COMMAND "/usr/bin/python3" -m compileall "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/python3/dist-packages/mav_nonlinear_mpc/cfg")
+endif()
+
+if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT)
+  file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/lib/python3/dist-packages/mav_nonlinear_mpc" TYPE DIRECTORY FILES "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/python3/dist-packages/mav_nonlinear_mpc/cfg")
+endif()
+
+if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT)
+  if(EXISTS "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/libmav_nonlinear_mpc_lib.so" AND
+     NOT IS_SYMLINK "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/libmav_nonlinear_mpc_lib.so")
+    file(RPATH_CHECK
+         FILE "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/libmav_nonlinear_mpc_lib.so"
+         RPATH "")
+  endif()
+  file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/lib" TYPE SHARED_LIBRARY FILES "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/libmav_nonlinear_mpc_lib.so")
+  if(EXISTS "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/libmav_nonlinear_mpc_lib.so" AND
+     NOT IS_SYMLINK "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/libmav_nonlinear_mpc_lib.so")
+    file(RPATH_CHANGE
+         FILE "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/libmav_nonlinear_mpc_lib.so"
+         OLD_RPATH "/opt/ros/noetic/lib:"
+         NEW_RPATH "")
+    if(CMAKE_INSTALL_DO_STRIP)
+      execute_process(COMMAND "/usr/bin/strip" "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/libmav_nonlinear_mpc_lib.so")
+    endif()
+  endif()
+endif()
+
+if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT)
+endif()
+
+if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT)
+  if(EXISTS "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/mav_nonlinear_mpc/nonlinear_mpc_node" AND
+     NOT IS_SYMLINK "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/mav_nonlinear_mpc/nonlinear_mpc_node")
+    file(RPATH_CHECK
+         FILE "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/mav_nonlinear_mpc/nonlinear_mpc_node"
+         RPATH "")
+  endif()
+  file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/lib/mav_nonlinear_mpc" TYPE EXECUTABLE FILES "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node")
+  if(EXISTS "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/mav_nonlinear_mpc/nonlinear_mpc_node" AND
+     NOT IS_SYMLINK "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/mav_nonlinear_mpc/nonlinear_mpc_node")
+    file(RPATH_CHANGE
+         FILE "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/mav_nonlinear_mpc/nonlinear_mpc_node"
+         OLD_RPATH "/opt/ros/noetic/lib:/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib:"
+         NEW_RPATH "")
+    if(CMAKE_INSTALL_DO_STRIP)
+      execute_process(COMMAND "/usr/bin/strip" "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/mav_nonlinear_mpc/nonlinear_mpc_node")
+    endif()
+  endif()
+endif()
+
+if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT)
+  file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/include" TYPE DIRECTORY FILES "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/include/" FILES_MATCHING REGEX "/[^/]*\\.h$" REGEX "/[^/]*\\.hpp$" REGEX "/\\.svn$" EXCLUDE)
+endif()
+
+if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT)
+  file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/share/mav_nonlinear_mpc/launch" TYPE DIRECTORY FILES "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/launch/")
+endif()
+
+if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT)
+  file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/lib/pkgconfig" TYPE FILE FILES "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/mav_nonlinear_mpc.pc")
+endif()
+
+if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT)
+  file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/share/mav_nonlinear_mpc/cmake" TYPE FILE FILES
+    "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/mav_nonlinear_mpcConfig.cmake"
+    "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/catkin_generated/installspace/mav_nonlinear_mpcConfig-version.cmake"
+    )
+endif()
+
+if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT)
+  file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/share/mav_nonlinear_mpc" TYPE FILE FILES "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/package.xml")
+endif()
+
+if(NOT CMAKE_INSTALL_LOCAL_ONLY)
+  # Include the install script for each subdirectory.
+  include("/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/cmake_install.cmake")
+
+endif()
+
+if(CMAKE_INSTALL_COMPONENT)
+  set(CMAKE_INSTALL_MANIFEST "install_manifest_${CMAKE_INSTALL_COMPONENT}.txt")
+else()
+  set(CMAKE_INSTALL_MANIFEST "install_manifest.txt")
+endif()
+
+string(REPLACE ";" "\n" CMAKE_INSTALL_MANIFEST_CONTENT
+       "${CMAKE_INSTALL_MANIFEST_FILES}")
+file(WRITE "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/${CMAKE_INSTALL_MANIFEST}"
+     "${CMAKE_INSTALL_MANIFEST_CONTENT}")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/.catkin b/mav_control_rw/mav_nonlinear_mpc/solver/devel/.catkin
new file mode 100644
index 0000000000000000000000000000000000000000..ddcc1bc32b984e3ef88967c18c4c12d964de5cb5
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/devel/.catkin
@@ -0,0 +1 @@
+/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
\ No newline at end of file
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/.rosinstall b/mav_control_rw/mav_nonlinear_mpc/solver/devel/.rosinstall
new file mode 100644
index 0000000000000000000000000000000000000000..0da04c9b02fcc3f87fdab4510e0bf70b3c02eee7
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/devel/.rosinstall
@@ -0,0 +1,2 @@
+- setup-file:
+    local-name: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/setup.sh
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/_setup_util.py b/mav_control_rw/mav_nonlinear_mpc/solver/devel/_setup_util.py
new file mode 100644
index 0000000000000000000000000000000000000000..cb721f76776998339077c845951ad674ed972969
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/devel/_setup_util.py
@@ -0,0 +1,304 @@
+#!/usr/bin/python3
+# -*- coding: utf-8 -*-
+
+# Software License Agreement (BSD License)
+#
+# Copyright (c) 2012, Willow Garage, Inc.
+# All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+#  * Redistributions of source code must retain the above copyright
+#    notice, this list of conditions and the following disclaimer.
+#  * Redistributions in binary form must reproduce the above
+#    copyright notice, this list of conditions and the following
+#    disclaimer in the documentation and/or other materials provided
+#    with the distribution.
+#  * Neither the name of Willow Garage, Inc. nor the names of its
+#    contributors may be used to endorse or promote products derived
+#    from this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+
+"""This file generates shell code for the setup.SHELL scripts to set environment variables."""
+
+from __future__ import print_function
+
+import argparse
+import copy
+import errno
+import os
+import platform
+import sys
+
+CATKIN_MARKER_FILE = '.catkin'
+
+system = platform.system()
+IS_DARWIN = (system == 'Darwin')
+IS_WINDOWS = (system == 'Windows')
+
+PATH_TO_ADD_SUFFIX = ['bin']
+if IS_WINDOWS:
+    # while catkin recommends putting dll's into bin, 3rd party packages often put dll's into lib
+    # since Windows finds dll's via the PATH variable, prepend it with path to lib
+    PATH_TO_ADD_SUFFIX.extend([['lib', os.path.join('lib', 'x86_64-linux-gnu')]])
+
+# subfolder of workspace prepended to CMAKE_PREFIX_PATH
+ENV_VAR_SUBFOLDERS = {
+    'CMAKE_PREFIX_PATH': '',
+    'LD_LIBRARY_PATH' if not IS_DARWIN else 'DYLD_LIBRARY_PATH': ['lib', os.path.join('lib', 'x86_64-linux-gnu')],
+    'PATH': PATH_TO_ADD_SUFFIX,
+    'PKG_CONFIG_PATH': [os.path.join('lib', 'pkgconfig'), os.path.join('lib', 'x86_64-linux-gnu', 'pkgconfig')],
+    'PYTHONPATH': 'lib/python3/dist-packages',
+}
+
+
+def rollback_env_variables(environ, env_var_subfolders):
+    """
+    Generate shell code to reset environment variables.
+
+    by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH.
+    This does not cover modifications performed by environment hooks.
+    """
+    lines = []
+    unmodified_environ = copy.copy(environ)
+    for key in sorted(env_var_subfolders.keys()):
+        subfolders = env_var_subfolders[key]
+        if not isinstance(subfolders, list):
+            subfolders = [subfolders]
+        value = _rollback_env_variable(unmodified_environ, key, subfolders)
+        if value is not None:
+            environ[key] = value
+            lines.append(assignment(key, value))
+    if lines:
+        lines.insert(0, comment('reset environment variables by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH'))
+    return lines
+
+
+def _rollback_env_variable(environ, name, subfolders):
+    """
+    For each catkin workspace in CMAKE_PREFIX_PATH remove the first entry from env[NAME] matching workspace + subfolder.
+
+    :param subfolders: list of str '' or subfoldername that may start with '/'
+    :returns: the updated value of the environment variable.
+    """
+    value = environ[name] if name in environ else ''
+    env_paths = [path for path in value.split(os.pathsep) if path]
+    value_modified = False
+    for subfolder in subfolders:
+        if subfolder:
+            if subfolder.startswith(os.path.sep) or (os.path.altsep and subfolder.startswith(os.path.altsep)):
+                subfolder = subfolder[1:]
+            if subfolder.endswith(os.path.sep) or (os.path.altsep and subfolder.endswith(os.path.altsep)):
+                subfolder = subfolder[:-1]
+        for ws_path in _get_workspaces(environ, include_fuerte=True, include_non_existing=True):
+            path_to_find = os.path.join(ws_path, subfolder) if subfolder else ws_path
+            path_to_remove = None
+            for env_path in env_paths:
+                env_path_clean = env_path[:-1] if env_path and env_path[-1] in [os.path.sep, os.path.altsep] else env_path
+                if env_path_clean == path_to_find:
+                    path_to_remove = env_path
+                    break
+            if path_to_remove:
+                env_paths.remove(path_to_remove)
+                value_modified = True
+    new_value = os.pathsep.join(env_paths)
+    return new_value if value_modified else None
+
+
+def _get_workspaces(environ, include_fuerte=False, include_non_existing=False):
+    """
+    Based on CMAKE_PREFIX_PATH return all catkin workspaces.
+
+    :param include_fuerte: The flag if paths starting with '/opt/ros/fuerte' should be considered workspaces, ``bool``
+    """
+    # get all cmake prefix paths
+    env_name = 'CMAKE_PREFIX_PATH'
+    value = environ[env_name] if env_name in environ else ''
+    paths = [path for path in value.split(os.pathsep) if path]
+    # remove non-workspace paths
+    workspaces = [path for path in paths if os.path.isfile(os.path.join(path, CATKIN_MARKER_FILE)) or (include_fuerte and path.startswith('/opt/ros/fuerte')) or (include_non_existing and not os.path.exists(path))]
+    return workspaces
+
+
+def prepend_env_variables(environ, env_var_subfolders, workspaces):
+    """Generate shell code to prepend environment variables for the all workspaces."""
+    lines = []
+    lines.append(comment('prepend folders of workspaces to environment variables'))
+
+    paths = [path for path in workspaces.split(os.pathsep) if path]
+
+    prefix = _prefix_env_variable(environ, 'CMAKE_PREFIX_PATH', paths, '')
+    lines.append(prepend(environ, 'CMAKE_PREFIX_PATH', prefix))
+
+    for key in sorted(key for key in env_var_subfolders.keys() if key != 'CMAKE_PREFIX_PATH'):
+        subfolder = env_var_subfolders[key]
+        prefix = _prefix_env_variable(environ, key, paths, subfolder)
+        lines.append(prepend(environ, key, prefix))
+    return lines
+
+
+def _prefix_env_variable(environ, name, paths, subfolders):
+    """
+    Return the prefix to prepend to the environment variable NAME.
+
+    Adding any path in NEW_PATHS_STR without creating duplicate or empty items.
+    """
+    value = environ[name] if name in environ else ''
+    environ_paths = [path for path in value.split(os.pathsep) if path]
+    checked_paths = []
+    for path in paths:
+        if not isinstance(subfolders, list):
+            subfolders = [subfolders]
+        for subfolder in subfolders:
+            path_tmp = path
+            if subfolder:
+                path_tmp = os.path.join(path_tmp, subfolder)
+            # skip nonexistent paths
+            if not os.path.exists(path_tmp):
+                continue
+            # exclude any path already in env and any path we already added
+            if path_tmp not in environ_paths and path_tmp not in checked_paths:
+                checked_paths.append(path_tmp)
+    prefix_str = os.pathsep.join(checked_paths)
+    if prefix_str != '' and environ_paths:
+        prefix_str += os.pathsep
+    return prefix_str
+
+
+def assignment(key, value):
+    if not IS_WINDOWS:
+        return 'export %s="%s"' % (key, value)
+    else:
+        return 'set %s=%s' % (key, value)
+
+
+def comment(msg):
+    if not IS_WINDOWS:
+        return '# %s' % msg
+    else:
+        return 'REM %s' % msg
+
+
+def prepend(environ, key, prefix):
+    if key not in environ or not environ[key]:
+        return assignment(key, prefix)
+    if not IS_WINDOWS:
+        return 'export %s="%s$%s"' % (key, prefix, key)
+    else:
+        return 'set %s=%s%%%s%%' % (key, prefix, key)
+
+
+def find_env_hooks(environ, cmake_prefix_path):
+    """Generate shell code with found environment hooks for the all workspaces."""
+    lines = []
+    lines.append(comment('found environment hooks in workspaces'))
+
+    generic_env_hooks = []
+    generic_env_hooks_workspace = []
+    specific_env_hooks = []
+    specific_env_hooks_workspace = []
+    generic_env_hooks_by_filename = {}
+    specific_env_hooks_by_filename = {}
+    generic_env_hook_ext = 'bat' if IS_WINDOWS else 'sh'
+    specific_env_hook_ext = environ['CATKIN_SHELL'] if not IS_WINDOWS and 'CATKIN_SHELL' in environ and environ['CATKIN_SHELL'] else None
+    # remove non-workspace paths
+    workspaces = [path for path in cmake_prefix_path.split(os.pathsep) if path and os.path.isfile(os.path.join(path, CATKIN_MARKER_FILE))]
+    for workspace in reversed(workspaces):
+        env_hook_dir = os.path.join(workspace, 'etc', 'catkin', 'profile.d')
+        if os.path.isdir(env_hook_dir):
+            for filename in sorted(os.listdir(env_hook_dir)):
+                if filename.endswith('.%s' % generic_env_hook_ext):
+                    # remove previous env hook with same name if present
+                    if filename in generic_env_hooks_by_filename:
+                        i = generic_env_hooks.index(generic_env_hooks_by_filename[filename])
+                        generic_env_hooks.pop(i)
+                        generic_env_hooks_workspace.pop(i)
+                    # append env hook
+                    generic_env_hooks.append(os.path.join(env_hook_dir, filename))
+                    generic_env_hooks_workspace.append(workspace)
+                    generic_env_hooks_by_filename[filename] = generic_env_hooks[-1]
+                elif specific_env_hook_ext is not None and filename.endswith('.%s' % specific_env_hook_ext):
+                    # remove previous env hook with same name if present
+                    if filename in specific_env_hooks_by_filename:
+                        i = specific_env_hooks.index(specific_env_hooks_by_filename[filename])
+                        specific_env_hooks.pop(i)
+                        specific_env_hooks_workspace.pop(i)
+                    # append env hook
+                    specific_env_hooks.append(os.path.join(env_hook_dir, filename))
+                    specific_env_hooks_workspace.append(workspace)
+                    specific_env_hooks_by_filename[filename] = specific_env_hooks[-1]
+    env_hooks = generic_env_hooks + specific_env_hooks
+    env_hooks_workspace = generic_env_hooks_workspace + specific_env_hooks_workspace
+    count = len(env_hooks)
+    lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_COUNT', count))
+    for i in range(count):
+        lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d' % i, env_hooks[i]))
+        lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d_WORKSPACE' % i, env_hooks_workspace[i]))
+    return lines
+
+
+def _parse_arguments(args=None):
+    parser = argparse.ArgumentParser(description='Generates code blocks for the setup.SHELL script.')
+    parser.add_argument('--extend', action='store_true', help='Skip unsetting previous environment variables to extend context')
+    parser.add_argument('--local', action='store_true', help='Only consider this prefix path and ignore other prefix path in the environment')
+    return parser.parse_known_args(args=args)[0]
+
+
+if __name__ == '__main__':
+    try:
+        try:
+            args = _parse_arguments()
+        except Exception as e:
+            print(e, file=sys.stderr)
+            sys.exit(1)
+
+        if not args.local:
+            # environment at generation time
+            CMAKE_PREFIX_PATH = r'/home/simhe502/catkin_ws/devel;/opt/ros/noetic'.split(';')
+        else:
+            # don't consider any other prefix path than this one
+            CMAKE_PREFIX_PATH = []
+        # prepend current workspace if not already part of CPP
+        base_path = os.path.dirname(__file__)
+        # CMAKE_PREFIX_PATH uses forward slash on all platforms, but __file__ is platform dependent
+        # base_path on Windows contains backward slashes, need to be converted to forward slashes before comparison
+        if os.path.sep != '/':
+            base_path = base_path.replace(os.path.sep, '/')
+
+        if base_path not in CMAKE_PREFIX_PATH:
+            CMAKE_PREFIX_PATH.insert(0, base_path)
+        CMAKE_PREFIX_PATH = os.pathsep.join(CMAKE_PREFIX_PATH)
+
+        environ = dict(os.environ)
+        lines = []
+        if not args.extend:
+            lines += rollback_env_variables(environ, ENV_VAR_SUBFOLDERS)
+        lines += prepend_env_variables(environ, ENV_VAR_SUBFOLDERS, CMAKE_PREFIX_PATH)
+        lines += find_env_hooks(environ, CMAKE_PREFIX_PATH)
+        print('\n'.join(lines))
+
+        # need to explicitly flush the output
+        sys.stdout.flush()
+    except IOError as e:
+        # and catch potential "broken pipe" if stdout is not writable
+        # which can happen when piping the output to a file but the disk is full
+        if e.errno == errno.EPIPE:
+            print(e, file=sys.stderr)
+            sys.exit(2)
+        raise
+
+    sys.exit(0)
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/cmake.lock b/mav_control_rw/mav_nonlinear_mpc/solver/devel/cmake.lock
new file mode 100644
index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/env.sh b/mav_control_rw/mav_nonlinear_mpc/solver/devel/env.sh
new file mode 100644
index 0000000000000000000000000000000000000000..8aa9d244ae9475039027a5f25a8d41a46174cddf
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/devel/env.sh
@@ -0,0 +1,16 @@
+#!/usr/bin/env sh
+# generated from catkin/cmake/templates/env.sh.in
+
+if [ $# -eq 0 ] ; then
+  /bin/echo "Usage: env.sh COMMANDS"
+  /bin/echo "Calling env.sh without arguments is not supported anymore. Instead spawn a subshell and source a setup file manually."
+  exit 1
+fi
+
+# ensure to not use different shell type which was set before
+CATKIN_SHELL=sh
+
+# source setup.sh from same directory as this file
+_CATKIN_SETUP_DIR=$(cd "`dirname "$0"`" > /dev/null && pwd)
+. "$_CATKIN_SETUP_DIR/setup.sh"
+exec "$@"
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h b/mav_control_rw/mav_nonlinear_mpc/solver/devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h
new file mode 100644
index 0000000000000000000000000000000000000000..db8f9540844d4917c053a12f90089ecc3335e5e9
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/devel/include/mav_nonlinear_mpc/NonLinearMPCConfig.h
@@ -0,0 +1,770 @@
+//#line 2 "/opt/ros/noetic/share/dynamic_reconfigure/cmake/../templates/ConfigType.h.template"
+// *********************************************************
+//
+// File autogenerated for the mav_nonlinear_mpc package
+// by the dynamic_reconfigure package.
+// Please do not edit.
+//
+// ********************************************************/
+
+#ifndef __mav_nonlinear_mpc__NONLINEARMPCCONFIG_H__
+#define __mav_nonlinear_mpc__NONLINEARMPCCONFIG_H__
+
+#if __cplusplus >= 201103L
+#define DYNAMIC_RECONFIGURE_FINAL final
+#else
+#define DYNAMIC_RECONFIGURE_FINAL
+#endif
+
+#include <dynamic_reconfigure/config_tools.h>
+#include <limits>
+#include <ros/node_handle.h>
+#include <dynamic_reconfigure/ConfigDescription.h>
+#include <dynamic_reconfigure/ParamDescription.h>
+#include <dynamic_reconfigure/Group.h>
+#include <dynamic_reconfigure/config_init_mutex.h>
+#include <boost/any.hpp>
+
+namespace mav_nonlinear_mpc
+{
+  class NonLinearMPCConfigStatics;
+
+  class NonLinearMPCConfig
+  {
+  public:
+    class AbstractParamDescription : public dynamic_reconfigure::ParamDescription
+    {
+    public:
+      AbstractParamDescription(std::string n, std::string t, uint32_t l,
+          std::string d, std::string e)
+      {
+        name = n;
+        type = t;
+        level = l;
+        description = d;
+        edit_method = e;
+      }
+      virtual ~AbstractParamDescription() = default;
+
+      virtual void clamp(NonLinearMPCConfig &config, const NonLinearMPCConfig &max, const NonLinearMPCConfig &min) const = 0;
+      virtual void calcLevel(uint32_t &level, const NonLinearMPCConfig &config1, const NonLinearMPCConfig &config2) const = 0;
+      virtual void fromServer(const ros::NodeHandle &nh, NonLinearMPCConfig &config) const = 0;
+      virtual void toServer(const ros::NodeHandle &nh, const NonLinearMPCConfig &config) const = 0;
+      virtual bool fromMessage(const dynamic_reconfigure::Config &msg, NonLinearMPCConfig &config) const = 0;
+      virtual void toMessage(dynamic_reconfigure::Config &msg, const NonLinearMPCConfig &config) const = 0;
+      virtual void getValue(const NonLinearMPCConfig &config, boost::any &val) const = 0;
+    };
+
+    typedef boost::shared_ptr<AbstractParamDescription> AbstractParamDescriptionPtr;
+    typedef boost::shared_ptr<const AbstractParamDescription> AbstractParamDescriptionConstPtr;
+
+    // Final keyword added to class because it has virtual methods and inherits
+    // from a class with a non-virtual destructor.
+    template <class T>
+    class ParamDescription DYNAMIC_RECONFIGURE_FINAL : public AbstractParamDescription
+    {
+    public:
+      ParamDescription(std::string a_name, std::string a_type, uint32_t a_level,
+          std::string a_description, std::string a_edit_method, T NonLinearMPCConfig::* a_f) :
+        AbstractParamDescription(a_name, a_type, a_level, a_description, a_edit_method),
+        field(a_f)
+      {}
+
+      T NonLinearMPCConfig::* field;
+
+      virtual void clamp(NonLinearMPCConfig &config, const NonLinearMPCConfig &max, const NonLinearMPCConfig &min) const override
+      {
+        if (config.*field > max.*field)
+          config.*field = max.*field;
+
+        if (config.*field < min.*field)
+          config.*field = min.*field;
+      }
+
+      virtual void calcLevel(uint32_t &comb_level, const NonLinearMPCConfig &config1, const NonLinearMPCConfig &config2) const override
+      {
+        if (config1.*field != config2.*field)
+          comb_level |= level;
+      }
+
+      virtual void fromServer(const ros::NodeHandle &nh, NonLinearMPCConfig &config) const override
+      {
+        nh.getParam(name, config.*field);
+      }
+
+      virtual void toServer(const ros::NodeHandle &nh, const NonLinearMPCConfig &config) const override
+      {
+        nh.setParam(name, config.*field);
+      }
+
+      virtual bool fromMessage(const dynamic_reconfigure::Config &msg, NonLinearMPCConfig &config) const override
+      {
+        return dynamic_reconfigure::ConfigTools::getParameter(msg, name, config.*field);
+      }
+
+      virtual void toMessage(dynamic_reconfigure::Config &msg, const NonLinearMPCConfig &config) const override
+      {
+        dynamic_reconfigure::ConfigTools::appendParameter(msg, name, config.*field);
+      }
+
+      virtual void getValue(const NonLinearMPCConfig &config, boost::any &val) const override
+      {
+        val = config.*field;
+      }
+    };
+
+    class AbstractGroupDescription : public dynamic_reconfigure::Group
+    {
+      public:
+      AbstractGroupDescription(std::string n, std::string t, int p, int i, bool s)
+      {
+        name = n;
+        type = t;
+        parent = p;
+        state = s;
+        id = i;
+      }
+
+      virtual ~AbstractGroupDescription() = default;
+
+      std::vector<AbstractParamDescriptionConstPtr> abstract_parameters;
+      bool state;
+
+      virtual void toMessage(dynamic_reconfigure::Config &msg, const boost::any &config) const = 0;
+      virtual bool fromMessage(const dynamic_reconfigure::Config &msg, boost::any &config) const =0;
+      virtual void updateParams(boost::any &cfg, NonLinearMPCConfig &top) const= 0;
+      virtual void setInitialState(boost::any &cfg) const = 0;
+
+
+      void convertParams()
+      {
+        for(std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = abstract_parameters.begin(); i != abstract_parameters.end(); ++i)
+        {
+          parameters.push_back(dynamic_reconfigure::ParamDescription(**i));
+        }
+      }
+    };
+
+    typedef boost::shared_ptr<AbstractGroupDescription> AbstractGroupDescriptionPtr;
+    typedef boost::shared_ptr<const AbstractGroupDescription> AbstractGroupDescriptionConstPtr;
+
+    // Final keyword added to class because it has virtual methods and inherits
+    // from a class with a non-virtual destructor.
+    template<class T, class PT>
+    class GroupDescription DYNAMIC_RECONFIGURE_FINAL : public AbstractGroupDescription
+    {
+    public:
+      GroupDescription(std::string a_name, std::string a_type, int a_parent, int a_id, bool a_s, T PT::* a_f) : AbstractGroupDescription(a_name, a_type, a_parent, a_id, a_s), field(a_f)
+      {
+      }
+
+      GroupDescription(const GroupDescription<T, PT>& g): AbstractGroupDescription(g.name, g.type, g.parent, g.id, g.state), field(g.field), groups(g.groups)
+      {
+        parameters = g.parameters;
+        abstract_parameters = g.abstract_parameters;
+      }
+
+      virtual bool fromMessage(const dynamic_reconfigure::Config &msg, boost::any &cfg) const override
+      {
+        PT* config = boost::any_cast<PT*>(cfg);
+        if(!dynamic_reconfigure::ConfigTools::getGroupState(msg, name, (*config).*field))
+          return false;
+
+        for(std::vector<AbstractGroupDescriptionConstPtr>::const_iterator i = groups.begin(); i != groups.end(); ++i)
+        {
+          boost::any n = &((*config).*field);
+          if(!(*i)->fromMessage(msg, n))
+            return false;
+        }
+
+        return true;
+      }
+
+      virtual void setInitialState(boost::any &cfg) const override
+      {
+        PT* config = boost::any_cast<PT*>(cfg);
+        T* group = &((*config).*field);
+        group->state = state;
+
+        for(std::vector<AbstractGroupDescriptionConstPtr>::const_iterator i = groups.begin(); i != groups.end(); ++i)
+        {
+          boost::any n = boost::any(&((*config).*field));
+          (*i)->setInitialState(n);
+        }
+
+      }
+
+      virtual void updateParams(boost::any &cfg, NonLinearMPCConfig &top) const override
+      {
+        PT* config = boost::any_cast<PT*>(cfg);
+
+        T* f = &((*config).*field);
+        f->setParams(top, abstract_parameters);
+
+        for(std::vector<AbstractGroupDescriptionConstPtr>::const_iterator i = groups.begin(); i != groups.end(); ++i)
+        {
+          boost::any n = &((*config).*field);
+          (*i)->updateParams(n, top);
+        }
+      }
+
+      virtual void toMessage(dynamic_reconfigure::Config &msg, const boost::any &cfg) const override
+      {
+        const PT config = boost::any_cast<PT>(cfg);
+        dynamic_reconfigure::ConfigTools::appendGroup<T>(msg, name, id, parent, config.*field);
+
+        for(std::vector<AbstractGroupDescriptionConstPtr>::const_iterator i = groups.begin(); i != groups.end(); ++i)
+        {
+          (*i)->toMessage(msg, config.*field);
+        }
+      }
+
+      T PT::* field;
+      std::vector<NonLinearMPCConfig::AbstractGroupDescriptionConstPtr> groups;
+    };
+
+class DEFAULT
+{
+  public:
+    DEFAULT()
+    {
+      state = true;
+      name = "Default";
+    }
+
+    void setParams(NonLinearMPCConfig &config, const std::vector<AbstractParamDescriptionConstPtr> params)
+    {
+      for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator _i = params.begin(); _i != params.end(); ++_i)
+      {
+        boost::any val;
+        (*_i)->getValue(config, val);
+
+        if("q_x"==(*_i)->name){q_x = boost::any_cast<double>(val);}
+        if("q_y"==(*_i)->name){q_y = boost::any_cast<double>(val);}
+        if("q_z"==(*_i)->name){q_z = boost::any_cast<double>(val);}
+        if("q_vx"==(*_i)->name){q_vx = boost::any_cast<double>(val);}
+        if("q_vy"==(*_i)->name){q_vy = boost::any_cast<double>(val);}
+        if("q_vz"==(*_i)->name){q_vz = boost::any_cast<double>(val);}
+        if("q_roll"==(*_i)->name){q_roll = boost::any_cast<double>(val);}
+        if("q_pitch"==(*_i)->name){q_pitch = boost::any_cast<double>(val);}
+        if("r_roll"==(*_i)->name){r_roll = boost::any_cast<double>(val);}
+        if("r_pitch"==(*_i)->name){r_pitch = boost::any_cast<double>(val);}
+        if("r_thrust"==(*_i)->name){r_thrust = boost::any_cast<double>(val);}
+        if("roll_max"==(*_i)->name){roll_max = boost::any_cast<double>(val);}
+        if("pitch_max"==(*_i)->name){pitch_max = boost::any_cast<double>(val);}
+        if("yaw_rate_max"==(*_i)->name){yaw_rate_max = boost::any_cast<double>(val);}
+        if("thrust_min"==(*_i)->name){thrust_min = boost::any_cast<double>(val);}
+        if("thrust_max"==(*_i)->name){thrust_max = boost::any_cast<double>(val);}
+        if("K_yaw"==(*_i)->name){K_yaw = boost::any_cast<double>(val);}
+        if("Ki_xy"==(*_i)->name){Ki_xy = boost::any_cast<double>(val);}
+        if("Ki_altitude"==(*_i)->name){Ki_altitude = boost::any_cast<double>(val);}
+        if("enable_offset_free"==(*_i)->name){enable_offset_free = boost::any_cast<bool>(val);}
+        if("enable_integrator"==(*_i)->name){enable_integrator = boost::any_cast<bool>(val);}
+      }
+    }
+
+    double q_x;
+double q_y;
+double q_z;
+double q_vx;
+double q_vy;
+double q_vz;
+double q_roll;
+double q_pitch;
+double r_roll;
+double r_pitch;
+double r_thrust;
+double roll_max;
+double pitch_max;
+double yaw_rate_max;
+double thrust_min;
+double thrust_max;
+double K_yaw;
+double Ki_xy;
+double Ki_altitude;
+bool enable_offset_free;
+bool enable_integrator;
+
+    bool state;
+    std::string name;
+
+    
+}groups;
+
+
+
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      double q_x;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      double q_y;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      double q_z;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      double q_vx;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      double q_vy;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      double q_vz;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      double q_roll;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      double q_pitch;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      double r_roll;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      double r_pitch;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      double r_thrust;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      double roll_max;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      double pitch_max;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      double yaw_rate_max;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      double thrust_min;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      double thrust_max;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      double K_yaw;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      double Ki_xy;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      double Ki_altitude;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      bool enable_offset_free;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      bool enable_integrator;
+//#line 231 "/opt/ros/noetic/share/dynamic_reconfigure/cmake/../templates/ConfigType.h.template"
+
+    bool __fromMessage__(dynamic_reconfigure::Config &msg)
+    {
+      const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
+      const std::vector<AbstractGroupDescriptionConstPtr> &__group_descriptions__ = __getGroupDescriptions__();
+
+      int count = 0;
+      for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); ++i)
+        if ((*i)->fromMessage(msg, *this))
+          count++;
+
+      for (std::vector<AbstractGroupDescriptionConstPtr>::const_iterator i = __group_descriptions__.begin(); i != __group_descriptions__.end(); i ++)
+      {
+        if ((*i)->id == 0)
+        {
+          boost::any n = boost::any(this);
+          (*i)->updateParams(n, *this);
+          (*i)->fromMessage(msg, n);
+        }
+      }
+
+      if (count != dynamic_reconfigure::ConfigTools::size(msg))
+      {
+        ROS_ERROR("NonLinearMPCConfig::__fromMessage__ called with an unexpected parameter.");
+        ROS_ERROR("Booleans:");
+        for (unsigned int i = 0; i < msg.bools.size(); i++)
+          ROS_ERROR("  %s", msg.bools[i].name.c_str());
+        ROS_ERROR("Integers:");
+        for (unsigned int i = 0; i < msg.ints.size(); i++)
+          ROS_ERROR("  %s", msg.ints[i].name.c_str());
+        ROS_ERROR("Doubles:");
+        for (unsigned int i = 0; i < msg.doubles.size(); i++)
+          ROS_ERROR("  %s", msg.doubles[i].name.c_str());
+        ROS_ERROR("Strings:");
+        for (unsigned int i = 0; i < msg.strs.size(); i++)
+          ROS_ERROR("  %s", msg.strs[i].name.c_str());
+        // @todo Check that there are no duplicates. Make this error more
+        // explicit.
+        return false;
+      }
+      return true;
+    }
+
+    // This version of __toMessage__ is used during initialization of
+    // statics when __getParamDescriptions__ can't be called yet.
+    void __toMessage__(dynamic_reconfigure::Config &msg, const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__, const std::vector<AbstractGroupDescriptionConstPtr> &__group_descriptions__) const
+    {
+      dynamic_reconfigure::ConfigTools::clear(msg);
+      for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); ++i)
+        (*i)->toMessage(msg, *this);
+
+      for (std::vector<AbstractGroupDescriptionConstPtr>::const_iterator i = __group_descriptions__.begin(); i != __group_descriptions__.end(); ++i)
+      {
+        if((*i)->id == 0)
+        {
+          (*i)->toMessage(msg, *this);
+        }
+      }
+    }
+
+    void __toMessage__(dynamic_reconfigure::Config &msg) const
+    {
+      const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
+      const std::vector<AbstractGroupDescriptionConstPtr> &__group_descriptions__ = __getGroupDescriptions__();
+      __toMessage__(msg, __param_descriptions__, __group_descriptions__);
+    }
+
+    void __toServer__(const ros::NodeHandle &nh) const
+    {
+      const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
+      for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); ++i)
+        (*i)->toServer(nh, *this);
+    }
+
+    void __fromServer__(const ros::NodeHandle &nh)
+    {
+      static bool setup=false;
+
+      const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
+      for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); ++i)
+        (*i)->fromServer(nh, *this);
+
+      const std::vector<AbstractGroupDescriptionConstPtr> &__group_descriptions__ = __getGroupDescriptions__();
+      for (std::vector<AbstractGroupDescriptionConstPtr>::const_iterator i = __group_descriptions__.begin(); i != __group_descriptions__.end(); i++){
+        if (!setup && (*i)->id == 0) {
+          setup = true;
+          boost::any n = boost::any(this);
+          (*i)->setInitialState(n);
+        }
+      }
+    }
+
+    void __clamp__()
+    {
+      const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
+      const NonLinearMPCConfig &__max__ = __getMax__();
+      const NonLinearMPCConfig &__min__ = __getMin__();
+      for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); ++i)
+        (*i)->clamp(*this, __max__, __min__);
+    }
+
+    uint32_t __level__(const NonLinearMPCConfig &config) const
+    {
+      const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
+      uint32_t level = 0;
+      for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); ++i)
+        (*i)->calcLevel(level, config, *this);
+      return level;
+    }
+
+    static const dynamic_reconfigure::ConfigDescription &__getDescriptionMessage__();
+    static const NonLinearMPCConfig &__getDefault__();
+    static const NonLinearMPCConfig &__getMax__();
+    static const NonLinearMPCConfig &__getMin__();
+    static const std::vector<AbstractParamDescriptionConstPtr> &__getParamDescriptions__();
+    static const std::vector<AbstractGroupDescriptionConstPtr> &__getGroupDescriptions__();
+
+  private:
+    static const NonLinearMPCConfigStatics *__get_statics__();
+  };
+
+  template <> // Max and min are ignored for strings.
+  inline void NonLinearMPCConfig::ParamDescription<std::string>::clamp(NonLinearMPCConfig &config, const NonLinearMPCConfig &max, const NonLinearMPCConfig &min) const
+  {
+    (void) config;
+    (void) min;
+    (void) max;
+    return;
+  }
+
+  class NonLinearMPCConfigStatics
+  {
+    friend class NonLinearMPCConfig;
+
+    NonLinearMPCConfigStatics()
+    {
+NonLinearMPCConfig::GroupDescription<NonLinearMPCConfig::DEFAULT, NonLinearMPCConfig> Default("Default", "", 0, 0, true, &NonLinearMPCConfig::groups);
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.q_x = 0.001;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.q_x = 200.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.q_x = 50.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("q_x", "double", 0, "Penality on x axis pos", "", &NonLinearMPCConfig::q_x)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("q_x", "double", 0, "Penality on x axis pos", "", &NonLinearMPCConfig::q_x)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.q_y = 0.001;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.q_y = 200.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.q_y = 50.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("q_y", "double", 0, "Penality on y axis pos", "", &NonLinearMPCConfig::q_y)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("q_y", "double", 0, "Penality on y axis pos", "", &NonLinearMPCConfig::q_y)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.q_z = 0.001;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.q_z = 200.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.q_z = 80.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("q_z", "double", 0, "Penality on z axis pos", "", &NonLinearMPCConfig::q_z)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("q_z", "double", 0, "Penality on z axis pos", "", &NonLinearMPCConfig::q_z)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.q_vx = 0.001;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.q_vx = 200.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.q_vx = 20.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("q_vx", "double", 0, "Penality on x axis vel", "", &NonLinearMPCConfig::q_vx)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("q_vx", "double", 0, "Penality on x axis vel", "", &NonLinearMPCConfig::q_vx)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.q_vy = 0.001;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.q_vy = 200.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.q_vy = 20.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("q_vy", "double", 0, "Penality on y axis vel", "", &NonLinearMPCConfig::q_vy)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("q_vy", "double", 0, "Penality on y axis vel", "", &NonLinearMPCConfig::q_vy)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.q_vz = 0.001;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.q_vz = 200.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.q_vz = 35.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("q_vz", "double", 0, "Penality on z axis vel", "", &NonLinearMPCConfig::q_vz)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("q_vz", "double", 0, "Penality on z axis vel", "", &NonLinearMPCConfig::q_vz)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.q_roll = 0.001;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.q_roll = 200.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.q_roll = 20.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("q_roll", "double", 0, "Penality on roll state", "", &NonLinearMPCConfig::q_roll)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("q_roll", "double", 0, "Penality on roll state", "", &NonLinearMPCConfig::q_roll)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.q_pitch = 0.001;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.q_pitch = 200.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.q_pitch = 20.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("q_pitch", "double", 0, "Penality on pitch state", "", &NonLinearMPCConfig::q_pitch)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("q_pitch", "double", 0, "Penality on pitch state", "", &NonLinearMPCConfig::q_pitch)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.r_roll = 1.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.r_roll = 200.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.r_roll = 30.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("r_roll", "double", 0, "Penality on roll cmd", "", &NonLinearMPCConfig::r_roll)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("r_roll", "double", 0, "Penality on roll cmd", "", &NonLinearMPCConfig::r_roll)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.r_pitch = 1.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.r_pitch = 200.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.r_pitch = 30.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("r_pitch", "double", 0, "Penality on pitch cmd", "", &NonLinearMPCConfig::r_pitch)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("r_pitch", "double", 0, "Penality on pitch cmd", "", &NonLinearMPCConfig::r_pitch)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.r_thrust = 1.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.r_thrust = 200.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.r_thrust = 5.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("r_thrust", "double", 0, "Penality on thrust cmd", "", &NonLinearMPCConfig::r_thrust)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("r_thrust", "double", 0, "Penality on thrust cmd", "", &NonLinearMPCConfig::r_thrust)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.roll_max = 0.1;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.roll_max = 1.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.roll_max = 0.45;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("roll_max", "double", 0, "max roll cmd [rad]", "", &NonLinearMPCConfig::roll_max)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("roll_max", "double", 0, "max roll cmd [rad]", "", &NonLinearMPCConfig::roll_max)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.pitch_max = 0.1;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.pitch_max = 1.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.pitch_max = 0.45;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("pitch_max", "double", 0, "max pitch cmd [rad]", "", &NonLinearMPCConfig::pitch_max)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("pitch_max", "double", 0, "max pitch cmd [rad]", "", &NonLinearMPCConfig::pitch_max)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.yaw_rate_max = 0.1;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.yaw_rate_max = 2.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.yaw_rate_max = 1.5;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("yaw_rate_max", "double", 0, "max yawrate cmd [rad/s]", "", &NonLinearMPCConfig::yaw_rate_max)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("yaw_rate_max", "double", 0, "max yawrate cmd [rad/s]", "", &NonLinearMPCConfig::yaw_rate_max)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.thrust_min = 5.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.thrust_min = 25.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.thrust_min = 5.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("thrust_min", "double", 0, "min thrust cmd [m/s2]", "", &NonLinearMPCConfig::thrust_min)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("thrust_min", "double", 0, "min thrust cmd [m/s2]", "", &NonLinearMPCConfig::thrust_min)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.thrust_max = 5.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.thrust_max = 25.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.thrust_max = 15.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("thrust_max", "double", 0, "max thrust cmd [m/s2]", "", &NonLinearMPCConfig::thrust_max)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("thrust_max", "double", 0, "max thrust cmd [m/s2]", "", &NonLinearMPCConfig::thrust_max)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.K_yaw = 0.01;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.K_yaw = 2.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.K_yaw = 0.5;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("K_yaw", "double", 0, "yaw gain", "", &NonLinearMPCConfig::K_yaw)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("K_yaw", "double", 0, "yaw gain", "", &NonLinearMPCConfig::K_yaw)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.Ki_xy = 0.01;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.Ki_xy = 3.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.Ki_xy = 0.2;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("Ki_xy", "double", 0, "integrator gain for xy", "", &NonLinearMPCConfig::Ki_xy)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("Ki_xy", "double", 0, "integrator gain for xy", "", &NonLinearMPCConfig::Ki_xy)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.Ki_altitude = 0.01;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.Ki_altitude = 3.0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.Ki_altitude = 0.2;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("Ki_altitude", "double", 0, "integrator gain for altitude", "", &NonLinearMPCConfig::Ki_altitude)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<double>("Ki_altitude", "double", 0, "integrator gain for altitude", "", &NonLinearMPCConfig::Ki_altitude)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.enable_offset_free = 0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.enable_offset_free = 1;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.enable_offset_free = 1;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<bool>("enable_offset_free", "bool", 0, "XY offset free MPC", "", &NonLinearMPCConfig::enable_offset_free)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<bool>("enable_offset_free", "bool", 0, "XY offset free MPC", "", &NonLinearMPCConfig::enable_offset_free)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __min__.enable_integrator = 0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __max__.enable_integrator = 1;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __default__.enable_integrator = 0;
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.abstract_parameters.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<bool>("enable_integrator", "bool", 0, "integral action", "", &NonLinearMPCConfig::enable_integrator)));
+//#line 291 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __param_descriptions__.push_back(NonLinearMPCConfig::AbstractParamDescriptionConstPtr(new NonLinearMPCConfig::ParamDescription<bool>("enable_integrator", "bool", 0, "integral action", "", &NonLinearMPCConfig::enable_integrator)));
+//#line 246 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      Default.convertParams();
+//#line 246 "/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py"
+      __group_descriptions__.push_back(NonLinearMPCConfig::AbstractGroupDescriptionConstPtr(new NonLinearMPCConfig::GroupDescription<NonLinearMPCConfig::DEFAULT, NonLinearMPCConfig>(Default)));
+//#line 369 "/opt/ros/noetic/share/dynamic_reconfigure/cmake/../templates/ConfigType.h.template"
+
+      for (std::vector<NonLinearMPCConfig::AbstractGroupDescriptionConstPtr>::const_iterator i = __group_descriptions__.begin(); i != __group_descriptions__.end(); ++i)
+      {
+        __description_message__.groups.push_back(**i);
+      }
+      __max__.__toMessage__(__description_message__.max, __param_descriptions__, __group_descriptions__);
+      __min__.__toMessage__(__description_message__.min, __param_descriptions__, __group_descriptions__);
+      __default__.__toMessage__(__description_message__.dflt, __param_descriptions__, __group_descriptions__);
+    }
+    std::vector<NonLinearMPCConfig::AbstractParamDescriptionConstPtr> __param_descriptions__;
+    std::vector<NonLinearMPCConfig::AbstractGroupDescriptionConstPtr> __group_descriptions__;
+    NonLinearMPCConfig __max__;
+    NonLinearMPCConfig __min__;
+    NonLinearMPCConfig __default__;
+    dynamic_reconfigure::ConfigDescription __description_message__;
+
+    static const NonLinearMPCConfigStatics *get_instance()
+    {
+      // Split this off in a separate function because I know that
+      // instance will get initialized the first time get_instance is
+      // called, and I am guaranteeing that get_instance gets called at
+      // most once.
+      static NonLinearMPCConfigStatics instance;
+      return &instance;
+    }
+  };
+
+  inline const dynamic_reconfigure::ConfigDescription &NonLinearMPCConfig::__getDescriptionMessage__()
+  {
+    return __get_statics__()->__description_message__;
+  }
+
+  inline const NonLinearMPCConfig &NonLinearMPCConfig::__getDefault__()
+  {
+    return __get_statics__()->__default__;
+  }
+
+  inline const NonLinearMPCConfig &NonLinearMPCConfig::__getMax__()
+  {
+    return __get_statics__()->__max__;
+  }
+
+  inline const NonLinearMPCConfig &NonLinearMPCConfig::__getMin__()
+  {
+    return __get_statics__()->__min__;
+  }
+
+  inline const std::vector<NonLinearMPCConfig::AbstractParamDescriptionConstPtr> &NonLinearMPCConfig::__getParamDescriptions__()
+  {
+    return __get_statics__()->__param_descriptions__;
+  }
+
+  inline const std::vector<NonLinearMPCConfig::AbstractGroupDescriptionConstPtr> &NonLinearMPCConfig::__getGroupDescriptions__()
+  {
+    return __get_statics__()->__group_descriptions__;
+  }
+
+  inline const NonLinearMPCConfigStatics *NonLinearMPCConfig::__get_statics__()
+  {
+    const static NonLinearMPCConfigStatics *statics;
+
+    if (statics) // Common case
+      return statics;
+
+    boost::mutex::scoped_lock lock(dynamic_reconfigure::__init_mutex__);
+
+    if (statics) // In case we lost a race.
+      return statics;
+
+    statics = NonLinearMPCConfigStatics::get_instance();
+
+    return statics;
+  }
+
+
+}
+
+#undef DYNAMIC_RECONFIGURE_FINAL
+
+#endif // __NONLINEARMPCRECONFIGURATOR_H__
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/libmav_nonlinear_mpc_lib.so b/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/libmav_nonlinear_mpc_lib.so
new file mode 100644
index 0000000000000000000000000000000000000000..1f13a2b7a7b83fd73873af00e4149829caaaedf2
Binary files /dev/null and b/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/libmav_nonlinear_mpc_lib.so differ
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node b/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node
new file mode 100644
index 0000000000000000000000000000000000000000..89d7309b9e8932db3f8dc65fd58440511a5db997
Binary files /dev/null and b/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/mav_nonlinear_mpc/nonlinear_mpc_node differ
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/pkgconfig/mav_nonlinear_mpc.pc b/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/pkgconfig/mav_nonlinear_mpc.pc
new file mode 100644
index 0000000000000000000000000000000000000000..2b1836670a75fee54d850abd1d84e934f4ed00c3
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/pkgconfig/mav_nonlinear_mpc.pc
@@ -0,0 +1,8 @@
+prefix=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel
+
+Name: mav_nonlinear_mpc
+Description: Description of mav_nonlinear_mpc
+Version: 1.0.0
+Cflags: -I/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/include -I/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/include
+Libs: -L${prefix}/lib -lmav_nonlinear_mpc_lib
+Requires: std_msgs cmake_modules roscpp dynamic_reconfigure tf
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/python3/dist-packages/mav_nonlinear_mpc/__init__.py b/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/python3/dist-packages/mav_nonlinear_mpc/__init__.py
new file mode 100644
index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/python3/dist-packages/mav_nonlinear_mpc/cfg/NonLinearMPCConfig.py b/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/python3/dist-packages/mav_nonlinear_mpc/cfg/NonLinearMPCConfig.py
new file mode 100644
index 0000000000000000000000000000000000000000..0063e6f361e5cde8b25074fa843520551f7387c4
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/python3/dist-packages/mav_nonlinear_mpc/cfg/NonLinearMPCConfig.py
@@ -0,0 +1,36 @@
+## *********************************************************
+##
+## File autogenerated for the mav_nonlinear_mpc package
+## by the dynamic_reconfigure package.
+## Please do not edit.
+##
+## ********************************************************/
+
+from dynamic_reconfigure.encoding import extract_params
+
+inf = float('inf')
+
+config_description = {'name': 'Default', 'type': '', 'state': True, 'cstate': 'true', 'id': 0, 'parent': 0, 'parameters': [{'name': 'q_x', 'type': 'double', 'default': 50.0, 'level': 0, 'description': 'Penality on x axis pos', 'min': 0.001, 'max': 200.0, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'double', 'cconsttype': 'const double'}, {'name': 'q_y', 'type': 'double', 'default': 50.0, 'level': 0, 'description': 'Penality on y axis pos', 'min': 0.001, 'max': 200.0, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'double', 'cconsttype': 'const double'}, {'name': 'q_z', 'type': 'double', 'default': 80.0, 'level': 0, 'description': 'Penality on z axis pos', 'min': 0.001, 'max': 200.0, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'double', 'cconsttype': 'const double'}, {'name': 'q_vx', 'type': 'double', 'default': 20.0, 'level': 0, 'description': 'Penality on x axis vel', 'min': 0.001, 'max': 200.0, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'double', 'cconsttype': 'const double'}, {'name': 'q_vy', 'type': 'double', 'default': 20.0, 'level': 0, 'description': 'Penality on y axis vel', 'min': 0.001, 'max': 200.0, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'double', 'cconsttype': 'const double'}, {'name': 'q_vz', 'type': 'double', 'default': 35.0, 'level': 0, 'description': 'Penality on z axis vel', 'min': 0.001, 'max': 200.0, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'double', 'cconsttype': 'const double'}, {'name': 'q_roll', 'type': 'double', 'default': 20.0, 'level': 0, 'description': 'Penality on roll state', 'min': 0.001, 'max': 200.0, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'double', 'cconsttype': 'const double'}, {'name': 'q_pitch', 'type': 'double', 'default': 20.0, 'level': 0, 'description': 'Penality on pitch state', 'min': 0.001, 'max': 200.0, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'double', 'cconsttype': 'const double'}, {'name': 'r_roll', 'type': 'double', 'default': 30.0, 'level': 0, 'description': 'Penality on roll cmd', 'min': 1.0, 'max': 200.0, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'double', 'cconsttype': 'const double'}, {'name': 'r_pitch', 'type': 'double', 'default': 30.0, 'level': 0, 'description': 'Penality on pitch cmd', 'min': 1.0, 'max': 200.0, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'double', 'cconsttype': 'const double'}, {'name': 'r_thrust', 'type': 'double', 'default': 5.0, 'level': 0, 'description': 'Penality on thrust cmd', 'min': 1.0, 'max': 200.0, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'double', 'cconsttype': 'const double'}, {'name': 'roll_max', 'type': 'double', 'default': 0.45, 'level': 0, 'description': 'max roll cmd [rad]', 'min': 0.1, 'max': 1.0, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'double', 'cconsttype': 'const double'}, {'name': 'pitch_max', 'type': 'double', 'default': 0.45, 'level': 0, 'description': 'max pitch cmd [rad]', 'min': 0.1, 'max': 1.0, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'double', 'cconsttype': 'const double'}, {'name': 'yaw_rate_max', 'type': 'double', 'default': 1.5, 'level': 0, 'description': 'max yawrate cmd [rad/s]', 'min': 0.1, 'max': 2.0, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'double', 'cconsttype': 'const double'}, {'name': 'thrust_min', 'type': 'double', 'default': 5.0, 'level': 0, 'description': 'min thrust cmd [m/s2]', 'min': 5.0, 'max': 25.0, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'double', 'cconsttype': 'const double'}, {'name': 'thrust_max', 'type': 'double', 'default': 15.0, 'level': 0, 'description': 'max thrust cmd [m/s2]', 'min': 5.0, 'max': 25.0, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'double', 'cconsttype': 'const double'}, {'name': 'K_yaw', 'type': 'double', 'default': 0.5, 'level': 0, 'description': 'yaw gain', 'min': 0.01, 'max': 2.0, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'double', 'cconsttype': 'const double'}, {'name': 'Ki_xy', 'type': 'double', 'default': 0.2, 'level': 0, 'description': 'integrator gain for xy', 'min': 0.01, 'max': 3.0, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'double', 'cconsttype': 'const double'}, {'name': 'Ki_altitude', 'type': 'double', 'default': 0.2, 'level': 0, 'description': 'integrator gain for altitude', 'min': 0.01, 'max': 3.0, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'double', 'cconsttype': 'const double'}, {'name': 'enable_offset_free', 'type': 'bool', 'default': True, 'level': 0, 'description': 'XY offset free MPC', 'min': False, 'max': True, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'bool', 'cconsttype': 'const bool'}, {'name': 'enable_integrator', 'type': 'bool', 'default': False, 'level': 0, 'description': 'integral action', 'min': False, 'max': True, 'srcline': 291, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'edit_method': '', 'ctype': 'bool', 'cconsttype': 'const bool'}], 'groups': [], 'srcline': 246, 'srcfile': '/opt/ros/noetic/lib/python3/dist-packages/dynamic_reconfigure/parameter_generator_catkin.py', 'class': 'DEFAULT', 'parentclass': '', 'parentname': 'Default', 'field': 'default', 'upper': 'DEFAULT', 'lower': 'groups'}
+
+min = {}
+max = {}
+defaults = {}
+level = {}
+type = {}
+all_level = 0
+
+#def extract_params(config):
+#    params = []
+#    params.extend(config['parameters'])
+#    for group in config['groups']:
+#        params.extend(extract_params(group))
+#    return params
+
+for param in extract_params(config_description):
+    min[param['name']] = param['min']
+    max[param['name']] = param['max']
+    defaults[param['name']] = param['default']
+    level[param['name']] = param['level']
+    type[param['name']] = param['type']
+    all_level = all_level | param['level']
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/python3/dist-packages/mav_nonlinear_mpc/cfg/__init__.py b/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/python3/dist-packages/mav_nonlinear_mpc/cfg/__init__.py
new file mode 100644
index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/local_setup.bash b/mav_control_rw/mav_nonlinear_mpc/solver/devel/local_setup.bash
new file mode 100644
index 0000000000000000000000000000000000000000..7da0d973d481c97d4aba63ab3a070fdc192dc3f8
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/devel/local_setup.bash
@@ -0,0 +1,8 @@
+#!/usr/bin/env bash
+# generated from catkin/cmake/templates/local_setup.bash.in
+
+CATKIN_SHELL=bash
+
+# source setup.sh from same directory as this file
+_CATKIN_SETUP_DIR=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null && pwd)
+. "$_CATKIN_SETUP_DIR/setup.sh" --extend --local
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/local_setup.sh b/mav_control_rw/mav_nonlinear_mpc/solver/devel/local_setup.sh
new file mode 100644
index 0000000000000000000000000000000000000000..644075365eab616dfdd29c936fd19e6837aeadfd
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/devel/local_setup.sh
@@ -0,0 +1,9 @@
+#!/usr/bin/env sh
+# generated from catkin/cmake/template/local_setup.sh.in
+
+# since this file is sourced either use the provided _CATKIN_SETUP_DIR
+# or fall back to the destination set at configure time
+: ${_CATKIN_SETUP_DIR:=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel}
+CATKIN_SETUP_UTIL_ARGS="--extend --local"
+. "$_CATKIN_SETUP_DIR/setup.sh"
+unset CATKIN_SETUP_UTIL_ARGS
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/local_setup.zsh b/mav_control_rw/mav_nonlinear_mpc/solver/devel/local_setup.zsh
new file mode 100644
index 0000000000000000000000000000000000000000..e692accfd3341ef2f575dec1c83d843bd786107f
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/devel/local_setup.zsh
@@ -0,0 +1,8 @@
+#!/usr/bin/env zsh
+# generated from catkin/cmake/templates/local_setup.zsh.in
+
+CATKIN_SHELL=zsh
+
+# source setup.sh from same directory as this file
+_CATKIN_SETUP_DIR=$(builtin cd -q "`dirname "$0"`" > /dev/null && pwd)
+emulate -R zsh -c 'source "$_CATKIN_SETUP_DIR/setup.sh" --extend --local'
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/setup.bash b/mav_control_rw/mav_nonlinear_mpc/solver/devel/setup.bash
new file mode 100644
index 0000000000000000000000000000000000000000..ff47af8f30bcc54efd5892530c84c4159250d4a3
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/devel/setup.bash
@@ -0,0 +1,8 @@
+#!/usr/bin/env bash
+# generated from catkin/cmake/templates/setup.bash.in
+
+CATKIN_SHELL=bash
+
+# source setup.sh from same directory as this file
+_CATKIN_SETUP_DIR=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null && pwd)
+. "$_CATKIN_SETUP_DIR/setup.sh"
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/setup.sh b/mav_control_rw/mav_nonlinear_mpc/solver/devel/setup.sh
new file mode 100644
index 0000000000000000000000000000000000000000..56b4712095b16c26f031ad40842535a7f2d49b50
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/devel/setup.sh
@@ -0,0 +1,96 @@
+#!/usr/bin/env sh
+# generated from catkin/cmake/template/setup.sh.in
+
+# Sets various environment variables and sources additional environment hooks.
+# It tries it's best to undo changes from a previously sourced setup file before.
+# Supported command line options:
+# --extend: skips the undoing of changes from a previously sourced setup file
+# --local: only considers this workspace but not the chained ones
+# In plain sh shell which doesn't support arguments for sourced scripts you can
+# set the environment variable `CATKIN_SETUP_UTIL_ARGS=--extend/--local` instead.
+
+# since this file is sourced either use the provided _CATKIN_SETUP_DIR
+# or fall back to the destination set at configure time
+: ${_CATKIN_SETUP_DIR:=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel}
+_SETUP_UTIL="$_CATKIN_SETUP_DIR/_setup_util.py"
+unset _CATKIN_SETUP_DIR
+
+if [ ! -f "$_SETUP_UTIL" ]; then
+  echo "Missing Python script: $_SETUP_UTIL"
+  return 22
+fi
+
+# detect if running on Darwin platform
+_UNAME=`uname -s`
+_IS_DARWIN=0
+if [ "$_UNAME" = "Darwin" ]; then
+  _IS_DARWIN=1
+fi
+unset _UNAME
+
+# make sure to export all environment variables
+export CMAKE_PREFIX_PATH
+if [ $_IS_DARWIN -eq 0 ]; then
+  export LD_LIBRARY_PATH
+else
+  export DYLD_LIBRARY_PATH
+fi
+unset _IS_DARWIN
+export PATH
+export PKG_CONFIG_PATH
+export PYTHONPATH
+
+# remember type of shell if not already set
+if [ -z "$CATKIN_SHELL" ]; then
+  CATKIN_SHELL=sh
+fi
+
+# invoke Python script to generate necessary exports of environment variables
+# use TMPDIR if it exists, otherwise fall back to /tmp
+if [ -d "${TMPDIR:-}" ]; then
+  _TMPDIR="${TMPDIR}"
+else
+  _TMPDIR=/tmp
+fi
+_SETUP_TMP=`mktemp "${_TMPDIR}/setup.sh.XXXXXXXXXX"`
+unset _TMPDIR
+if [ $? -ne 0 -o ! -f "$_SETUP_TMP" ]; then
+  echo "Could not create temporary file: $_SETUP_TMP"
+  return 1
+fi
+CATKIN_SHELL=$CATKIN_SHELL "$_SETUP_UTIL" $@ ${CATKIN_SETUP_UTIL_ARGS:-} >> "$_SETUP_TMP"
+_RC=$?
+if [ $_RC -ne 0 ]; then
+  if [ $_RC -eq 2 ]; then
+    echo "Could not write the output of '$_SETUP_UTIL' to temporary file '$_SETUP_TMP': may be the disk if full?"
+  else
+    echo "Failed to run '\"$_SETUP_UTIL\" $@': return code $_RC"
+  fi
+  unset _RC
+  unset _SETUP_UTIL
+  rm -f "$_SETUP_TMP"
+  unset _SETUP_TMP
+  return 1
+fi
+unset _RC
+unset _SETUP_UTIL
+. "$_SETUP_TMP"
+rm -f "$_SETUP_TMP"
+unset _SETUP_TMP
+
+# source all environment hooks
+_i=0
+while [ $_i -lt $_CATKIN_ENVIRONMENT_HOOKS_COUNT ]; do
+  eval _envfile=\$_CATKIN_ENVIRONMENT_HOOKS_$_i
+  unset _CATKIN_ENVIRONMENT_HOOKS_$_i
+  eval _envfile_workspace=\$_CATKIN_ENVIRONMENT_HOOKS_${_i}_WORKSPACE
+  unset _CATKIN_ENVIRONMENT_HOOKS_${_i}_WORKSPACE
+  # set workspace for environment hook
+  CATKIN_ENV_HOOK_WORKSPACE=$_envfile_workspace
+  . "$_envfile"
+  unset CATKIN_ENV_HOOK_WORKSPACE
+  _i=$((_i + 1))
+done
+unset _i
+
+unset _CATKIN_ENVIRONMENT_HOOKS_COUNT
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/setup.zsh b/mav_control_rw/mav_nonlinear_mpc/solver/devel/setup.zsh
new file mode 100644
index 0000000000000000000000000000000000000000..9f780b741031d8037b90514441a80f9fed39d02b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/devel/setup.zsh
@@ -0,0 +1,8 @@
+#!/usr/bin/env zsh
+# generated from catkin/cmake/templates/setup.zsh.in
+
+CATKIN_SHELL=zsh
+
+# source setup.sh from same directory as this file
+_CATKIN_SETUP_DIR=$(builtin cd -q "`dirname "$0"`" > /dev/null && pwd)
+emulate -R zsh -c 'source "$_CATKIN_SETUP_DIR/setup.sh"'
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/share/mav_nonlinear_mpc/cmake/mav_nonlinear_mpcConfig-version.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/devel/share/mav_nonlinear_mpc/cmake/mav_nonlinear_mpcConfig-version.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..de35aa22a9bd546ca9e0b4e63357adc254d83544
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/devel/share/mav_nonlinear_mpc/cmake/mav_nonlinear_mpcConfig-version.cmake
@@ -0,0 +1,14 @@
+# generated from catkin/cmake/template/pkgConfig-version.cmake.in
+set(PACKAGE_VERSION "1.0.0")
+
+set(PACKAGE_VERSION_EXACT False)
+set(PACKAGE_VERSION_COMPATIBLE False)
+
+if("${PACKAGE_FIND_VERSION}" VERSION_EQUAL "${PACKAGE_VERSION}")
+  set(PACKAGE_VERSION_EXACT True)
+  set(PACKAGE_VERSION_COMPATIBLE True)
+endif()
+
+if("${PACKAGE_FIND_VERSION}" VERSION_LESS "${PACKAGE_VERSION}")
+  set(PACKAGE_VERSION_COMPATIBLE True)
+endif()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/share/mav_nonlinear_mpc/cmake/mav_nonlinear_mpcConfig.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/devel/share/mav_nonlinear_mpc/cmake/mav_nonlinear_mpcConfig.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..d09d1535d0d7e3a5dcf6a14abfbba74e56a20a48
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/devel/share/mav_nonlinear_mpc/cmake/mav_nonlinear_mpcConfig.cmake
@@ -0,0 +1,223 @@
+# generated from catkin/cmake/template/pkgConfig.cmake.in
+
+# append elements to a list and remove existing duplicates from the list
+# copied from catkin/cmake/list_append_deduplicate.cmake to keep pkgConfig
+# self contained
+macro(_list_append_deduplicate listname)
+  if(NOT "${ARGN}" STREQUAL "")
+    if(${listname})
+      list(REMOVE_ITEM ${listname} ${ARGN})
+    endif()
+    list(APPEND ${listname} ${ARGN})
+  endif()
+endmacro()
+
+# append elements to a list if they are not already in the list
+# copied from catkin/cmake/list_append_unique.cmake to keep pkgConfig
+# self contained
+macro(_list_append_unique listname)
+  foreach(_item ${ARGN})
+    list(FIND ${listname} ${_item} _index)
+    if(_index EQUAL -1)
+      list(APPEND ${listname} ${_item})
+    endif()
+  endforeach()
+endmacro()
+
+# pack a list of libraries with optional build configuration keywords
+# copied from catkin/cmake/catkin_libraries.cmake to keep pkgConfig
+# self contained
+macro(_pack_libraries_with_build_configuration VAR)
+  set(${VAR} "")
+  set(_argn ${ARGN})
+  list(LENGTH _argn _count)
+  set(_index 0)
+  while(${_index} LESS ${_count})
+    list(GET _argn ${_index} lib)
+    if("${lib}" MATCHES "^(debug|optimized|general)$")
+      math(EXPR _index "${_index} + 1")
+      if(${_index} EQUAL ${_count})
+        message(FATAL_ERROR "_pack_libraries_with_build_configuration() the list of libraries '${ARGN}' ends with '${lib}' which is a build configuration keyword and must be followed by a library")
+      endif()
+      list(GET _argn ${_index} library)
+      list(APPEND ${VAR} "${lib}${CATKIN_BUILD_CONFIGURATION_KEYWORD_SEPARATOR}${library}")
+    else()
+      list(APPEND ${VAR} "${lib}")
+    endif()
+    math(EXPR _index "${_index} + 1")
+  endwhile()
+endmacro()
+
+# unpack a list of libraries with optional build configuration keyword prefixes
+# copied from catkin/cmake/catkin_libraries.cmake to keep pkgConfig
+# self contained
+macro(_unpack_libraries_with_build_configuration VAR)
+  set(${VAR} "")
+  foreach(lib ${ARGN})
+    string(REGEX REPLACE "^(debug|optimized|general)${CATKIN_BUILD_CONFIGURATION_KEYWORD_SEPARATOR}(.+)$" "\\1;\\2" lib "${lib}")
+    list(APPEND ${VAR} "${lib}")
+  endforeach()
+endmacro()
+
+
+if(mav_nonlinear_mpc_CONFIG_INCLUDED)
+  return()
+endif()
+set(mav_nonlinear_mpc_CONFIG_INCLUDED TRUE)
+
+# set variables for source/devel/install prefixes
+if("TRUE" STREQUAL "TRUE")
+  set(mav_nonlinear_mpc_SOURCE_PREFIX /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc)
+  set(mav_nonlinear_mpc_DEVEL_PREFIX /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel)
+  set(mav_nonlinear_mpc_INSTALL_PREFIX "")
+  set(mav_nonlinear_mpc_PREFIX ${mav_nonlinear_mpc_DEVEL_PREFIX})
+else()
+  set(mav_nonlinear_mpc_SOURCE_PREFIX "")
+  set(mav_nonlinear_mpc_DEVEL_PREFIX "")
+  set(mav_nonlinear_mpc_INSTALL_PREFIX /usr/local)
+  set(mav_nonlinear_mpc_PREFIX ${mav_nonlinear_mpc_INSTALL_PREFIX})
+endif()
+
+# warn when using a deprecated package
+if(NOT "" STREQUAL "")
+  set(_msg "WARNING: package 'mav_nonlinear_mpc' is deprecated")
+  # append custom deprecation text if available
+  if(NOT "" STREQUAL "TRUE")
+    set(_msg "${_msg} ()")
+  endif()
+  message("${_msg}")
+endif()
+
+# flag project as catkin-based to distinguish if a find_package()-ed project is a catkin project
+set(mav_nonlinear_mpc_FOUND_CATKIN_PROJECT TRUE)
+
+if(NOT "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/include;/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/include " STREQUAL " ")
+  set(mav_nonlinear_mpc_INCLUDE_DIRS "")
+  set(_include_dirs "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/include;/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/include")
+  if(NOT " " STREQUAL " ")
+    set(_report "Check the issue tracker '' and consider creating a ticket if the problem has not been reported yet.")
+  elseif(NOT " " STREQUAL " ")
+    set(_report "Check the website '' for information and consider reporting the problem.")
+  else()
+    set(_report "Report the problem to the maintainer 'Mina Kamel <mina.kamel@mavt.ethz.com>' and request to fix the problem.")
+  endif()
+  foreach(idir ${_include_dirs})
+    if(IS_ABSOLUTE ${idir} AND IS_DIRECTORY ${idir})
+      set(include ${idir})
+    elseif("${idir} " STREQUAL "include ")
+      get_filename_component(include "${mav_nonlinear_mpc_DIR}/../../../include" ABSOLUTE)
+      if(NOT IS_DIRECTORY ${include})
+        message(FATAL_ERROR "Project 'mav_nonlinear_mpc' specifies '${idir}' as an include dir, which is not found.  It does not exist in '${include}'.  ${_report}")
+      endif()
+    else()
+      message(FATAL_ERROR "Project 'mav_nonlinear_mpc' specifies '${idir}' as an include dir, which is not found.  It does neither exist as an absolute directory nor in '/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/${idir}'.  ${_report}")
+    endif()
+    _list_append_unique(mav_nonlinear_mpc_INCLUDE_DIRS ${include})
+  endforeach()
+endif()
+
+set(libraries "mav_nonlinear_mpc_lib")
+foreach(library ${libraries})
+  # keep build configuration keywords, target names and absolute libraries as-is
+  if("${library}" MATCHES "^(debug|optimized|general)$")
+    list(APPEND mav_nonlinear_mpc_LIBRARIES ${library})
+  elseif(${library} MATCHES "^-l")
+    list(APPEND mav_nonlinear_mpc_LIBRARIES ${library})
+  elseif(${library} MATCHES "^-")
+    # This is a linker flag/option (like -pthread)
+    # There's no standard variable for these, so create an interface library to hold it
+    if(NOT mav_nonlinear_mpc_NUM_DUMMY_TARGETS)
+      set(mav_nonlinear_mpc_NUM_DUMMY_TARGETS 0)
+    endif()
+    # Make sure the target name is unique
+    set(interface_target_name "catkin::mav_nonlinear_mpc::wrapped-linker-option${mav_nonlinear_mpc_NUM_DUMMY_TARGETS}")
+    while(TARGET "${interface_target_name}")
+      math(EXPR mav_nonlinear_mpc_NUM_DUMMY_TARGETS "${mav_nonlinear_mpc_NUM_DUMMY_TARGETS}+1")
+      set(interface_target_name "catkin::mav_nonlinear_mpc::wrapped-linker-option${mav_nonlinear_mpc_NUM_DUMMY_TARGETS}")
+    endwhile()
+    add_library("${interface_target_name}" INTERFACE IMPORTED)
+    if("${CMAKE_VERSION}" VERSION_LESS "3.13.0")
+      set_property(
+        TARGET
+        "${interface_target_name}"
+        APPEND PROPERTY
+        INTERFACE_LINK_LIBRARIES "${library}")
+    else()
+      target_link_options("${interface_target_name}" INTERFACE "${library}")
+    endif()
+    list(APPEND mav_nonlinear_mpc_LIBRARIES "${interface_target_name}")
+  elseif(TARGET ${library})
+    list(APPEND mav_nonlinear_mpc_LIBRARIES ${library})
+  elseif(IS_ABSOLUTE ${library})
+    list(APPEND mav_nonlinear_mpc_LIBRARIES ${library})
+  else()
+    set(lib_path "")
+    set(lib "${library}-NOTFOUND")
+    # since the path where the library is found is returned we have to iterate over the paths manually
+    foreach(path /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib;/home/simhe502/catkin_ws/devel/lib;/opt/ros/noetic/lib)
+      find_library(lib ${library}
+        PATHS ${path}
+        NO_DEFAULT_PATH NO_CMAKE_FIND_ROOT_PATH)
+      if(lib)
+        set(lib_path ${path})
+        break()
+      endif()
+    endforeach()
+    if(lib)
+      _list_append_unique(mav_nonlinear_mpc_LIBRARY_DIRS ${lib_path})
+      list(APPEND mav_nonlinear_mpc_LIBRARIES ${lib})
+    else()
+      # as a fall back for non-catkin libraries try to search globally
+      find_library(lib ${library})
+      if(NOT lib)
+        message(FATAL_ERROR "Project '${PROJECT_NAME}' tried to find library '${library}'.  The library is neither a target nor built/installed properly.  Did you compile project 'mav_nonlinear_mpc'?  Did you find_package() it before the subdirectory containing its code is included?")
+      endif()
+      list(APPEND mav_nonlinear_mpc_LIBRARIES ${lib})
+    endif()
+  endif()
+endforeach()
+
+set(mav_nonlinear_mpc_EXPORTED_TARGETS "mav_nonlinear_mpc_gencfg")
+# create dummy targets for exported code generation targets to make life of users easier
+foreach(t ${mav_nonlinear_mpc_EXPORTED_TARGETS})
+  if(NOT TARGET ${t})
+    add_custom_target(${t})
+  endif()
+endforeach()
+
+set(depends "std_msgs;cmake_modules;roscpp;dynamic_reconfigure;tf")
+foreach(depend ${depends})
+  string(REPLACE " " ";" depend_list ${depend})
+  # the package name of the dependency must be kept in a unique variable so that it is not overwritten in recursive calls
+  list(GET depend_list 0 mav_nonlinear_mpc_dep)
+  list(LENGTH depend_list count)
+  if(${count} EQUAL 1)
+    # simple dependencies must only be find_package()-ed once
+    if(NOT ${mav_nonlinear_mpc_dep}_FOUND)
+      find_package(${mav_nonlinear_mpc_dep} REQUIRED NO_MODULE)
+    endif()
+  else()
+    # dependencies with components must be find_package()-ed again
+    list(REMOVE_AT depend_list 0)
+    find_package(${mav_nonlinear_mpc_dep} REQUIRED NO_MODULE ${depend_list})
+  endif()
+  _list_append_unique(mav_nonlinear_mpc_INCLUDE_DIRS ${${mav_nonlinear_mpc_dep}_INCLUDE_DIRS})
+
+  # merge build configuration keywords with library names to correctly deduplicate
+  _pack_libraries_with_build_configuration(mav_nonlinear_mpc_LIBRARIES ${mav_nonlinear_mpc_LIBRARIES})
+  _pack_libraries_with_build_configuration(_libraries ${${mav_nonlinear_mpc_dep}_LIBRARIES})
+  _list_append_deduplicate(mav_nonlinear_mpc_LIBRARIES ${_libraries})
+  # undo build configuration keyword merging after deduplication
+  _unpack_libraries_with_build_configuration(mav_nonlinear_mpc_LIBRARIES ${mav_nonlinear_mpc_LIBRARIES})
+
+  _list_append_unique(mav_nonlinear_mpc_LIBRARY_DIRS ${${mav_nonlinear_mpc_dep}_LIBRARY_DIRS})
+  _list_append_deduplicate(mav_nonlinear_mpc_EXPORTED_TARGETS ${${mav_nonlinear_mpc_dep}_EXPORTED_TARGETS})
+endforeach()
+
+set(pkg_cfg_extras "")
+foreach(extra ${pkg_cfg_extras})
+  if(NOT IS_ABSOLUTE ${extra})
+    set(extra ${mav_nonlinear_mpc_DIR}/${extra})
+  endif()
+  include(${extra})
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig-usage.dox b/mav_control_rw/mav_nonlinear_mpc/solver/devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig-usage.dox
new file mode 100644
index 0000000000000000000000000000000000000000..9d6183e7f6a133627b014077f1792d4f54c87cbf
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig-usage.dox
@@ -0,0 +1,27 @@
+\subsubsection usage Usage
+\verbatim
+<node name="Config" pkg="mav_nonlinear_mpc" type="Config">
+  <param name="q_x" type="double" value="50.0" />
+  <param name="q_y" type="double" value="50.0" />
+  <param name="q_z" type="double" value="80.0" />
+  <param name="q_vx" type="double" value="20.0" />
+  <param name="q_vy" type="double" value="20.0" />
+  <param name="q_vz" type="double" value="35.0" />
+  <param name="q_roll" type="double" value="20.0" />
+  <param name="q_pitch" type="double" value="20.0" />
+  <param name="r_roll" type="double" value="30.0" />
+  <param name="r_pitch" type="double" value="30.0" />
+  <param name="r_thrust" type="double" value="5.0" />
+  <param name="roll_max" type="double" value="0.45" />
+  <param name="pitch_max" type="double" value="0.45" />
+  <param name="yaw_rate_max" type="double" value="1.5" />
+  <param name="thrust_min" type="double" value="5.0" />
+  <param name="thrust_max" type="double" value="15.0" />
+  <param name="K_yaw" type="double" value="0.5" />
+  <param name="Ki_xy" type="double" value="0.2" />
+  <param name="Ki_altitude" type="double" value="0.2" />
+  <param name="enable_offset_free" type="bool" value="True" />
+  <param name="enable_integrator" type="bool" value="False" />
+</node>
+\endverbatim
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig.dox b/mav_control_rw/mav_nonlinear_mpc/solver/devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig.dox
new file mode 100644
index 0000000000000000000000000000000000000000..87e94e91ebdc7b93a7afaae33c941165d355e791
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig.dox
@@ -0,0 +1,26 @@
+\subsubsection parameters ROS parameters
+
+Reads and maintains the following parameters on the ROS server
+
+- \b "~q_x" : \b [double] Penality on x axis pos min: 0.001, default: 50.0, max: 200.0
+- \b "~q_y" : \b [double] Penality on y axis pos min: 0.001, default: 50.0, max: 200.0
+- \b "~q_z" : \b [double] Penality on z axis pos min: 0.001, default: 80.0, max: 200.0
+- \b "~q_vx" : \b [double] Penality on x axis vel min: 0.001, default: 20.0, max: 200.0
+- \b "~q_vy" : \b [double] Penality on y axis vel min: 0.001, default: 20.0, max: 200.0
+- \b "~q_vz" : \b [double] Penality on z axis vel min: 0.001, default: 35.0, max: 200.0
+- \b "~q_roll" : \b [double] Penality on roll state min: 0.001, default: 20.0, max: 200.0
+- \b "~q_pitch" : \b [double] Penality on pitch state min: 0.001, default: 20.0, max: 200.0
+- \b "~r_roll" : \b [double] Penality on roll cmd min: 1.0, default: 30.0, max: 200.0
+- \b "~r_pitch" : \b [double] Penality on pitch cmd min: 1.0, default: 30.0, max: 200.0
+- \b "~r_thrust" : \b [double] Penality on thrust cmd min: 1.0, default: 5.0, max: 200.0
+- \b "~roll_max" : \b [double] max roll cmd [rad] min: 0.1, default: 0.45, max: 1.0
+- \b "~pitch_max" : \b [double] max pitch cmd [rad] min: 0.1, default: 0.45, max: 1.0
+- \b "~yaw_rate_max" : \b [double] max yawrate cmd [rad/s] min: 0.1, default: 1.5, max: 2.0
+- \b "~thrust_min" : \b [double] min thrust cmd [m/s2] min: 5.0, default: 5.0, max: 25.0
+- \b "~thrust_max" : \b [double] max thrust cmd [m/s2] min: 5.0, default: 15.0, max: 25.0
+- \b "~K_yaw" : \b [double] yaw gain min: 0.01, default: 0.5, max: 2.0
+- \b "~Ki_xy" : \b [double] integrator gain for xy min: 0.01, default: 0.2, max: 3.0
+- \b "~Ki_altitude" : \b [double] integrator gain for altitude min: 0.01, default: 0.2, max: 3.0
+- \b "~enable_offset_free" : \b [bool] XY offset free MPC min: False, default: True, max: True
+- \b "~enable_integrator" : \b [bool] integral action min: False, default: False, max: True
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig.wikidoc b/mav_control_rw/mav_nonlinear_mpc/solver/devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig.wikidoc
new file mode 100644
index 0000000000000000000000000000000000000000..9dd17e48a938415c9e9581e8835e5b04f3ea855c
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/devel/share/mav_nonlinear_mpc/docs/NonLinearMPCConfig.wikidoc
@@ -0,0 +1,92 @@
+# Autogenerated param section. Do not hand edit.
+param {
+group.0 {
+name=Dynamically Reconfigurable Parameters
+desc=See the [[dynamic_reconfigure]] package for details on dynamically reconfigurable parameters.
+0.name= ~q_x
+0.default= 50.0
+0.type= double
+0.desc=Penality on x axis pos Range: 0.001 to 200.0
+1.name= ~q_y
+1.default= 50.0
+1.type= double
+1.desc=Penality on y axis pos Range: 0.001 to 200.0
+2.name= ~q_z
+2.default= 80.0
+2.type= double
+2.desc=Penality on z axis pos Range: 0.001 to 200.0
+3.name= ~q_vx
+3.default= 20.0
+3.type= double
+3.desc=Penality on x axis vel Range: 0.001 to 200.0
+4.name= ~q_vy
+4.default= 20.0
+4.type= double
+4.desc=Penality on y axis vel Range: 0.001 to 200.0
+5.name= ~q_vz
+5.default= 35.0
+5.type= double
+5.desc=Penality on z axis vel Range: 0.001 to 200.0
+6.name= ~q_roll
+6.default= 20.0
+6.type= double
+6.desc=Penality on roll state Range: 0.001 to 200.0
+7.name= ~q_pitch
+7.default= 20.0
+7.type= double
+7.desc=Penality on pitch state Range: 0.001 to 200.0
+8.name= ~r_roll
+8.default= 30.0
+8.type= double
+8.desc=Penality on roll cmd Range: 1.0 to 200.0
+9.name= ~r_pitch
+9.default= 30.0
+9.type= double
+9.desc=Penality on pitch cmd Range: 1.0 to 200.0
+10.name= ~r_thrust
+10.default= 5.0
+10.type= double
+10.desc=Penality on thrust cmd Range: 1.0 to 200.0
+11.name= ~roll_max
+11.default= 0.45
+11.type= double
+11.desc=max roll cmd [rad] Range: 0.1 to 1.0
+12.name= ~pitch_max
+12.default= 0.45
+12.type= double
+12.desc=max pitch cmd [rad] Range: 0.1 to 1.0
+13.name= ~yaw_rate_max
+13.default= 1.5
+13.type= double
+13.desc=max yawrate cmd [rad/s] Range: 0.1 to 2.0
+14.name= ~thrust_min
+14.default= 5.0
+14.type= double
+14.desc=min thrust cmd [m/s2] Range: 5.0 to 25.0
+15.name= ~thrust_max
+15.default= 15.0
+15.type= double
+15.desc=max thrust cmd [m/s2] Range: 5.0 to 25.0
+16.name= ~K_yaw
+16.default= 0.5
+16.type= double
+16.desc=yaw gain Range: 0.01 to 2.0
+17.name= ~Ki_xy
+17.default= 0.2
+17.type= double
+17.desc=integrator gain for xy Range: 0.01 to 3.0
+18.name= ~Ki_altitude
+18.default= 0.2
+18.type= double
+18.desc=integrator gain for altitude Range: 0.01 to 3.0
+19.name= ~enable_offset_free
+19.default= True
+19.type= bool
+19.desc=XY offset free MPC 
+20.name= ~enable_integrator
+20.default= False
+20.type= bool
+20.desc=integral action 
+}
+}
+# End of autogenerated section. You may edit below.
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/CMakeFiles/CMakeDirectoryInformation.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/CMakeFiles/CMakeDirectoryInformation.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..46e0ec6387beb0b3840c859d69495e05600f1816
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/CMakeFiles/CMakeDirectoryInformation.cmake
@@ -0,0 +1,16 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Relative path conversion top directories.
+set(CMAKE_RELATIVE_PATH_TOP_SOURCE "/usr/src/googletest")
+set(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver")
+
+# Force unix paths in dependencies.
+set(CMAKE_FORCE_UNIX_PATHS 1)
+
+
+# The C and CXX include file regular expressions for this directory.
+set(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$")
+set(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$")
+set(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN})
+set(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN})
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/CMakeFiles/progress.marks b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/CMakeFiles/progress.marks
new file mode 100644
index 0000000000000000000000000000000000000000..573541ac9702dd3969c9bc859d2b91ec1f7e6e56
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/CMakeFiles/progress.marks
@@ -0,0 +1 @@
+0
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/CTestTestfile.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/CTestTestfile.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..6b1fc650edc885201ad4b257315d3d007c4bb9f4
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/CTestTestfile.cmake
@@ -0,0 +1,7 @@
+# CMake generated Testfile for 
+# Source directory: /usr/src/googletest
+# Build directory: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest
+# 
+# This file includes the relevant testing commands required for 
+# testing this directory and lists subdirectories to be tested as well.
+subdirs("googlemock")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/Makefile b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/Makefile
new file mode 100644
index 0000000000000000000000000000000000000000..4dc8bbee1765d3a5799475d26ccb525819f32f5c
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/Makefile
@@ -0,0 +1,196 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Default target executed when no arguments are given to make.
+default_target: all
+
+.PHONY : default_target
+
+# Allow only one "make -f Makefile2" at a time, but pass parallelism.
+.NOTPARALLEL:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+#=============================================================================
+# Targets provided globally by CMake.
+
+# Special rule for the target install/strip
+install/strip: preinstall
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Installing the project stripped..."
+	/usr/bin/cmake -DCMAKE_INSTALL_DO_STRIP=1 -P cmake_install.cmake
+.PHONY : install/strip
+
+# Special rule for the target install/strip
+install/strip/fast: preinstall/fast
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Installing the project stripped..."
+	/usr/bin/cmake -DCMAKE_INSTALL_DO_STRIP=1 -P cmake_install.cmake
+.PHONY : install/strip/fast
+
+# Special rule for the target install/local
+install/local: preinstall
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Installing only the local directory..."
+	/usr/bin/cmake -DCMAKE_INSTALL_LOCAL_ONLY=1 -P cmake_install.cmake
+.PHONY : install/local
+
+# Special rule for the target install/local
+install/local/fast: preinstall/fast
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Installing only the local directory..."
+	/usr/bin/cmake -DCMAKE_INSTALL_LOCAL_ONLY=1 -P cmake_install.cmake
+.PHONY : install/local/fast
+
+# Special rule for the target install
+install: preinstall
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Install the project..."
+	/usr/bin/cmake -P cmake_install.cmake
+.PHONY : install
+
+# Special rule for the target install
+install/fast: preinstall/fast
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Install the project..."
+	/usr/bin/cmake -P cmake_install.cmake
+.PHONY : install/fast
+
+# Special rule for the target list_install_components
+list_install_components:
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Available install components are: \"Unspecified\""
+.PHONY : list_install_components
+
+# Special rule for the target list_install_components
+list_install_components/fast: list_install_components
+
+.PHONY : list_install_components/fast
+
+# Special rule for the target rebuild_cache
+rebuild_cache:
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..."
+	/usr/bin/cmake -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR)
+.PHONY : rebuild_cache
+
+# Special rule for the target rebuild_cache
+rebuild_cache/fast: rebuild_cache
+
+.PHONY : rebuild_cache/fast
+
+# Special rule for the target edit_cache
+edit_cache:
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake cache editor..."
+	/usr/bin/ccmake -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR)
+.PHONY : edit_cache
+
+# Special rule for the target edit_cache
+edit_cache/fast: edit_cache
+
+.PHONY : edit_cache/fast
+
+# Special rule for the target test
+test:
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running tests..."
+	/usr/bin/ctest --force-new-ctest-process $(ARGS)
+.PHONY : test
+
+# Special rule for the target test
+test/fast: test
+
+.PHONY : test/fast
+
+# The main all target
+all: cmake_check_build_system
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/CMakeFiles/progress.marks
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f CMakeFiles/Makefile2 gtest/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : all
+
+# The main clean target
+clean:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f CMakeFiles/Makefile2 gtest/clean
+.PHONY : clean
+
+# The main clean target
+clean/fast: clean
+
+.PHONY : clean/fast
+
+# Prepare targets for installation.
+preinstall: all
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f CMakeFiles/Makefile2 gtest/preinstall
+.PHONY : preinstall
+
+# Prepare targets for installation.
+preinstall/fast:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f CMakeFiles/Makefile2 gtest/preinstall
+.PHONY : preinstall/fast
+
+# clear depends
+depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1
+.PHONY : depend
+
+# Help Target
+help:
+	@echo "The following are some of the valid targets for this Makefile:"
+	@echo "... all (the default if no target is provided)"
+	@echo "... clean"
+	@echo "... depend"
+	@echo "... install/strip"
+	@echo "... install/local"
+	@echo "... install"
+	@echo "... list_install_components"
+	@echo "... rebuild_cache"
+	@echo "... edit_cache"
+	@echo "... test"
+.PHONY : help
+
+
+
+#=============================================================================
+# Special targets to cleanup operation of make.
+
+# Special rule to run CMake to check the build system integrity.
+# No rule that depends on this can have commands that come from listfiles
+# because they might be regenerated.
+cmake_check_build_system:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0
+.PHONY : cmake_check_build_system
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/cmake_install.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/cmake_install.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..c72e53399607e2137aa35e1eb4b350d9f393de1c
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/cmake_install.cmake
@@ -0,0 +1,45 @@
+# Install script for directory: /usr/src/googletest
+
+# Set the install prefix
+if(NOT DEFINED CMAKE_INSTALL_PREFIX)
+  set(CMAKE_INSTALL_PREFIX "/usr/local")
+endif()
+string(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}")
+
+# Set the install configuration name.
+if(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME)
+  if(BUILD_TYPE)
+    string(REGEX REPLACE "^[^A-Za-z0-9_]+" ""
+           CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}")
+  else()
+    set(CMAKE_INSTALL_CONFIG_NAME "Release")
+  endif()
+  message(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"")
+endif()
+
+# Set the component getting installed.
+if(NOT CMAKE_INSTALL_COMPONENT)
+  if(COMPONENT)
+    message(STATUS "Install component: \"${COMPONENT}\"")
+    set(CMAKE_INSTALL_COMPONENT "${COMPONENT}")
+  else()
+    set(CMAKE_INSTALL_COMPONENT)
+  endif()
+endif()
+
+# Install shared libraries without execute permission?
+if(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE)
+  set(CMAKE_INSTALL_SO_NO_EXE "1")
+endif()
+
+# Is this installation the result of a crosscompile?
+if(NOT DEFINED CMAKE_CROSSCOMPILING)
+  set(CMAKE_CROSSCOMPILING "FALSE")
+endif()
+
+if(NOT CMAKE_INSTALL_LOCAL_ONLY)
+  # Include the install script for each subdirectory.
+  include("/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/cmake_install.cmake")
+
+endif()
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/CMakeDirectoryInformation.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/CMakeDirectoryInformation.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..46e0ec6387beb0b3840c859d69495e05600f1816
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/CMakeDirectoryInformation.cmake
@@ -0,0 +1,16 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Relative path conversion top directories.
+set(CMAKE_RELATIVE_PATH_TOP_SOURCE "/usr/src/googletest")
+set(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver")
+
+# Force unix paths in dependencies.
+set(CMAKE_FORCE_UNIX_PATHS 1)
+
+
+# The C and CXX include file regular expressions for this directory.
+set(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$")
+set(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$")
+set(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN})
+set(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN})
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..ace25a1cb153a102ba72bf24b721f4227202526d
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/DependInfo.cmake
@@ -0,0 +1,31 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  "CXX"
+  )
+# The set of files for implicit dependencies of each language:
+set(CMAKE_DEPENDS_CHECK_CXX
+  "/usr/src/googletest/googlemock/src/gmock-all.cc" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/src/gmock-all.cc.o"
+  )
+set(CMAKE_CXX_COMPILER_ID "GNU")
+
+# Preprocessor definitions for this target.
+set(CMAKE_TARGET_DEFINITIONS_CXX
+  "GTEST_CREATE_SHARED_LIBRARY=1"
+  "gmock_EXPORTS"
+  )
+
+# The include file search paths:
+set(CMAKE_CXX_TARGET_INCLUDE_PATH
+  "/usr/src/googletest/googlemock/include"
+  "/usr/src/googletest/googlemock"
+  "/usr/src/googletest/googletest/include"
+  "/usr/src/googletest/googletest"
+  )
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/DependInfo.cmake"
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..0f1ffd7a50a6882fbd6bb52d349883737e06e144
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/build.make
@@ -0,0 +1,99 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Include any dependencies generated for this target.
+include gtest/googlemock/CMakeFiles/gmock.dir/depend.make
+
+# Include the progress variables for this target.
+include gtest/googlemock/CMakeFiles/gmock.dir/progress.make
+
+# Include the compile flags for this target's objects.
+include gtest/googlemock/CMakeFiles/gmock.dir/flags.make
+
+gtest/googlemock/CMakeFiles/gmock.dir/src/gmock-all.cc.o: gtest/googlemock/CMakeFiles/gmock.dir/flags.make
+gtest/googlemock/CMakeFiles/gmock.dir/src/gmock-all.cc.o: /usr/src/googletest/googlemock/src/gmock-all.cc
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_1) "Building CXX object gtest/googlemock/CMakeFiles/gmock.dir/src/gmock-all.cc.o"
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock && /usr/bin/c++  $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -o CMakeFiles/gmock.dir/src/gmock-all.cc.o -c /usr/src/googletest/googlemock/src/gmock-all.cc
+
+gtest/googlemock/CMakeFiles/gmock.dir/src/gmock-all.cc.i: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/gmock.dir/src/gmock-all.cc.i"
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock && /usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /usr/src/googletest/googlemock/src/gmock-all.cc > CMakeFiles/gmock.dir/src/gmock-all.cc.i
+
+gtest/googlemock/CMakeFiles/gmock.dir/src/gmock-all.cc.s: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/gmock.dir/src/gmock-all.cc.s"
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock && /usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /usr/src/googletest/googlemock/src/gmock-all.cc -o CMakeFiles/gmock.dir/src/gmock-all.cc.s
+
+# Object files for target gmock
+gmock_OBJECTS = \
+"CMakeFiles/gmock.dir/src/gmock-all.cc.o"
+
+# External object files for target gmock
+gmock_EXTERNAL_OBJECTS =
+
+gtest/lib/libgmock.so: gtest/googlemock/CMakeFiles/gmock.dir/src/gmock-all.cc.o
+gtest/lib/libgmock.so: gtest/googlemock/CMakeFiles/gmock.dir/build.make
+gtest/lib/libgmock.so: gtest/lib/libgtest.so
+gtest/lib/libgmock.so: gtest/googlemock/CMakeFiles/gmock.dir/link.txt
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --bold --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_2) "Linking CXX shared library ../lib/libgmock.so"
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock && $(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/gmock.dir/link.txt --verbose=$(VERBOSE)
+
+# Rule to build all files generated by this target.
+gtest/googlemock/CMakeFiles/gmock.dir/build: gtest/lib/libgmock.so
+
+.PHONY : gtest/googlemock/CMakeFiles/gmock.dir/build
+
+gtest/googlemock/CMakeFiles/gmock.dir/clean:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock && $(CMAKE_COMMAND) -P CMakeFiles/gmock.dir/cmake_clean.cmake
+.PHONY : gtest/googlemock/CMakeFiles/gmock.dir/clean
+
+gtest/googlemock/CMakeFiles/gmock.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /usr/src/googletest/googlemock /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : gtest/googlemock/CMakeFiles/gmock.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..53a6e779eab5b6445dab372d240621d7d54cf4b9
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/cmake_clean.cmake
@@ -0,0 +1,10 @@
+file(REMOVE_RECURSE
+  "../../bin/libgmock.pdb"
+  "../lib/libgmock.so"
+  "CMakeFiles/gmock.dir/src/gmock-all.cc.o"
+)
+
+# Per-language clean rules from dependency scanning.
+foreach(lang CXX)
+  include(CMakeFiles/gmock.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..7a05e2f1995722edd1ef296a9e722270b2f5bb3d
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/depend.make
@@ -0,0 +1,2 @@
+# Empty dependencies file for gmock.
+# This may be replaced when dependencies are built.
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/flags.make b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/flags.make
new file mode 100644
index 0000000000000000000000000000000000000000..4f642bad45b1086023d9b20eefd3b9113a3ba705
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/flags.make
@@ -0,0 +1,10 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# compile CXX with /usr/bin/c++
+CXX_FLAGS = -O3 -DNDEBUG -fPIC   -Wall -Wshadow -Wno-error=dangling-else -DGTEST_HAS_PTHREAD=1 -fexceptions -Wextra -Wno-unused-parameter -Wno-missing-field-initializers -DGTEST_HAS_PTHREAD=1 -std=c++11
+
+CXX_DEFINES = -DGTEST_CREATE_SHARED_LIBRARY=1 -Dgmock_EXPORTS
+
+CXX_INCLUDES = -I/usr/src/googletest/googlemock/include -I/usr/src/googletest/googlemock -isystem /usr/src/googletest/googletest/include -isystem /usr/src/googletest/googletest 
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/link.txt b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/link.txt
new file mode 100644
index 0000000000000000000000000000000000000000..5754531d7a91e5d7090e9fd3b7c5565dae89027b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/link.txt
@@ -0,0 +1 @@
+/usr/bin/c++ -fPIC -O3 -DNDEBUG  -shared -Wl,-soname,libgmock.so -o ../lib/libgmock.so CMakeFiles/gmock.dir/src/gmock-all.cc.o  -Wl,-rpath,/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/lib ../lib/libgtest.so -lpthread 
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..abadeb0c3abaa81d622026fcd3ae096d03dd29b7
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/progress.make
@@ -0,0 +1,3 @@
+CMAKE_PROGRESS_1 = 1
+CMAKE_PROGRESS_2 = 2
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..3310421a8a42d47f17475d733601b9d8a534ab02
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/DependInfo.cmake
@@ -0,0 +1,32 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  "CXX"
+  )
+# The set of files for implicit dependencies of each language:
+set(CMAKE_DEPENDS_CHECK_CXX
+  "/usr/src/googletest/googlemock/src/gmock_main.cc" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/src/gmock_main.cc.o"
+  )
+set(CMAKE_CXX_COMPILER_ID "GNU")
+
+# Preprocessor definitions for this target.
+set(CMAKE_TARGET_DEFINITIONS_CXX
+  "GTEST_CREATE_SHARED_LIBRARY=1"
+  "gmock_main_EXPORTS"
+  )
+
+# The include file search paths:
+set(CMAKE_CXX_TARGET_INCLUDE_PATH
+  "/usr/src/googletest/googlemock/include"
+  "/usr/src/googletest/googlemock"
+  "/usr/src/googletest/googletest/include"
+  "/usr/src/googletest/googletest"
+  )
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock.dir/DependInfo.cmake"
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/DependInfo.cmake"
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..a5800533f8e66952ed1389fb2d3b1bdb8689ee3a
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/build.make
@@ -0,0 +1,100 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Include any dependencies generated for this target.
+include gtest/googlemock/CMakeFiles/gmock_main.dir/depend.make
+
+# Include the progress variables for this target.
+include gtest/googlemock/CMakeFiles/gmock_main.dir/progress.make
+
+# Include the compile flags for this target's objects.
+include gtest/googlemock/CMakeFiles/gmock_main.dir/flags.make
+
+gtest/googlemock/CMakeFiles/gmock_main.dir/src/gmock_main.cc.o: gtest/googlemock/CMakeFiles/gmock_main.dir/flags.make
+gtest/googlemock/CMakeFiles/gmock_main.dir/src/gmock_main.cc.o: /usr/src/googletest/googlemock/src/gmock_main.cc
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_1) "Building CXX object gtest/googlemock/CMakeFiles/gmock_main.dir/src/gmock_main.cc.o"
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock && /usr/bin/c++  $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -o CMakeFiles/gmock_main.dir/src/gmock_main.cc.o -c /usr/src/googletest/googlemock/src/gmock_main.cc
+
+gtest/googlemock/CMakeFiles/gmock_main.dir/src/gmock_main.cc.i: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/gmock_main.dir/src/gmock_main.cc.i"
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock && /usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /usr/src/googletest/googlemock/src/gmock_main.cc > CMakeFiles/gmock_main.dir/src/gmock_main.cc.i
+
+gtest/googlemock/CMakeFiles/gmock_main.dir/src/gmock_main.cc.s: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/gmock_main.dir/src/gmock_main.cc.s"
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock && /usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /usr/src/googletest/googlemock/src/gmock_main.cc -o CMakeFiles/gmock_main.dir/src/gmock_main.cc.s
+
+# Object files for target gmock_main
+gmock_main_OBJECTS = \
+"CMakeFiles/gmock_main.dir/src/gmock_main.cc.o"
+
+# External object files for target gmock_main
+gmock_main_EXTERNAL_OBJECTS =
+
+gtest/lib/libgmock_main.so: gtest/googlemock/CMakeFiles/gmock_main.dir/src/gmock_main.cc.o
+gtest/lib/libgmock_main.so: gtest/googlemock/CMakeFiles/gmock_main.dir/build.make
+gtest/lib/libgmock_main.so: gtest/lib/libgmock.so
+gtest/lib/libgmock_main.so: gtest/lib/libgtest.so
+gtest/lib/libgmock_main.so: gtest/googlemock/CMakeFiles/gmock_main.dir/link.txt
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --bold --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_2) "Linking CXX shared library ../lib/libgmock_main.so"
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock && $(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/gmock_main.dir/link.txt --verbose=$(VERBOSE)
+
+# Rule to build all files generated by this target.
+gtest/googlemock/CMakeFiles/gmock_main.dir/build: gtest/lib/libgmock_main.so
+
+.PHONY : gtest/googlemock/CMakeFiles/gmock_main.dir/build
+
+gtest/googlemock/CMakeFiles/gmock_main.dir/clean:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock && $(CMAKE_COMMAND) -P CMakeFiles/gmock_main.dir/cmake_clean.cmake
+.PHONY : gtest/googlemock/CMakeFiles/gmock_main.dir/clean
+
+gtest/googlemock/CMakeFiles/gmock_main.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /usr/src/googletest/googlemock /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : gtest/googlemock/CMakeFiles/gmock_main.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..ace4a8ff4732b2812ec7e7fc7af18fccebd6f2ba
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/cmake_clean.cmake
@@ -0,0 +1,10 @@
+file(REMOVE_RECURSE
+  "../../bin/libgmock_main.pdb"
+  "../lib/libgmock_main.so"
+  "CMakeFiles/gmock_main.dir/src/gmock_main.cc.o"
+)
+
+# Per-language clean rules from dependency scanning.
+foreach(lang CXX)
+  include(CMakeFiles/gmock_main.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..4a18b61b44c09e7c55e5cfcaedb4d5c068d9de16
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/depend.make
@@ -0,0 +1,2 @@
+# Empty dependencies file for gmock_main.
+# This may be replaced when dependencies are built.
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/flags.make b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/flags.make
new file mode 100644
index 0000000000000000000000000000000000000000..d99d7c3fe373b50c560c788ecc551b72cee2a914
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/flags.make
@@ -0,0 +1,10 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# compile CXX with /usr/bin/c++
+CXX_FLAGS = -O3 -DNDEBUG -fPIC   -Wall -Wshadow -Wno-error=dangling-else -DGTEST_HAS_PTHREAD=1 -fexceptions -Wextra -Wno-unused-parameter -Wno-missing-field-initializers -DGTEST_HAS_PTHREAD=1 -std=c++11
+
+CXX_DEFINES = -DGTEST_CREATE_SHARED_LIBRARY=1 -Dgmock_main_EXPORTS
+
+CXX_INCLUDES = -isystem /usr/src/googletest/googlemock/include -isystem /usr/src/googletest/googlemock -isystem /usr/src/googletest/googletest/include -isystem /usr/src/googletest/googletest 
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/link.txt b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/link.txt
new file mode 100644
index 0000000000000000000000000000000000000000..b289cd8b5312e576bc7bf43a3e810441c2f7c305
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/link.txt
@@ -0,0 +1 @@
+/usr/bin/c++ -fPIC -O3 -DNDEBUG  -shared -Wl,-soname,libgmock_main.so -o ../lib/libgmock_main.so CMakeFiles/gmock_main.dir/src/gmock_main.cc.o  -Wl,-rpath,/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/lib ../lib/libgmock.so ../lib/libgtest.so -lpthread 
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..8c8fb6fbbc138d8387b9ed9bdb2088ee8aa036f6
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/gmock_main.dir/progress.make
@@ -0,0 +1,3 @@
+CMAKE_PROGRESS_1 = 3
+CMAKE_PROGRESS_2 = 4
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/progress.marks b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/progress.marks
new file mode 100644
index 0000000000000000000000000000000000000000..573541ac9702dd3969c9bc859d2b91ec1f7e6e56
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/progress.marks
@@ -0,0 +1 @@
+0
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CTestTestfile.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CTestTestfile.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..d8154d9836deb50789134c424326c265f49ac5da
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CTestTestfile.cmake
@@ -0,0 +1,7 @@
+# CMake generated Testfile for 
+# Source directory: /usr/src/googletest/googlemock
+# Build directory: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock
+# 
+# This file includes the relevant testing commands required for 
+# testing this directory and lists subdirectories to be tested as well.
+subdirs("../googletest")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/Makefile b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/Makefile
new file mode 100644
index 0000000000000000000000000000000000000000..ac2f29073f246446fcc8801ae143efb4e738c4c2
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/Makefile
@@ -0,0 +1,288 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Default target executed when no arguments are given to make.
+default_target: all
+
+.PHONY : default_target
+
+# Allow only one "make -f Makefile2" at a time, but pass parallelism.
+.NOTPARALLEL:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+#=============================================================================
+# Targets provided globally by CMake.
+
+# Special rule for the target install/strip
+install/strip: preinstall
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Installing the project stripped..."
+	/usr/bin/cmake -DCMAKE_INSTALL_DO_STRIP=1 -P cmake_install.cmake
+.PHONY : install/strip
+
+# Special rule for the target install/strip
+install/strip/fast: preinstall/fast
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Installing the project stripped..."
+	/usr/bin/cmake -DCMAKE_INSTALL_DO_STRIP=1 -P cmake_install.cmake
+.PHONY : install/strip/fast
+
+# Special rule for the target install/local
+install/local: preinstall
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Installing only the local directory..."
+	/usr/bin/cmake -DCMAKE_INSTALL_LOCAL_ONLY=1 -P cmake_install.cmake
+.PHONY : install/local
+
+# Special rule for the target install/local
+install/local/fast: preinstall/fast
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Installing only the local directory..."
+	/usr/bin/cmake -DCMAKE_INSTALL_LOCAL_ONLY=1 -P cmake_install.cmake
+.PHONY : install/local/fast
+
+# Special rule for the target install
+install: preinstall
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Install the project..."
+	/usr/bin/cmake -P cmake_install.cmake
+.PHONY : install
+
+# Special rule for the target install
+install/fast: preinstall/fast
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Install the project..."
+	/usr/bin/cmake -P cmake_install.cmake
+.PHONY : install/fast
+
+# Special rule for the target list_install_components
+list_install_components:
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Available install components are: \"Unspecified\""
+.PHONY : list_install_components
+
+# Special rule for the target list_install_components
+list_install_components/fast: list_install_components
+
+.PHONY : list_install_components/fast
+
+# Special rule for the target rebuild_cache
+rebuild_cache:
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..."
+	/usr/bin/cmake -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR)
+.PHONY : rebuild_cache
+
+# Special rule for the target rebuild_cache
+rebuild_cache/fast: rebuild_cache
+
+.PHONY : rebuild_cache/fast
+
+# Special rule for the target edit_cache
+edit_cache:
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake cache editor..."
+	/usr/bin/ccmake -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR)
+.PHONY : edit_cache
+
+# Special rule for the target edit_cache
+edit_cache/fast: edit_cache
+
+.PHONY : edit_cache/fast
+
+# Special rule for the target test
+test:
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running tests..."
+	/usr/bin/ctest --force-new-ctest-process $(ARGS)
+.PHONY : test
+
+# Special rule for the target test
+test/fast: test
+
+.PHONY : test/fast
+
+# The main all target
+all: cmake_check_build_system
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/CMakeFiles/progress.marks
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f CMakeFiles/Makefile2 gtest/googlemock/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : all
+
+# The main clean target
+clean:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f CMakeFiles/Makefile2 gtest/googlemock/clean
+.PHONY : clean
+
+# The main clean target
+clean/fast: clean
+
+.PHONY : clean/fast
+
+# Prepare targets for installation.
+preinstall: all
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f CMakeFiles/Makefile2 gtest/googlemock/preinstall
+.PHONY : preinstall
+
+# Prepare targets for installation.
+preinstall/fast:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f CMakeFiles/Makefile2 gtest/googlemock/preinstall
+.PHONY : preinstall/fast
+
+# clear depends
+depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1
+.PHONY : depend
+
+# Convenience name for target.
+gtest/googlemock/CMakeFiles/gmock_main.dir/rule:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f CMakeFiles/Makefile2 gtest/googlemock/CMakeFiles/gmock_main.dir/rule
+.PHONY : gtest/googlemock/CMakeFiles/gmock_main.dir/rule
+
+# Convenience name for target.
+gmock_main: gtest/googlemock/CMakeFiles/gmock_main.dir/rule
+
+.PHONY : gmock_main
+
+# fast build rule for target.
+gmock_main/fast:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f gtest/googlemock/CMakeFiles/gmock_main.dir/build.make gtest/googlemock/CMakeFiles/gmock_main.dir/build
+.PHONY : gmock_main/fast
+
+# Convenience name for target.
+gtest/googlemock/CMakeFiles/gmock.dir/rule:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f CMakeFiles/Makefile2 gtest/googlemock/CMakeFiles/gmock.dir/rule
+.PHONY : gtest/googlemock/CMakeFiles/gmock.dir/rule
+
+# Convenience name for target.
+gmock: gtest/googlemock/CMakeFiles/gmock.dir/rule
+
+.PHONY : gmock
+
+# fast build rule for target.
+gmock/fast:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f gtest/googlemock/CMakeFiles/gmock.dir/build.make gtest/googlemock/CMakeFiles/gmock.dir/build
+.PHONY : gmock/fast
+
+src/gmock-all.o: src/gmock-all.cc.o
+
+.PHONY : src/gmock-all.o
+
+# target to build an object file
+src/gmock-all.cc.o:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f gtest/googlemock/CMakeFiles/gmock.dir/build.make gtest/googlemock/CMakeFiles/gmock.dir/src/gmock-all.cc.o
+.PHONY : src/gmock-all.cc.o
+
+src/gmock-all.i: src/gmock-all.cc.i
+
+.PHONY : src/gmock-all.i
+
+# target to preprocess a source file
+src/gmock-all.cc.i:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f gtest/googlemock/CMakeFiles/gmock.dir/build.make gtest/googlemock/CMakeFiles/gmock.dir/src/gmock-all.cc.i
+.PHONY : src/gmock-all.cc.i
+
+src/gmock-all.s: src/gmock-all.cc.s
+
+.PHONY : src/gmock-all.s
+
+# target to generate assembly for a file
+src/gmock-all.cc.s:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f gtest/googlemock/CMakeFiles/gmock.dir/build.make gtest/googlemock/CMakeFiles/gmock.dir/src/gmock-all.cc.s
+.PHONY : src/gmock-all.cc.s
+
+src/gmock_main.o: src/gmock_main.cc.o
+
+.PHONY : src/gmock_main.o
+
+# target to build an object file
+src/gmock_main.cc.o:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f gtest/googlemock/CMakeFiles/gmock_main.dir/build.make gtest/googlemock/CMakeFiles/gmock_main.dir/src/gmock_main.cc.o
+.PHONY : src/gmock_main.cc.o
+
+src/gmock_main.i: src/gmock_main.cc.i
+
+.PHONY : src/gmock_main.i
+
+# target to preprocess a source file
+src/gmock_main.cc.i:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f gtest/googlemock/CMakeFiles/gmock_main.dir/build.make gtest/googlemock/CMakeFiles/gmock_main.dir/src/gmock_main.cc.i
+.PHONY : src/gmock_main.cc.i
+
+src/gmock_main.s: src/gmock_main.cc.s
+
+.PHONY : src/gmock_main.s
+
+# target to generate assembly for a file
+src/gmock_main.cc.s:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f gtest/googlemock/CMakeFiles/gmock_main.dir/build.make gtest/googlemock/CMakeFiles/gmock_main.dir/src/gmock_main.cc.s
+.PHONY : src/gmock_main.cc.s
+
+# Help Target
+help:
+	@echo "The following are some of the valid targets for this Makefile:"
+	@echo "... all (the default if no target is provided)"
+	@echo "... clean"
+	@echo "... depend"
+	@echo "... install/strip"
+	@echo "... install/local"
+	@echo "... install"
+	@echo "... list_install_components"
+	@echo "... rebuild_cache"
+	@echo "... edit_cache"
+	@echo "... test"
+	@echo "... gmock_main"
+	@echo "... gmock"
+	@echo "... src/gmock-all.o"
+	@echo "... src/gmock-all.i"
+	@echo "... src/gmock-all.s"
+	@echo "... src/gmock_main.o"
+	@echo "... src/gmock_main.i"
+	@echo "... src/gmock_main.s"
+.PHONY : help
+
+
+
+#=============================================================================
+# Special targets to cleanup operation of make.
+
+# Special rule to run CMake to check the build system integrity.
+# No rule that depends on this can have commands that come from listfiles
+# because they might be regenerated.
+cmake_check_build_system:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0
+.PHONY : cmake_check_build_system
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/cmake_install.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/cmake_install.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..952e07037aa716650921c60a8a2e090d5df92fd5
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googlemock/cmake_install.cmake
@@ -0,0 +1,45 @@
+# Install script for directory: /usr/src/googletest/googlemock
+
+# Set the install prefix
+if(NOT DEFINED CMAKE_INSTALL_PREFIX)
+  set(CMAKE_INSTALL_PREFIX "/usr/local")
+endif()
+string(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}")
+
+# Set the install configuration name.
+if(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME)
+  if(BUILD_TYPE)
+    string(REGEX REPLACE "^[^A-Za-z0-9_]+" ""
+           CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}")
+  else()
+    set(CMAKE_INSTALL_CONFIG_NAME "Release")
+  endif()
+  message(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"")
+endif()
+
+# Set the component getting installed.
+if(NOT CMAKE_INSTALL_COMPONENT)
+  if(COMPONENT)
+    message(STATUS "Install component: \"${COMPONENT}\"")
+    set(CMAKE_INSTALL_COMPONENT "${COMPONENT}")
+  else()
+    set(CMAKE_INSTALL_COMPONENT)
+  endif()
+endif()
+
+# Install shared libraries without execute permission?
+if(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE)
+  set(CMAKE_INSTALL_SO_NO_EXE "1")
+endif()
+
+# Is this installation the result of a crosscompile?
+if(NOT DEFINED CMAKE_CROSSCOMPILING)
+  set(CMAKE_CROSSCOMPILING "FALSE")
+endif()
+
+if(NOT CMAKE_INSTALL_LOCAL_ONLY)
+  # Include the install script for each subdirectory.
+  include("/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/cmake_install.cmake")
+
+endif()
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/CMakeDirectoryInformation.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/CMakeDirectoryInformation.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..46e0ec6387beb0b3840c859d69495e05600f1816
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/CMakeDirectoryInformation.cmake
@@ -0,0 +1,16 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Relative path conversion top directories.
+set(CMAKE_RELATIVE_PATH_TOP_SOURCE "/usr/src/googletest")
+set(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver")
+
+# Force unix paths in dependencies.
+set(CMAKE_FORCE_UNIX_PATHS 1)
+
+
+# The C and CXX include file regular expressions for this directory.
+set(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$")
+set(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$")
+set(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN})
+set(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN})
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..c5cddf75db44273d02dc6ed5d567fa78277ff18b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/DependInfo.cmake
@@ -0,0 +1,28 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  "CXX"
+  )
+# The set of files for implicit dependencies of each language:
+set(CMAKE_DEPENDS_CHECK_CXX
+  "/usr/src/googletest/googletest/src/gtest-all.cc" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/src/gtest-all.cc.o"
+  )
+set(CMAKE_CXX_COMPILER_ID "GNU")
+
+# Preprocessor definitions for this target.
+set(CMAKE_TARGET_DEFINITIONS_CXX
+  "GTEST_CREATE_SHARED_LIBRARY=1"
+  "gtest_EXPORTS"
+  )
+
+# The include file search paths:
+set(CMAKE_CXX_TARGET_INCLUDE_PATH
+  "/usr/src/googletest/googletest/include"
+  "/usr/src/googletest/googletest"
+  )
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..3968acd4c7f27ca93252b5c6f60f8873b1639804
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/build.make
@@ -0,0 +1,98 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Include any dependencies generated for this target.
+include gtest/googletest/CMakeFiles/gtest.dir/depend.make
+
+# Include the progress variables for this target.
+include gtest/googletest/CMakeFiles/gtest.dir/progress.make
+
+# Include the compile flags for this target's objects.
+include gtest/googletest/CMakeFiles/gtest.dir/flags.make
+
+gtest/googletest/CMakeFiles/gtest.dir/src/gtest-all.cc.o: gtest/googletest/CMakeFiles/gtest.dir/flags.make
+gtest/googletest/CMakeFiles/gtest.dir/src/gtest-all.cc.o: /usr/src/googletest/googletest/src/gtest-all.cc
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_1) "Building CXX object gtest/googletest/CMakeFiles/gtest.dir/src/gtest-all.cc.o"
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest && /usr/bin/c++  $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -o CMakeFiles/gtest.dir/src/gtest-all.cc.o -c /usr/src/googletest/googletest/src/gtest-all.cc
+
+gtest/googletest/CMakeFiles/gtest.dir/src/gtest-all.cc.i: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/gtest.dir/src/gtest-all.cc.i"
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest && /usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /usr/src/googletest/googletest/src/gtest-all.cc > CMakeFiles/gtest.dir/src/gtest-all.cc.i
+
+gtest/googletest/CMakeFiles/gtest.dir/src/gtest-all.cc.s: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/gtest.dir/src/gtest-all.cc.s"
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest && /usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /usr/src/googletest/googletest/src/gtest-all.cc -o CMakeFiles/gtest.dir/src/gtest-all.cc.s
+
+# Object files for target gtest
+gtest_OBJECTS = \
+"CMakeFiles/gtest.dir/src/gtest-all.cc.o"
+
+# External object files for target gtest
+gtest_EXTERNAL_OBJECTS =
+
+gtest/lib/libgtest.so: gtest/googletest/CMakeFiles/gtest.dir/src/gtest-all.cc.o
+gtest/lib/libgtest.so: gtest/googletest/CMakeFiles/gtest.dir/build.make
+gtest/lib/libgtest.so: gtest/googletest/CMakeFiles/gtest.dir/link.txt
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --bold --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_2) "Linking CXX shared library ../lib/libgtest.so"
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest && $(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/gtest.dir/link.txt --verbose=$(VERBOSE)
+
+# Rule to build all files generated by this target.
+gtest/googletest/CMakeFiles/gtest.dir/build: gtest/lib/libgtest.so
+
+.PHONY : gtest/googletest/CMakeFiles/gtest.dir/build
+
+gtest/googletest/CMakeFiles/gtest.dir/clean:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest && $(CMAKE_COMMAND) -P CMakeFiles/gtest.dir/cmake_clean.cmake
+.PHONY : gtest/googletest/CMakeFiles/gtest.dir/clean
+
+gtest/googletest/CMakeFiles/gtest.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /usr/src/googletest/googletest /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : gtest/googletest/CMakeFiles/gtest.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..0efb9da04bdb2c176a94b1b4d6704ddb276cc6a9
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/cmake_clean.cmake
@@ -0,0 +1,10 @@
+file(REMOVE_RECURSE
+  "../../bin/libgtest.pdb"
+  "../lib/libgtest.so"
+  "CMakeFiles/gtest.dir/src/gtest-all.cc.o"
+)
+
+# Per-language clean rules from dependency scanning.
+foreach(lang CXX)
+  include(CMakeFiles/gtest.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..37ac348dbdee84ac90462c82dae3a4f7ca757dc1
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/depend.make
@@ -0,0 +1,2 @@
+# Empty dependencies file for gtest.
+# This may be replaced when dependencies are built.
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/flags.make b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/flags.make
new file mode 100644
index 0000000000000000000000000000000000000000..9d7a49435c86bbc849b857a1c863617bd8c086d7
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/flags.make
@@ -0,0 +1,10 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# compile CXX with /usr/bin/c++
+CXX_FLAGS = -O3 -DNDEBUG -fPIC   -Wall -Wshadow -Wno-error=dangling-else -DGTEST_HAS_PTHREAD=1 -fexceptions -Wextra -Wno-unused-parameter -Wno-missing-field-initializers -std=c++11
+
+CXX_DEFINES = -DGTEST_CREATE_SHARED_LIBRARY=1 -Dgtest_EXPORTS
+
+CXX_INCLUDES = -I/usr/src/googletest/googletest/include -I/usr/src/googletest/googletest 
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/link.txt b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/link.txt
new file mode 100644
index 0000000000000000000000000000000000000000..40380ea20156300c126c2ee8130ded7d151befbe
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/link.txt
@@ -0,0 +1 @@
+/usr/bin/c++ -fPIC -O3 -DNDEBUG  -shared -Wl,-soname,libgtest.so -o ../lib/libgtest.so CMakeFiles/gtest.dir/src/gtest-all.cc.o  -lpthread 
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..3a86673aa7c1868ad77aa16c631effd83be0da02
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/progress.make
@@ -0,0 +1,3 @@
+CMAKE_PROGRESS_1 = 5
+CMAKE_PROGRESS_2 = 6
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/DependInfo.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/DependInfo.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..1ef7f504d9a042c09205ec24630ead2faf6d7a6b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/DependInfo.cmake
@@ -0,0 +1,29 @@
+# The set of languages for which implicit dependencies are needed:
+set(CMAKE_DEPENDS_LANGUAGES
+  "CXX"
+  )
+# The set of files for implicit dependencies of each language:
+set(CMAKE_DEPENDS_CHECK_CXX
+  "/usr/src/googletest/googletest/src/gtest_main.cc" "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/src/gtest_main.cc.o"
+  )
+set(CMAKE_CXX_COMPILER_ID "GNU")
+
+# Preprocessor definitions for this target.
+set(CMAKE_TARGET_DEFINITIONS_CXX
+  "GTEST_CREATE_SHARED_LIBRARY=1"
+  "gtest_main_EXPORTS"
+  )
+
+# The include file search paths:
+set(CMAKE_CXX_TARGET_INCLUDE_PATH
+  "/usr/src/googletest/googletest/include"
+  "/usr/src/googletest/googletest"
+  )
+
+# Targets to which this target links.
+set(CMAKE_TARGET_LINKED_INFO_FILES
+  "/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest.dir/DependInfo.cmake"
+  )
+
+# Fortran module output directory.
+set(CMAKE_Fortran_TARGET_MODULE_DIR "")
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/build.make b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/build.make
new file mode 100644
index 0000000000000000000000000000000000000000..906da154c55766c0a3eae4d85615b3f415d9225e
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/build.make
@@ -0,0 +1,99 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Delete rule output on recipe failure.
+.DELETE_ON_ERROR:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+# Include any dependencies generated for this target.
+include gtest/googletest/CMakeFiles/gtest_main.dir/depend.make
+
+# Include the progress variables for this target.
+include gtest/googletest/CMakeFiles/gtest_main.dir/progress.make
+
+# Include the compile flags for this target's objects.
+include gtest/googletest/CMakeFiles/gtest_main.dir/flags.make
+
+gtest/googletest/CMakeFiles/gtest_main.dir/src/gtest_main.cc.o: gtest/googletest/CMakeFiles/gtest_main.dir/flags.make
+gtest/googletest/CMakeFiles/gtest_main.dir/src/gtest_main.cc.o: /usr/src/googletest/googletest/src/gtest_main.cc
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_1) "Building CXX object gtest/googletest/CMakeFiles/gtest_main.dir/src/gtest_main.cc.o"
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest && /usr/bin/c++  $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -o CMakeFiles/gtest_main.dir/src/gtest_main.cc.o -c /usr/src/googletest/googletest/src/gtest_main.cc
+
+gtest/googletest/CMakeFiles/gtest_main.dir/src/gtest_main.cc.i: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/gtest_main.dir/src/gtest_main.cc.i"
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest && /usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /usr/src/googletest/googletest/src/gtest_main.cc > CMakeFiles/gtest_main.dir/src/gtest_main.cc.i
+
+gtest/googletest/CMakeFiles/gtest_main.dir/src/gtest_main.cc.s: cmake_force
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/gtest_main.dir/src/gtest_main.cc.s"
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest && /usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /usr/src/googletest/googletest/src/gtest_main.cc -o CMakeFiles/gtest_main.dir/src/gtest_main.cc.s
+
+# Object files for target gtest_main
+gtest_main_OBJECTS = \
+"CMakeFiles/gtest_main.dir/src/gtest_main.cc.o"
+
+# External object files for target gtest_main
+gtest_main_EXTERNAL_OBJECTS =
+
+gtest/lib/libgtest_main.so: gtest/googletest/CMakeFiles/gtest_main.dir/src/gtest_main.cc.o
+gtest/lib/libgtest_main.so: gtest/googletest/CMakeFiles/gtest_main.dir/build.make
+gtest/lib/libgtest_main.so: gtest/lib/libgtest.so
+gtest/lib/libgtest_main.so: gtest/googletest/CMakeFiles/gtest_main.dir/link.txt
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --bold --progress-dir=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles --progress-num=$(CMAKE_PROGRESS_2) "Linking CXX shared library ../lib/libgtest_main.so"
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest && $(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/gtest_main.dir/link.txt --verbose=$(VERBOSE)
+
+# Rule to build all files generated by this target.
+gtest/googletest/CMakeFiles/gtest_main.dir/build: gtest/lib/libgtest_main.so
+
+.PHONY : gtest/googletest/CMakeFiles/gtest_main.dir/build
+
+gtest/googletest/CMakeFiles/gtest_main.dir/clean:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest && $(CMAKE_COMMAND) -P CMakeFiles/gtest_main.dir/cmake_clean.cmake
+.PHONY : gtest/googletest/CMakeFiles/gtest_main.dir/clean
+
+gtest/googletest/CMakeFiles/gtest_main.dir/depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc /usr/src/googletest/googletest /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/DependInfo.cmake --color=$(COLOR)
+.PHONY : gtest/googletest/CMakeFiles/gtest_main.dir/depend
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/cmake_clean.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/cmake_clean.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..663b59e2e43c8ea3915014c2d68128167bd597a2
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/cmake_clean.cmake
@@ -0,0 +1,10 @@
+file(REMOVE_RECURSE
+  "../../bin/libgtest_main.pdb"
+  "../lib/libgtest_main.so"
+  "CMakeFiles/gtest_main.dir/src/gtest_main.cc.o"
+)
+
+# Per-language clean rules from dependency scanning.
+foreach(lang CXX)
+  include(CMakeFiles/gtest_main.dir/cmake_clean_${lang}.cmake OPTIONAL)
+endforeach()
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/depend.make b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/depend.make
new file mode 100644
index 0000000000000000000000000000000000000000..1d67c1ab524a35ba28518428e16051e4728c8c11
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/depend.make
@@ -0,0 +1,2 @@
+# Empty dependencies file for gtest_main.
+# This may be replaced when dependencies are built.
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/flags.make b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/flags.make
new file mode 100644
index 0000000000000000000000000000000000000000..2b70858a41517125f46da2352f628d1d9fb55031
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/flags.make
@@ -0,0 +1,10 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# compile CXX with /usr/bin/c++
+CXX_FLAGS = -O3 -DNDEBUG -fPIC   -Wall -Wshadow -Wno-error=dangling-else -DGTEST_HAS_PTHREAD=1 -fexceptions -Wextra -Wno-unused-parameter -Wno-missing-field-initializers -DGTEST_HAS_PTHREAD=1 -std=c++11
+
+CXX_DEFINES = -DGTEST_CREATE_SHARED_LIBRARY=1 -Dgtest_main_EXPORTS
+
+CXX_INCLUDES = -isystem /usr/src/googletest/googletest/include -isystem /usr/src/googletest/googletest 
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/link.txt b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/link.txt
new file mode 100644
index 0000000000000000000000000000000000000000..c4e7a97d17a71c3a5f9bc73f6562939bb5756bfd
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/link.txt
@@ -0,0 +1 @@
+/usr/bin/c++ -fPIC -O3 -DNDEBUG  -shared -Wl,-soname,libgtest_main.so -o ../lib/libgtest_main.so CMakeFiles/gtest_main.dir/src/gtest_main.cc.o  -Wl,-rpath,/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/lib ../lib/libgtest.so -lpthread 
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/progress.make b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/progress.make
new file mode 100644
index 0000000000000000000000000000000000000000..72bb7dd025afc5824222cbd3a1e64841afc2792c
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/gtest_main.dir/progress.make
@@ -0,0 +1,3 @@
+CMAKE_PROGRESS_1 = 7
+CMAKE_PROGRESS_2 = 8
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/progress.marks b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/progress.marks
new file mode 100644
index 0000000000000000000000000000000000000000..573541ac9702dd3969c9bc859d2b91ec1f7e6e56
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/progress.marks
@@ -0,0 +1 @@
+0
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CTestTestfile.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CTestTestfile.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..6bfdec116a3efe2e0b109f5e47df69f2a537d364
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CTestTestfile.cmake
@@ -0,0 +1,6 @@
+# CMake generated Testfile for 
+# Source directory: /usr/src/googletest/googletest
+# Build directory: /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest
+# 
+# This file includes the relevant testing commands required for 
+# testing this directory and lists subdirectories to be tested as well.
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/Makefile b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/Makefile
new file mode 100644
index 0000000000000000000000000000000000000000..4af34f0495e2b4a4208ad7e8e85dd1b9db349596
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/Makefile
@@ -0,0 +1,288 @@
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 3.16
+
+# Default target executed when no arguments are given to make.
+default_target: all
+
+.PHONY : default_target
+
+# Allow only one "make -f Makefile2" at a time, but pass parallelism.
+.NOTPARALLEL:
+
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canonical targets will work.
+.SUFFIXES:
+
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+
+# A target that is always out of date.
+cmake_force:
+
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /usr/bin/cmake
+
+# The command to remove a file.
+RM = /usr/bin/cmake -E remove -f
+
+# Escaping for special characters.
+EQUALS = =
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver
+
+#=============================================================================
+# Targets provided globally by CMake.
+
+# Special rule for the target install/strip
+install/strip: preinstall
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Installing the project stripped..."
+	/usr/bin/cmake -DCMAKE_INSTALL_DO_STRIP=1 -P cmake_install.cmake
+.PHONY : install/strip
+
+# Special rule for the target install/strip
+install/strip/fast: preinstall/fast
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Installing the project stripped..."
+	/usr/bin/cmake -DCMAKE_INSTALL_DO_STRIP=1 -P cmake_install.cmake
+.PHONY : install/strip/fast
+
+# Special rule for the target install/local
+install/local: preinstall
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Installing only the local directory..."
+	/usr/bin/cmake -DCMAKE_INSTALL_LOCAL_ONLY=1 -P cmake_install.cmake
+.PHONY : install/local
+
+# Special rule for the target install/local
+install/local/fast: preinstall/fast
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Installing only the local directory..."
+	/usr/bin/cmake -DCMAKE_INSTALL_LOCAL_ONLY=1 -P cmake_install.cmake
+.PHONY : install/local/fast
+
+# Special rule for the target install
+install: preinstall
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Install the project..."
+	/usr/bin/cmake -P cmake_install.cmake
+.PHONY : install
+
+# Special rule for the target install
+install/fast: preinstall/fast
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Install the project..."
+	/usr/bin/cmake -P cmake_install.cmake
+.PHONY : install/fast
+
+# Special rule for the target list_install_components
+list_install_components:
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Available install components are: \"Unspecified\""
+.PHONY : list_install_components
+
+# Special rule for the target list_install_components
+list_install_components/fast: list_install_components
+
+.PHONY : list_install_components/fast
+
+# Special rule for the target rebuild_cache
+rebuild_cache:
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..."
+	/usr/bin/cmake -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR)
+.PHONY : rebuild_cache
+
+# Special rule for the target rebuild_cache
+rebuild_cache/fast: rebuild_cache
+
+.PHONY : rebuild_cache/fast
+
+# Special rule for the target edit_cache
+edit_cache:
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake cache editor..."
+	/usr/bin/ccmake -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR)
+.PHONY : edit_cache
+
+# Special rule for the target edit_cache
+edit_cache/fast: edit_cache
+
+.PHONY : edit_cache/fast
+
+# Special rule for the target test
+test:
+	@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running tests..."
+	/usr/bin/ctest --force-new-ctest-process $(ARGS)
+.PHONY : test
+
+# Special rule for the target test
+test/fast: test
+
+.PHONY : test/fast
+
+# The main all target
+all: cmake_check_build_system
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/CMakeFiles/progress.marks
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f CMakeFiles/Makefile2 gtest/googletest/all
+	$(CMAKE_COMMAND) -E cmake_progress_start /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/CMakeFiles 0
+.PHONY : all
+
+# The main clean target
+clean:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f CMakeFiles/Makefile2 gtest/googletest/clean
+.PHONY : clean
+
+# The main clean target
+clean/fast: clean
+
+.PHONY : clean/fast
+
+# Prepare targets for installation.
+preinstall: all
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f CMakeFiles/Makefile2 gtest/googletest/preinstall
+.PHONY : preinstall
+
+# Prepare targets for installation.
+preinstall/fast:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f CMakeFiles/Makefile2 gtest/googletest/preinstall
+.PHONY : preinstall/fast
+
+# clear depends
+depend:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1
+.PHONY : depend
+
+# Convenience name for target.
+gtest/googletest/CMakeFiles/gtest_main.dir/rule:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f CMakeFiles/Makefile2 gtest/googletest/CMakeFiles/gtest_main.dir/rule
+.PHONY : gtest/googletest/CMakeFiles/gtest_main.dir/rule
+
+# Convenience name for target.
+gtest_main: gtest/googletest/CMakeFiles/gtest_main.dir/rule
+
+.PHONY : gtest_main
+
+# fast build rule for target.
+gtest_main/fast:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f gtest/googletest/CMakeFiles/gtest_main.dir/build.make gtest/googletest/CMakeFiles/gtest_main.dir/build
+.PHONY : gtest_main/fast
+
+# Convenience name for target.
+gtest/googletest/CMakeFiles/gtest.dir/rule:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f CMakeFiles/Makefile2 gtest/googletest/CMakeFiles/gtest.dir/rule
+.PHONY : gtest/googletest/CMakeFiles/gtest.dir/rule
+
+# Convenience name for target.
+gtest: gtest/googletest/CMakeFiles/gtest.dir/rule
+
+.PHONY : gtest
+
+# fast build rule for target.
+gtest/fast:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f gtest/googletest/CMakeFiles/gtest.dir/build.make gtest/googletest/CMakeFiles/gtest.dir/build
+.PHONY : gtest/fast
+
+src/gtest-all.o: src/gtest-all.cc.o
+
+.PHONY : src/gtest-all.o
+
+# target to build an object file
+src/gtest-all.cc.o:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f gtest/googletest/CMakeFiles/gtest.dir/build.make gtest/googletest/CMakeFiles/gtest.dir/src/gtest-all.cc.o
+.PHONY : src/gtest-all.cc.o
+
+src/gtest-all.i: src/gtest-all.cc.i
+
+.PHONY : src/gtest-all.i
+
+# target to preprocess a source file
+src/gtest-all.cc.i:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f gtest/googletest/CMakeFiles/gtest.dir/build.make gtest/googletest/CMakeFiles/gtest.dir/src/gtest-all.cc.i
+.PHONY : src/gtest-all.cc.i
+
+src/gtest-all.s: src/gtest-all.cc.s
+
+.PHONY : src/gtest-all.s
+
+# target to generate assembly for a file
+src/gtest-all.cc.s:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f gtest/googletest/CMakeFiles/gtest.dir/build.make gtest/googletest/CMakeFiles/gtest.dir/src/gtest-all.cc.s
+.PHONY : src/gtest-all.cc.s
+
+src/gtest_main.o: src/gtest_main.cc.o
+
+.PHONY : src/gtest_main.o
+
+# target to build an object file
+src/gtest_main.cc.o:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f gtest/googletest/CMakeFiles/gtest_main.dir/build.make gtest/googletest/CMakeFiles/gtest_main.dir/src/gtest_main.cc.o
+.PHONY : src/gtest_main.cc.o
+
+src/gtest_main.i: src/gtest_main.cc.i
+
+.PHONY : src/gtest_main.i
+
+# target to preprocess a source file
+src/gtest_main.cc.i:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f gtest/googletest/CMakeFiles/gtest_main.dir/build.make gtest/googletest/CMakeFiles/gtest_main.dir/src/gtest_main.cc.i
+.PHONY : src/gtest_main.cc.i
+
+src/gtest_main.s: src/gtest_main.cc.s
+
+.PHONY : src/gtest_main.s
+
+# target to generate assembly for a file
+src/gtest_main.cc.s:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(MAKE) -f gtest/googletest/CMakeFiles/gtest_main.dir/build.make gtest/googletest/CMakeFiles/gtest_main.dir/src/gtest_main.cc.s
+.PHONY : src/gtest_main.cc.s
+
+# Help Target
+help:
+	@echo "The following are some of the valid targets for this Makefile:"
+	@echo "... all (the default if no target is provided)"
+	@echo "... clean"
+	@echo "... depend"
+	@echo "... install/strip"
+	@echo "... install/local"
+	@echo "... install"
+	@echo "... list_install_components"
+	@echo "... rebuild_cache"
+	@echo "... edit_cache"
+	@echo "... test"
+	@echo "... gtest_main"
+	@echo "... gtest"
+	@echo "... src/gtest-all.o"
+	@echo "... src/gtest-all.i"
+	@echo "... src/gtest-all.s"
+	@echo "... src/gtest_main.o"
+	@echo "... src/gtest_main.i"
+	@echo "... src/gtest_main.s"
+.PHONY : help
+
+
+
+#=============================================================================
+# Special targets to cleanup operation of make.
+
+# Special rule to run CMake to check the build system integrity.
+# No rule that depends on this can have commands that come from listfiles
+# because they might be regenerated.
+cmake_check_build_system:
+	cd /home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver && $(CMAKE_COMMAND) -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0
+.PHONY : cmake_check_build_system
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/cmake_install.cmake b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/cmake_install.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..850932b7145dfa79e53d117ed6761a89e1ff4730
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/gtest/googletest/cmake_install.cmake
@@ -0,0 +1,39 @@
+# Install script for directory: /usr/src/googletest/googletest
+
+# Set the install prefix
+if(NOT DEFINED CMAKE_INSTALL_PREFIX)
+  set(CMAKE_INSTALL_PREFIX "/usr/local")
+endif()
+string(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}")
+
+# Set the install configuration name.
+if(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME)
+  if(BUILD_TYPE)
+    string(REGEX REPLACE "^[^A-Za-z0-9_]+" ""
+           CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}")
+  else()
+    set(CMAKE_INSTALL_CONFIG_NAME "Release")
+  endif()
+  message(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"")
+endif()
+
+# Set the component getting installed.
+if(NOT CMAKE_INSTALL_COMPONENT)
+  if(COMPONENT)
+    message(STATUS "Install component: \"${COMPONENT}\"")
+    set(CMAKE_INSTALL_COMPONENT "${COMPONENT}")
+  else()
+    set(CMAKE_INSTALL_COMPONENT)
+  endif()
+endif()
+
+# Install shared libraries without execute permission?
+if(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE)
+  set(CMAKE_INSTALL_SO_NO_EXE "1")
+endif()
+
+# Is this installation the result of a crosscompile?
+if(NOT DEFINED CMAKE_CROSSCOMPILING)
+  set(CMAKE_CROSSCOMPILING "FALSE")
+endif()
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/make_acado_solver.m b/mav_control_rw/mav_nonlinear_mpc/solver/make_acado_solver.m
new file mode 100644
index 0000000000000000000000000000000000000000..668fd11c29ec1e4016bd2147dd310ba24ff14b7f
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/make_acado_solver.m
@@ -0,0 +1,85 @@
+%
+%    This file was auto-generated using the ACADO Toolkit.
+%    
+%    While ACADO Toolkit is free software released under the terms of
+%    the GNU Lesser General Public License (LGPL), the generated code
+%    as such remains the property of the user who used ACADO Toolkit
+%    to generate this code. In particular, user dependent data of the code
+%    do not inherit the GNU LGPL license. On the other hand, parts of the
+%    generated code that are a direct copy of source code from the
+%    ACADO Toolkit or the software tools it is based on, remain, as derived
+%    work, automatically covered by the LGPL license.
+%    
+%    ACADO Toolkit is distributed in the hope that it will be useful,
+%    but WITHOUT ANY WARRANTY; without even the implied warranty of
+%    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+%    
+
+
+function make_acado_solver( name )
+
+	% Output file name, and also function name
+	if (nargin > 0)
+		fileOut = name;
+	else
+		fileOut = 'acado_solver';
+	end;
+		
+	% Root folder of code generation
+	CGRoot = '.';	
+	
+	% qpOASES embedded source files
+	qpOASESSources = [ ...
+		'CGRoot/qpoases/SRC/Bounds.cpp ' ...
+		'CGRoot/qpoases/SRC/Constraints.cpp ' ...
+		'CGRoot/qpoases/SRC/CyclingManager.cpp ' ...
+		'CGRoot/qpoases/SRC/Indexlist.cpp ' ...
+		'CGRoot/qpoases/SRC/MessageHandling.cpp ' ...
+		'CGRoot/qpoases/SRC/QProblem.cpp ' ...
+		'CGRoot/qpoases/SRC/QProblemB.cpp ' ...
+		'CGRoot/qpoases/SRC/SubjectTo.cpp ' ...
+		'CGRoot/qpoases/SRC/Utils.cpp ' ...
+		'CGRoot/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp ' ...
+		];
+		
+	% Auto-generated files
+	CGSources = [ ...
+		'CGRoot/acado_solver_mex.c ' ...
+		'CGRoot/acado_solver.c ' ...
+		'CGRoot/acado_integrator.c ' ...
+		'CGRoot/acado_auxiliary_functions.c ' ...
+		'CGRoot/acado_qpoases_interface.cpp ' ...
+		];
+	if (nargin > 1)
+		CGSources = [CGSources extern];
+	end
+		
+	% Adding additional linker flags for Linux
+	ldFlags = '';
+	if (isunix() && ~ismac())
+		ldFlags = '-lrt';
+    elseif (ispc)
+        ldFlags = '-DWIN32';
+	end;
+
+	% Recipe for compilation
+	CGRecipe = [ ...
+		'mex -O' ...
+		' -I. -I''CGRoot'' -I''CGRoot/qpoases'' -I''CGRoot/qpoases/INCLUDE'' -I''CGRoot/qpoases/SRC''' ...
+		' ldFlags' ...
+		' -D__MATLAB__ -DQPOASES_CUSTOM_INTERFACE="acado_qpoases_interface.hpp" -O CGSources qpOASESSources -output %s.%s' ...
+		];
+
+% Compilation
+qpOASESSources = regexprep(qpOASESSources, 'CGRoot', CGRoot);
+CGSources = regexprep(CGSources, 'CGRoot', CGRoot);
+
+CGRecipe = regexprep(CGRecipe, 'CGRoot', CGRoot);
+CGRecipe = regexprep(CGRecipe, 'CGSources', CGSources);
+CGRecipe = regexprep(CGRecipe, 'qpOASESSources', qpOASESSources);
+CGRecipe = regexprep(CGRecipe, 'ldFlags', ldFlags);
+
+% disp( sprintf( CGRecipe, fileOut, mexext ) ); 
+fprintf( 'compiling... ' );
+eval( sprintf(CGRecipe, fileOut, mexext) );
+fprintf( ['done! --> ' fileOut '.' mexext '\n'] );
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/nmpc_solver_setup b/mav_control_rw/mav_nonlinear_mpc/solver/nmpc_solver_setup
new file mode 100644
index 0000000000000000000000000000000000000000..a4ad5b521bc550b0c90470f7fff32b5ffc6dcec4
Binary files /dev/null and b/mav_control_rw/mav_nonlinear_mpc/solver/nmpc_solver_setup differ
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/nmpc_solver_setup.m b/mav_control_rw/mav_nonlinear_mpc/solver/nmpc_solver_setup.m
new file mode 100644
index 0000000000000000000000000000000000000000..9ab2e1c85a24fe2a0442889f95cbb082904ec8dc
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/nmpc_solver_setup.m
@@ -0,0 +1,93 @@
+clc;
+clear all;
+close all;
+
+Ts = 0.1; %prediction sampling time
+EXPORT = 1;
+
+DifferentialState velocity(3) roll pitch yaw position(3) ;
+Control roll_ref pitch_ref thrust;
+
+OnlineData roll_tau;
+OnlineData roll_gain;
+OnlineData pitch_tau;
+OnlineData pitch_gain;
+OnlineData linear_drag_coefficient(2);
+OnlineData external_forces(3);
+
+n_XD = length(diffStates);
+n_U = length(controls);
+
+g = [0;0;9.8066];
+
+%% Differential Equation
+
+R = [cos(yaw)*cos(pitch)  cos(yaw)*sin(pitch)*sin(roll)-cos(roll)*sin(yaw)  (cos(yaw)*sin(pitch)*cos(roll)+sin(yaw)*sin(roll)); ...
+    cos(pitch)*sin(yaw)  cos(yaw)*cos(roll)+sin(yaw)*sin(pitch)*sin(roll)  (sin(yaw)*sin(pitch)*cos(roll)-cos(yaw)*sin(roll)); ...
+    -sin(pitch)                            cos(pitch)*sin(roll)                            cos(pitch)*cos(roll)];
+
+z_B = R(:,3);
+
+%nonlinear drag model
+drag_acc = thrust*[linear_drag_coefficient1 0 0; 0 linear_drag_coefficient2 0; 0 0 0]*R'*velocity;
+
+droll = (1/roll_tau)*(roll_gain*roll_ref - roll);
+dpitch = (1/pitch_tau)*(pitch_gain*pitch_ref - pitch);
+
+
+f = dot([velocity; roll; pitch; yaw; position]) == ...
+    [z_B*thrust-g-drag_acc+external_forces;...
+    droll; ...
+    dpitch;...
+    0;...
+    velocity;...
+    ];
+
+h = [position;...
+    velocity;...
+    roll;...
+    pitch;...
+    roll_ref;...
+    pitch_ref;...
+    z_B(3)*thrust-g(3)];
+
+hN = [position;...
+    velocity];
+
+%% MPCexport
+acadoSet('problemname', 'mav_position_mpc');
+
+N = 20;
+ocp = acado.OCP( 0.0, N*Ts, N );
+
+W_mat = eye(length(h));
+WN_mat = eye(length(hN));
+W = acado.BMatrix(W_mat);
+WN = acado.BMatrix(WN_mat);
+
+ocp.minimizeLSQ( W, h );
+ocp.minimizeLSQEndTerm( WN, hN );
+ocp.subjectTo(-deg2rad(45) <= [roll_ref; pitch_ref] <= deg2rad(45));
+ocp.subjectTo( g(3)/2.0 <= thrust <= g(3)*1.5);
+ocp.setModel(f);
+
+
+mpc = acado.OCPexport( ocp );
+mpc.set( 'HESSIAN_APPROXIMATION',       'GAUSS_NEWTON'      );
+mpc.set( 'DISCRETIZATION_TYPE',         'MULTIPLE_SHOOTING' );
+mpc.set( 'SPARSE_QP_SOLUTION',        'FULL_CONDENSING_N2'  ); %FULL_CONDENsinG_N2
+mpc.set( 'INTEGRATOR_TYPE',             'INT_IRK_GL2'       );
+mpc.set( 'NUM_INTEGRATOR_STEPS',         N                  );
+mpc.set( 'QP_SOLVER',                   'QP_QPOASES'    	);
+mpc.set( 'HOTSTART_QP',                 'NO'             	);
+mpc.set( 'LEVENBERG_MARQUARDT',          1e-10				);
+mpc.set( 'LINEAR_ALGEBRA_SOLVER',        'GAUSS_LU'         );
+mpc.set( 'IMPLICIT_INTEGRATOR_NUM_ITS',  2                  );
+mpc.set( 'CG_USE_OPENMP',                'YES'              );
+mpc.set( 'CG_HARDCODE_CONSTRAINT_VALUES', 'NO'              );
+mpc.set( 'CG_USE_VARIABLE_WEIGHTING_MATRIX', 'NO'           );
+
+
+if EXPORT
+    mpc.exportCode('.');
+end
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/EXAMPLES/example1.cpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/EXAMPLES/example1.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..92b47fc93798d2601ffc8c1810c187f94ac93df9
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/EXAMPLES/example1.cpp
@@ -0,0 +1,74 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file EXAMPLES/example1.cpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Very simple example for testing qpOASES (using QProblem class).
+ */
+
+
+#include <QProblem.hpp>
+
+
+/** Example for qpOASES main function using the QProblem class. */
+int main( )
+{
+	/* Setup data of first QP. */
+	real_t H[2*2] = { 1.0, 0.0, 0.0, 0.5 };
+	real_t A[1*2] = { 1.0, 1.0 };
+	real_t g[2] = { 1.5, 1.0 };
+	real_t lb[2] = { 0.5, -2.0 };
+	real_t ub[2] = { 5.0, 2.0 };
+	real_t lbA[1] = { -1.0 };
+	real_t ubA[1] = { 2.0 };
+
+	/* Setup data of second QP. */
+	real_t g_new[2] = { 1.0, 1.5 };
+	real_t lb_new[2] = { 0.0, -1.0 };
+	real_t ub_new[2] = { 5.0, -0.5 };
+	real_t lbA_new[1] = { -2.0 };
+	real_t ubA_new[1] = { 1.0 };
+
+
+	/* Setting up QProblem object. */
+	QProblem example( 2,1 );
+
+	/* Solve first QP. */
+	int nWSR = 10;
+	example.init( H,g,A,lb,ub,lbA,ubA, nWSR,0 );
+
+	/* Solve second QP. */
+	nWSR = 10;
+	example.hotstart( g_new,lb_new,ub_new,lbA_new,ubA_new, nWSR,0 );
+
+	return 0;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/EXAMPLES/example1b.cpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/EXAMPLES/example1b.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..331f19d8da0cbc8a530d9f6a36c5e0f57577e7ea
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/EXAMPLES/example1b.cpp
@@ -0,0 +1,69 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file EXAMPLES/example1b.cpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3
+ *	\date 2007-2008
+ *
+ *	Very simple example for testing qpOASES using the QProblemB class.
+ */
+
+
+#include <QProblemB.hpp>
+
+
+/** Example for qpOASES main function using the QProblemB class. */
+int main( )
+{
+	/* Setup data of first QP. */
+	real_t H[2*2] = { 1.0, 0.0, 0.0, 0.5 };
+	real_t g[2] = { 1.5, 1.0 };
+	real_t lb[2] = { 0.5, -2.0 };
+	real_t ub[2] = { 5.0, 2.0 };
+
+	/* Setup data of second QP. */
+	real_t g_new[2] = { 1.0, 1.5 };
+	real_t lb_new[2] = { 0.0, -1.0 };
+	real_t ub_new[2] = { 5.0, -0.5 };
+
+
+	/* Setting up QProblemB object. */
+	QProblemB example( 2 );
+
+	/* Solve first QP. */
+	int nWSR = 10;
+	example.init( H,g,lb,ub, nWSR,0 );
+
+	/* Solve second QP. */
+	nWSR = 10;
+	example.hotstart( g_new,lb_new,ub_new, nWSR,0 );
+
+	return 0;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/Bounds.hpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/Bounds.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..7260756da07b5b698599dd08077f6320cac7f4a8
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/Bounds.hpp
@@ -0,0 +1,189 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/Bounds.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Declaration of the Bounds class designed to manage working sets of
+ *	bounds within a QProblem.
+ */
+
+
+#ifndef QPOASES_BOUNDS_HPP
+#define QPOASES_BOUNDS_HPP
+
+
+#include <SubjectTo.hpp>
+
+
+
+/** This class manages working sets of bounds by storing
+ *	index sets and other status information.
+ *
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ */
+class Bounds : public SubjectTo
+{
+	/*
+	 *	PUBLIC MEMBER FUNCTIONS
+	 */
+	public:
+		/** Default constructor. */
+		Bounds( );
+
+		/** Copy constructor (deep copy). */
+		Bounds(	const Bounds& rhs	/**< Rhs object. */
+				);
+
+		/** Destructor. */
+		~Bounds( );
+
+		/** Assignment operator (deep copy). */
+		Bounds& operator=(	const Bounds& rhs	/**< Rhs object. */
+							);
+
+
+		/** Pseudo-constructor takes the number of bounds.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue init(	int n	/**< Number of bounds. */
+							);
+
+
+		/** Initially adds number of a new (i.e. not yet in the list) bound to
+		 *  given index set.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_SETUP_BOUND_FAILED \n
+					RET_INDEX_OUT_OF_BOUNDS \n
+					RET_INVALID_ARGUMENTS */
+		returnValue setupBound(	int _number,					/**< Number of new bound. */
+								SubjectToStatus _status			/**< Status of new bound. */
+								);
+
+		/** Initially adds all numbers of new (i.e. not yet in the list) bounds to
+		 *  to the index set of free bounds; the order depends on the SujectToType
+		 *  of each index.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_SETUP_BOUND_FAILED */
+		returnValue setupAllFree( );
+
+
+		/** Moves index of a bound from index list of fixed to that of free bounds.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_MOVING_BOUND_FAILED \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		returnValue moveFixedToFree(	int _number				/**< Number of bound to be freed. */
+										);
+
+		/** Moves index of a bound from index list of free to that of fixed bounds.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_MOVING_BOUND_FAILED \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		returnValue moveFreeToFixed(	int _number,			/**< Number of bound to be fixed. */
+										SubjectToStatus _status	/**< Status of bound to be fixed. */
+										);
+
+		/** Swaps the indices of two free bounds within the index set.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_SWAPINDEX_FAILED */
+		returnValue swapFree(	int number1,					/**< Number of first constraint or bound. */
+								int number2						/**< Number of second constraint or bound. */
+								);
+
+
+		/** Returns number of variables.
+		 *	\return Number of variables. */
+		inline int getNV( ) const;
+
+		/** Returns number of implicitly fixed variables.
+		 *	\return Number of implicitly fixed variables. */
+		inline int getNFV( ) const;
+
+		/** Returns number of bounded (but possibly free) variables.
+		 *	\return Number of bounded (but possibly free) variables. */
+		inline int getNBV( ) const;
+
+		/** Returns number of unbounded variables.
+		 *	\return Number of unbounded variables. */
+		inline int getNUV( ) const;
+
+
+		/** Sets number of implicitly fixed variables.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setNFV(	int n	/**< Number of implicitly fixed variables. */
+									);
+
+		/** Sets number of bounded (but possibly free) variables.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setNBV(	int n	/**< Number of bounded (but possibly free) variables. */
+									);
+
+		/** Sets number of unbounded variables.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setNUV(	int n	/**< Number of unbounded variables */
+									);
+
+
+		/** Returns number of free variables.
+		 *	\return Number of free variables. */
+		inline int getNFR( );
+
+		/** Returns number of fixed variables.
+		 *	\return Number of fixed variables. */
+		inline int getNFX( );
+
+
+		/** Returns a pointer to free variables index list.
+		 *	\return Pointer to free variables index list. */
+		inline Indexlist* getFree( );
+
+		/** Returns a pointer to fixed variables index list.
+		 *	\return Pointer to fixed variables index list. */
+		inline Indexlist* getFixed( );
+
+
+	/*
+	 *	PROTECTED MEMBER VARIABLES
+	 */
+	protected:
+		int nV;					/**< Number of variables (nV = nFV + nBV + nUV). */
+		int nFV;				/**< Number of implicitly fixed variables. */
+		int	nBV;				/**< Number of bounded (but possibly free) variables. */
+		int nUV;				/**< Number of unbounded variables. */
+
+		Indexlist free;			/**< Index list of free variables. */
+		Indexlist fixed;		/**< Index list of fixed variables. */
+};
+
+#include <Bounds.ipp>
+
+#endif	/* QPOASES_BOUNDS_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/Constants.hpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/Constants.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..92ee812295bf3746c1ebaf4899c851fa79f36aaf
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/Constants.hpp
@@ -0,0 +1,108 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/Constants.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2008
+ *
+ *	Definition of all global constants.
+ */
+
+
+#ifndef QPOASES_CONSTANTS_HPP
+#define QPOASES_CONSTANTS_HPP
+
+#ifndef QPOASES_CUSTOM_INTERFACE
+#include "acado_qpoases_interface.hpp"
+#else
+  #define XSTR(x) #x
+  #define STR(x) XSTR(x)
+  #include STR(QPOASES_CUSTOM_INTERFACE)
+#endif
+
+/** Maximum number of variables within a QP formulation.
+	Note: this value has to be positive! */
+const int NVMAX = QPOASES_NVMAX;
+
+/** Maximum number of constraints within a QP formulation.
+	Note: this value has to be positive! */
+const int NCMAX = QPOASES_NCMAX;
+
+/** Redefinition of NCMAX used for memory allocation, to avoid zero sized arrays
+    and compiler errors. */
+const int NCMAX_ALLOC = (NCMAX == 0) ? 1 : NCMAX;
+
+/**< Maximum number of working set recalculations.
+	Note: this value has to be positive! */
+const int NWSRMAX = QPOASES_NWSRMAX;
+
+/** Desired KKT tolerance of QP solution; a warning RET_INACCURATE_SOLUTION is
+ *  issued if this tolerance is not met.
+ *	Note: this value has to be positive! */
+const real_t DESIREDACCURACY = (real_t) 1.0e-3;
+
+/** Critical KKT tolerance of QP solution; an error is issued if this
+ *  tolerance is not met.
+ *	Note: this value has to be positive! */
+const real_t CRITICALACCURACY = (real_t) 1.0e-2;
+
+
+
+/** Numerical value of machine precision (min eps, s.t. 1+eps > 1).
+	Note: this value has to be positive! */
+const real_t EPS = (real_t) QPOASES_EPS;
+
+/** Numerical value of zero (for situations in which it would be
+ *	unreasonable to compare with 0.0).
+ *	Note: this value has to be positive! */
+const real_t ZERO = (real_t) 1.0e-50;
+
+/** Numerical value of infinity (e.g. for non-existing bounds).
+ *	Note: this value has to be positive! */
+const real_t INFTY = (real_t) 1.0e12;
+
+
+/** Lower/upper (constraints') bound tolerance (an inequality constraint
+ *	whose lower and upper bound differ by less than BOUNDTOL is regarded
+ *	to be an equality constraint).
+ *	Note: this value has to be positive! */
+const real_t BOUNDTOL = (real_t) 1.0e-10;
+
+/** Offset for relaxing (constraints') bounds at beginning of an initial homotopy.
+ *	Note: this value has to be positive! */
+const real_t BOUNDRELAXATION = (real_t) 1.0e3;
+
+
+/** Factor that determines physical lengths of index lists.
+ *	Note: this value has to be greater than 1! */
+const int INDEXLISTFACTOR = 5;
+
+
+#endif	/* QPOASES_CONSTANTS_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/Constraints.hpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/Constraints.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..899167942a7dd3637513c89c14ce4346358d275a
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/Constraints.hpp
@@ -0,0 +1,181 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/Constraints.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Declaration of the Constraints class designed to manage working sets of
+ *	constraints within a QProblem.
+ */
+
+
+#ifndef QPOASES_CONSTRAINTS_HPP
+#define QPOASES_CONSTRAINTS_HPP
+
+
+#include <SubjectTo.hpp>
+
+
+
+/** This class manages working sets of constraints by storing
+ *	index sets and other status information.
+ *
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ */
+class Constraints : public SubjectTo
+{
+	/*
+	 *	PUBLIC MEMBER FUNCTIONS
+	 */
+	public:
+		/** Default constructor. */
+		Constraints( );
+
+		/** Copy constructor (deep copy). */
+		Constraints(	const Constraints& rhs	/**< Rhs object. */
+						);
+
+		/** Destructor. */
+		~Constraints( );
+
+		/** Assignment operator (deep copy). */
+		Constraints& operator=(	const Constraints& rhs	/**< Rhs object. */
+								);
+
+
+		/** Pseudo-constructor takes the number of constraints.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue init(	int n	/**< Number of constraints. */
+							);
+
+
+		/** Initially adds number of a new (i.e. not yet in the list) constraint to
+		 *  a given index set.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_SETUP_CONSTRAINT_FAILED \n
+					RET_INDEX_OUT_OF_BOUNDS \n
+					RET_INVALID_ARGUMENTS */
+		returnValue setupConstraint(	int _number,				/**< Number of new constraint. */
+										SubjectToStatus _status		/**< Status of new constraint. */
+										);
+
+		/** Initially adds all enabled numbers of new (i.e. not yet in the list) constraints to
+		 *  to the index set of inactive constraints; the order depends on the SujectToType
+		 *  of each index. Only disabled constraints are added to index set of disabled constraints!
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_SETUP_CONSTRAINT_FAILED */
+		returnValue setupAllInactive( );
+
+
+		/** Moves index of a constraint from index list of active to that of inactive constraints.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_MOVING_CONSTRAINT_FAILED */
+		returnValue moveActiveToInactive(	int _number				/**< Number of constraint to become inactive. */
+											);
+
+		/** Moves index of a constraint from index list of inactive to that of active constraints.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_MOVING_CONSTRAINT_FAILED */
+		returnValue moveInactiveToActive(	int _number,			/**< Number of constraint to become active. */
+											SubjectToStatus _status	/**< Status of constraint to become active. */
+											);
+
+
+		/** Returns the number of constraints.
+		 *	\return Number of constraints. */
+		inline int getNC( ) const;
+
+		/** Returns the number of implicit equality constraints.
+		 *	\return Number of implicit equality constraints. */
+		inline int getNEC( ) const;
+
+		/** Returns the number of "real" inequality constraints.
+		 *	\return Number of "real" inequality constraints. */
+		inline int getNIC( ) const;
+
+		/** Returns the number of unbounded constraints (i.e. without any bounds).
+		 *	\return Number of unbounded constraints (i.e. without any bounds). */
+		inline int getNUC( ) const;
+
+
+		/** Sets number of implicit equality constraints.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setNEC(	int n	/**< Number of implicit equality constraints. */
+							);
+
+		/** Sets number of "real" inequality constraints.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setNIC(	int n	/**< Number of "real" inequality constraints. */
+									);
+
+		/** Sets number of unbounded constraints (i.e. without any bounds).
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setNUC(	int n	/**< Number of unbounded constraints (i.e. without any bounds). */
+									);
+
+
+		/** Returns the number of active constraints.
+		 *	\return Number of constraints. */
+		inline int getNAC( );
+
+		/** Returns the number of inactive constraints.
+		 *	\return Number of constraints. */
+		inline int getNIAC( );
+
+
+		/** Returns a pointer to active constraints index list.
+		 *	\return Pointer to active constraints index list. */
+		inline Indexlist* getActive( );
+
+		/** Returns a pointer to inactive constraints index list.
+		 *	\return Pointer to inactive constraints index list. */
+		inline Indexlist* getInactive( );
+
+
+	/*
+	 *	PROTECTED MEMBER VARIABLES
+	 */
+	protected:
+		int nC;					/**< Number of constraints (nC = nEC + nIC + nUC). */
+		int nEC;				/**< Number of implicit equality constraints. */
+		int	nIC;				/**< Number of "real" inequality constraints. */
+		int nUC;				/**< Number of unbounded constraints (i.e. without any bounds). */
+
+		Indexlist active;		/**< Index list of active constraints. */
+		Indexlist inactive;		/**< Index list of inactive constraints. */
+};
+
+
+#include <Constraints.ipp>
+
+#endif	/* QPOASES_CONSTRAINTS_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/CyclingManager.hpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/CyclingManager.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..b4410b106e61eade36587f56b5ccbadc1ed6a9a4
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/CyclingManager.hpp
@@ -0,0 +1,126 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/CyclingManager.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Declaration of the CyclingManager class designed to detect
+ *	and handle possible cycling during QP iterations.
+ */
+
+
+#ifndef QPOASES_CYCLINGMANAGER_HPP
+#define QPOASES_CYCLINGMANAGER_HPP
+
+
+#include <Utils.hpp>
+
+
+
+/** This class is intended to detect and handle possible cycling during QP iterations.
+ *	As cycling seems to occur quite rarely, this class is NOT FULLY IMPLEMENTED YET!
+ *
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ */
+class CyclingManager
+{
+	/*
+	 *	PUBLIC MEMBER FUNCTIONS
+	 */
+	public:
+		/** Default constructor. */
+		CyclingManager( );
+
+		/** Copy constructor (deep copy). */
+		CyclingManager(	const CyclingManager& rhs	/**< Rhs object. */
+						);
+
+		/** Destructor. */
+		~CyclingManager( );
+
+		/** Copy asingment operator (deep copy). */
+		CyclingManager& operator=(	const CyclingManager& rhs	/**< Rhs object. */
+									);
+
+
+		/** Pseudo-constructor which takes the number of bounds/constraints.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue init(	int _nV,	/**< Number of bounds to be managed. */
+							int _nC		/**< Number of constraints to be managed. */
+							);
+
+
+		/** Stores index of a bound/constraint that might cause cycling.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		returnValue setCyclingStatus(	int number,				/**< Number of bound/constraint. */
+										BooleanType isBound,	/**< Flag that indicates if given number corresponds to a
+																 *   bound (BT_TRUE) or a constraint (BT_FALSE). */
+										CyclingStatus _status	/**< Cycling status of bound/constraint. */
+										);
+
+		/** Returns if bound/constraint might cause cycling.
+		 *	\return BT_TRUE: bound/constraint might cause cycling \n
+		 			BT_FALSE: otherwise */
+		CyclingStatus getCyclingStatus(	int number,			/**< Number of bound/constraint. */
+										BooleanType isBound	/**< Flag that indicates if given number corresponds to
+															 *   a bound (BT_TRUE) or a constraint (BT_FALSE). */
+										) const;
+
+
+		/** Clears all previous cycling information.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue clearCyclingData( );
+
+
+		/** Returns if cycling was detected.
+		 *	\return BT_TRUE iff cycling was detected. */
+		inline BooleanType isCyclingDetected( ) const;
+
+
+	/*
+	 *	PROTECTED MEMBER VARIABLES
+	 */
+	protected:
+		int	nV;									/**< Number of managed bounds. */
+		int	nC;									/**< Number of managed constraints. */
+
+		CyclingStatus status[NVMAX+NCMAX];		/**< Array to store cycling status of all bounds/constraints. */
+
+		BooleanType cyclingDetected;			/**< Flag if cycling was detected. */
+};
+
+
+#include <CyclingManager.ipp>
+
+#endif	/* QPOASES_CYCLINGMANAGER_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..056bb26f02d09dab6949e9e25a9f0e87f67597e2
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp
@@ -0,0 +1,107 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/EXTRAS/SolutionAnalysis.hpp
+ *	\author Milan Vukov, Boris Houska, Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2012
+ *
+ *	Solution analysis class, based on a class in the standard version of the qpOASES
+ */
+
+
+//
+
+#ifndef QPOASES_SOLUTIONANALYSIS_HPP
+#define QPOASES_SOLUTIONANALYSIS_HPP
+
+#include <QProblem.hpp>
+
+/** Enables the computation of variance as is in the standard version of qpOASES */
+#define QPOASES_USE_OLD_VERSION 0
+
+#if QPOASES_USE_OLD_VERSION
+#define KKT_DIM (2 * NVMAX + NCMAX)
+#endif
+
+class SolutionAnalysis
+{
+public:
+	
+	/** Default constructor. */
+	SolutionAnalysis( );
+	
+	/** Copy constructor (deep copy). */
+	SolutionAnalysis( 	const SolutionAnalysis& rhs	/**< Rhs object. */
+						);
+	
+	/** Destructor. */
+	~SolutionAnalysis( );
+	
+	/** Copy asingment operator (deep copy). */
+	SolutionAnalysis& operator=(	const SolutionAnalysis& rhs	/**< Rhs object. */
+									);
+	
+	/** A routine for computation of inverse of the Hessian matrix. */
+	returnValue getHessianInverse(
+									QProblem* qp,			/** QP */
+									real_t* hessianInverse	/** Inverse of the Hessian matrix*/
+									);
+	
+	/** A routine for computation of inverse of the Hessian matrix. */
+	returnValue getHessianInverse(	QProblemB* qp,			/** QP */
+									real_t* hessianInverse	/** Inverse of the Hessian matrix*/
+									);
+
+#if QPOASES_USE_OLD_VERSION
+	returnValue getVarianceCovariance(
+										QProblem* qp,
+										real_t* g_b_bA_VAR,
+										real_t* Primal_Dual_VAR
+										);
+#endif
+	
+private:
+	
+	real_t delta_g_cov[ NVMAX ];		/** A covariance-vector of g */
+	real_t delta_lb_cov[ NVMAX ];		/** A covariance-vector of lb */
+	real_t delta_ub_cov[ NVMAX ];		/** A covariance-vector of ub */
+	real_t delta_lbA_cov[ NCMAX_ALLOC ];		/** A covariance-vector of lbA */
+	real_t delta_ubA_cov[ NCMAX_ALLOC ];		/** A covariance-vector of ubA */
+	
+#if QPOASES_USE_OLD_VERSION
+	real_t K[KKT_DIM * KKT_DIM];		/** A matrix to store an intermediate result */
+#endif
+	
+	int FR_idx[ NVMAX ];				/** Index array for free variables */
+	int FX_idx[ NVMAX ];				/** Index array for fixed variables */
+	int AC_idx[ NCMAX_ALLOC ];				/** Index array for active constraints */
+	
+	real_t delta_xFR[ NVMAX ];			/** QP reaction, primal, w.r.t. free */
+	real_t delta_xFX[ NVMAX ];			/** QP reaction, primal, w.r.t. fixed */
+	real_t delta_yAC[ NVMAX ];			/** QP reaction, dual, w.r.t. active */
+	real_t delta_yFX[ NVMAX ];			/** QP reaction, dual, w.r.t. fixed*/
+};
+
+#endif // QPOASES_SOLUTIONANALYSIS_HPP
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/Indexlist.hpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/Indexlist.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..21c31ddb9215bb98c59788986fff8db7ce92888d
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/Indexlist.hpp
@@ -0,0 +1,154 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/Indexlist.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Declaration of the Indexlist class designed to manage index lists of
+ *	constraints and bounds within a SubjectTo object.
+ */
+
+
+#ifndef QPOASES_INDEXLIST_HPP
+#define QPOASES_INDEXLIST_HPP
+
+
+#include <Utils.hpp>
+
+
+/** This class manages index lists.
+ *
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ */
+class Indexlist
+{
+	/*
+	 *	PUBLIC MEMBER FUNCTIONS
+	 */
+	public:
+		/** Default constructor. */
+		Indexlist( );
+
+		/** Copy constructor (deep copy). */
+		Indexlist(	const Indexlist& rhs	/**< Rhs object. */
+					);
+
+		/** Destructor. */
+		~Indexlist( );
+
+		/** Assingment operator (deep copy). */
+		Indexlist& operator=(	const Indexlist& rhs	/**< Rhs object. */
+								);
+
+		/** Pseudo-constructor.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue init( );
+
+
+		/** Creates an array of all numbers within the index set in correct order.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_INDEXLIST_CORRUPTED */
+		returnValue	getNumberArray(	int* const numberarray	/**< Output: Array of numbers (NULL on error). */
+									) const;
+
+
+		/** Determines the index within the index list at with a given number is stored.
+		 *	\return >= 0: Index of given number. \n
+		 			-1: Number not found. */
+		int	getIndex(	int givennumber	/**< Number whose index shall be determined. */
+						) const;
+
+		/** Determines the physical index within the index list at with a given number is stored.
+		 *	\return >= 0: Index of given number. \n
+		 			-1: Number not found. */
+		int	getPhysicalIndex(	int givennumber	/**< Number whose physical index shall be determined. */
+								) const;
+
+		/** Returns the number stored at a given physical index.
+		 *	\return >= 0: Number stored at given physical index. \n
+		 			-RET_INDEXLIST_OUTOFBOUNDS */
+		int	getNumber(	int physicalindex	/**< Physical index of the number to be returned. */
+						) const;
+
+
+		/** Returns the current length of the index list.
+		 *	\return Current length of the index list. */
+		inline int getLength( );
+
+		/** Returns last number within the index list.
+		 *	\return Last number within the index list. */
+		inline int getLastNumber( ) const;
+
+
+		/** Adds number to index list.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_INDEXLIST_MUST_BE_REORDERD \n
+		 			RET_INDEXLIST_EXCEEDS_MAX_LENGTH */
+		returnValue addNumber(	int addnumber	/**< Number to be added. */
+								);
+
+		/** Removes number from index list.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue removeNumber(	int removenumber	/**< Number to be removed. */
+									);
+
+		/** Swaps two numbers within index list.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue swapNumbers(	int number1,/**< First number for swapping. */
+									int number2	/**< Second number for swapping. */
+									);
+
+		/** Determines if a given number is contained in the index set.
+		 *	\return BT_TRUE iff number is contain in the index set */
+		inline BooleanType isMember(	int _number	/**< Number to be tested for membership. */
+										) const;
+
+
+	/*
+	 *	PROTECTED MEMBER VARIABLES
+	 */
+	protected:
+		int number[INDEXLISTFACTOR*(NVMAX+NCMAX)];		/**< Array to store numbers of constraints or bounds. */
+		int next[INDEXLISTFACTOR*(NVMAX+NCMAX)];		/**< Array to store physical index of successor. */
+		int previous[INDEXLISTFACTOR*(NVMAX+NCMAX)];	/**< Array to store physical index of predecossor. */
+		int	length;										/**< Length of index list. */
+		int	first;										/**< Physical index of first element. */
+		int	last;										/**< Physical index of last element. */
+		int	lastusedindex;								/**< Physical index of last entry in index list. */
+		int	physicallength;								/**< Physical length of index list. */
+};
+
+
+#include <Indexlist.ipp>
+
+#endif	/* QPOASES_INDEXLIST_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/MessageHandling.hpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/MessageHandling.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..3d17498ade0738c5fa356bbe56446ebfb6f3ada9
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/MessageHandling.hpp
@@ -0,0 +1,415 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/MessageHandling.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Declaration of the MessageHandling class including global return values.
+ */
+
+
+#ifndef QPOASES_MESSAGEHANDLING_HPP
+#define QPOASES_MESSAGEHANDLING_HPP
+
+// #define PC_DEBUG
+
+#ifdef PC_DEBUG
+  #include <stdio.h>
+
+  /** Defines an alias for  FILE  from stdio.h. */
+  #define myFILE FILE
+  /** Defines an alias for  stderr  from stdio.h. */
+  #define myStderr stderr
+  /** Defines an alias for  stdout  from stdio.h. */
+  #define myStdout stdout
+#else
+  /** Defines an alias for  FILE  from stdio.h. */
+  #define myFILE int
+  /** Defines an alias for  stderr  from stdio.h. */
+  #define myStderr 0
+  /** Defines an alias for  stdout  from stdio.h. */
+  #define myStdout 0
+#endif
+
+
+#include <Types.hpp>
+#include <Constants.hpp>
+
+
+/** Defines symbols for global return values. \n
+ *  Important: All return values are assumed to be nonnegative! */
+enum returnValue
+{
+TERMINAL_LIST_ELEMENT = -1,						/**< Terminal list element, internal usage only! */
+/* miscellaneous */
+SUCCESSFUL_RETURN = 0,							/**< Successful return. */
+RET_DIV_BY_ZERO,		   						/**< Division by zero. */
+RET_INDEX_OUT_OF_BOUNDS,						/**< Index out of bounds. */
+RET_INVALID_ARGUMENTS,							/**< At least one of the arguments is invalid. */
+RET_ERROR_UNDEFINED,							/**< Error number undefined. */
+RET_WARNING_UNDEFINED,							/**< Warning number undefined. */
+RET_INFO_UNDEFINED,								/**< Info number undefined. */
+RET_EWI_UNDEFINED,								/**< Error/warning/info number undefined. */
+RET_AVAILABLE_WITH_LINUX_ONLY,					/**< This function is available under Linux only. */
+RET_UNKNOWN_BUG,								/**< The error occured is not yet known. */
+RET_PRINTLEVEL_CHANGED,							/**< 10 Print level changed. */
+RET_NOT_YET_IMPLEMENTED,						/**< Requested function is not yet implemented in this version of qpOASES. */
+/* Indexlist */
+RET_INDEXLIST_MUST_BE_REORDERD,					/**< Index list has to be reordered. */
+RET_INDEXLIST_EXCEEDS_MAX_LENGTH,				/**< Index list exceeds its maximal physical length. */
+RET_INDEXLIST_CORRUPTED,						/**< Index list corrupted. */
+RET_INDEXLIST_OUTOFBOUNDS,						/**< Physical index is out of bounds. */
+RET_INDEXLIST_ADD_FAILED,						/**< Adding indices from another index set failed. */
+RET_INDEXLIST_INTERSECT_FAILED,					/**< Intersection with another index set failed. */
+/* SubjectTo / Bounds / Constraints */
+RET_INDEX_ALREADY_OF_DESIRED_STATUS,			/**< Index is already of desired status. */
+RET_ADDINDEX_FAILED,							/**< Cannot swap between different indexsets. */
+RET_SWAPINDEX_FAILED,							/**< 20 Adding index to index set failed. */
+RET_NOTHING_TO_DO,								/**< Nothing to do. */
+RET_SETUP_BOUND_FAILED,							/**< Setting up bound index failed. */
+RET_SETUP_CONSTRAINT_FAILED,					/**< Setting up constraint index failed. */
+RET_MOVING_BOUND_FAILED,						/**< Moving bound between index sets failed. */
+RET_MOVING_CONSTRAINT_FAILED,					/**< Moving constraint between index sets failed. */
+/* QProblem */
+RET_QP_ALREADY_INITIALISED,						/**< QProblem has already been initialised. */
+RET_NO_INIT_WITH_STANDARD_SOLVER,				/**< Initialisation via extern QP solver is not yet implemented. */
+RET_RESET_FAILED,								/**< Reset failed. */
+RET_INIT_FAILED,								/**< Initialisation failed. */
+RET_INIT_FAILED_TQ,								/**< 30 Initialisation failed due to TQ factorisation. */
+RET_INIT_FAILED_CHOLESKY,						/**< Initialisation failed due to Cholesky decomposition. */
+RET_INIT_FAILED_HOTSTART,						/**< Initialisation failed! QP could not be solved! */
+RET_INIT_FAILED_INFEASIBILITY,					/**< Initial QP could not be solved due to infeasibility! */
+RET_INIT_FAILED_UNBOUNDEDNESS,					/**< Initial QP could not be solved due to unboundedness! */
+RET_INIT_SUCCESSFUL,							/**< Initialisation done. */
+RET_OBTAINING_WORKINGSET_FAILED,				/**< Failed to obtain working set for auxiliary QP. */
+RET_SETUP_WORKINGSET_FAILED,					/**< Failed to setup working set for auxiliary QP. */
+RET_SETUP_AUXILIARYQP_FAILED,					/**< Failed to setup auxiliary QP for initialised homotopy. */
+RET_NO_EXTERN_SOLVER,							/**< No extern QP solver available. */
+RET_QP_UNBOUNDED,								/**< 40 QP is unbounded. */
+RET_QP_INFEASIBLE,								/**< QP is infeasible. */
+RET_QP_NOT_SOLVED,								/**< Problems occured while solving QP with standard solver. */
+RET_QP_SOLVED,									/**< QP successfully solved. */
+RET_UNABLE_TO_SOLVE_QP,							/**< Problems occured while solving QP. */
+RET_INITIALISATION_STARTED,						/**< Starting problem initialisation. */
+RET_HOTSTART_FAILED,							/**< Unable to perform homotopy due to internal error. */
+RET_HOTSTART_FAILED_TO_INIT,					/**< Unable to initialise problem. */
+RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED,		/**< Unable to perform homotopy as previous QP is not solved. */
+RET_ITERATION_STARTED,							/**< Iteration... */
+RET_SHIFT_DETERMINATION_FAILED,					/**< 50 Determination of shift of the QP data failed. */
+RET_STEPDIRECTION_DETERMINATION_FAILED,			/**< Determination of step direction failed. */
+RET_STEPLENGTH_DETERMINATION_FAILED,			/**< Determination of step direction failed. */
+RET_OPTIMAL_SOLUTION_FOUND,						/**< Optimal solution of neighbouring QP found. */
+RET_HOMOTOPY_STEP_FAILED,						/**< Unable to perform homotopy step. */
+RET_HOTSTART_STOPPED_INFEASIBILITY,				/**< Premature homotopy termination because QP is infeasible. */
+RET_HOTSTART_STOPPED_UNBOUNDEDNESS,				/**< Premature homotopy termination because QP is unbounded. */
+RET_WORKINGSET_UPDATE_FAILED,					/**< Unable to update working sets according to initial guesses. */
+RET_MAX_NWSR_REACHED,							/**< Maximum number of working set recalculations performed. */
+RET_CONSTRAINTS_NOT_SPECIFIED,					/**< Problem does comprise constraints! You also have to specify new constraints' bounds. */
+RET_INVALID_FACTORISATION_FLAG,					/**< 60 Invalid factorisation flag. */
+RET_UNABLE_TO_SAVE_QPDATA,						/**< Unable to save QP data. */
+RET_STEPDIRECTION_FAILED_TQ,					/**< Abnormal termination due to TQ factorisation. */
+RET_STEPDIRECTION_FAILED_CHOLESKY,				/**< Abnormal termination due to Cholesky factorisation. */
+RET_CYCLING_DETECTED,							/**< Cycling detected. */
+RET_CYCLING_NOT_RESOLVED,						/**< Cycling cannot be resolved, QP probably infeasible. */
+RET_CYCLING_RESOLVED,							/**< Cycling probably resolved. */
+RET_STEPSIZE,									/**< For displaying performed stepsize. */
+RET_STEPSIZE_NONPOSITIVE,						/**< For displaying non-positive stepsize. */
+RET_SETUPSUBJECTTOTYPE_FAILED,					/**< Setup of SubjectToTypes failed. */
+RET_ADDCONSTRAINT_FAILED,						/**< 70 Addition of constraint to working set failed. */
+RET_ADDCONSTRAINT_FAILED_INFEASIBILITY,			/**< Addition of constraint to working set failed (due to QP infeasibility). */
+RET_ADDBOUND_FAILED,							/**< Addition of bound to working set failed. */
+RET_ADDBOUND_FAILED_INFEASIBILITY,				/**< Addition of bound to working set failed (due to QP infeasibility). */
+RET_REMOVECONSTRAINT_FAILED,					/**< Removal of constraint from working set failed. */
+RET_REMOVEBOUND_FAILED,							/**< Removal of bound from working set failed. */
+RET_REMOVE_FROM_ACTIVESET,						/**< Removing from active set... */
+RET_ADD_TO_ACTIVESET,							/**< Adding to active set... */
+RET_REMOVE_FROM_ACTIVESET_FAILED,				/**< Removing from active set failed. */
+RET_ADD_TO_ACTIVESET_FAILED,					/**< Adding to active set failed. */
+RET_CONSTRAINT_ALREADY_ACTIVE,					/**< 80 Constraint is already active. */
+RET_ALL_CONSTRAINTS_ACTIVE,						/**< All constraints are active, no further constraint can be added. */
+RET_LINEARLY_DEPENDENT,							/**< New bound/constraint is linearly dependent. */
+RET_LINEARLY_INDEPENDENT,						/**< New bound/constraint is linearly independent. */
+RET_LI_RESOLVED,								/**< Linear independence of active contraint matrix successfully resolved. */
+RET_ENSURELI_FAILED,							/**< Failed to ensure linear indepence of active contraint matrix. */
+RET_ENSURELI_FAILED_TQ,							/**< Abnormal termination due to TQ factorisation. */
+RET_ENSURELI_FAILED_NOINDEX,					/**< No index found, QP probably infeasible. */
+RET_ENSURELI_FAILED_CYCLING,					/**< Cycling detected, QP probably infeasible. */
+RET_BOUND_ALREADY_ACTIVE,						/**< Bound is already active. */
+RET_ALL_BOUNDS_ACTIVE,							/**< 90 All bounds are active, no further bound can be added. */
+RET_CONSTRAINT_NOT_ACTIVE,						/**< Constraint is not active. */
+RET_BOUND_NOT_ACTIVE,							/**< Bound is not active. */
+RET_HESSIAN_NOT_SPD,							/**< Projected Hessian matrix not positive definite. */
+RET_MATRIX_SHIFT_FAILED,						/**< Unable to update matrices or to transform vectors. */
+RET_MATRIX_FACTORISATION_FAILED,				/**< Unable to calculate new matrix factorisations. */
+RET_PRINT_ITERATION_FAILED,						/**< Unable to print information on current iteration. */
+RET_NO_GLOBAL_MESSAGE_OUTPUTFILE,				/**< No global message output file initialised. */
+/* Utils */
+RET_UNABLE_TO_OPEN_FILE,						/**< Unable to open file. */
+RET_UNABLE_TO_WRITE_FILE,						/**< Unable to write into file. */
+RET_UNABLE_TO_READ_FILE,						/**< 100 Unable to read from file. */
+RET_FILEDATA_INCONSISTENT,						/**< File contains inconsistent data. */
+/* SolutionAnalysis */
+RET_NO_SOLUTION, 								/**< QP solution does not satisfy KKT optimality conditions. */
+RET_INACCURATE_SOLUTION							/**< KKT optimality conditions not satisfied to sufficient accuracy. */
+};
+
+
+
+/** This class handles all kinds of messages (errors, warnings, infos) initiated
+ *  by qpOASES modules and stores the correspoding global preferences.
+ *
+ *	\author Hans Joachim Ferreau (special thanks to Leonard Wirsching)
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ */
+class MessageHandling
+{
+	/*
+	 *	INTERNAL DATA STRUCTURES
+	 */
+	public:
+		/** Data structure for entries in global message list. */
+		typedef struct {
+			returnValue key;							/**< Global return value. */
+			const char* data;							/**< Corresponding message. */
+			VisibilityStatus globalVisibilityStatus; 	/**< Determines if message can be printed.
+														* 	 If this value is set to VS_HIDDEN, no message is printed! */
+		} ReturnValueList;
+
+
+	/*
+	 *	PUBLIC MEMBER FUNCTIONS
+	 */
+	public:
+		/** Default constructor. */
+		MessageHandling( );
+
+		/** Constructor which takes the desired output file. */
+		MessageHandling(  myFILE* _outputFile					/**< Output file. */
+						  );
+
+		/** Constructor which takes the desired visibility states. */
+		MessageHandling(	VisibilityStatus _errorVisibility,	/**< Visibility status for error messages. */
+							VisibilityStatus _warningVisibility,/**< Visibility status for warning messages. */
+							VisibilityStatus _infoVisibility	/**< Visibility status for info messages. */
+							);
+
+		/** Constructor which takes the desired output file and desired visibility states. */
+		MessageHandling(	myFILE* _outputFile,				/**< Output file. */
+							VisibilityStatus _errorVisibility,	/**< Visibility status for error messages. */
+							VisibilityStatus _warningVisibility,/**< Visibility status for warning messages. */
+							VisibilityStatus _infoVisibility	/**< Visibility status for info messages. */
+							);
+
+		/** Copy constructor (deep copy). */
+		MessageHandling(	const MessageHandling& rhs	/**< Rhs object. */
+							);
+
+		/** Destructor. */
+		~MessageHandling( );
+
+		/** Assignment operator (deep copy). */
+		MessageHandling& operator=(	const MessageHandling& rhs	/**< Rhs object. */
+									);
+
+
+		/** Prints an error message(a simplified macro THROWERROR is also provided). \n
+		 *  Errors are definied as abnormal events which cause an immediate termination of the current (sub) function.
+		 *  Errors of a sub function should be commented by the calling function by means of a warning message
+		 *  (if this error does not cause an error of the calling function, either)!
+		 *  \return Error number returned by sub function call
+		 */
+		returnValue throwError(
+			returnValue Enumber,					/**< Error number returned by sub function call. */
+			const char* additionaltext,				/**< Additional error text (0, if none). */
+			const char* functionname,				/**< Name of function which caused the error. */
+			const char* filename,					/**< Name of file which caused the error. */
+			const unsigned long linenumber,			/**< Number of line which caused the error.incompatible binary file */
+			VisibilityStatus localVisibilityStatus	/**< Determines (locally) if error message can be printed to myStderr.
+			   									 *   If GLOBAL visibility status of the message is set to VS_HIDDEN,
+	   			 								 *   no message is printed, anyway! */
+		);
+
+		/** Prints a warning message (a simplified macro THROWWARNING is also provided).
+		 *  Warnings are definied as abnormal events which does NOT cause an immediate termination of the current (sub) function.
+		 *  \return Warning number returned by sub function call
+		 */
+		returnValue throwWarning(
+			returnValue Wnumber,	 				/**< Warning number returned by sub function call. */
+			const char* additionaltext,				/**< Additional warning text (0, if none). */
+			const char* functionname,				/**< Name of function which caused the warning. */
+			const char* filename,   				/**< Name of file which caused the warning. */
+			const unsigned long linenumber,	 		/**< Number of line which caused the warning. */
+			VisibilityStatus localVisibilityStatus	/**< Determines (locally) if warning message can be printed to myStderr.
+		   		  									 *   If GLOBAL visibility status of the message is set to VS_HIDDEN,
+					 								 *   no message is printed, anyway! */
+			);
+
+	   /** Prints a info message (a simplified macro THROWINFO is also provided).
+		 *  \return Info number returned by sub function call
+		 */
+		returnValue throwInfo(
+			returnValue Inumber,	 				/**< Info number returned by sub function call. */
+			const char* additionaltext,	 			/**< Additional warning text (0, if none). */
+			const char* functionname,				/**< Name of function which submitted the info. */
+			const char* filename,   				/**< Name of file which submitted the info. */
+			const unsigned long linenumber,			/**< Number of line which submitted the info. */
+			VisibilityStatus localVisibilityStatus	/**< Determines (locally) if info message can be printed to myStderr.
+				  									 *   If GLOBAL visibility status of the message is set to VS_HIDDEN,
+				   									 *   no message is printed, anyway! */
+			);
+
+
+		/** Resets all preferences to default values.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue reset( );
+
+
+		/** Prints a complete list of all messages to output file.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue listAllMessages( );
+
+
+		/** Returns visibility status for error messages.
+		 *	\return Visibility status for error messages. */
+		inline VisibilityStatus getErrorVisibilityStatus( ) const;
+
+		/** Returns visibility status for warning messages.
+		 *	\return Visibility status for warning messages. */
+		inline VisibilityStatus getWarningVisibilityStatus( ) const;
+
+		/** Returns visibility status for info messages.
+		 *	\return Visibility status for info messages. */
+		inline VisibilityStatus getInfoVisibilityStatus( ) const;
+
+		/** Returns pointer to output file.
+		 *	\return Pointer to output file. */
+		inline myFILE* getOutputFile( ) const;
+
+		/** Returns error count value.
+		 *	\return Error count value. */
+		inline int getErrorCount( ) const;
+
+
+		/** Changes visibility status for error messages. */
+		inline void setErrorVisibilityStatus(	VisibilityStatus _errorVisibility	/**< New visibility status for error messages. */
+												);
+
+		/** Changes visibility status for warning messages. */
+		inline void setWarningVisibilityStatus(	VisibilityStatus _warningVisibility	/**< New visibility status for warning messages. */
+												);
+
+		/** Changes visibility status for info messages. */
+		inline void setInfoVisibilityStatus(	VisibilityStatus _infoVisibility	/**< New visibility status for info messages. */
+												);
+
+		/** Changes output file for messages. */
+		inline void setOutputFile(	myFILE* _outputFile	/**< New output file for messages. */
+									);
+
+		/** Changes error count.
+		 * \return SUCCESSFUL_RETURN \n
+		 *		   RET_INVALID_ARGUMENT */
+		inline returnValue setErrorCount(	int _errorCount	/**< New error count value. */
+											);
+
+		/** Return the error code string. */
+		static const char* getErrorString(int error);
+
+	/*
+	 *	PROTECTED MEMBER FUNCTIONS
+	 */
+	protected:
+		/** Prints a info message to myStderr (auxiliary function).
+		 *  \return Error/warning/info number returned by sub function call
+		 */
+		returnValue throwMessage(
+			returnValue RETnumber,	 				/**< Error/warning/info number returned by sub function call. */
+			const char* additionaltext,				/**< Additional warning text (0, if none). */
+			const char* functionname,				/**< Name of function which caused the error/warning/info. */
+			const char* filename,   				/**< Name of file which caused the error/warning/info. */
+			const unsigned long linenumber,			/**< Number of line which caused the error/warning/info. */
+			VisibilityStatus localVisibilityStatus,	/**< Determines (locally) if info message can be printed to myStderr.
+					  								 *   If GLOBAL visibility status of the message is set to VS_HIDDEN,
+				   									 *   no message is printed, anyway! */
+			const char* RETstring					/**< Leading string of error/warning/info message. */
+			);
+
+
+	/*
+	 *	PROTECTED MEMBER VARIABLES
+	 */
+	protected:
+		VisibilityStatus errorVisibility;		/**< Error messages visible? */
+		VisibilityStatus warningVisibility;		/**< Warning messages visible? */
+		VisibilityStatus infoVisibility;		/**< Info messages visible? */
+
+		myFILE* outputFile;						/**< Output file for messages. */
+
+		int errorCount; 						/**< Counts number of errors (for nicer output only). */
+};
+
+
+#ifndef __FUNCTION__
+  /** Ensures that __FUNCTION__ macro is defined. */
+  #define __FUNCTION__ 0
+#endif
+
+#ifndef __FILE__
+  /** Ensures that __FILE__ macro is defined. */
+  #define __FILE__ 0
+#endif
+
+#ifndef __LINE__
+  /** Ensures that __LINE__ macro is defined. */
+  #define __LINE__ 0
+#endif
+
+
+/** Short version of throwError with default values, only returnValue is needed */
+#define THROWERROR(retval) ( getGlobalMessageHandler( )->throwError((retval),0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE) )
+
+/** Short version of throwWarning with default values, only returnValue is needed */
+#define THROWWARNING(retval) ( getGlobalMessageHandler( )->throwWarning((retval),0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE) )
+
+/** Short version of throwInfo with default values, only returnValue is needed */
+#define THROWINFO(retval) ( getGlobalMessageHandler( )->throwInfo((retval),0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE) )
+
+
+/** Returns a pointer to global message handler.
+ *  \return Pointer to global message handler.
+ */
+MessageHandling* getGlobalMessageHandler( );
+
+
+#include <MessageHandling.ipp>
+
+#endif /* QPOASES_MESSAGEHANDLING_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/QProblem.hpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/QProblem.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..91dc43417542a5eb5091e3d6d6cd942482c5bd0a
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/QProblem.hpp
@@ -0,0 +1,666 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/QProblem.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Declaration of the QProblem class which is able to use the newly
+ *	developed online active set strategy for parametric quadratic programming.
+ */
+
+
+
+#ifndef QPOASES_QPROBLEM_HPP
+#define QPOASES_QPROBLEM_HPP
+
+
+#include <QProblemB.hpp>
+#include <Constraints.hpp>
+#include <CyclingManager.hpp>
+
+
+/** A class for setting up and solving quadratic programs. The main feature is
+ *	the possibily to use the newly developed online active set strategy for
+ * 	parametric quadratic programming.
+ *
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ */
+class QProblem : public QProblemB
+{
+	/* allow SolutionAnalysis class to access private members */
+	friend class SolutionAnalysis;
+	
+	/*
+	 *	PUBLIC MEMBER FUNCTIONS
+	 */
+	public:
+		/** Default constructor. */
+		QProblem( );
+
+		/** Constructor which takes the QP dimensions only. */
+		QProblem(	int _nV,	  				/**< Number of variables. */
+					int _nC  					/**< Number of constraints. */
+					);
+
+		/** Copy constructor (deep copy). */
+		QProblem(	const QProblem& rhs	/**< Rhs object. */
+					);
+
+		/** Destructor. */
+		~QProblem( );
+
+		/** Assignment operator (deep copy). */
+		QProblem& operator=(	const QProblem& rhs		/**< Rhs object. */
+								);
+
+
+		/** Clears all data structures of QProblemB except for QP data.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_RESET_FAILED */
+		returnValue reset( );
+
+
+		/** Initialises a QProblem with given QP data and solves it
+		 *	using an initial homotopy with empty working set (at most nWSR iterations).
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_INIT_FAILED \n
+					RET_INIT_FAILED_CHOLESKY \n
+					RET_INIT_FAILED_TQ \n
+					RET_INIT_FAILED_HOTSTART \n
+					RET_INIT_FAILED_INFEASIBILITY \n
+					RET_INIT_FAILED_UNBOUNDEDNESS \n
+					RET_MAX_NWSR_REACHED \n
+					RET_INVALID_ARGUMENTS \n
+					RET_INACCURATE_SOLUTION \n
+		 			RET_NO_SOLUTION */
+		returnValue init(	const real_t* const _H, 		/**< Hessian matrix. */
+							const real_t* const _g, 		/**< Gradient vector. */
+							const real_t* const _A,  		/**< Constraint matrix. */
+							const real_t* const _lb,		/**< Lower bound vector (on variables). \n
+																If no lower bounds exist, a NULL pointer can be passed. */
+							const real_t* const _ub,		/**< Upper bound vector (on variables). \n
+																If no upper bounds exist, a NULL pointer can be passed. */
+							const real_t* const _lbA,		/**< Lower constraints' bound vector. \n
+																If no lower constraints' bounds exist, a NULL pointer can be passed. */
+							const real_t* const _ubA,		/**< Upper constraints' bound vector. \n
+																If no lower constraints' bounds exist, a NULL pointer can be passed. */
+							int& nWSR,						/**< Input: Maximum number of working set recalculations when using initial homotopy.
+																Output: Number of performed working set recalculations. */
+							const real_t* const yOpt = 0,	/**< Initial guess for dual solution vector. */
+							real_t* const cputime = 0		/**< Output: CPU time required to initialise QP. */
+							);
+
+
+		/** Initialises a QProblem with given QP data and solves it
+		 *	using an initial homotopy with empty working set (at most nWSR iterations).
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_INIT_FAILED \n
+					RET_INIT_FAILED_CHOLESKY \n
+					RET_INIT_FAILED_TQ \n
+					RET_INIT_FAILED_HOTSTART \n
+					RET_INIT_FAILED_INFEASIBILITY \n
+					RET_INIT_FAILED_UNBOUNDEDNESS \n
+					RET_MAX_NWSR_REACHED \n
+					RET_INVALID_ARGUMENTS \n
+					RET_INACCURATE_SOLUTION \n
+		 			RET_NO_SOLUTION */
+		returnValue init(	const real_t* const _H, 		/**< Hessian matrix. */
+							const real_t* const _R, 		/**< Cholesky factorization of the Hessian matrix. */
+							const real_t* const _g, 		/**< Gradient vector. */
+							const real_t* const _A,  		/**< Constraint matrix. */
+							const real_t* const _lb,		/**< Lower bound vector (on variables). \n
+																If no lower bounds exist, a NULL pointer can be passed. */
+							const real_t* const _ub,		/**< Upper bound vector (on variables). \n
+																If no upper bounds exist, a NULL pointer can be passed. */
+							const real_t* const _lbA,		/**< Lower constraints' bound vector. \n
+																If no lower constraints' bounds exist, a NULL pointer can be passed. */
+							const real_t* const _ubA,		/**< Upper constraints' bound vector. \n
+																If no lower constraints' bounds exist, a NULL pointer can be passed. */
+							int& nWSR,						/**< Input: Maximum number of working set recalculations when using initial homotopy.
+																Output: Number of performed working set recalculations. */
+							const real_t* const yOpt = 0,	/**< Initial guess for dual solution vector. */
+							real_t* const cputime = 0		/**< Output: CPU time required to initialise QP. */
+							);
+
+
+		/** Solves QProblem using online active set strategy.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_MAX_NWSR_REACHED \n
+		 			RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n
+					RET_HOTSTART_FAILED \n
+					RET_SHIFT_DETERMINATION_FAILED \n
+					RET_STEPDIRECTION_DETERMINATION_FAILED \n
+					RET_STEPLENGTH_DETERMINATION_FAILED \n
+					RET_HOMOTOPY_STEP_FAILED \n
+					RET_HOTSTART_STOPPED_INFEASIBILITY \n
+					RET_HOTSTART_STOPPED_UNBOUNDEDNESS \n
+					RET_INACCURATE_SOLUTION \n
+		 			RET_NO_SOLUTION */
+		returnValue hotstart(	const real_t* const g_new,		/**< Gradient of neighbouring QP to be solved. */
+								const real_t* const lb_new,		/**< Lower bounds of neighbouring QP to be solved. \n
+													 			 	 If no lower bounds exist, a NULL pointer can be passed. */
+								const real_t* const ub_new,		/**< Upper bounds of neighbouring QP to be solved. \n
+													 			 	 If no upper bounds exist, a NULL pointer can be passed. */
+								const real_t* const lbA_new,	/**< Lower constraints' bounds of neighbouring QP to be solved. \n
+													 			 	 If no lower constraints' bounds exist, a NULL pointer can be passed. */
+								const real_t* const ubA_new,	/**< Upper constraints' bounds of neighbouring QP to be solved. \n
+													 			 	 If no upper constraints' bounds exist, a NULL pointer can be passed. */
+								int& nWSR,						/**< Input: Maximum number of working set recalculations; \n
+															 		 Output: Number of performed working set recalculations. */
+								real_t* const cputime			/**< Output: CPU time required to solve QP (or to perform nWSR iterations). */
+								);
+
+
+		/** Returns constraint matrix of the QP (deep copy).
+		  *	\return SUCCESSFUL_RETURN */
+		inline returnValue getA(	real_t* const _A	/**< Array of appropriate dimension for copying constraint matrix.*/
+									) const;
+
+		/** Returns a single row of constraint matrix of the QP (deep copy).
+		  *	\return SUCCESSFUL_RETURN \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue getA(	int number,			/**< Number of entry to be returned. */
+									real_t* const row	/**< Array of appropriate dimension for copying (number)th constraint. */
+									) const;
+
+		/** Returns lower constraints' bound vector of the QP (deep copy).
+		  *	\return SUCCESSFUL_RETURN */
+		inline returnValue getLBA(	real_t* const _lbA	/**< Array of appropriate dimension for copying lower constraints' bound vector.*/
+									) const;
+
+		/** Returns single entry of lower constraints' bound vector of the QP.
+		  *	\return SUCCESSFUL_RETURN \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue getLBA(	int number,		/**< Number of entry to be returned. */
+									real_t& value	/**< Output: lbA[number].*/
+									) const;
+
+		/** Returns upper constraints' bound vector of the QP (deep copy).
+		  *	\return SUCCESSFUL_RETURN */
+		inline returnValue getUBA(	real_t* const _ubA	/**< Array of appropriate dimension for copying upper constraints' bound vector.*/
+									) const;
+
+		/** Returns single entry of upper constraints' bound vector of the QP.
+		  *	\return SUCCESSFUL_RETURN \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue getUBA(	int number,		/**< Number of entry to be returned. */
+									real_t& value	/**< Output: ubA[number].*/
+									) const;
+
+
+		/** Returns current constraints object of the QP (deep copy).
+		  *	\return SUCCESSFUL_RETURN */
+		inline returnValue getConstraints(	Constraints* const _constraints	/** Output: Constraints object. */
+											) const;
+
+
+		/** Returns the number of constraints.
+		 *	\return Number of constraints. */
+		inline int getNC( ) const;
+
+		/** Returns the number of (implicitly defined) equality constraints.
+		 *	\return Number of (implicitly defined) equality constraints. */
+		inline int getNEC( ) const;
+
+		/** Returns the number of active constraints.
+		 *	\return Number of active constraints. */
+		inline int getNAC( );
+
+		/** Returns the number of inactive constraints.
+		 *	\return Number of inactive constraints. */
+		inline int getNIAC( );
+
+		/** Returns the dimension of null space.
+		 *	\return Dimension of null space. */
+		int getNZ( );
+
+
+		/** Returns the dual solution vector (deep copy).
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_QP_NOT_SOLVED */
+		returnValue getDualSolution(	real_t* const yOpt	/**< Output: Dual solution vector (if QP has been solved). */
+										) const;
+
+
+	/*
+	 *	PROTECTED MEMBER FUNCTIONS
+	 */
+	protected:
+		/** Determines type of constraints and bounds (i.e. implicitly fixed, unbounded etc.).
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_SETUPSUBJECTTOTYPE_FAILED */
+		returnValue setupSubjectToType( );
+
+		/** Computes the Cholesky decomposition R of the projected Hessian (i.e. R^T*R = Z^T*H*Z).
+		 *	\return SUCCESSFUL_RETURN \n
+		 *			RET_INDEXLIST_CORRUPTED */
+		returnValue setupCholeskyDecompositionProjected( );
+
+		/** Initialises TQ factorisation of A (i.e. A*Q = [0 T]) if NO constraint is active.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_INDEXLIST_CORRUPTED */
+		returnValue setupTQfactorisation( );
+
+
+		/** Solves a QProblem whose QP data is assumed to be stored in the member variables.
+		 *  A guess for its primal/dual optimal solution vectors and the corresponding
+		 *  working sets of bounds and constraints can be provided.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_INIT_FAILED \n
+					RET_INIT_FAILED_CHOLESKY \n
+					RET_INIT_FAILED_TQ \n
+					RET_INIT_FAILED_HOTSTART \n
+					RET_INIT_FAILED_INFEASIBILITY \n
+					RET_INIT_FAILED_UNBOUNDEDNESS \n
+					RET_MAX_NWSR_REACHED */
+		returnValue solveInitialQP(	const real_t* const xOpt,						/**< Optimal primal solution vector.
+																					 *	 A NULL pointer can be passed. */
+									const real_t* const yOpt,						/**< Optimal dual solution vector.
+																					 *	 A NULL pointer can be passed. */
+									const Bounds* const guessedBounds,				/**< Guessed working set of bounds for solution (xOpt,yOpt).
+																		 			 *	 A NULL pointer can be passed. */
+									const Constraints* const guessedConstraints,	/**< Optimal working set of constraints for solution (xOpt,yOpt).
+																		 			 *	 A NULL pointer can be passed. */
+									int& nWSR, 										/**< Input: Maximum number of working set recalculations; \n
+																 					 *	 Output: Number of performed working set recalculations. */
+									real_t* const cputime							/**< Output: CPU time required to solve QP (or to perform nWSR iterations). */
+									);
+
+		/** Obtains the desired working set for the auxiliary initial QP in
+		 *  accordance with the user specifications
+		 *  (assumes that member AX has already been initialised!)
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_OBTAINING_WORKINGSET_FAILED \n
+					RET_INVALID_ARGUMENTS */
+		returnValue obtainAuxiliaryWorkingSet(	const real_t* const xOpt,						/**< Optimal primal solution vector.
+																								 *	 If a NULL pointer is passed, all entries are assumed to be zero. */
+												const real_t* const yOpt,						/**< Optimal dual solution vector.
+																								 *	 If a NULL pointer is passed, all entries are assumed to be zero. */
+												const Bounds* const guessedBounds,				/**< Guessed working set of bounds for solution (xOpt,yOpt). */
+												const Constraints* const guessedConstraints,	/**< Guessed working set for solution (xOpt,yOpt). */
+												Bounds* auxiliaryBounds,						/**< Input: Allocated bound object. \n
+																								 *	 Ouput: Working set of constraints for auxiliary QP. */
+												Constraints* auxiliaryConstraints				/**< Input: Allocated bound object. \n
+																								 *	 Ouput: Working set for auxiliary QP. */
+												) const;
+
+		/** Setups bound and constraints data structures according to auxiliaryBounds/Constraints.
+		 *  (If the working set shall be setup afresh, make sure that
+		 *  bounds and constraints data structure have been resetted
+		 *  and the TQ factorisation has been initialised!)
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_SETUP_WORKINGSET_FAILED \n
+					RET_INVALID_ARGUMENTS \n
+					RET_UNKNOWN BUG */
+		returnValue setupAuxiliaryWorkingSet(	const Bounds* const auxiliaryBounds,			/**< Working set of bounds for auxiliary QP. */
+												const Constraints* const auxiliaryConstraints,	/**< Working set of constraints for auxiliary QP. */
+												BooleanType setupAfresh							/**< Flag indicating if given working set shall be
+																								 *    setup afresh or by updating the current one. */
+												);
+
+		/** Setups the optimal primal/dual solution of the auxiliary initial QP.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue setupAuxiliaryQPsolution(	const real_t* const xOpt,			/**< Optimal primal solution vector.
+																				 	*	 If a NULL pointer is passed, all entries are set to zero. */
+												const real_t* const yOpt			/**< Optimal dual solution vector.
+																					 *	 If a NULL pointer is passed, all entries are set to zero. */
+												);
+
+		/** Setups gradient of the auxiliary initial QP for given
+		 *  optimal primal/dual solution and given initial working set
+		 *  (assumes that members X, Y and BOUNDS, CONSTRAINTS have already been initialised!).
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue setupAuxiliaryQPgradient( );
+
+		/** Setups (constraints') bounds of the auxiliary initial QP for given
+		 *  optimal primal/dual solution and given initial working set
+		 *  (assumes that members X, Y and BOUNDS, CONSTRAINTS have already been initialised!).
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_UNKNOWN BUG */
+		returnValue setupAuxiliaryQPbounds(	const Bounds* const auxiliaryBounds,			/**< Working set of bounds for auxiliary QP. */
+											const Constraints* const auxiliaryConstraints,	/**< Working set of constraints for auxiliary QP. */
+											BooleanType useRelaxation						/**< Flag indicating if inactive (constraints') bounds shall be relaxed. */
+											);
+
+
+		/** Adds a constraint to active set.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_ADDCONSTRAINT_FAILED \n
+					RET_ADDCONSTRAINT_FAILED_INFEASIBILITY \n
+					RET_ENSURELI_FAILED */
+		returnValue addConstraint(	int number,					/**< Number of constraint to be added to active set. */
+									SubjectToStatus C_status,	/**< Status of new active constraint. */
+									BooleanType updateCholesky	/**< Flag indicating if Cholesky decomposition shall be updated. */
+									);
+
+		/** Checks if new active constraint to be added is linearly dependent from
+		 *	from row of the active constraints matrix.
+		 *	\return	 RET_LINEARLY_DEPENDENT \n
+		 			 RET_LINEARLY_INDEPENDENT \n
+					 RET_INDEXLIST_CORRUPTED */
+		returnValue addConstraint_checkLI(	int number			/**< Number of constraint to be added to active set. */
+											);
+
+		/** Ensures linear independence of constraint matrix when a new constraint is added.
+		 * 	To this end a bound or constraint is removed simultaneously if necessary.
+		 *	\return	 SUCCESSFUL_RETURN \n
+		 			 RET_LI_RESOLVED \n
+					 RET_ENSURELI_FAILED \n
+					 RET_ENSURELI_FAILED_TQ \n
+					 RET_ENSURELI_FAILED_NOINDEX \n
+					 RET_REMOVE_FROM_ACTIVESET */
+		returnValue addConstraint_ensureLI(	int number,					/**< Number of constraint to be added to active set. */
+											SubjectToStatus C_status	/**< Status of new active bound. */
+											);
+
+		/** Adds a bound to active set.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_ADDBOUND_FAILED \n
+					RET_ADDBOUND_FAILED_INFEASIBILITY \n
+					RET_ENSURELI_FAILED */
+		returnValue addBound(	int number,					/**< Number of bound to be added to active set. */
+								SubjectToStatus B_status,	/**< Status of new active bound. */
+								BooleanType updateCholesky	/**< Flag indicating if Cholesky decomposition shall be updated. */
+								);
+
+		/** Checks if new active bound to be added is linearly dependent from
+		 *	from row of the active constraints matrix.
+		 *	\return	 RET_LINEARLY_DEPENDENT \n
+		 			 RET_LINEARLY_INDEPENDENT */
+		returnValue addBound_checkLI(	int number			/**< Number of bound to be added to active set. */
+										);
+
+		/** Ensures linear independence of constraint matrix when a new bound is added.
+		 *	To this end a bound or constraint is removed simultaneously if necessary.
+		 *	\return	 SUCCESSFUL_RETURN \n
+		 			 RET_LI_RESOLVED \n
+					 RET_ENSURELI_FAILED \n
+					 RET_ENSURELI_FAILED_TQ \n
+					 RET_ENSURELI_FAILED_NOINDEX \n
+					 RET_REMOVE_FROM_ACTIVESET */
+		returnValue addBound_ensureLI(	int number,					/**< Number of bound to be added to active set. */
+										SubjectToStatus B_status	/**< Status of new active bound. */
+										);
+
+		/** Removes a constraint from active set.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_CONSTRAINT_NOT_ACTIVE \n
+					RET_REMOVECONSTRAINT_FAILED \n
+					RET_HESSIAN_NOT_SPD */
+		returnValue removeConstraint(	int number,					/**< Number of constraint to be removed from active set. */
+										BooleanType updateCholesky	/**< Flag indicating if Cholesky decomposition shall be updated. */
+										);
+
+		/** Removes a bounds from active set.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_BOUND_NOT_ACTIVE \n
+					RET_HESSIAN_NOT_SPD \n
+					RET_REMOVEBOUND_FAILED */
+		returnValue removeBound(	int number,					/**< Number of bound to be removed from active set. */
+									BooleanType updateCholesky	/**< Flag indicating if Cholesky decomposition shall be updated. */
+									);
+
+
+		/** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_DIV_BY_ZERO */
+		returnValue backsolveR(	const real_t* const b,	/**< Right hand side vector. */
+								BooleanType transposed,	/**< Indicates if the transposed system shall be solved. */
+								real_t* const a 		/**< Output: Solution vector */
+								);
+
+		/** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix. \n
+		 *  Special variant for the case that this function is called from within "removeBound()".
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_DIV_BY_ZERO */
+		returnValue backsolveR(	const real_t* const b,		/**< Right hand side vector. */
+								BooleanType transposed,		/**< Indicates if the transposed system shall be solved. */
+								BooleanType removingBound,	/**< Indicates if function is called from "removeBound()". */
+								real_t* const a 			/**< Output: Solution vector */
+								);
+
+
+		/** Solves the system Ta = b or T^Ta = b where T is a reverse upper triangular matrix.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_DIV_BY_ZERO */
+		returnValue backsolveT(	const real_t* const b,	/**< Right hand side vector. */
+								BooleanType transposed,	/**< Indicates if the transposed system shall be solved. */
+								real_t* const a 		/**< Output: Solution vector */
+								);
+
+
+		/** Determines step direction of the shift of the QP data.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue hotstart_determineDataShift(const int* const FX_idx, 	/**< Index array of fixed variables. */
+												const int* const AC_idx, 	/**< Index array of active constraints. */
+												const real_t* const g_new,	/**< New gradient vector. */
+												const real_t* const lbA_new,/**< New lower constraints' bounds. */
+												const real_t* const ubA_new,/**< New upper constraints' bounds. */
+												const real_t* const lb_new,	/**< New lower bounds. */
+												const real_t* const ub_new,	/**< New upper bounds. */
+												real_t* const delta_g,	 	/**< Output: Step direction of gradient vector. */
+												real_t* const delta_lbA,	/**< Output: Step direction of lower constraints' bounds. */
+												real_t* const delta_ubA,	/**< Output: Step direction of upper constraints' bounds. */
+												real_t* const delta_lb,	 	/**< Output: Step direction of lower bounds. */
+												real_t* const delta_ub,	 	/**< Output: Step direction of upper bounds. */
+												BooleanType& Delta_bC_isZero,/**< Output: Indicates if active constraints' bounds are to be shifted. */
+												BooleanType& Delta_bB_isZero/**< Output: Indicates if active bounds are to be shifted. */
+												);
+
+		/** Determines step direction of the homotopy path.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_STEPDIRECTION_FAILED_TQ \n
+					RET_STEPDIRECTION_FAILED_CHOLESKY */
+		returnValue hotstart_determineStepDirection(const int* const FR_idx, 		/**< Index array of free variables. */
+													const int* const FX_idx, 		/**< Index array of fixed variables. */
+													const int* const AC_idx, 		/**< Index array of active constraints. */
+													const real_t* const delta_g,	/**< Step direction of gradient vector. */
+													const real_t* const delta_lbA,	/**< Step direction of lower constraints' bounds. */
+													const real_t* const delta_ubA,	/**< Step direction of upper constraints' bounds. */
+													const real_t* const delta_lb,	/**< Step direction of lower bounds. */
+													const real_t* const delta_ub,	/**< Step direction of upper bounds. */
+													BooleanType Delta_bC_isZero, 	/**< Indicates if active constraints' bounds are to be shifted. */
+													BooleanType Delta_bB_isZero,	/**< Indicates if active bounds are to be shifted. */
+													real_t* const delta_xFX, 		/**< Output: Primal homotopy step direction of fixed variables. */
+													real_t* const delta_xFR,	 	/**< Output: Primal homotopy step direction of free variables. */
+													real_t* const delta_yAC, 		/**< Output: Dual homotopy step direction of active constraints' multiplier. */
+													real_t* const delta_yFX 		/**< Output: Dual homotopy step direction of fixed variables' multiplier. */
+													);
+
+		/** Determines the maximum possible step length along the homotopy path.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue hotstart_determineStepLength(	const int* const FR_idx, 			/**< Index array of free variables. */
+													const int* const FX_idx, 			/**< Index array of fixed variables. */
+													const int* const AC_idx, 			/**< Index array of active constraints. */
+													const int* const IAC_idx, 			/**< Index array of inactive constraints. */
+													const real_t* const delta_lbA,		/**< Step direction of lower constraints' bounds. */
+													const real_t* const delta_ubA,		/**< Step direction of upper constraints' bounds. */
+													const real_t* const delta_lb,	 	/**< Step direction of lower bounds. */
+													const real_t* const delta_ub,	 	/**< Step direction of upper bounds. */
+													const real_t* const delta_xFX, 		/**< Primal homotopy step direction of fixed variables. */
+													const real_t* const delta_xFR,		/**< Primal homotopy step direction of free variables. */
+													const real_t* const delta_yAC,		/**< Dual homotopy step direction of active constraints' multiplier. */
+													const real_t* const delta_yFX,		/**< Dual homotopy step direction of fixed variables' multiplier. */
+													real_t* const delta_Ax,				/**< Output: Step in vector Ax. */
+													int& BC_idx, 						/**< Output: Index of blocking constraint. */
+													SubjectToStatus& BC_status,			/**< Output: Status of blocking constraint. */
+													BooleanType& BC_isBound 			/**< Output: Indicates if blocking constraint is a bound. */
+													);
+
+		/** Performs a step along the homotopy path (and updates active set).
+		 *	\return  SUCCESSFUL_RETURN \n
+		 			 RET_OPTIMAL_SOLUTION_FOUND \n
+		 			 RET_REMOVE_FROM_ACTIVESET_FAILED \n
+					 RET_ADD_TO_ACTIVESET_FAILED \n
+					 RET_QP_INFEASIBLE */
+		returnValue hotstart_performStep(	const int* const FR_idx, 			/**< Index array of free variables. */
+											const int* const FX_idx, 			/**< Index array of fixed variables. */
+											const int* const AC_idx, 			/**< Index array of active constraints. */
+											const int* const IAC_idx, 			/**< Index array of inactive constraints. */
+											const real_t* const delta_g,	 	/**< Step direction of gradient vector. */
+											const real_t* const delta_lbA,	 	/**< Step direction of lower constraints' bounds. */
+											const real_t* const delta_ubA,	 	/**< Step direction of upper constraints' bounds. */
+											const real_t* const delta_lb,	 	/**< Step direction of lower bounds. */
+											const real_t* const delta_ub,	 	/**< Step direction of upper bounds. */
+											const real_t* const delta_xFX, 		/**< Primal homotopy step direction of fixed variables. */
+											const real_t* const delta_xFR,	 	/**< Primal homotopy step direction of free variables. */
+											const real_t* const delta_yAC,	 	/**< Dual homotopy step direction of active constraints' multiplier. */
+											const real_t* const delta_yFX, 		/**< Dual homotopy step direction of fixed variables' multiplier. */
+											const real_t* const delta_Ax, 		/**< Step in vector Ax. */
+											int BC_idx, 						/**< Index of blocking constraint. */
+											SubjectToStatus BC_status,			/**< Status of blocking constraint. */
+											BooleanType BC_isBound 				/**< Indicates if blocking constraint is a bound. */
+											);
+
+
+		/** Checks if lower/upper (constraints') bounds remain consistent
+		 *  (i.e. if lb <= ub and lbA <= ubA ) during the current step.
+		 *	\return BT_TRUE iff (constraints") bounds remain consistent
+		 */
+		BooleanType areBoundsConsistent(	const real_t* const delta_lb,	/**< Step direction of lower bounds. */
+											const real_t* const delta_ub,	/**< Step direction of upper bounds. */
+											const real_t* const delta_lbA,	/**< Step direction of lower constraints' bounds. */
+											const real_t* const delta_ubA	/**< Step direction of upper constraints' bounds. */
+											) const;
+
+
+		/** Setups internal QP data.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_INVALID_ARGUMENTS */
+		returnValue setupQPdata(	const real_t* const _H, 	/**< Hessian matrix. */
+									const real_t* const _R, 	/**< Cholesky factorization of the Hessian matrix. */
+									const real_t* const _g, 	/**< Gradient vector. */
+									const real_t* const _A,  	/**< Constraint matrix. */
+									const real_t* const _lb,	/**< Lower bound vector (on variables). \n
+																	 If no lower bounds exist, a NULL pointer can be passed. */
+									const real_t* const _ub,	/**< Upper bound vector (on variables). \n
+																	 If no upper bounds exist, a NULL pointer can be passed. */
+									const real_t* const _lbA,	/**< Lower constraints' bound vector. \n
+																	 If no lower constraints' bounds exist, a NULL pointer can be passed. */
+									const real_t* const _ubA	/**< Upper constraints' bound vector. \n
+																	 If no lower constraints' bounds exist, a NULL pointer can be passed. */
+									);
+
+
+		#ifdef PC_DEBUG  /* Define print functions only for debugging! */
+
+		/** Prints concise information on the current iteration.
+		 *	\return  SUCCESSFUL_RETURN \n */
+		returnValue printIteration(	int iteration,				/**< Number of current iteration. */
+									int BC_idx, 				/**< Index of blocking constraint. */
+									SubjectToStatus BC_status,	/**< Status of blocking constraint. */
+									BooleanType BC_isBound 		/**< Indicates if blocking constraint is a bound. */
+									);
+
+		/** Prints concise information on the current iteration.
+		 *  NOTE: ONLY DEFINED FOR SUPPRESSING A COMPILER WARNING!!
+		 *	\return  SUCCESSFUL_RETURN \n */
+		returnValue printIteration(	int iteration,				/**< Number of current iteration. */
+									int BC_idx, 				/**< Index of blocking bound. */
+									SubjectToStatus BC_status	/**< Status of blocking bound. */
+									);
+
+		#endif  /* PC_DEBUG */
+
+
+		/** Determines the maximum violation of the KKT optimality conditions
+		 *  of the current iterate within the QProblem object.
+		 *	\return SUCCESSFUL_RETURN \n
+		 * 			RET_INACCURATE_SOLUTION \n
+		 * 			RET_NO_SOLUTION */
+		returnValue checkKKTconditions( );
+
+
+		/** Sets constraint matrix of the QP. \n
+			(Remark: Also internal vector Ax is recomputed!)
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setA(	const real_t* const A_new	/**< New constraint matrix (with correct dimension!). */
+									);
+
+		/** Changes single row of constraint matrix of the QP. \n
+			(Remark: Also correponding component of internal vector Ax is recomputed!)
+		 *	\return SUCCESSFUL_RETURN  \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue setA(	int number,					/**< Number of row to be changed. */
+									const real_t* const value	/**< New (number)th constraint (with correct dimension!). */
+									);
+
+
+		/** Sets constraints' lower bound vector of the QP.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setLBA(	const real_t* const lbA_new	/**< New constraints' lower bound vector (with correct dimension!). */
+									);
+
+		/** Changes single entry of lower constraints' bound vector of the QP.
+		 *	\return SUCCESSFUL_RETURN  \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue setLBA(	int number,		/**< Number of entry to be changed. */
+									real_t value	/**< New value for entry of lower constraints' bound vector (with correct dimension!). */
+									);
+
+		/** Sets constraints' upper bound vector of the QP.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setUBA(	const real_t* const ubA_new	/**< New constraints' upper bound vector (with correct dimension!). */
+									);
+
+		/** Changes single entry of upper constraints' bound vector of the QP.
+		 *	\return SUCCESSFUL_RETURN  \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue setUBA(	int number,		/**< Number of entry to be changed. */
+									real_t value	/**< New value for entry of upper constraints' bound vector (with correct dimension!). */
+									);
+
+
+	/*
+	 *	PROTECTED MEMBER VARIABLES
+	 */
+	protected:
+		real_t A[NCMAX_ALLOC*NVMAX];		/**< Constraint matrix. */
+		real_t lbA[NCMAX_ALLOC];			/**< Lower constraints' bound vector. */
+		real_t ubA[NCMAX_ALLOC];			/**< Upper constraints' bound vector. */
+
+		Constraints constraints;			/**< Data structure for problem's constraints. */
+
+		real_t T[NVMAX*NVMAX];				/**< Reverse triangular matrix, A = [0 T]*Q'. */
+		real_t Q[NVMAX*NVMAX];				/**< Orthonormal quadratic matrix, A = [0 T]*Q'. */
+		int sizeT;							/**< Matrix T is stored in a (sizeT x sizeT) array. */
+
+		real_t Ax[NCMAX_ALLOC];				/**< Stores the current product A*x (for increased efficiency only). */
+
+		CyclingManager cyclingManager;		/**< Data structure for storing (possible) cycling information (NOT YET IMPLEMENTED!). */
+};
+
+
+#include <QProblem.ipp>
+
+#endif	/* QPOASES_QPROBLEM_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/QProblemB.hpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/QProblemB.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..49ace9ef9d00472edfdc167df71d920842f712bd
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/QProblemB.hpp
@@ -0,0 +1,628 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/QProblemB.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Declaration of the QProblemB class which is able to use the newly
+ *	developed online active set strategy for parametric quadratic programming
+ *	for problems with (simple) bounds only.
+ */
+
+
+
+#ifndef QPOASES_QPROBLEMB_HPP
+#define QPOASES_QPROBLEMB_HPP
+
+
+#include <Bounds.hpp>
+
+
+
+class SolutionAnalysis;
+
+/** Class for setting up and solving quadratic programs with (simple) bounds only.
+ *	The main feature is the possibily to use the newly developed online active set strategy
+ *	for parametric quadratic programming.
+ *
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ */
+class QProblemB
+{
+	/* allow SolutionAnalysis class to access private members */
+	friend class SolutionAnalysis;
+	
+	/*
+	 *	PUBLIC MEMBER FUNCTIONS
+	 */
+	public:
+		/** Default constructor. */
+		QProblemB( );
+
+		/** Constructor which takes the QP dimension only. */
+		QProblemB(	int _nV						/**< Number of variables. */
+					);
+
+		/** Copy constructor (deep copy). */
+		QProblemB(	const QProblemB& rhs	/**< Rhs object. */
+					);
+
+		/** Destructor. */
+		~QProblemB( );
+
+		/** Assignment operator (deep copy). */
+		QProblemB& operator=(	const QProblemB& rhs	/**< Rhs object. */
+								);
+
+
+		/** Clears all data structures of QProblemB except for QP data.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_RESET_FAILED */
+		returnValue reset( );
+
+
+		/** Initialises a QProblemB with given QP data and solves it
+		 *	using an initial homotopy with empty working set (at most nWSR iterations).
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_INIT_FAILED \n
+					RET_INIT_FAILED_CHOLESKY \n
+					RET_INIT_FAILED_HOTSTART \n
+					RET_INIT_FAILED_INFEASIBILITY \n
+					RET_INIT_FAILED_UNBOUNDEDNESS \n
+					RET_MAX_NWSR_REACHED \n
+					RET_INVALID_ARGUMENTS \n
+					RET_INACCURATE_SOLUTION \n
+		 			RET_NO_SOLUTION */
+		returnValue init(	const real_t* const _H, 		/**< Hessian matrix. */
+							const real_t* const _g,			/**< Gradient vector. */
+							const real_t* const _lb,		/**< Lower bounds (on variables). \n
+																If no lower bounds exist, a NULL pointer can be passed. */
+							const real_t* const _ub,		/**< Upper bounds (on variables). \n
+																If no upper bounds exist, a NULL pointer can be passed. */
+							int& nWSR, 						/**< Input: Maximum number of working set recalculations when using initial homotopy. \n
+																Output: Number of performed working set recalculations. */
+							const real_t* const yOpt = 0,	/**< Initial guess for dual solution vector. */
+				 			real_t* const cputime = 0		/**< Output: CPU time required to initialise QP. */
+							);
+
+
+		/** Initialises a QProblemB with given QP data and solves it
+		 *	using an initial homotopy with empty working set (at most nWSR iterations).
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_INIT_FAILED \n
+					RET_INIT_FAILED_CHOLESKY \n
+					RET_INIT_FAILED_HOTSTART \n
+					RET_INIT_FAILED_INFEASIBILITY \n
+					RET_INIT_FAILED_UNBOUNDEDNESS \n
+					RET_MAX_NWSR_REACHED \n
+					RET_INVALID_ARGUMENTS \n
+					RET_INACCURATE_SOLUTION \n
+		 			RET_NO_SOLUTION */
+		returnValue init(	const real_t* const _H, 		/**< Hessian matrix. */
+							const real_t* const _R, 		/**< Cholesky factorization of the Hessian matrix. */
+							const real_t* const _g,			/**< Gradient vector. */
+							const real_t* const _lb,		/**< Lower bounds (on variables). \n
+																If no lower bounds exist, a NULL pointer can be passed. */
+							const real_t* const _ub,		/**< Upper bounds (on variables). \n
+																If no upper bounds exist, a NULL pointer can be passed. */
+							int& nWSR, 						/**< Input: Maximum number of working set recalculations when using initial homotopy. \n
+																Output: Number of performed working set recalculations. */
+							const real_t* const yOpt = 0,	/**< Initial guess for dual solution vector. */
+				 			real_t* const cputime = 0		/**< Output: CPU time required to initialise QP. */
+							);
+
+
+		/** Solves an initialised QProblemB using online active set strategy.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_MAX_NWSR_REACHED \n
+					RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n
+					RET_HOTSTART_FAILED \n
+					RET_SHIFT_DETERMINATION_FAILED \n
+					RET_STEPDIRECTION_DETERMINATION_FAILED \n
+					RET_STEPLENGTH_DETERMINATION_FAILED \n
+					RET_HOMOTOPY_STEP_FAILED \n
+					RET_HOTSTART_STOPPED_INFEASIBILITY \n
+					RET_HOTSTART_STOPPED_UNBOUNDEDNESS \n
+					RET_INACCURATE_SOLUTION \n
+		 			RET_NO_SOLUTION */
+		returnValue hotstart(	const real_t* const g_new,	/**< Gradient of neighbouring QP to be solved. */
+								const real_t* const lb_new,	/**< Lower bounds of neighbouring QP to be solved. \n
+													 			 If no lower bounds exist, a NULL pointer can be passed. */
+								const real_t* const ub_new,	/**< Upper bounds of neighbouring QP to be solved. \n
+													 			 If no upper bounds exist, a NULL pointer can be passed. */
+								int& nWSR,					/**< Input: Maximum number of working set recalculations; \n
+																 Output: Number of performed working set recalculations. */
+								real_t* const cputime		/**< Output: CPU time required to solve QP (or to perform nWSR iterations). */
+								);
+
+
+		/** Returns Hessian matrix of the QP (deep copy).
+		  *	\return SUCCESSFUL_RETURN */
+		inline returnValue getH(	real_t* const _H	/**< Array of appropriate dimension for copying Hessian matrix.*/
+									) const;
+
+		/** Returns gradient vector of the QP (deep copy).
+		  *	\return SUCCESSFUL_RETURN */
+		inline returnValue getG(	real_t* const _g	/**< Array of appropriate dimension for copying gradient vector.*/
+									) const;
+
+		/** Returns lower bound vector of the QP (deep copy).
+		  *	\return SUCCESSFUL_RETURN */
+		inline returnValue getLB(	real_t* const _lb	/**< Array of appropriate dimension for copying lower bound vector.*/
+									) const;
+
+		/** Returns single entry of lower bound vector of the QP.
+		  *	\return SUCCESSFUL_RETURN \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue getLB(	int number,		/**< Number of entry to be returned. */
+									real_t& value	/**< Output: lb[number].*/
+									) const;
+
+		/** Returns upper bound vector of the QP (deep copy).
+		  *	\return SUCCESSFUL_RETURN */
+		inline returnValue getUB(	real_t* const _ub	/**< Array of appropriate dimension for copying upper bound vector.*/
+									) const;
+
+		/** Returns single entry of upper bound vector of the QP.
+		  *	\return SUCCESSFUL_RETURN \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue getUB(	int number,		/**< Number of entry to be returned. */
+									real_t& value	/**< Output: ub[number].*/
+									) const;
+
+
+		/** Returns current bounds object of the QP (deep copy).
+		  *	\return SUCCESSFUL_RETURN */
+		inline returnValue getBounds(	Bounds* const _bounds	/** Output: Bounds object. */
+										) const;
+
+
+		/** Returns the number of variables.
+		 *	\return Number of variables. */
+		inline int getNV( ) const;
+
+		/** Returns the number of free variables.
+		 *	\return Number of free variables. */
+		inline int getNFR( );
+
+		/** Returns the number of fixed variables.
+		 *	\return Number of fixed variables. */
+		inline int getNFX( );
+
+		/** Returns the number of implicitly fixed variables.
+		 *	\return Number of implicitly fixed variables. */
+		inline int getNFV( ) const;
+
+		/** Returns the dimension of null space.
+		 *	\return Dimension of null space. */
+		int getNZ( );
+
+
+		/** Returns the optimal objective function value.
+		 *	\return finite value: Optimal objective function value (QP was solved) \n
+		 			+infinity:	  QP was not yet solved */
+		real_t getObjVal( ) const;
+
+		/** Returns the objective function value at an arbitrary point x.
+		 *	\return Objective function value at point x */
+		real_t getObjVal(	const real_t* const _x	/**< Point at which the objective function shall be evaluated. */
+							) const;
+
+		/** Returns the primal solution vector.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_QP_NOT_SOLVED */
+		returnValue getPrimalSolution(	real_t* const xOpt			/**< Output: Primal solution vector (if QP has been solved). */
+										) const;
+
+		/** Returns the dual solution vector.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_QP_NOT_SOLVED */
+		returnValue getDualSolution(	real_t* const yOpt	/**< Output: Dual solution vector (if QP has been solved). */
+										) const;
+
+
+		/** Returns status of the solution process.
+		 *	\return Status of solution process. */
+		inline QProblemStatus getStatus( ) const;
+
+
+		/** Returns if the QProblem object is initialised.
+		 *	\return BT_TRUE:  QProblemB initialised \n
+		 			BT_FALSE: QProblemB not initialised */
+		inline BooleanType isInitialised( ) const;
+
+		/** Returns if the QP has been solved.
+		 *	\return BT_TRUE:  QProblemB solved \n
+		 			BT_FALSE: QProblemB not solved */
+		inline BooleanType isSolved( ) const;
+
+		/** Returns if the QP is infeasible.
+		 *	\return BT_TRUE:  QP infeasible \n
+		 			BT_FALSE: QP feasible (or not known to be infeasible!) */
+		inline BooleanType isInfeasible( ) const;
+
+		/** Returns if the QP is unbounded.
+		 *	\return BT_TRUE:  QP unbounded \n
+		 			BT_FALSE: QP unbounded (or not known to be unbounded!) */
+		inline BooleanType isUnbounded( ) const;
+
+
+		/** Returns the print level.
+		 *	\return Print level. */
+		inline PrintLevel getPrintLevel( ) const;
+
+		/** Changes the print level.
+ 		 *	\return SUCCESSFUL_RETURN */
+		returnValue setPrintLevel(	PrintLevel _printlevel	/**< New print level. */
+									);
+
+
+		/** Returns Hessian type flag (type is not determined due to this call!).
+		 *	\return Hessian type. */
+		inline HessianType getHessianType( ) const;
+
+		/** Changes the print level.
+ 		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setHessianType(	HessianType _hessianType /**< New Hessian type. */
+											);
+
+
+	/*
+	 *	PROTECTED MEMBER FUNCTIONS
+	 */
+	protected:
+		/** Checks if Hessian happens to be the identity matrix,
+		 *  and sets corresponding status flag (otherwise the flag remains unaltered!).
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue checkForIdentityHessian( );
+
+		/** Determines type of constraints and bounds (i.e. implicitly fixed, unbounded etc.).
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_SETUPSUBJECTTOTYPE_FAILED */
+		returnValue setupSubjectToType( );
+
+		/** Computes the Cholesky decomposition R of the (simply projected) Hessian (i.e. R^T*R = Z^T*H*Z).
+		 *  It only works in the case where Z is a simple projection matrix!
+		 *	\return SUCCESSFUL_RETURN \n
+		 *			RET_INDEXLIST_CORRUPTED */
+		returnValue setupCholeskyDecomposition( );
+
+
+		/** Solves a QProblemB whose QP data is assumed to be stored in the member variables.
+		 *  A guess for its primal/dual optimal solution vectors and the corresponding
+		 *  optimal working set can be provided.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_INIT_FAILED \n
+					RET_INIT_FAILED_CHOLESKY \n
+					RET_INIT_FAILED_HOTSTART \n
+					RET_INIT_FAILED_INFEASIBILITY \n
+					RET_INIT_FAILED_UNBOUNDEDNESS \n
+					RET_MAX_NWSR_REACHED */
+		returnValue solveInitialQP(	const real_t* const xOpt,			/**< Optimal primal solution vector.
+																		 *	 A NULL pointer can be passed. */
+									const real_t* const yOpt,			/**< Optimal dual solution vector.
+																		 *	 A NULL pointer can be passed. */
+									const Bounds* const guessedBounds,	/**< Guessed working set for solution (xOpt,yOpt).
+																		 *	 A NULL pointer can be passed. */
+									int& nWSR, 							/**< Input: Maximum number of working set recalculations; \n
+																 		 *	 Output: Number of performed working set recalculations. */
+									real_t* const cputime				/**< Output: CPU time required to solve QP (or to perform nWSR iterations). */
+									);
+
+
+		/** Obtains the desired working set for the auxiliary initial QP in
+		 *  accordance with the user specifications
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_OBTAINING_WORKINGSET_FAILED \n
+					RET_INVALID_ARGUMENTS */
+		returnValue obtainAuxiliaryWorkingSet(	const real_t* const xOpt,			/**< Optimal primal solution vector.
+																					 *	 If a NULL pointer is passed, all entries are assumed to be zero. */
+												const real_t* const yOpt,			/**< Optimal dual solution vector.
+																					 *	 If a NULL pointer is passed, all entries are assumed to be zero. */
+												const Bounds* const guessedBounds,	/**< Guessed working set for solution (xOpt,yOpt). */
+												Bounds* auxiliaryBounds				/**< Input: Allocated bound object. \n
+																					 *	 Ouput: Working set for auxiliary QP. */
+												) const;
+
+		/** Setups bound data structure according to auxiliaryBounds.
+		 *  (If the working set shall be setup afresh, make sure that
+		 *  bounds data structure has been resetted!)
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_SETUP_WORKINGSET_FAILED \n
+					RET_INVALID_ARGUMENTS \n
+					RET_UNKNOWN BUG */
+		returnValue setupAuxiliaryWorkingSet(	const Bounds* const auxiliaryBounds,	/**< Working set for auxiliary QP. */
+												BooleanType setupAfresh					/**< Flag indicating if given working set shall be
+																						 *    setup afresh or by updating the current one. */
+												);
+
+		/** Setups the optimal primal/dual solution of the auxiliary initial QP.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue setupAuxiliaryQPsolution(	const real_t* const xOpt,			/**< Optimal primal solution vector.
+																				 	*	 If a NULL pointer is passed, all entries are set to zero. */
+												const real_t* const yOpt			/**< Optimal dual solution vector.
+																					 *	 If a NULL pointer is passed, all entries are set to zero. */
+												);
+
+		/** Setups gradient of the auxiliary initial QP for given
+		 *  optimal primal/dual solution and given initial working set
+		 *  (assumes that members X, Y and BOUNDS have already been initialised!).
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue setupAuxiliaryQPgradient( );
+
+		/** Setups bounds of the auxiliary initial QP for given
+		 *  optimal primal/dual solution and given initial working set
+		 *  (assumes that members X, Y and BOUNDS have already been initialised!).
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_UNKNOWN BUG */
+		returnValue setupAuxiliaryQPbounds( BooleanType useRelaxation	/**< Flag indicating if inactive bounds shall be relaxed. */
+											);
+
+
+		/** Adds a bound to active set (specialised version for the case where no constraints exist).
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_ADDBOUND_FAILED */
+		returnValue addBound(	int number,					/**< Number of bound to be added to active set. */
+								SubjectToStatus B_status,	/**< Status of new active bound. */
+								BooleanType updateCholesky	/**< Flag indicating if Cholesky decomposition shall be updated. */
+								);
+
+		/** Removes a bounds from active set (specialised version for the case where no constraints exist).
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_HESSIAN_NOT_SPD \n
+					RET_REMOVEBOUND_FAILED */
+		returnValue removeBound(	int number,					/**< Number of bound to be removed from active set. */
+									BooleanType updateCholesky	/**< Flag indicating if Cholesky decomposition shall be updated. */
+									);
+
+
+		/** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_DIV_BY_ZERO */
+		returnValue backsolveR(	const real_t* const b,	/**< Right hand side vector. */
+								BooleanType transposed,	/**< Indicates if the transposed system shall be solved. */
+								real_t* const a 		/**< Output: Solution vector */
+								);
+
+		/** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix. \n
+		 *  Special variant for the case that this function is called from within "removeBound()".
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_DIV_BY_ZERO */
+		returnValue backsolveR(	const real_t* const b,		/**< Right hand side vector. */
+								BooleanType transposed,		/**< Indicates if the transposed system shall be solved. */
+								BooleanType removingBound,	/**< Indicates if function is called from "removeBound()". */
+								real_t* const a 			/**< Output: Solution vector */
+								);
+
+
+		/** Determines step direction of the shift of the QP data.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue hotstart_determineDataShift(const int* const FX_idx, 	/**< Index array of fixed variables. */
+												const real_t* const g_new,	/**< New gradient vector. */
+												const real_t* const lb_new,	/**< New lower bounds. */
+												const real_t* const ub_new,	/**< New upper bounds. */
+												real_t* const delta_g,	 	/**< Output: Step direction of gradient vector. */
+												real_t* const delta_lb,	 	/**< Output: Step direction of lower bounds. */
+												real_t* const delta_ub,	 	/**< Output: Step direction of upper bounds. */
+												BooleanType& Delta_bB_isZero/**< Output: Indicates if active bounds are to be shifted. */
+												);
+
+
+		/** Checks if lower/upper bounds remain consistent
+		 *  (i.e. if lb <= ub) during the current step.
+		 *	\return BT_TRUE iff bounds remain consistent
+		 */
+		BooleanType areBoundsConsistent(	const real_t* const delta_lb,		/**< Step direction of lower bounds. */
+											const real_t* const delta_ub		/**< Step direction of upper bounds. */
+											) const;
+
+
+		/** Setups internal QP data.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_INVALID_ARGUMENTS */
+		returnValue setupQPdata(	const real_t* const _H, 	/**< Hessian matrix. */
+									const real_t* const _R, 	/**< Cholesky factorization of the Hessian matrix. */
+									const real_t* const _g,		/**< Gradient vector. */
+									const real_t* const _lb,	/**< Lower bounds (on variables). \n
+																	 If no lower bounds exist, a NULL pointer can be passed. */
+									const real_t* const _ub		/**< Upper bounds (on variables). \n
+																	 If no upper bounds exist, a NULL pointer can be passed. */
+									);
+
+
+		/** Sets Hessian matrix of the QP.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setH(	const real_t* const H_new	/**< New Hessian matrix (with correct dimension!). */
+									);
+
+		/** Changes gradient vector of the QP.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setG(	const real_t* const g_new	/**< New gradient vector (with correct dimension!). */
+									);
+
+		/** Changes lower bound vector of the QP.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setLB(	const real_t* const lb_new	/**< New lower bound vector (with correct dimension!). */
+									);
+
+		/** Changes single entry of lower bound vector of the QP.
+		 *	\return SUCCESSFUL_RETURN  \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue setLB(	int number,		/**< Number of entry to be changed. */
+									real_t value	/**< New value for entry of lower bound vector. */
+									);
+
+		/** Changes upper bound vector of the QP.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setUB(	const real_t* const ub_new	/**< New upper bound vector (with correct dimension!). */
+									);
+
+		/** Changes single entry of upper bound vector of the QP.
+		 *	\return SUCCESSFUL_RETURN  \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue setUB(	int number,		/**< Number of entry to be changed. */
+									real_t value	/**< New value for entry of upper bound vector. */
+									);
+
+
+		/** Computes parameters for the Givens matrix G for which [x,y]*G = [z,0]
+		 *	\return SUCCESSFUL_RETURN */
+		inline void computeGivens(	real_t xold,	/**< Matrix entry to be normalised. */
+									real_t yold,	/**< Matrix entry to be annihilated. */
+									real_t& xnew,	/**< Output: Normalised matrix entry. */
+									real_t& ynew,	/**< Output: Annihilated matrix entry. */
+									real_t& c,		/**< Output: Cosine entry of Givens matrix. */
+									real_t& s 		/**< Output: Sine entry of Givens matrix. */
+									) const;
+
+		/** Applies Givens matrix determined by c and s (cf. computeGivens).
+		 *	\return SUCCESSFUL_RETURN */
+		inline void applyGivens(	real_t c,		/**< Cosine entry of Givens matrix. */
+									real_t s,		/**< Sine entry of Givens matrix. */
+									real_t xold,	/**< Matrix entry to be transformed corresponding to
+													 *	 the normalised entry of the original matrix. */
+									real_t yold, 	/**< Matrix entry to be transformed corresponding to
+													 *	 the annihilated entry of the original matrix. */
+									real_t& xnew,	/**< Output: Transformed matrix entry corresponding to
+													 *	 the normalised entry of the original matrix. */
+									real_t& ynew	/**< Output: Transformed matrix entry corresponding to
+													 *	 the annihilated entry of the original matrix. */
+									) const;
+
+
+	/*
+	 *	PRIVATE MEMBER FUNCTIONS
+	 */
+	private:
+		/** Determines step direction of the homotopy path.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_STEPDIRECTION_FAILED_CHOLESKY */
+		returnValue hotstart_determineStepDirection(const int* const FR_idx, 		/**< Index array of free variables. */
+													const int* const FX_idx, 		/**< Index array of fixed variables. */
+													const real_t* const delta_g,	/**< Step direction of gradient vector. */
+													const real_t* const delta_lb,	/**< Step direction of lower bounds. */
+													const real_t* const delta_ub,	/**< Step direction of upper bounds. */
+													BooleanType Delta_bB_isZero,	/**< Indicates if active bounds are to be shifted. */
+													real_t* const delta_xFX, 		/**< Output: Primal homotopy step direction of fixed variables. */
+													real_t* const delta_xFR,	 	/**< Output: Primal homotopy step direction of free variables. */
+													real_t* const delta_yFX 		/**< Output: Dual homotopy step direction of fixed variables' multiplier. */
+													);
+
+		/** Determines the maximum possible step length along the homotopy path.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue hotstart_determineStepLength(	const int* const FR_idx, 		/**< Index array of free variables. */
+													const int* const FX_idx, 		/**< Index array of fixed variables. */
+													const real_t* const delta_lb,	/**< Step direction of lower bounds. */
+													const real_t* const delta_ub,	/**< Step direction of upper bounds. */
+													const real_t* const delta_xFR,	/**< Primal homotopy step direction of free variables. */
+													const real_t* const delta_yFX,	/**< Dual homotopy step direction of fixed variables' multiplier. */
+													int& BC_idx, 					/**< Output: Index of blocking constraint. */
+													SubjectToStatus& BC_status		/**< Output: Status of blocking constraint. */
+													);
+
+		/** Performs a step along the homotopy path (and updates active set).
+		 *	\return  SUCCESSFUL_RETURN \n
+		 			 RET_OPTIMAL_SOLUTION_FOUND \n
+		 			 RET_REMOVE_FROM_ACTIVESET_FAILED \n
+					 RET_ADD_TO_ACTIVESET_FAILED \n
+					 RET_QP_INFEASIBLE */
+		returnValue hotstart_performStep(	const int* const FR_idx, 			/**< Index array of free variables. */
+											const int* const FX_idx, 			/**< Index array of fixed variables. */
+											const real_t* const delta_g,	 	/**< Step direction of gradient vector. */
+											const real_t* const delta_lb,	 	/**< Step direction of lower bounds. */
+											const real_t* const delta_ub,	 	/**< Step direction of upper bounds. */
+											const real_t* const delta_xFX, 		/**< Primal homotopy step direction of fixed variables. */
+											const real_t* const delta_xFR,	 	/**< Primal homotopy step direction of free variables. */
+											const real_t* const delta_yFX, 		/**< Dual homotopy step direction of fixed variables' multiplier. */
+											int BC_idx, 						/**< Index of blocking constraint. */
+											SubjectToStatus BC_status 			/**< Status of blocking constraint. */
+											);
+
+
+		#ifdef PC_DEBUG  /* Define print functions only for debugging! */
+
+		/** Prints concise information on the current iteration.
+		 *	\return  SUCCESSFUL_RETURN \n */
+		returnValue printIteration(	int iteration,				/**< Number of current iteration. */
+									int BC_idx, 				/**< Index of blocking bound. */
+									SubjectToStatus BC_status	/**< Status of blocking bound. */
+									);
+
+		#endif  /* PC_DEBUG */
+
+
+		/** Determines the maximum violation of the KKT optimality conditions
+		 *  of the current iterate within the QProblemB object.
+		 *	\return SUCCESSFUL_RETURN \n
+		 * 			RET_INACCURATE_SOLUTION \n
+		 * 			RET_NO_SOLUTION */
+		returnValue checkKKTconditions( );
+
+
+	/*
+	 *	PROTECTED MEMBER VARIABLES
+	 */
+	protected:
+		real_t H[NVMAX*NVMAX];		/**< Hessian matrix. */
+		BooleanType hasHessian;		/**< Flag indicating whether H contains Hessian or corresponding Cholesky factor R; \sa init. */
+
+		real_t g[NVMAX];			/**< Gradient. */
+		real_t lb[NVMAX];			/**< Lower bound vector (on variables). */
+		real_t ub[NVMAX];			/**< Upper bound vector (on variables). */
+
+		Bounds bounds;				/**< Data structure for problem's bounds. */
+
+		real_t R[NVMAX*NVMAX];		/**< Cholesky decomposition of H (i.e. H = R^T*R). */
+		BooleanType hasCholesky;	/**< Flag indicating whether Cholesky decomposition has already been setup. */
+
+		real_t x[NVMAX];			/**< Primal solution vector. */
+		real_t y[NVMAX+NCMAX];		/**< Dual solution vector. */
+
+		real_t tau;					/**< Last homotopy step length. */
+
+		QProblemStatus status;		/**< Current status of the solution process. */
+
+		BooleanType infeasible;		/**< QP infeasible? */
+		BooleanType unbounded;		/**< QP unbounded? */
+
+		HessianType hessianType;	/**< Type of Hessian matrix. */
+
+		PrintLevel printlevel;		/**< Print level. */
+
+		int count;					/**< Counts the number of hotstart function calls (internal usage only!). */
+};
+
+
+#include <QProblemB.ipp>
+
+#endif	/* QPOASES_QPROBLEMB_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/SubjectTo.hpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/SubjectTo.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..e07bf0421ec799492637834acaee6f53730ae88b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/SubjectTo.hpp
@@ -0,0 +1,178 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/SubjectTo.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Declaration of the SubjectTo class designed to manage working sets of
+ *	constraints and bounds within a QProblem.
+ */
+
+
+#ifndef QPOASES_SUBJECTTO_HPP
+#define QPOASES_SUBJECTTO_HPP
+
+
+#include <Indexlist.hpp>
+
+
+
+/** This class manages working sets of constraints and bounds by storing
+ *	index sets and other status information.
+ *
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ */
+class SubjectTo
+{
+	/*
+	 *	PUBLIC MEMBER FUNCTIONS
+	 */
+	public:
+		/** Default constructor. */
+		SubjectTo( );
+
+		/** Copy constructor (deep copy). */
+		SubjectTo(	const SubjectTo& rhs	/**< Rhs object. */
+					);
+
+		/** Destructor. */
+		~SubjectTo( );
+
+		/** Assignment operator (deep copy). */
+		SubjectTo& operator=(	const SubjectTo& rhs	/**< Rhs object. */
+								);
+
+
+		/** Pseudo-constructor takes the number of constraints or bounds.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue init(	int n 	/**< Number of constraints or bounds. */
+							);
+
+
+		/** Returns type of (constraints') bound.
+		 *	\return Type of (constraints') bound \n
+		 			RET_INDEX_OUT_OF_BOUNDS */
+		inline SubjectToType getType(	int i		/**< Number of (constraints') bound. */
+										) const ;
+
+		/** Returns status of (constraints') bound.
+		 *	\return Status of (constraints') bound \n
+		 			ST_UNDEFINED */
+		inline SubjectToStatus getStatus(	int i		/**< Number of (constraints') bound. */
+											) const;
+
+
+		/** Sets type of (constraints') bound.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue setType(	int i,				/**< Number of (constraints') bound. */
+									SubjectToType value	/**< Type of (constraints') bound. */
+									);
+
+		/** Sets status of (constraints') bound.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue setStatus(	int i,					/**< Number of (constraints') bound. */
+										SubjectToStatus value	/**< Status of (constraints') bound. */
+										);
+
+
+		/** Sets status of lower (constraints') bounds. */
+		inline void setNoLower(	BooleanType _status		/**< Status of lower (constraints') bounds. */
+								);
+
+		/** Sets status of upper (constraints') bounds. */
+		inline void setNoUpper(	BooleanType _status		/**< Status of upper (constraints') bounds. */
+								);
+
+
+		/** Returns status of lower (constraints') bounds.
+		 *	\return BT_TRUE if there is no lower (constraints') bound on any variable. */
+		inline BooleanType isNoLower( ) const;
+
+		/** Returns status of upper bounds.
+		 *	\return BT_TRUE if there is no upper (constraints') bound on any variable. */
+		inline BooleanType isNoUpper( ) const;
+
+
+	/*
+	 *	PROTECTED MEMBER FUNCTIONS
+	 */
+	protected:
+		/** Adds the index of a new constraint or bound to index set.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_ADDINDEX_FAILED */
+		returnValue addIndex(	Indexlist* const indexlist,	/**< Index list to which the new index shall be added. */
+								int newnumber,				/**< Number of new constraint or bound. */
+								SubjectToStatus newstatus	/**< Status of new constraint or bound. */
+								);
+
+		/** Removes the index of a constraint or bound from index set.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_UNKNOWN_BUG */
+		returnValue removeIndex(	Indexlist* const indexlist,	/**< Index list from which the new index shall be removed. */
+									int removenumber			/**< Number of constraint or bound to be removed. */
+									);
+
+		/** Swaps the indices of two constraints or bounds within the index set.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_SWAPINDEX_FAILED */
+		returnValue swapIndex(	Indexlist* const indexlist,	/**< Index list in which the indices shold be swapped. */
+								int number1,				/**< Number of first constraint or bound. */
+								int number2					/**< Number of second constraint or bound. */
+								);
+
+
+	/*
+	 *	PROTECTED MEMBER VARIABLES
+	 */
+	protected:
+		SubjectToType type[NVMAX+NCMAX]; 		/**< Type of constraints/bounds. */
+		SubjectToStatus status[NVMAX+NCMAX];	/**< Status of constraints/bounds. */
+
+		BooleanType noLower;				 	/**< This flag indicates if there is no lower bound on any variable. */
+		BooleanType noUpper;	 				/**< This flag indicates if there is no upper bound on any variable. */
+
+
+	/*
+	 *	PRIVATE MEMBER VARIABLES
+	 */
+	private:
+		int size;
+};
+
+
+
+#include <SubjectTo.ipp>
+
+#endif	/* QPOASES_SUBJECTTO_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/Types.hpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/Types.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..5b873ad070a875bb5e6a82b8371ea145202ed3d4
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/Types.hpp
@@ -0,0 +1,131 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/Types.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2008
+ *
+ *	Declaration of all non-built-in types (except for classes).
+ */
+
+
+#ifndef QPOASES_TYPES_HPP
+#define QPOASES_TYPES_HPP
+
+
+
+/** Define real_t for facilitating switching between double and float. */
+// typedef double real_t;
+
+
+/** Summarises all possible logical values. */
+enum BooleanType
+{
+	BT_FALSE,					/**< Logical value for "false". */
+	BT_TRUE						/**< Logical value for "true". */
+};
+
+
+/** Summarises all possible print levels. Print levels are used to describe
+ *	the desired amount of output during runtime of qpOASES. */
+enum PrintLevel
+{
+	PL_NONE,					/**< No output. */
+	PL_LOW,						/**< Print error messages only. */
+	PL_MEDIUM,					/**< Print error and warning messages as well as concise info messages. */
+	PL_HIGH						/**< Print all messages with full details. */
+};
+
+
+/** Defines visibility status of a message. */
+enum VisibilityStatus
+{
+	VS_VISIBLE,					/**< Message visible. */
+	VS_HIDDEN					/**< Message not visible. */
+};
+
+
+/** Summarises all possible states of the (S)QProblem(B) object during the
+solution process of a QP sequence. */
+enum QProblemStatus
+{
+	QPS_NOTINITIALISED,			/**< QProblem object is freshly instantiated or reset. */
+	QPS_PREPARINGAUXILIARYQP,	/**< An auxiliary problem is currently setup, either at the very beginning
+								 *   via an initial homotopy or after changing the QP matrices. */
+	QPS_AUXILIARYQPSOLVED,		/**< An auxilary problem was solved, either at the very beginning
+								 *   via an initial homotopy or after changing the QP matrices. */
+	QPS_PERFORMINGHOMOTOPY,		/**< A homotopy according to the main idea of the online active
+								 *   set strategy is performed. */
+	QPS_HOMOTOPYQPSOLVED,		/**< An intermediate QP along the homotopy path was solved. */
+	QPS_SOLVED					/**< The solution of the actual QP was found. */
+};
+
+
+/** Summarises all possible types of bounds and constraints. */
+enum SubjectToType
+{
+	ST_UNBOUNDED,				/**< Bound/constraint is unbounded. */
+	ST_BOUNDED,					/**< Bound/constraint is bounded but not fixed. */
+	ST_EQUALITY,				/**< Bound/constraint is fixed (implicit equality bound/constraint). */
+	ST_UNKNOWN					/**< Type of bound/constraint unknown. */
+};
+
+
+/** Summarises all possible states of bounds and constraints. */
+enum SubjectToStatus
+{
+	ST_INACTIVE,				/**< Bound/constraint is inactive. */
+	ST_LOWER,					/**< Bound/constraint is at its lower bound. */
+	ST_UPPER,					/**< Bound/constraint is at its upper bound. */
+	ST_UNDEFINED				/**< Status of bound/constraint undefined. */
+};
+
+
+/** Summarises all possible cycling states of bounds and constraints. */
+enum CyclingStatus
+{
+	CYC_NOT_INVOLVED,			/**< Bound/constraint is not involved in current cycling. */
+	CYC_PREV_ADDED,				/**< Bound/constraint has previously been added during the current cycling. */
+	CYC_PREV_REMOVED			/**< Bound/constraint has previously been removed during the current cycling. */
+};
+
+
+/** Summarises all possible types of the QP's Hessian matrix. */
+enum HessianType
+{
+	HST_SEMIDEF,				/**< Hessian is positive semi-definite. */
+	HST_POSDEF_NULLSPACE,		/**< Hessian is positive definite on null space of active bounds/constraints. */
+	HST_POSDEF,					/**< Hessian is (strictly) positive definite. */
+	HST_IDENTITY				/**< Hessian is identity matrix. */
+};
+
+
+
+#endif	/* QPOASES_TYPES_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/Utils.hpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/Utils.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..a91ee78ccb5cd724efbabc393f257f2cd293f863
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/INCLUDE/Utils.hpp
@@ -0,0 +1,197 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/Utils.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Declaration of global utility functions for working with qpOASES.
+ */
+
+
+#ifndef QPOASES_UTILS_HPP
+#define QPOASES_UTILS_HPP
+
+
+#include <MessageHandling.hpp>
+
+
+#ifdef PC_DEBUG  /* Define print functions only for debugging! */
+
+/** Prints a vector.
+ * \return SUCCESSFUL_RETURN */
+returnValue print(	const real_t* const v,	/**< Vector to be printed. */
+					int n					/**< Length of vector. */
+					);
+
+/** Prints a permuted vector.
+ * \return SUCCESSFUL_RETURN */
+returnValue print(	const real_t* const v,		/**< Vector to be printed. */
+					int n,						/**< Length of vector. */
+					const int* const V_idx		/**< Pemutation vector. */
+					);
+
+/** Prints a named vector.
+ * \return SUCCESSFUL_RETURN */
+returnValue print(	const real_t* const v,	/**< Vector to be printed. */
+					int n,					/**< Length of vector. */
+					const char* name		/** Name of vector. */
+					);
+
+/** Prints a matrix.
+ * \return SUCCESSFUL_RETURN */
+returnValue print(	const real_t* const M,	/**< Matrix to be printed. */
+					int nrow,				/**< Row number of matrix. */
+					int ncol				/**< Column number of matrix. */
+					);
+
+/** Prints a permuted matrix.
+ * \return SUCCESSFUL_RETURN */
+returnValue print(	const real_t* const M,		/**< Matrix to be printed. */
+					int nrow,					/**< Row number of matrix. */
+					int ncol	,				/**< Column number of matrix. */
+					const int* const ROW_idx,	/**< Row pemutation vector. */
+					const int* const COL_idx	/**< Column pemutation vector. */
+					);
+
+/** Prints a named matrix.
+ * \return SUCCESSFUL_RETURN */
+returnValue print(	const real_t* const M,	/**< Matrix to be printed. */
+					int nrow,				/**< Row number of matrix. */
+					int ncol,				/**< Column number of matrix. */
+					const char* name		/** Name of matrix. */
+					);
+
+/** Prints an index array.
+ * \return SUCCESSFUL_RETURN */
+returnValue print(	const int* const index,	/**< Index array to be printed. */
+					int n					/**< Length of index array. */
+					);
+
+/** Prints a named index array.
+ * \return SUCCESSFUL_RETURN */
+returnValue print(	const int* const index,	/**< Index array to be printed. */
+					int n,					/**< Length of index array. */
+					const char* name		/**< Name of index array. */
+					);
+
+
+/** Prints a string to desired output target (useful also for MATLAB output!).
+ * \return SUCCESSFUL_RETURN */
+returnValue myPrintf(	const char* s	/**< String to be written. */
+						);
+
+
+/** Prints qpOASES copyright notice.
+ * \return SUCCESSFUL_RETURN */
+returnValue printCopyrightNotice( );
+
+
+/** Reads a real_t matrix from file.
+ * \return SUCCESSFUL_RETURN \n
+ 		   RET_UNABLE_TO_OPEN_FILE \n
+		   RET_UNABLE_TO_READ_FILE */
+returnValue readFromFile(	real_t* data,				/**< Matrix to be read from file. */
+							int nrow,					/**< Row number of matrix. */
+							int ncol,					/**< Column number of matrix. */
+							const char* datafilename	/**< Data file name. */
+							);
+
+/** Reads a real_t vector from file.
+ * \return SUCCESSFUL_RETURN \n
+ 		   RET_UNABLE_TO_OPEN_FILE \n
+		   RET_UNABLE_TO_READ_FILE */
+returnValue readFromFile(	real_t* data,				/**< Vector to be read from file. */
+							int n,						/**< Length of vector. */
+							const char* datafilename	/**< Data file name. */
+							);
+
+/** Reads an integer (column) vector from file.
+ * \return SUCCESSFUL_RETURN \n
+ 		   RET_UNABLE_TO_OPEN_FILE \n
+		   RET_UNABLE_TO_READ_FILE */
+returnValue readFromFile(	int* data,					/**< Vector to be read from file. */
+							int n,						/**< Length of vector. */
+							const char* datafilename	/**< Data file name. */
+							);
+
+
+/** Writes a real_t matrix into a file.
+ * \return SUCCESSFUL_RETURN \n
+ 		   RET_UNABLE_TO_OPEN_FILE  */
+returnValue writeIntoFile(	const real_t* const data,	/**< Matrix to be written into file. */
+							int nrow,					/**< Row number of matrix. */
+							int ncol,					/**< Column number of matrix. */
+							const char* datafilename,	/**< Data file name. */
+							BooleanType append			/**< Indicates if data shall be appended if the file already exists (otherwise it is overwritten). */
+							);
+
+/** Writes a real_t vector into a file.
+ * \return SUCCESSFUL_RETURN \n
+ 		   RET_UNABLE_TO_OPEN_FILE  */
+returnValue writeIntoFile(	const real_t* const data,	/**< Vector to be written into file. */
+							int n,						/**< Length of vector. */
+							const char* datafilename,	/**< Data file name. */
+							BooleanType append			/**< Indicates if data shall be appended if the file already exists (otherwise it is overwritten). */
+							);
+
+/** Writes an integer (column) vector into a file.
+ * \return SUCCESSFUL_RETURN \n
+ 		   RET_UNABLE_TO_OPEN_FILE */
+returnValue writeIntoFile(	const int* const integer,	/**< Integer vector to be written into file. */
+							int n,						/**< Length of vector. */
+							const char* datafilename,	/**< Data file name. */
+							BooleanType append			/**< Indicates if integer shall be appended if the file already exists (otherwise it is overwritten). */
+							);
+
+#endif  /* PC_DEBUG */
+
+
+/** Returns the current system time.
+ * \return current system time */
+real_t getCPUtime( );
+
+
+/** Returns the Euclidean norm of a vector.
+ * \return 0: successful */
+real_t getNorm(	const real_t* const v,	/**< Vector. */
+				int n					/**< Vector's dimension. */
+				);
+
+/** Returns the absolute value of a real_t.
+ * \return Absolute value of a real_t */
+inline real_t getAbs(	real_t x		/**< Input argument. */
+						);
+
+
+
+#include <Utils.ipp>
+
+#endif	/* QPOASES_UTILS_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/LICENSE.txt b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/LICENSE.txt
new file mode 100644
index 0000000000000000000000000000000000000000..5ab7695ab8cabe0c5c8a814bb0ab1e8066578fbb
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/LICENSE.txt
@@ -0,0 +1,504 @@
+		  GNU LESSER GENERAL PUBLIC LICENSE
+		       Version 2.1, February 1999
+
+ Copyright (C) 1991, 1999 Free Software Foundation, Inc.
+ 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ Everyone is permitted to copy and distribute verbatim copies
+ of this license document, but changing it is not allowed.
+
+[This is the first released version of the Lesser GPL.  It also counts
+ as the successor of the GNU Library Public License, version 2, hence
+ the version number 2.1.]
+
+			    Preamble
+
+  The licenses for most software are designed to take away your
+freedom to share and change it.  By contrast, the GNU General Public
+Licenses are intended to guarantee your freedom to share and change
+free software--to make sure the software is free for all its users.
+
+  This license, the Lesser General Public License, applies to some
+specially designated software packages--typically libraries--of the
+Free Software Foundation and other authors who decide to use it.  You
+can use it too, but we suggest you first think carefully about whether
+this license or the ordinary General Public License is the better
+strategy to use in any particular case, based on the explanations below.
+
+  When we speak of free software, we are referring to freedom of use,
+not price.  Our General Public Licenses are designed to make sure that
+you have the freedom to distribute copies of free software (and charge
+for this service if you wish); that you receive source code or can get
+it if you want it; that you can change the software and use pieces of
+it in new free programs; and that you are informed that you can do
+these things.
+
+  To protect your rights, we need to make restrictions that forbid
+distributors to deny you these rights or to ask you to surrender these
+rights.  These restrictions translate to certain responsibilities for
+you if you distribute copies of the library or if you modify it.
+
+  For example, if you distribute copies of the library, whether gratis
+or for a fee, you must give the recipients all the rights that we gave
+you.  You must make sure that they, too, receive or can get the source
+code.  If you link other code with the library, you must provide
+complete object files to the recipients, so that they can relink them
+with the library after making changes to the library and recompiling
+it.  And you must show them these terms so they know their rights.
+
+  We protect your rights with a two-step method: (1) we copyright the
+library, and (2) we offer you this license, which gives you legal
+permission to copy, distribute and/or modify the library.
+
+  To protect each distributor, we want to make it very clear that
+there is no warranty for the free library.  Also, if the library is
+modified by someone else and passed on, the recipients should know
+that what they have is not the original version, so that the original
+author's reputation will not be affected by problems that might be
+introduced by others.
+
+  Finally, software patents pose a constant threat to the existence of
+any free program.  We wish to make sure that a company cannot
+effectively restrict the users of a free program by obtaining a
+restrictive license from a patent holder.  Therefore, we insist that
+any patent license obtained for a version of the library must be
+consistent with the full freedom of use specified in this license.
+
+  Most GNU software, including some libraries, is covered by the
+ordinary GNU General Public License.  This license, the GNU Lesser
+General Public License, applies to certain designated libraries, and
+is quite different from the ordinary General Public License.  We use
+this license for certain libraries in order to permit linking those
+libraries into non-free programs.
+
+  When a program is linked with a library, whether statically or using
+a shared library, the combination of the two is legally speaking a
+combined work, a derivative of the original library.  The ordinary
+General Public License therefore permits such linking only if the
+entire combination fits its criteria of freedom.  The Lesser General
+Public License permits more lax criteria for linking other code with
+the library.
+
+  We call this license the "Lesser" General Public License because it
+does Less to protect the user's freedom than the ordinary General
+Public License.  It also provides other free software developers Less
+of an advantage over competing non-free programs.  These disadvantages
+are the reason we use the ordinary General Public License for many
+libraries.  However, the Lesser license provides advantages in certain
+special circumstances.
+
+  For example, on rare occasions, there may be a special need to
+encourage the widest possible use of a certain library, so that it becomes
+a de-facto standard.  To achieve this, non-free programs must be
+allowed to use the library.  A more frequent case is that a free
+library does the same job as widely used non-free libraries.  In this
+case, there is little to gain by limiting the free library to free
+software only, so we use the Lesser General Public License.
+
+  In other cases, permission to use a particular library in non-free
+programs enables a greater number of people to use a large body of
+free software.  For example, permission to use the GNU C Library in
+non-free programs enables many more people to use the whole GNU
+operating system, as well as its variant, the GNU/Linux operating
+system.
+
+  Although the Lesser General Public License is Less protective of the
+users' freedom, it does ensure that the user of a program that is
+linked with the Library has the freedom and the wherewithal to run
+that program using a modified version of the Library.
+
+  The precise terms and conditions for copying, distribution and
+modification follow.  Pay close attention to the difference between a
+"work based on the library" and a "work that uses the library".  The
+former contains code derived from the library, whereas the latter must
+be combined with the library in order to run.
+
+		  GNU LESSER GENERAL PUBLIC LICENSE
+   TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION
+
+  0. This License Agreement applies to any software library or other
+program which contains a notice placed by the copyright holder or
+other authorized party saying it may be distributed under the terms of
+this Lesser General Public License (also called "this License").
+Each licensee is addressed as "you".
+
+  A "library" means a collection of software functions and/or data
+prepared so as to be conveniently linked with application programs
+(which use some of those functions and data) to form executables.
+
+  The "Library", below, refers to any such software library or work
+which has been distributed under these terms.  A "work based on the
+Library" means either the Library or any derivative work under
+copyright law: that is to say, a work containing the Library or a
+portion of it, either verbatim or with modifications and/or translated
+straightforwardly into another language.  (Hereinafter, translation is
+included without limitation in the term "modification".)
+
+  "Source code" for a work means the preferred form of the work for
+making modifications to it.  For a library, complete source code means
+all the source code for all modules it contains, plus any associated
+interface definition files, plus the scripts used to control compilation
+and installation of the library.
+
+  Activities other than copying, distribution and modification are not
+covered by this License; they are outside its scope.  The act of
+running a program using the Library is not restricted, and output from
+such a program is covered only if its contents constitute a work based
+on the Library (independent of the use of the Library in a tool for
+writing it).  Whether that is true depends on what the Library does
+and what the program that uses the Library does.
+  
+  1. You may copy and distribute verbatim copies of the Library's
+complete source code as you receive it, in any medium, provided that
+you conspicuously and appropriately publish on each copy an
+appropriate copyright notice and disclaimer of warranty; keep intact
+all the notices that refer to this License and to the absence of any
+warranty; and distribute a copy of this License along with the
+Library.
+
+  You may charge a fee for the physical act of transferring a copy,
+and you may at your option offer warranty protection in exchange for a
+fee.
+
+  2. You may modify your copy or copies of the Library or any portion
+of it, thus forming a work based on the Library, and copy and
+distribute such modifications or work under the terms of Section 1
+above, provided that you also meet all of these conditions:
+
+    a) The modified work must itself be a software library.
+
+    b) You must cause the files modified to carry prominent notices
+    stating that you changed the files and the date of any change.
+
+    c) You must cause the whole of the work to be licensed at no
+    charge to all third parties under the terms of this License.
+
+    d) If a facility in the modified Library refers to a function or a
+    table of data to be supplied by an application program that uses
+    the facility, other than as an argument passed when the facility
+    is invoked, then you must make a good faith effort to ensure that,
+    in the event an application does not supply such function or
+    table, the facility still operates, and performs whatever part of
+    its purpose remains meaningful.
+
+    (For example, a function in a library to compute square roots has
+    a purpose that is entirely well-defined independent of the
+    application.  Therefore, Subsection 2d requires that any
+    application-supplied function or table used by this function must
+    be optional: if the application does not supply it, the square
+    root function must still compute square roots.)
+
+These requirements apply to the modified work as a whole.  If
+identifiable sections of that work are not derived from the Library,
+and can be reasonably considered independent and separate works in
+themselves, then this License, and its terms, do not apply to those
+sections when you distribute them as separate works.  But when you
+distribute the same sections as part of a whole which is a work based
+on the Library, the distribution of the whole must be on the terms of
+this License, whose permissions for other licensees extend to the
+entire whole, and thus to each and every part regardless of who wrote
+it.
+
+Thus, it is not the intent of this section to claim rights or contest
+your rights to work written entirely by you; rather, the intent is to
+exercise the right to control the distribution of derivative or
+collective works based on the Library.
+
+In addition, mere aggregation of another work not based on the Library
+with the Library (or with a work based on the Library) on a volume of
+a storage or distribution medium does not bring the other work under
+the scope of this License.
+
+  3. You may opt to apply the terms of the ordinary GNU General Public
+License instead of this License to a given copy of the Library.  To do
+this, you must alter all the notices that refer to this License, so
+that they refer to the ordinary GNU General Public License, version 2,
+instead of to this License.  (If a newer version than version 2 of the
+ordinary GNU General Public License has appeared, then you can specify
+that version instead if you wish.)  Do not make any other change in
+these notices.
+
+  Once this change is made in a given copy, it is irreversible for
+that copy, so the ordinary GNU General Public License applies to all
+subsequent copies and derivative works made from that copy.
+
+  This option is useful when you wish to copy part of the code of
+the Library into a program that is not a library.
+
+  4. You may copy and distribute the Library (or a portion or
+derivative of it, under Section 2) in object code or executable form
+under the terms of Sections 1 and 2 above provided that you accompany
+it with the complete corresponding machine-readable source code, which
+must be distributed under the terms of Sections 1 and 2 above on a
+medium customarily used for software interchange.
+
+  If distribution of object code is made by offering access to copy
+from a designated place, then offering equivalent access to copy the
+source code from the same place satisfies the requirement to
+distribute the source code, even though third parties are not
+compelled to copy the source along with the object code.
+
+  5. A program that contains no derivative of any portion of the
+Library, but is designed to work with the Library by being compiled or
+linked with it, is called a "work that uses the Library".  Such a
+work, in isolation, is not a derivative work of the Library, and
+therefore falls outside the scope of this License.
+
+  However, linking a "work that uses the Library" with the Library
+creates an executable that is a derivative of the Library (because it
+contains portions of the Library), rather than a "work that uses the
+library".  The executable is therefore covered by this License.
+Section 6 states terms for distribution of such executables.
+
+  When a "work that uses the Library" uses material from a header file
+that is part of the Library, the object code for the work may be a
+derivative work of the Library even though the source code is not.
+Whether this is true is especially significant if the work can be
+linked without the Library, or if the work is itself a library.  The
+threshold for this to be true is not precisely defined by law.
+
+  If such an object file uses only numerical parameters, data
+structure layouts and accessors, and small macros and small inline
+functions (ten lines or less in length), then the use of the object
+file is unrestricted, regardless of whether it is legally a derivative
+work.  (Executables containing this object code plus portions of the
+Library will still fall under Section 6.)
+
+  Otherwise, if the work is a derivative of the Library, you may
+distribute the object code for the work under the terms of Section 6.
+Any executables containing that work also fall under Section 6,
+whether or not they are linked directly with the Library itself.
+
+  6. As an exception to the Sections above, you may also combine or
+link a "work that uses the Library" with the Library to produce a
+work containing portions of the Library, and distribute that work
+under terms of your choice, provided that the terms permit
+modification of the work for the customer's own use and reverse
+engineering for debugging such modifications.
+
+  You must give prominent notice with each copy of the work that the
+Library is used in it and that the Library and its use are covered by
+this License.  You must supply a copy of this License.  If the work
+during execution displays copyright notices, you must include the
+copyright notice for the Library among them, as well as a reference
+directing the user to the copy of this License.  Also, you must do one
+of these things:
+
+    a) Accompany the work with the complete corresponding
+    machine-readable source code for the Library including whatever
+    changes were used in the work (which must be distributed under
+    Sections 1 and 2 above); and, if the work is an executable linked
+    with the Library, with the complete machine-readable "work that
+    uses the Library", as object code and/or source code, so that the
+    user can modify the Library and then relink to produce a modified
+    executable containing the modified Library.  (It is understood
+    that the user who changes the contents of definitions files in the
+    Library will not necessarily be able to recompile the application
+    to use the modified definitions.)
+
+    b) Use a suitable shared library mechanism for linking with the
+    Library.  A suitable mechanism is one that (1) uses at run time a
+    copy of the library already present on the user's computer system,
+    rather than copying library functions into the executable, and (2)
+    will operate properly with a modified version of the library, if
+    the user installs one, as long as the modified version is
+    interface-compatible with the version that the work was made with.
+
+    c) Accompany the work with a written offer, valid for at
+    least three years, to give the same user the materials
+    specified in Subsection 6a, above, for a charge no more
+    than the cost of performing this distribution.
+
+    d) If distribution of the work is made by offering access to copy
+    from a designated place, offer equivalent access to copy the above
+    specified materials from the same place.
+
+    e) Verify that the user has already received a copy of these
+    materials or that you have already sent this user a copy.
+
+  For an executable, the required form of the "work that uses the
+Library" must include any data and utility programs needed for
+reproducing the executable from it.  However, as a special exception,
+the materials to be distributed need not include anything that is
+normally distributed (in either source or binary form) with the major
+components (compiler, kernel, and so on) of the operating system on
+which the executable runs, unless that component itself accompanies
+the executable.
+
+  It may happen that this requirement contradicts the license
+restrictions of other proprietary libraries that do not normally
+accompany the operating system.  Such a contradiction means you cannot
+use both them and the Library together in an executable that you
+distribute.
+
+  7. You may place library facilities that are a work based on the
+Library side-by-side in a single library together with other library
+facilities not covered by this License, and distribute such a combined
+library, provided that the separate distribution of the work based on
+the Library and of the other library facilities is otherwise
+permitted, and provided that you do these two things:
+
+    a) Accompany the combined library with a copy of the same work
+    based on the Library, uncombined with any other library
+    facilities.  This must be distributed under the terms of the
+    Sections above.
+
+    b) Give prominent notice with the combined library of the fact
+    that part of it is a work based on the Library, and explaining
+    where to find the accompanying uncombined form of the same work.
+
+  8. You may not copy, modify, sublicense, link with, or distribute
+the Library except as expressly provided under this License.  Any
+attempt otherwise to copy, modify, sublicense, link with, or
+distribute the Library is void, and will automatically terminate your
+rights under this License.  However, parties who have received copies,
+or rights, from you under this License will not have their licenses
+terminated so long as such parties remain in full compliance.
+
+  9. You are not required to accept this License, since you have not
+signed it.  However, nothing else grants you permission to modify or
+distribute the Library or its derivative works.  These actions are
+prohibited by law if you do not accept this License.  Therefore, by
+modifying or distributing the Library (or any work based on the
+Library), you indicate your acceptance of this License to do so, and
+all its terms and conditions for copying, distributing or modifying
+the Library or works based on it.
+
+  10. Each time you redistribute the Library (or any work based on the
+Library), the recipient automatically receives a license from the
+original licensor to copy, distribute, link with or modify the Library
+subject to these terms and conditions.  You may not impose any further
+restrictions on the recipients' exercise of the rights granted herein.
+You are not responsible for enforcing compliance by third parties with
+this License.
+
+  11. If, as a consequence of a court judgment or allegation of patent
+infringement or for any other reason (not limited to patent issues),
+conditions are imposed on you (whether by court order, agreement or
+otherwise) that contradict the conditions of this License, they do not
+excuse you from the conditions of this License.  If you cannot
+distribute so as to satisfy simultaneously your obligations under this
+License and any other pertinent obligations, then as a consequence you
+may not distribute the Library at all.  For example, if a patent
+license would not permit royalty-free redistribution of the Library by
+all those who receive copies directly or indirectly through you, then
+the only way you could satisfy both it and this License would be to
+refrain entirely from distribution of the Library.
+
+If any portion of this section is held invalid or unenforceable under any
+particular circumstance, the balance of the section is intended to apply,
+and the section as a whole is intended to apply in other circumstances.
+
+It is not the purpose of this section to induce you to infringe any
+patents or other property right claims or to contest validity of any
+such claims; this section has the sole purpose of protecting the
+integrity of the free software distribution system which is
+implemented by public license practices.  Many people have made
+generous contributions to the wide range of software distributed
+through that system in reliance on consistent application of that
+system; it is up to the author/donor to decide if he or she is willing
+to distribute software through any other system and a licensee cannot
+impose that choice.
+
+This section is intended to make thoroughly clear what is believed to
+be a consequence of the rest of this License.
+
+  12. If the distribution and/or use of the Library is restricted in
+certain countries either by patents or by copyrighted interfaces, the
+original copyright holder who places the Library under this License may add
+an explicit geographical distribution limitation excluding those countries,
+so that distribution is permitted only in or among countries not thus
+excluded.  In such case, this License incorporates the limitation as if
+written in the body of this License.
+
+  13. The Free Software Foundation may publish revised and/or new
+versions of the Lesser General Public License from time to time.
+Such new versions will be similar in spirit to the present version,
+but may differ in detail to address new problems or concerns.
+
+Each version is given a distinguishing version number.  If the Library
+specifies a version number of this License which applies to it and
+"any later version", you have the option of following the terms and
+conditions either of that version or of any later version published by
+the Free Software Foundation.  If the Library does not specify a
+license version number, you may choose any version ever published by
+the Free Software Foundation.
+
+  14. If you wish to incorporate parts of the Library into other free
+programs whose distribution conditions are incompatible with these,
+write to the author to ask for permission.  For software which is
+copyrighted by the Free Software Foundation, write to the Free
+Software Foundation; we sometimes make exceptions for this.  Our
+decision will be guided by the two goals of preserving the free status
+of all derivatives of our free software and of promoting the sharing
+and reuse of software generally.
+
+			    NO WARRANTY
+
+  15. BECAUSE THE LIBRARY IS LICENSED FREE OF CHARGE, THERE IS NO
+WARRANTY FOR THE LIBRARY, TO THE EXTENT PERMITTED BY APPLICABLE LAW.
+EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR
+OTHER PARTIES PROVIDE THE LIBRARY "AS IS" WITHOUT WARRANTY OF ANY
+KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE
+IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
+PURPOSE.  THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE
+LIBRARY IS WITH YOU.  SHOULD THE LIBRARY PROVE DEFECTIVE, YOU ASSUME
+THE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION.
+
+  16. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN
+WRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY
+AND/OR REDISTRIBUTE THE LIBRARY AS PERMITTED ABOVE, BE LIABLE TO YOU
+FOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR
+CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE
+LIBRARY (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING
+RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A
+FAILURE OF THE LIBRARY TO OPERATE WITH ANY OTHER SOFTWARE), EVEN IF
+SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH
+DAMAGES.
+
+		     END OF TERMS AND CONDITIONS
+
+           How to Apply These Terms to Your New Libraries
+
+  If you develop a new library, and you want it to be of the greatest
+possible use to the public, we recommend making it free software that
+everyone can redistribute and change.  You can do so by permitting
+redistribution under these terms (or, alternatively, under the terms of the
+ordinary General Public License).
+
+  To apply these terms, attach the following notices to the library.  It is
+safest to attach them to the start of each source file to most effectively
+convey the exclusion of warranty; and each file should have at least the
+"copyright" line and a pointer to where the full notice is found.
+
+    <one line to give the library's name and a brief idea of what it does.>
+    Copyright (C) <year>  <name of author>
+
+    This library is free software; you can redistribute it and/or
+    modify it under the terms of the GNU Lesser General Public
+    License as published by the Free Software Foundation; either
+    version 2.1 of the License, or (at your option) any later version.
+
+    This library is distributed in the hope that it will be useful,
+    but WITHOUT ANY WARRANTY; without even the implied warranty of
+    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+    Lesser General Public License for more details.
+
+    You should have received a copy of the GNU Lesser General Public
+    License along with this library; if not, write to the Free Software
+    Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+
+Also add information on how to contact you by electronic and paper mail.
+
+You should also get your employer (if you work as a programmer) or your
+school, if any, to sign a "copyright disclaimer" for the library, if
+necessary.  Here is a sample; alter the names:
+
+  Yoyodyne, Inc., hereby disclaims all copyright interest in the
+  library `Frob' (a library for tweaking knobs) written by James Random Hacker.
+
+  <signature of Ty Coon>, 1 April 1990
+  Ty Coon, President of Vice
+
+That's all there is to it!
+
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/README.txt b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/README.txt
new file mode 100644
index 0000000000000000000000000000000000000000..53fc2ab4f86279d99ce969744a5a762f17c6dd7f
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/README.txt
@@ -0,0 +1,92 @@
+##
+##	qpOASES -- An Implementation of the Online Active Set Strategy.
+##	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+##
+##	qpOASES is free software; you can redistribute it and/or
+##	modify it under the terms of the GNU Lesser General Public
+##	License as published by the Free Software Foundation; either
+##	version 2.1 of the License, or (at your option) any later version.
+##
+##	qpOASES is distributed in the hope that it will be useful,
+##	but WITHOUT ANY WARRANTY; without even the implied warranty of
+##	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+##	Lesser General Public License for more details.
+##
+##	You should have received a copy of the GNU Lesser General Public
+##	License along with qpOASES; if not, write to the Free Software
+##	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+##
+
+
+
+INTRODUCTION
+=============
+
+qpOASES is an open-source C++ implementation of the recently proposed 
+online active set strategy (see [1], [2]), which was inspired by important 
+observations from the field of parametric quadratic programming. It has 
+several theoretical features that make it particularly suited for model 
+predictive control (MPC) applications.
+
+The software package qpOASES implements these ideas and has already been 
+successfully used for closed-loop control of a real-world Diesel engine [3].
+
+
+References:
+
+[1] H.J. Ferreau. An Online Active Set Strategy for Fast Solution of 
+Parametric Quadratic Programs with Applications to Predictive Engine Control. 
+Diplom thesis, University of Heidelberg, 2006.
+
+[2] H.J. Ferreau, H.G. Bock, M. Diehl. An online active set strategy to 
+overcome the limitations of explicit MPC. International Journal of Robust 
+and Nonlinear Control, 18 (8), pp. 816-830, 2008.
+
+[3] H.J. Ferreau, P. Ortner, P. Langthaler, L. del Re, M. Diehl. Predictive 
+Control of a Real-World Diesel Engine using an Extended Online Active Set 
+Strategy. Annual Reviews in Control, 31 (2), pp. 293-301, 2007.
+
+
+
+GETTING STARTED
+================
+
+1. For installation, usage and additional information on this software package 
+   see the qpOASES User's Manual located at ./DOC/manual.pdf!
+
+
+2. The file ./LICENSE.txt contains a copy of the GNU Lesser General Public 
+   License. Please read it carefully before using qpOASES!
+
+
+3. The whole software package can be downloaded from 
+
+        http://homes.esat.kuleuven.be/~optec/software/qpOASES/ 
+
+   On this webpage you will also find a list of frequently asked questions.
+
+
+
+CONTACT THE AUTHORS
+====================
+
+If you have got questions, remarks or comments on qpOASES 
+please contact the main author:
+
+        Hans Joachim Ferreau
+        Katholieke Universiteit Leuven
+        Department of Electrical Engineering (ESAT)
+        Kasteelpark Arenberg 10, bus 2446
+        B-3001 Leuven-Heverlee, Belgium
+
+        Phone: +32 16 32 03 63
+        E-mail: joachim.ferreau@esat.kuleuven.be
+                qpOASES@esat.kuleuven.be
+
+Also bug reports and source code extensions are most welcome!
+
+
+
+##
+##	end of file
+##
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Bounds.cpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Bounds.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..cf8ed69890623f1be8a2798bc097298ce09c1442
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Bounds.cpp
@@ -0,0 +1,252 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/Bounds.cpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of the Bounds class designed to manage working sets of
+ *	bounds within a QProblem.
+ */
+
+
+#include <Bounds.hpp>
+
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+
+/*
+ *	B o u n d s
+ */
+Bounds::Bounds( ) :	SubjectTo( ),
+					nV( 0 ),
+					nFV( 0 ),
+					nBV( 0 ),
+					nUV( 0 )
+{
+}
+
+
+/*
+ *	B o u n d s
+ */
+Bounds::Bounds( const Bounds& rhs ) :	SubjectTo( rhs ),
+										nV( rhs.nV ),
+										nFV( rhs.nFV ),
+										nBV( rhs.nBV ),
+										nUV( rhs.nUV )
+{
+	free  = rhs.free;
+	fixed = rhs.fixed;
+}
+
+
+/*
+ *	~ B o u n d s
+ */
+Bounds::~Bounds( )
+{
+}
+
+
+/*
+ *	o p e r a t o r =
+ */
+Bounds& Bounds::operator=( const Bounds& rhs )
+{
+	if ( this != &rhs )
+	{
+		SubjectTo::operator=( rhs );
+
+		nV  = rhs.nV;
+		nFV = rhs.nFV;
+		nBV = rhs.nBV;
+		nUV = rhs.nUV;
+
+		free  = rhs.free;
+		fixed = rhs.fixed;
+	}
+
+	return *this;
+}
+
+
+/*
+ *	i n i t
+ */
+returnValue Bounds::init( int n )
+{
+	nV = n;
+	nFV = 0;
+	nBV = 0;
+	nUV = 0;
+
+	free.init( );
+	fixed.init( );
+
+	return SubjectTo::init( n );
+}
+
+
+/*
+ *	s e t u p B o u n d
+ */
+returnValue Bounds::setupBound(	int _number, SubjectToStatus _status
+								)
+{
+	/* consistency check */
+	if ( ( _number < 0 ) || ( _number >= getNV( ) ) )
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+	
+	/* Add bound index to respective index list. */
+	switch ( _status )
+	{
+		case ST_INACTIVE:
+			if ( this->addIndex( this->getFree( ),_number,_status ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_BOUND_FAILED );
+			break;
+
+		case ST_LOWER:
+			if ( this->addIndex( this->getFixed( ),_number,_status ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_BOUND_FAILED );
+			break;
+
+		case ST_UPPER:
+			if ( this->addIndex( this->getFixed( ),_number,_status ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_BOUND_FAILED );
+			break;
+
+		default:
+			return THROWERROR( RET_INVALID_ARGUMENTS );
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p A l l F r e e
+ */
+returnValue Bounds::setupAllFree( )
+{
+	int i;
+
+	/* 1) Place unbounded variables at the beginning of the index list of free variables. */
+	for( i=0; i<nV; ++i )
+	{
+		if ( getType( i ) == ST_UNBOUNDED )
+		{
+			if ( setupBound( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_SETUP_BOUND_FAILED );
+		}
+	}
+
+	/* 2) Add remaining (i.e. bounded but possibly free) variables to the index list of free variables. */
+	for( i=0; i<nV; ++i )
+	{
+		if ( getType( i ) == ST_BOUNDED )
+		{
+			if ( setupBound( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_BOUND_FAILED );
+		}
+	}
+
+	/* 3) Place implicitly fixed variables at the end of the index list of free variables. */
+	for( i=0; i<nV; ++i )
+	{
+		if ( getType( i ) == ST_EQUALITY )
+		{
+			if ( setupBound( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_BOUND_FAILED );
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	m o v e F i x e d T o F r e e
+ */
+returnValue Bounds::moveFixedToFree( int _number )
+{
+	/* consistency check */
+	if ( ( _number < 0 ) || ( _number >= getNV( ) ) )
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+
+	/* Move index from indexlist of fixed variables to that of free ones. */
+	if ( this->removeIndex( this->getFixed( ),_number ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_MOVING_BOUND_FAILED );
+
+	if ( this->addIndex( this->getFree( ),_number,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_MOVING_BOUND_FAILED );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	m o v e F r e e T o F i x e d
+ */
+returnValue Bounds::moveFreeToFixed(	int _number, SubjectToStatus _status
+										)
+{
+	/* consistency check */
+	if ( ( _number < 0 ) || ( _number >= getNV( ) ) )
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+
+	/* Move index from indexlist of free variables to that of fixed ones. */
+	if ( this->removeIndex( this->getFree( ),_number ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_MOVING_BOUND_FAILED );
+
+	if ( this->addIndex( this->getFixed( ),_number,_status ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_MOVING_BOUND_FAILED );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s w a p F r e e
+ */
+returnValue Bounds::swapFree(	int number1, int number2
+								)
+{
+	/* consistency check */
+	if ( ( number1 < 0 ) || ( number1 >= getNV( ) ) || ( number2 < 0 ) || ( number2 >= getNV( ) ) )
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+
+	/* Swap index within indexlist of free variables. */
+	return this->swapIndex( this->getFree( ),number1,number2 );
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Bounds.ipp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Bounds.ipp
new file mode 100644
index 0000000000000000000000000000000000000000..d2ab1ba2d89835a1f1de05a5e7f50836123f5905
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Bounds.ipp
@@ -0,0 +1,144 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/Bounds.ipp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of inlined member functions of the Bounds class designed 
+ *	to manage working sets of bounds within a QProblem.
+ */
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+/*
+ *	g e t N V
+ */
+inline int Bounds::getNV( ) const
+{
+ 	return nV;
+}
+
+
+/*
+ *	g e t N F X
+ */
+inline int Bounds::getNFV( ) const
+{
+ 	return nFV;
+}
+
+
+/*
+ *	g e t N B V
+ */
+inline int Bounds::getNBV( ) const
+{
+ 	return nBV;
+}
+ 
+
+/*
+ *	g e t N U V
+ */
+inline int Bounds::getNUV( ) const
+{
+	return nUV;
+}
+
+
+
+/*
+ *	s e t N F X
+ */
+inline returnValue Bounds::setNFV( int n )
+{
+ 	nFV = n;
+	return SUCCESSFUL_RETURN;	
+}
+ 
+ 
+/*
+ *	s e t N B V
+ */
+inline returnValue Bounds::setNBV( int n )
+{
+ 	nBV = n;
+	return SUCCESSFUL_RETURN;
+}
+ 
+
+/*
+ *	s e t N U V
+ */
+inline returnValue Bounds::setNUV( int n )
+{
+	nUV = n;
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t N F R
+ */
+inline int Bounds::getNFR( )
+{
+ 	return free.getLength( );
+}
+
+
+/*
+ *	g e t N F X
+ */
+inline int Bounds::getNFX( )
+{
+ 	return fixed.getLength( );
+}
+
+
+/*
+ *	g e t F r e e
+ */
+inline Indexlist* Bounds::getFree( )
+{
+	return &free;
+}
+
+
+/*
+ *	g e t F i x e d
+ */
+inline Indexlist* Bounds::getFixed( )
+{
+	return &fixed;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Constraints.cpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Constraints.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..b2ad5bd111547e064fc44eabc520fdbe748bef5d
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Constraints.cpp
@@ -0,0 +1,248 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/Constraints.cpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of the Constraints class designed to manage working sets of
+ *	constraints within a QProblem.
+ */
+
+
+#include <Constraints.hpp>
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+
+/*
+ *	C o n s t r a i n t s
+ */
+Constraints::Constraints( ) :	SubjectTo( ),
+								nC( 0 ),
+								nEC( 0 ),
+								nIC( 0 ),
+								nUC( 0 )
+{
+}
+
+
+/*
+ *	C o n s t r a i n t s
+ */
+Constraints::Constraints( const Constraints& rhs ) :	SubjectTo( rhs ),
+														nC( rhs.nC ),
+														nEC( rhs.nEC ),
+														nIC( rhs.nIC ),
+														nUC( rhs.nUC )
+{
+	active =   rhs.active;
+	inactive = rhs.inactive;
+}
+
+
+/*
+ *	~ C o n s t r a i n t s
+ */
+Constraints::~Constraints( )
+{
+}
+
+
+/*
+ *	o p e r a t o r =
+ */
+Constraints& Constraints::operator=( const Constraints& rhs )
+{
+	if ( this != &rhs )
+	{
+		SubjectTo::operator=( rhs );
+
+		nC  = rhs.nC;
+		nEC = rhs.nEC;
+		nIC = rhs.nIC;
+		nUC = rhs.nUC;
+
+		active =   rhs.active;
+		inactive = rhs.inactive;
+	}
+
+	return *this;
+}
+
+
+/*
+ *	i n i t
+ */
+returnValue Constraints::init( int n )
+{
+	nC = n;
+	nEC = 0;
+	nIC = 0;
+	nUC = 0;
+
+	active.init( );
+	inactive.init( );
+
+	return SubjectTo::init( n );
+}
+
+
+/*
+ *	s e t u p C o n s t r a i n t
+ */
+returnValue Constraints::setupConstraint(	int _number, SubjectToStatus _status
+											)
+{
+	/* consistency check */
+	if ( ( _number < 0 ) || ( _number >= getNC( ) ) )
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+	
+	/* Add constraint index to respective index list. */
+	switch ( _status )
+	{
+		case ST_INACTIVE:
+			if ( this->addIndex( this->getInactive( ),_number,_status ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_CONSTRAINT_FAILED );
+			break;
+
+		case ST_LOWER:
+			if ( this->addIndex( this->getActive( ),_number,_status ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_CONSTRAINT_FAILED );
+			break;
+
+		case ST_UPPER:
+			if ( this->addIndex( this->getActive( ),_number,_status ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_CONSTRAINT_FAILED );
+			break;
+
+		default:
+			return THROWERROR( RET_INVALID_ARGUMENTS );
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p A l l I n a c t i v e
+ */
+returnValue Constraints::setupAllInactive( )
+{
+	int i;
+
+
+	/* 1) Place unbounded constraints at the beginning of the index list of inactive constraints. */
+	for( i=0; i<nC; ++i )
+	{
+		if ( getType( i ) == ST_UNBOUNDED )
+		{
+			if ( setupConstraint( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_CONSTRAINT_FAILED );
+		}
+	}
+
+	/* 2) Add remaining (i.e. "real" inequality) constraints to the index list of inactive constraints. */
+	for( i=0; i<nC; ++i )
+	{
+		if ( getType( i ) == ST_BOUNDED )
+		{
+			if ( setupConstraint( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_CONSTRAINT_FAILED );
+		}
+	}
+
+	/* 3) Place implicit equality constraints at the end of the index list of inactive constraints. */
+	for( i=0; i<nC; ++i )
+	{
+		if ( getType( i ) == ST_EQUALITY )
+		{
+			if ( setupConstraint( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_CONSTRAINT_FAILED );
+		}
+	}
+
+	/* 4) Moreover, add all constraints of unknown type. */
+	for( i=0; i<nC; ++i )
+	{
+		if ( getType( i ) == ST_UNKNOWN )
+		{
+			if ( setupConstraint( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_CONSTRAINT_FAILED );
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	m o v e A c t i v e T o I n a c t i v e
+ */
+returnValue Constraints::moveActiveToInactive( int _number )
+{
+	/* consistency check */
+	if ( ( _number < 0 ) || ( _number >= getNC( ) ) )
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+
+	/* Move index from indexlist of active constraints to that of inactive ones. */
+	if ( this->removeIndex( this->getActive( ),_number ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_MOVING_BOUND_FAILED );
+
+	if ( this->addIndex( this->getInactive( ),_number,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_MOVING_BOUND_FAILED );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	m o v e I n a c t i v e T o A c t i v e
+ */
+returnValue Constraints::moveInactiveToActive(	int _number, SubjectToStatus _status
+												)
+{
+	/* consistency check */
+	if ( ( _number < 0 ) || ( _number >= getNC( ) ) )
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+
+	/* Move index from indexlist of inactive constraints to that of active ones. */
+	if ( this->removeIndex( this->getInactive( ),_number ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_MOVING_BOUND_FAILED );
+
+	if ( this->addIndex( this->getActive( ),_number,_status ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_MOVING_BOUND_FAILED );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Constraints.ipp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Constraints.ipp
new file mode 100644
index 0000000000000000000000000000000000000000..1b874ef3c6596bf52bda2ae93147e2bb7e942be9
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Constraints.ipp
@@ -0,0 +1,144 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/Constraints.ipp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Declaration of inlined member functions of the Constraints class designed 
+ *	to manage working sets of constraints within a QProblem.
+ */
+
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+/*
+ *	g e t N C
+ */
+inline int Constraints::getNC( ) const
+{
+ 	return nC;
+}
+ 
+
+/*
+ *	g e t N E C
+ */
+inline int Constraints::getNEC( ) const
+{
+ 	return nEC;
+}
+ 
+
+/*
+ *	g e t N I C
+ */
+inline int Constraints::getNIC( ) const
+{
+ 	return nIC;
+}
+ 
+
+/*
+ *	g e t N U C
+ */
+inline int Constraints::getNUC( ) const
+{
+ 	return nUC;
+}
+
+
+/*
+ *	s e t N E C
+ */
+inline returnValue Constraints::setNEC( int n )
+{
+ 	nEC = n;
+	return SUCCESSFUL_RETURN;
+}
+ 
+
+/*
+ *	s e t N I C
+ */
+inline returnValue Constraints::setNIC( int n )
+{
+ 	nIC = n;
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t N U C
+ */
+inline returnValue Constraints::setNUC( int n )
+{
+ 	nUC = n;
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t N A C
+ */
+inline int Constraints::getNAC( )
+{
+ 	return active.getLength( );
+}
+
+
+/*
+ *	g e t N I A C
+ */
+inline int Constraints::getNIAC( )
+{
+ 	return inactive.getLength( );
+}
+
+
+/*
+ *	g e t A c t i v e
+ */
+inline Indexlist* Constraints::getActive( )
+{
+	return &active;
+}
+
+
+/*
+ *	g e t I n a c t i v e
+ */
+inline Indexlist* Constraints::getInactive( )
+{
+	return &inactive;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/CyclingManager.cpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/CyclingManager.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..27c2996ef3fff2e3ac8234f4e59cb4511571d3b0
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/CyclingManager.cpp
@@ -0,0 +1,188 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/CyclingManager.cpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of the CyclingManager class designed to detect
+ *	and handle possible cycling during QP iterations.
+ *
+ */
+
+
+#include <CyclingManager.hpp>
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+
+/*
+ *	C y c l i n g M a n a g e r
+ */
+CyclingManager::CyclingManager( ) :	nV( 0 ),
+									nC( 0 )
+{
+	cyclingDetected = BT_FALSE;
+}
+
+
+/*
+ *	C y c l i n g M a n a g e r
+ */
+CyclingManager::CyclingManager( const CyclingManager& rhs ) :	nV( rhs.nV ),
+																nC( rhs.nC ),
+																cyclingDetected( rhs.cyclingDetected )
+{
+	int i;
+
+	for( i=0; i<nV+nC; ++i )
+		status[i] = rhs.status[i];
+}
+
+
+/*
+ *	~ C y c l i n g M a n a g e r
+ */
+CyclingManager::~CyclingManager( )
+{
+}
+
+
+/*
+ *	o p e r a t o r =
+ */
+CyclingManager& CyclingManager::operator=( const CyclingManager& rhs )
+{
+	int i;
+
+	if ( this != &rhs )
+	{
+		nV = rhs.nV;
+		nC = rhs.nC;
+
+		for( i=0; i<nV+nC; ++i )
+			status[i] = rhs.status[i];
+
+		cyclingDetected = rhs.cyclingDetected;
+	}
+
+	return *this;
+}
+
+
+
+/*
+ *	i n i t
+ */
+returnValue CyclingManager::init( int _nV, int _nC )
+{
+	nV = _nV;
+	nC = _nC;
+
+	cyclingDetected = BT_FALSE;
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*
+ *	s e t C y c l i n g S t a t u s
+ */
+returnValue CyclingManager::setCyclingStatus(	int number,
+												BooleanType isBound, CyclingStatus _status
+												)
+{
+	if ( isBound == BT_TRUE )
+	{
+		/* Set cycling status of a bound. */
+		if ( ( number >= 0 ) && ( number < nV ) )
+		{
+			status[number] = _status;
+			return SUCCESSFUL_RETURN;
+		}
+		else
+			return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+	}
+	else
+	{
+		/* Set cycling status of a constraint. */
+		if ( ( number >= 0 ) && ( number < nC ) )
+		{
+			status[nV+number] = _status;
+			return SUCCESSFUL_RETURN;
+		}
+		else
+			return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+	}
+}
+
+
+/*
+ *	g e t C y c l i n g S t a t u s
+ */
+CyclingStatus CyclingManager::getCyclingStatus( int number, BooleanType isBound ) const
+{
+	if ( isBound == BT_TRUE )
+	{
+		/* Return cycling status of a bound. */
+		if ( ( number >= 0 ) && ( number < nV ) )
+			return status[number];
+	}
+	else
+	{
+		/* Return cycling status of a constraint. */
+		if ( ( number >= 0 ) && ( number < nC ) )
+			return status[nV+number];
+	}
+
+	return CYC_NOT_INVOLVED;
+}
+
+
+/*
+ *	c l e a r C y c l i n g D a t a
+ */
+returnValue CyclingManager::clearCyclingData( )
+{
+	int i;
+
+	/* Reset all status values ... */
+	for( i=0; i<nV+nC; ++i )
+		status[i] = CYC_NOT_INVOLVED;
+
+	/* ... and the main cycling flag. */
+	cyclingDetected = BT_FALSE;
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/CyclingManager.ipp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/CyclingManager.ipp
new file mode 100644
index 0000000000000000000000000000000000000000..386409a532bee46494649700215b5fd731c81716
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/CyclingManager.ipp
@@ -0,0 +1,51 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/CyclingManager.ipp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of inlined member functions of the CyclingManager class 
+ *	designed to detect and handle possible cycling during QP iterations.
+ *	
+ */
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+/*
+ *	i s C y c l i n g D e t e c t e d
+ */
+inline BooleanType CyclingManager::isCyclingDetected( ) const
+{
+	return cyclingDetected;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..c744adc0d60fb6066c6c5347b1adbe3c941565ab
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp
@@ -0,0 +1,434 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/EXTRAS/SolutionAnalysis.cpp
+ *	\author Milan Vukov, Boris Houska, Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2012
+ *
+ *	Solution analysis class, based on a class in the standard version of the qpOASES
+ */
+
+#include <EXTRAS/SolutionAnalysis.hpp>
+
+/*
+ *	S o l u t i o n A n a l y s i s
+ */
+SolutionAnalysis::SolutionAnalysis( )
+{
+	
+}
+
+/*
+ *	S o l u t i o n A n a l y s i s
+ */
+SolutionAnalysis::SolutionAnalysis( const SolutionAnalysis& rhs )
+{
+	
+}
+
+/*
+ *	~ S o l u t i o n A n a l y s i s
+ */
+SolutionAnalysis::~SolutionAnalysis( )
+{
+	
+}
+
+/*
+ *	o p e r a t o r =
+ */
+SolutionAnalysis& SolutionAnalysis::operator=( const SolutionAnalysis& rhs )
+{
+	if ( this != &rhs )
+	{
+		
+	}
+	
+	return *this;
+}
+
+/*
+ * g e t H e s s i a n I n v e r s e
+ */
+returnValue SolutionAnalysis::getHessianInverse( QProblem* qp, real_t* hessianInverse )
+{
+	returnValue returnvalue; /* the return value */
+	BooleanType Delta_bC_isZero = BT_FALSE; /* (just use FALSE here) */
+	BooleanType Delta_bB_isZero = BT_FALSE; /* (just use FALSE here) */
+	
+	register int run1, run2, run3;
+	
+	register int nFR, nFX;
+	
+	/* Ask for the number of free and fixed variables, assumes that active set
+	 * is constant for the covariance evaluation */
+	nFR = qp->getNFR( );
+	nFX = qp->getNFX( );
+	
+	/* Ask for the corresponding index arrays: */
+	if ( qp->bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_HOTSTART_FAILED );
+	
+	if ( qp->bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_HOTSTART_FAILED );
+	
+	if ( qp->constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_HOTSTART_FAILED );
+	
+	/* Initialization: */
+	for( run1 = 0; run1 < NVMAX; run1++ )
+		delta_g_cov[ run1 ] = 0.0;
+	
+	for( run1 = 0; run1 < NVMAX; run1++ )
+		delta_lb_cov[ run1 ] = 0.0;
+	
+	for( run1 = 0; run1 < NVMAX; run1++ )
+		delta_ub_cov[ run1 ] = 0.0;
+	
+	for( run1 = 0; run1 < NCMAX; run1++ )
+		delta_lbA_cov[ run1 ] = 0.0;
+	
+	for( run1 = 0; run1 < NCMAX; run1++ )
+		delta_ubA_cov[ run1 ] = 0.0;
+	
+	/* The following loop solves the following:
+	 *
+	 * KKT * x =
+	 *   [delta_g_cov', delta_lbA_cov', delta_ubA_cov', delta_lb_cov', delta_ub_cov]'
+	 *
+	 * for the first NVMAX (negative) elementary vectors in order to get
+	 * transposed inverse of the Hessian. Assuming that the Hessian is
+	 * symmetric, the function will return transposed inverse, instead of the
+	 * true inverse.
+	 *
+	 * Note, that we use negative elementary vectors due because internal
+	 * implementation of the function hotstart_determineStepDirection requires
+	 * so.
+	 *
+	 * */
+	
+	for( run3 = 0; run3 < NVMAX; run3++ )
+	{
+		/* Line wise loading of the corresponding (negative) elementary vector: */
+		delta_g_cov[ run3 ] = -1.0;
+		
+		/* Evaluation of the step: */
+		returnvalue = qp->hotstart_determineStepDirection(
+			FR_idx, FX_idx, AC_idx,
+			delta_g_cov, delta_lbA_cov, delta_ubA_cov, delta_lb_cov, delta_ub_cov,
+			Delta_bC_isZero, Delta_bB_isZero,
+			delta_xFX, delta_xFR, delta_yAC, delta_yFX
+			);
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			return returnvalue;
+		}
+		
+		/* Line wise storage of the QP reaction: */
+		for( run1 = 0; run1 < nFR; run1++ )
+		{
+			run2 = FR_idx[ run1 ];
+			
+			hessianInverse[run3 * NVMAX + run2] = delta_xFR[ run1 ];
+		} 
+		
+		for( run1 = 0; run1 < nFX; run1++ )
+		{ 
+			run2 = FX_idx[ run1 ];
+			
+			hessianInverse[run3 * NVMAX + run2] = delta_xFX[ run1 ];
+		}
+		
+		/* Prepare for the next iteration */
+		delta_g_cov[ run3 ] = 0.0;
+	}
+	
+	// TODO: Perform the transpose of the inverse of the Hessian matrix
+	
+	return SUCCESSFUL_RETURN; 
+}
+
+/*
+ * g e t H e s s i a n I n v e r s e
+ */
+returnValue SolutionAnalysis::getHessianInverse( QProblemB* qp, real_t* hessianInverse )
+{
+	returnValue returnvalue; /* the return value */
+	BooleanType Delta_bB_isZero = BT_FALSE; /* (just use FALSE here) */
+	
+	register int run1, run2, run3;
+	
+	register int nFR, nFX;
+	
+	/* Ask for the number of free and fixed variables, assumes that active set
+	 * is constant for the covariance evaluation */
+	nFR = qp->getNFR( );
+	nFX = qp->getNFX( );
+	
+	/* Ask for the corresponding index arrays: */
+	if ( qp->bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_HOTSTART_FAILED );
+	
+	if ( qp->bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_HOTSTART_FAILED );
+	
+	/* Initialization: */
+	for( run1 = 0; run1 < NVMAX; run1++ )
+		delta_g_cov[ run1 ] = 0.0;
+	
+	for( run1 = 0; run1 < NVMAX; run1++ )
+		delta_lb_cov[ run1 ] = 0.0;
+	
+	for( run1 = 0; run1 < NVMAX; run1++ )
+		delta_ub_cov[ run1 ] = 0.0;
+	
+	/* The following loop solves the following:
+	 *
+	 * KKT * x =
+	 *   [delta_g_cov', delta_lb_cov', delta_ub_cov']'
+	 *
+	 * for the first NVMAX (negative) elementary vectors in order to get
+	 * transposed inverse of the Hessian. Assuming that the Hessian is
+	 * symmetric, the function will return transposed inverse, instead of the
+	 * true inverse.
+	 *
+	 * Note, that we use negative elementary vectors due because internal
+	 * implementation of the function hotstart_determineStepDirection requires
+	 * so.
+	 *
+	 * */
+	
+	for( run3 = 0; run3 < NVMAX; run3++ )
+	{
+		/* Line wise loading of the corresponding (negative) elementary vector: */
+		delta_g_cov[ run3 ] = -1.0;
+		
+		/* Evaluation of the step: */
+		returnvalue = qp->hotstart_determineStepDirection(
+			FR_idx, FX_idx,
+			delta_g_cov, delta_lb_cov, delta_ub_cov,
+			Delta_bB_isZero,
+			delta_xFX, delta_xFR, delta_yFX
+			);
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			return returnvalue;
+		}
+				
+		/* Line wise storage of the QP reaction: */
+		for( run1 = 0; run1 < nFR; run1++ )
+		{
+			run2 = FR_idx[ run1 ];
+			
+			hessianInverse[run3 * NVMAX + run2] = delta_xFR[ run1 ];
+		} 
+		
+		for( run1 = 0; run1 < nFX; run1++ )
+		{ 
+			run2 = FX_idx[ run1 ];
+			
+			hessianInverse[run3 * NVMAX + run2] = delta_xFX[ run1 ];
+		}
+		
+		/* Prepare for the next iteration */
+		delta_g_cov[ run3 ] = 0.0;
+	}
+	
+	// TODO: Perform the transpose of the inverse of the Hessian matrix
+	
+	return SUCCESSFUL_RETURN; 
+}
+
+/*
+ * g e t V a r i a n c e C o v a r i a n c e
+ */
+
+#if QPOASES_USE_OLD_VERSION
+
+returnValue SolutionAnalysis::getVarianceCovariance( QProblem* qp, real_t* g_b_bA_VAR, real_t* Primal_Dual_VAR )
+{
+	int run1, run2, run3; /* simple run variables (for loops). */
+	
+	returnValue returnvalue; /* the return value */
+	BooleanType Delta_bC_isZero = BT_FALSE; /* (just use FALSE here) */
+	BooleanType Delta_bB_isZero = BT_FALSE; /* (just use FALSE here) */
+	
+	/* ASK FOR THE NUMBER OF FREE AND FIXED VARIABLES:
+	 * (ASSUMES THAT ACTIVE SET IS CONSTANT FOR THE
+	 *  VARIANCE-COVARIANCE EVALUATION)
+	 * ----------------------------------------------- */
+	int nFR, nFX, nAC;
+	
+	nFR = qp->getNFR( );
+	nFX = qp->getNFX( );
+	nAC = qp->getNAC( );
+	
+	if ( qp->bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_HOTSTART_FAILED );
+	
+	if ( qp->bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_HOTSTART_FAILED );
+	
+	if ( qp->constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_HOTSTART_FAILED );
+	
+	/* SOME INITIALIZATIONS:
+	 * --------------------- */
+	for( run1 = 0; run1 < KKT_DIM * KKT_DIM; run1++ )
+	{
+		K [run1] = 0.0;
+		Primal_Dual_VAR[run1] = 0.0;
+	}
+	
+	/* ================================================================= */
+	
+	/* FIRST MATRIX MULTIPLICATION (OBTAINS THE INTERMEDIATE RESULT
+	 *  K := [ ("ACTIVE" KKT-MATRIX OF THE QP)^(-1) * g_b_bA_VAR ]^T )
+	 * THE EVALUATION OF THE INVERSE OF THE KKT-MATRIX OF THE QP
+	 * WITH RESPECT TO THE CURRENT ACTIVE SET
+	 * USES THE EXISTING CHOLESKY AND TQ-DECOMPOSITIONS. FOR DETAILS
+	 * cf. THE (protected) FUNCTION determineStepDirection. */
+	
+	for( run3 = 0; run3 < KKT_DIM; run3++ )
+	{
+		
+		for( run1 = 0; run1 < NVMAX; run1++ )
+		{
+			delta_g_cov [run1] = g_b_bA_VAR[run3*KKT_DIM+run1];
+			delta_lb_cov [run1] = g_b_bA_VAR[run3*KKT_DIM+NVMAX+run1]; /*  LINE-WISE LOADING OF THE INPUT */
+			delta_ub_cov [run1] = g_b_bA_VAR[run3*KKT_DIM+NVMAX+run1]; /*  VARIANCE-COVARIANCE            */
+		}
+		for( run1 = 0; run1 < NCMAX; run1++ )
+		{
+			delta_lbA_cov [run1] = g_b_bA_VAR[run3*KKT_DIM+2*NVMAX+run1];
+			delta_ubA_cov [run1] = g_b_bA_VAR[run3*KKT_DIM+2*NVMAX+run1];
+		}
+		
+		/* EVALUATION OF THE STEP:
+		 * ------------------------------------------------------------------------------ */
+		
+		returnvalue = qp->hotstart_determineStepDirection(
+			FR_idx, FX_idx, AC_idx,
+			delta_g_cov, delta_lbA_cov, delta_ubA_cov, delta_lb_cov, delta_ub_cov,
+			Delta_bC_isZero, Delta_bB_isZero, delta_xFX,delta_xFR,
+			delta_yAC,delta_yFX );
+		
+		/* ------------------------------------------------------------------------------ */
+		
+		/* STOP THE ALGORITHM IN THE CASE OF NO SUCCESFUL RETURN:
+		 * ------------------------------------------------------ */
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			return returnvalue;
+		}
+		
+		/*  LINE WISE                  */
+		/*  STORAGE OF THE QP-REACTION */
+		/*  (uses the index list)      */
+		
+		for( run1=0; run1<nFR; run1++ )
+		{
+			run2 = FR_idx[run1];
+			K[run3*KKT_DIM+run2] = delta_xFR[run1];
+		} 
+		for( run1=0; run1<nFX; run1++ )
+		{ 
+			run2 = FX_idx[run1]; 
+			K[run3*KKT_DIM+run2] = delta_xFX[run1];
+			K[run3*KKT_DIM+NVMAX+run2] = delta_yFX[run1];
+		}
+		for( run1=0; run1<nAC; run1++ )
+		{
+			run2 = AC_idx[run1];
+			K[run3*KKT_DIM+2*NVMAX+run2] = delta_yAC[run1];
+		}
+	}
+	
+	/* ================================================================= */
+	
+	/* SECOND MATRIX MULTIPLICATION (OBTAINS THE FINAL RESULT
+	 * Primal_Dual_VAR := ("ACTIVE" KKT-MATRIX OF THE QP)^(-1) * K )
+	 * THE APPLICATION OF THE KKT-INVERSE IS AGAIN REALIZED
+	 * BY USING THE PROTECTED FUNCTION
+	 * determineStepDirection */
+	
+	for( run3 = 0; run3 < KKT_DIM; run3++ )
+	{
+		
+		for( run1 = 0; run1 < NVMAX; run1++ )
+		{
+			delta_g_cov [run1] = K[run3+ run1*KKT_DIM];
+			delta_lb_cov [run1] = K[run3+(NVMAX+run1)*KKT_DIM]; /*  ROW WISE LOADING OF THE */
+			delta_ub_cov [run1] = K[run3+(NVMAX+run1)*KKT_DIM]; /*  INTERMEDIATE RESULT K   */
+		}
+		for( run1 = 0; run1 < NCMAX; run1++ )
+		{
+			delta_lbA_cov [run1] = K[run3+(2*NVMAX+run1)*KKT_DIM];
+			delta_ubA_cov [run1] = K[run3+(2*NVMAX+run1)*KKT_DIM];
+		}
+		
+		/* EVALUATION OF THE STEP:
+		 * ------------------------------------------------------------------------------ */
+		
+		returnvalue = qp->hotstart_determineStepDirection(
+			FR_idx, FX_idx, AC_idx,
+			delta_g_cov, delta_lbA_cov, delta_ubA_cov, delta_lb_cov, delta_ub_cov,
+			Delta_bC_isZero, Delta_bB_isZero, delta_xFX,delta_xFR,
+			delta_yAC,delta_yFX );
+		
+		/* ------------------------------------------------------------------------------ */
+		
+		/* STOP THE ALGORITHM IN THE CASE OF NO SUCCESFUL RETURN:
+		 * ------------------------------------------------------ */
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			return returnvalue;
+		}
+		
+		/*  ROW-WISE STORAGE */
+		/*  OF THE RESULT.   */
+		
+		for( run1=0; run1<nFR; run1++ )
+		{
+			run2 = FR_idx[run1];
+			Primal_Dual_VAR[run3+run2*KKT_DIM] = delta_xFR[run1];
+		}
+		for( run1=0; run1<nFX; run1++ )
+		{ 
+			run2 = FX_idx[run1]; 
+			Primal_Dual_VAR[run3+run2*KKT_DIM ] = delta_xFX[run1];
+			Primal_Dual_VAR[run3+(NVMAX+run2)*KKT_DIM] = delta_yFX[run1];
+		}
+		for( run1=0; run1<nAC; run1++ )
+		{
+			run2 = AC_idx[run1];
+			Primal_Dual_VAR[run3+(2*NVMAX+run2)*KKT_DIM] = delta_yAC[run1];
+		}
+	}
+	
+	return SUCCESSFUL_RETURN;
+}
+
+#endif
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Indexlist.cpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Indexlist.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..b512569a800be25deee4f9090b07511eaa608153
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Indexlist.cpp
@@ -0,0 +1,342 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/Indexlist.cpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of the Indexlist class designed to manage index lists of
+ *	constraints and bounds within a QProblem_SubjectTo.
+ */
+
+
+#include <Indexlist.hpp>
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+
+/*
+ *	I n d e x l i s t
+ */
+Indexlist::Indexlist( ) :	length( 0 ),
+							first( -1 ),
+							last( -1 ),
+							lastusedindex( -1 ),
+							physicallength( INDEXLISTFACTOR*(NVMAX+NCMAX) )
+{
+	int i;
+
+	for( i=0; i<physicallength; ++i )
+	{
+		number[i] = -1;
+		next[i] = -1;
+		previous[i] = -1;
+	}
+}
+
+
+/*
+ *	I n d e x l i s t
+ */
+Indexlist::Indexlist( const Indexlist& rhs ) :	length( rhs.length ),
+												first( rhs.first ),
+												last( rhs.last ),
+												lastusedindex( rhs.lastusedindex ),
+												physicallength( rhs.physicallength )
+{
+	int i;
+
+	for( i=0; i<physicallength; ++i )
+	{
+		number[i] = rhs.number[i];
+		next[i] = rhs.next[i];
+		previous[i] = rhs.previous[i];
+	}
+}
+
+
+/*
+ *	~ I n d e x l i s t
+ */
+Indexlist::~Indexlist( )
+{
+}
+
+
+/*
+ *	o p e r a t o r =
+ */
+Indexlist& Indexlist::operator=( const Indexlist& rhs )
+{
+	int i;
+
+	if ( this != &rhs )
+	{
+		length = rhs.length;
+		first = rhs.first;
+		last = rhs.last;
+		lastusedindex = rhs.lastusedindex;
+		physicallength = rhs.physicallength;
+
+		for( i=0; i<physicallength; ++i )
+		{
+			number[i] = rhs.number[i];
+			next[i] = rhs.next[i];
+			previous[i] = rhs.previous[i];
+		}
+	}
+
+	return *this;
+}
+
+
+/*
+ *	i n i t
+ */
+returnValue Indexlist::init( )
+{
+	int i;
+
+	length = 0;
+	first = -1;
+	last = -1;
+	lastusedindex = -1;
+	physicallength = INDEXLISTFACTOR*(NVMAX+NCMAX);
+
+	for( i=0; i<physicallength; ++i )
+	{
+		number[i] = -1;
+		next[i] = -1;
+		previous[i] = -1;
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t N u m b e r A r r a y
+ */
+returnValue Indexlist::getNumberArray( int* const numberarray ) const
+{
+	int i;
+	int n = first;
+
+	/* Run trough indexlist and store numbers in numberarray. */
+	for( i=0; i<length; ++i )
+	{
+		if ( ( n >= 0 ) && ( number[n] >= 0 ) )
+			numberarray[i] = number[n];
+		else
+			return THROWERROR( RET_INDEXLIST_CORRUPTED );
+
+		n = next[n];
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t I n d e x
+ */
+int Indexlist::getIndex( int givennumber ) const
+{
+	int i;
+	int n = first;
+	int index = -1;	/* return -1 by default */
+
+	/* Run trough indexlist until number is found, if so return it index. */
+	for ( i=0; i<length; ++i )
+	{
+		if ( number[n] == givennumber )
+		{
+			index = i;
+			break;
+		}
+
+		n = next[n];
+	}
+
+	return index;
+}
+
+
+/*
+ *	g e t P h y s i c a l I n d e x
+ */
+int Indexlist::getPhysicalIndex( int givennumber ) const
+{
+	int i;
+	int n = first;
+	int index = -1;	/* return -1 by default */
+
+	/* Run trough indexlist until number is found, if so return it physicalindex. */
+	for ( i=0; i<length; ++i )
+	{
+		if ( number[n] == givennumber )
+		{
+			index = n;
+			break;
+		}
+
+		n = next[n];
+	}
+
+	return index;
+}
+
+
+/*
+ *	a d d N u m b e r
+ */
+returnValue Indexlist::addNumber( int addnumber )
+{
+	int i;
+
+	if ( lastusedindex+1 < physicallength )
+	{
+		/* If there is enough storage, add number to indexlist. */
+		++lastusedindex;
+		number[lastusedindex] = addnumber;
+		next[lastusedindex] = 0;
+
+		if ( length == 0 )
+		{
+			first = lastusedindex;
+			previous[lastusedindex] = 0;
+		}
+		else
+		{
+			next[last] = lastusedindex;
+			previous[lastusedindex] = last;
+		}
+
+		last = lastusedindex;
+		++length;
+
+		return SUCCESSFUL_RETURN;
+	}
+	else
+	{
+		/* Rearrangement of index list necessary! */
+		if ( length == physicallength )
+			return THROWERROR( RET_INDEXLIST_EXCEEDS_MAX_LENGTH );
+		else
+		{
+			int numberArray[NVMAX+NCMAX];
+			getNumberArray( numberArray );
+
+			/* copy existing elements */
+			for ( i=0; i<length; ++i )
+			{
+				number[i] = numberArray[i];
+				next[i] = i+1;
+				previous[i] = i-1;
+			}
+
+			/* add new number at end of list */
+			number[length] = addnumber;
+			next[length] = -1;
+			previous[length] = length-1;
+
+			/* and set remaining entries to empty */
+			for ( i=length+1; i<physicallength; ++i )
+			{
+				number[i] = -1;
+				next[i] = -1;
+				previous[i] = -1;
+			}
+
+			first = 0;
+			last = length;
+			lastusedindex = length;
+			++length;
+
+			return THROWWARNING( RET_INDEXLIST_MUST_BE_REORDERD );
+		}
+	}
+}
+
+
+/*
+ *	r e m o v e N u m b e r
+ */
+returnValue Indexlist::removeNumber( int removenumber )
+{
+	int i = getPhysicalIndex( removenumber );
+
+	/* nothing to be done if number is not contained in index set */
+	if ( i < 0 )
+		return SUCCESSFUL_RETURN;
+
+	int p = previous[i];
+	int n = next[i];
+
+	if ( i == last )
+		last = p;
+	else
+		previous[n] = p;
+
+	if ( i == first )
+		first = n;
+	else
+		next[p] = n;
+
+	number[i] = -1;
+	next[i] = -1;
+	previous[i] = -1;
+	--length;
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s w a p N u m b e r s
+ */
+returnValue Indexlist::swapNumbers( int number1, int number2 )
+{
+	int index1 = getPhysicalIndex( number1 );
+	int index2 = getPhysicalIndex( number2 );
+
+	/* consistency check */
+	if ( ( index1 < 0 ) || ( index2 < 0 ) )
+		return THROWERROR( RET_INDEXLIST_CORRUPTED );
+
+	int tmp = number[index1];
+	number[index1] = number[index2];
+	number[index2] = tmp;
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Indexlist.ipp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Indexlist.ipp
new file mode 100644
index 0000000000000000000000000000000000000000..b75db81ae974901fb4ed77fa7c18e92dfeaedf99
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Indexlist.ipp
@@ -0,0 +1,85 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/Indexlist.ipp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of inlined member functions of the Indexlist class designed 
+ *	to manage index lists of constraints and bounds within a QProblem_SubjectTo.
+ */
+
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+/*
+ *	g e t N u m b e r
+ */
+inline int Indexlist::getNumber( int physicalindex ) const
+{
+	/* consistency check */
+	if ( ( physicalindex < 0 ) || ( physicalindex > length ) )
+		return -RET_INDEXLIST_OUTOFBOUNDS;
+
+	return number[physicalindex];
+}
+
+
+/*
+ *	g e t L e n g t h
+ */
+inline int Indexlist::getLength( )
+{
+	return length;
+}
+
+
+/*
+ *	g e t L a s t N u m b e r
+ */
+inline int Indexlist::getLastNumber( ) const
+{
+	return number[last];
+}
+
+
+/*
+ *	g e t L a s t N u m b e r
+ */
+inline BooleanType Indexlist::isMember( int _number ) const
+{
+	if ( getIndex( _number ) >= 0 )
+		return BT_TRUE;
+	else
+		return BT_FALSE;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/MessageHandling.cpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/MessageHandling.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..18a7654a104afaa86f46c3d198939c40fb04747e
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/MessageHandling.cpp
@@ -0,0 +1,529 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/MessageHandling.cpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of the MessageHandling class including global return values.
+ *
+ */
+
+
+
+#include <MessageHandling.hpp>
+#include <Utils.hpp>
+
+
+
+
+/** Defines pairs of global return values and messages. */
+MessageHandling::ReturnValueList returnValueList[] =
+{
+/* miscellaneous */
+{ SUCCESSFUL_RETURN, "Successful return", VS_VISIBLE },
+{ RET_DIV_BY_ZERO, "Division by zero", VS_VISIBLE },
+{ RET_INDEX_OUT_OF_BOUNDS, "Index out of bounds", VS_VISIBLE },
+{ RET_INVALID_ARGUMENTS, "At least one of the arguments is invalid", VS_VISIBLE },
+{ RET_ERROR_UNDEFINED, "Error number undefined", VS_VISIBLE },
+{ RET_WARNING_UNDEFINED, "Warning number undefined", VS_VISIBLE },
+{ RET_INFO_UNDEFINED, "Info number undefined", VS_VISIBLE },
+{ RET_EWI_UNDEFINED, "Error/warning/info number undefined", VS_VISIBLE },
+{ RET_AVAILABLE_WITH_LINUX_ONLY, "This function is available under Linux only", VS_HIDDEN },
+{ RET_UNKNOWN_BUG, "The error occured is not yet known", VS_VISIBLE },
+{ RET_PRINTLEVEL_CHANGED, "Print level changed", VS_VISIBLE },
+{ RET_NOT_YET_IMPLEMENTED, "Requested function is not yet implemented.", VS_VISIBLE },
+/* Indexlist */
+{ RET_INDEXLIST_MUST_BE_REORDERD, "Index list has to be reordered", VS_VISIBLE },
+{ RET_INDEXLIST_EXCEEDS_MAX_LENGTH, "Index list exceeds its maximal physical length", VS_VISIBLE },
+{ RET_INDEXLIST_CORRUPTED, "Index list corrupted", VS_VISIBLE },
+{ RET_INDEXLIST_OUTOFBOUNDS, "Physical index is out of bounds", VS_VISIBLE },
+{ RET_INDEXLIST_ADD_FAILED, "Adding indices from another index set failed", VS_VISIBLE },
+{ RET_INDEXLIST_INTERSECT_FAILED, "Intersection with another index set failed", VS_VISIBLE },
+/* SubjectTo / Bounds / Constraints */
+{ RET_INDEX_ALREADY_OF_DESIRED_STATUS, "Index is already of desired status", VS_VISIBLE },
+{ RET_SWAPINDEX_FAILED, "Cannot swap between different indexsets", VS_VISIBLE },
+{ RET_ADDINDEX_FAILED, "Adding index to index set failed", VS_VISIBLE },
+{ RET_NOTHING_TO_DO, "Nothing to do", VS_VISIBLE },
+{ RET_SETUP_BOUND_FAILED, "Setting up bound index failed", VS_VISIBLE },
+{ RET_SETUP_CONSTRAINT_FAILED, "Setting up constraint index failed", VS_VISIBLE },
+{ RET_MOVING_BOUND_FAILED, "Moving bound between index sets failed", VS_VISIBLE },
+{ RET_MOVING_CONSTRAINT_FAILED, "Moving constraint between index sets failed", VS_VISIBLE },
+/* QProblem */
+{ RET_QP_ALREADY_INITIALISED, "QProblem has already been initialised", VS_VISIBLE },
+{ RET_NO_INIT_WITH_STANDARD_SOLVER, "Initialisation via extern QP solver is not yet implemented", VS_VISIBLE },
+{ RET_RESET_FAILED, "Reset failed", VS_VISIBLE },
+{ RET_INIT_FAILED, "Initialisation failed", VS_VISIBLE },
+{ RET_INIT_FAILED_TQ, "Initialisation failed due to TQ factorisation", VS_VISIBLE },
+{ RET_INIT_FAILED_CHOLESKY, "Initialisation failed due to Cholesky decomposition", VS_VISIBLE },
+{ RET_INIT_FAILED_HOTSTART, "Initialisation failed! QP could not be solved!", VS_VISIBLE },
+{ RET_INIT_FAILED_INFEASIBILITY, "Initial QP could not be solved due to infeasibility!", VS_VISIBLE },
+{ RET_INIT_FAILED_UNBOUNDEDNESS, "Initial QP could not be solved due to unboundedness!", VS_VISIBLE },
+{ RET_INIT_SUCCESSFUL, "Initialisation done", VS_VISIBLE },
+{ RET_OBTAINING_WORKINGSET_FAILED, "Failed to obtain working set for auxiliary QP", VS_VISIBLE },
+{ RET_SETUP_WORKINGSET_FAILED, "Failed to setup working set for auxiliary QP", VS_VISIBLE },
+{ RET_SETUP_AUXILIARYQP_FAILED, "Failed to setup auxiliary QP for initialised homotopy", VS_VISIBLE },
+{ RET_NO_EXTERN_SOLVER, "No extern QP solver available", VS_VISIBLE },
+{ RET_QP_UNBOUNDED, "QP is unbounded", VS_VISIBLE },
+{ RET_QP_INFEASIBLE, "QP is infeasible", VS_VISIBLE },
+{ RET_QP_NOT_SOLVED, "Problems occured while solving QP with standard solver", VS_VISIBLE },
+{ RET_QP_SOLVED, "QP successfully solved", VS_VISIBLE },
+{ RET_UNABLE_TO_SOLVE_QP, "Problems occured while solving QP", VS_VISIBLE },
+{ RET_INITIALISATION_STARTED, "Starting problem initialisation...", VS_VISIBLE },
+{ RET_HOTSTART_FAILED, "Unable to perform homotopy due to internal error", VS_VISIBLE },
+{ RET_HOTSTART_FAILED_TO_INIT, "Unable to initialise problem", VS_VISIBLE },
+{ RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED, "Unable to perform homotopy as previous QP is not solved", VS_VISIBLE },
+{ RET_ITERATION_STARTED, "Iteration", VS_VISIBLE },
+{ RET_SHIFT_DETERMINATION_FAILED, "Determination of shift of the QP data failed", VS_VISIBLE },
+{ RET_STEPDIRECTION_DETERMINATION_FAILED, "Determination of step direction failed", VS_VISIBLE },
+{ RET_STEPLENGTH_DETERMINATION_FAILED, "Determination of step direction failed", VS_VISIBLE },
+{ RET_OPTIMAL_SOLUTION_FOUND, "Optimal solution of neighbouring QP found", VS_VISIBLE },
+{ RET_HOMOTOPY_STEP_FAILED, "Unable to perform homotopy step", VS_VISIBLE },
+{ RET_HOTSTART_STOPPED_INFEASIBILITY, "Premature homotopy termination because QP is infeasible", VS_VISIBLE },
+{ RET_HOTSTART_STOPPED_UNBOUNDEDNESS, "Premature homotopy termination because QP is unbounded", VS_VISIBLE },
+{ RET_WORKINGSET_UPDATE_FAILED, "Unable to update working sets according to initial guesses", VS_VISIBLE },
+{ RET_MAX_NWSR_REACHED, "Maximum number of working set recalculations performed", VS_VISIBLE },
+{ RET_CONSTRAINTS_NOT_SPECIFIED, "Problem does comprise constraints! You have to specify new constraints' bounds", VS_VISIBLE },
+{ RET_INVALID_FACTORISATION_FLAG, "Invalid factorisation flag", VS_VISIBLE },
+{ RET_UNABLE_TO_SAVE_QPDATA, "Unable to save QP data", VS_VISIBLE },
+{ RET_STEPDIRECTION_FAILED_TQ, "Abnormal termination due to TQ factorisation", VS_VISIBLE },
+{ RET_STEPDIRECTION_FAILED_CHOLESKY, "Abnormal termination due to Cholesky factorisation", VS_VISIBLE },
+{ RET_CYCLING_DETECTED, "Cycling detected", VS_VISIBLE },
+{ RET_CYCLING_NOT_RESOLVED, "Cycling cannot be resolved, QP is probably infeasible", VS_VISIBLE },
+{ RET_CYCLING_RESOLVED, "Cycling probably resolved", VS_VISIBLE },
+{ RET_STEPSIZE, "", VS_VISIBLE },
+{ RET_STEPSIZE_NONPOSITIVE, "", VS_VISIBLE },
+{ RET_SETUPSUBJECTTOTYPE_FAILED, "Setup of SubjectToTypes failed", VS_VISIBLE },
+{ RET_ADDCONSTRAINT_FAILED, "Addition of constraint to working set failed", VS_VISIBLE },
+{ RET_ADDCONSTRAINT_FAILED_INFEASIBILITY, "Addition of constraint to working set failed", VS_VISIBLE },
+{ RET_ADDBOUND_FAILED, "Addition of bound to working set failed", VS_VISIBLE },
+{ RET_ADDBOUND_FAILED_INFEASIBILITY, "Addition of bound to working set failed", VS_VISIBLE },
+{ RET_REMOVECONSTRAINT_FAILED, "Removal of constraint from working set failed", VS_VISIBLE },
+{ RET_REMOVEBOUND_FAILED, "Removal of bound from working set failed", VS_VISIBLE },
+{ RET_REMOVE_FROM_ACTIVESET, "Removing from active set:", VS_VISIBLE },
+{ RET_ADD_TO_ACTIVESET, "Adding to active set:", VS_VISIBLE },
+{ RET_REMOVE_FROM_ACTIVESET_FAILED, "Removing from active set failed", VS_VISIBLE },
+{ RET_ADD_TO_ACTIVESET_FAILED, "Adding to active set failed", VS_VISIBLE },
+{ RET_CONSTRAINT_ALREADY_ACTIVE, "Constraint is already active", VS_VISIBLE },
+{ RET_ALL_CONSTRAINTS_ACTIVE, "All constraints are active, no further constraint can be added", VS_VISIBLE },
+{ RET_LINEARLY_DEPENDENT, "New bound/constraint is linearly dependent", VS_VISIBLE },
+{ RET_LINEARLY_INDEPENDENT, "New bound/constraint is linearly independent", VS_VISIBLE },
+{ RET_LI_RESOLVED, "Linear independence of active contraint matrix successfully resolved", VS_VISIBLE },
+{ RET_ENSURELI_FAILED, "Failed to ensure linear indepence of active contraint matrix", VS_VISIBLE },
+{ RET_ENSURELI_FAILED_TQ, "Abnormal termination due to TQ factorisation", VS_VISIBLE },
+{ RET_ENSURELI_FAILED_NOINDEX, "No index found, QP is probably infeasible", VS_VISIBLE },
+{ RET_ENSURELI_FAILED_CYCLING, "Cycling detected, QP is probably infeasible", VS_VISIBLE },
+{ RET_BOUND_ALREADY_ACTIVE, "Bound is already active", VS_VISIBLE },
+{ RET_ALL_BOUNDS_ACTIVE, "All bounds are active, no further bound can be added", VS_VISIBLE },
+{ RET_CONSTRAINT_NOT_ACTIVE, "Constraint is not active", VS_VISIBLE },
+{ RET_BOUND_NOT_ACTIVE, "Bound is not active", VS_VISIBLE },
+{ RET_HESSIAN_NOT_SPD, "Projected Hessian matrix not positive definite", VS_VISIBLE },
+{ RET_MATRIX_SHIFT_FAILED, "Unable to update matrices or to transform vectors", VS_VISIBLE },
+{ RET_MATRIX_FACTORISATION_FAILED, "Unable to calculate new matrix factorisations", VS_VISIBLE },
+{ RET_PRINT_ITERATION_FAILED, "Unable to print information on current iteration", VS_VISIBLE },
+{ RET_NO_GLOBAL_MESSAGE_OUTPUTFILE, "No global message output file initialised", VS_VISIBLE },
+/* Utils */
+{ RET_UNABLE_TO_OPEN_FILE, "Unable to open file", VS_VISIBLE },
+{ RET_UNABLE_TO_WRITE_FILE, "Unable to write into file", VS_VISIBLE },
+{ RET_UNABLE_TO_READ_FILE, "Unable to read from file", VS_VISIBLE },
+{ RET_FILEDATA_INCONSISTENT, "File contains inconsistent data", VS_VISIBLE },
+/* SolutionAnalysis */
+{ RET_NO_SOLUTION, "QP solution does not satisfy KKT optimality conditions", VS_VISIBLE },
+{ RET_INACCURATE_SOLUTION, "KKT optimality conditions not satisfied to sufficient accuracy", VS_VISIBLE },
+{ TERMINAL_LIST_ELEMENT, "", VS_HIDDEN } /* IMPORTANT: Terminal list element! */
+};
+
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+
+/*
+ *	M e s s a g e H a n d l i n g
+ */
+MessageHandling::MessageHandling( ) :	errorVisibility( VS_VISIBLE ),
+										warningVisibility( VS_VISIBLE ),
+										infoVisibility( VS_VISIBLE ),
+										outputFile( myStdout ),
+										errorCount( 0 )
+{
+}
+
+/*
+ *	M e s s a g e H a n d l i n g
+ */
+MessageHandling::MessageHandling( myFILE* _outputFile ) :
+										errorVisibility( VS_VISIBLE ),
+										warningVisibility( VS_VISIBLE ),
+										infoVisibility( VS_VISIBLE ),
+										outputFile( _outputFile ),
+										errorCount( 0 )
+{
+}
+
+/*
+ *	M e s s a g e H a n d l i n g
+ */
+MessageHandling::MessageHandling(	VisibilityStatus _errorVisibility,
+									VisibilityStatus _warningVisibility,
+		 							VisibilityStatus _infoVisibility
+									) :
+										errorVisibility( _errorVisibility ),
+										warningVisibility( _warningVisibility ),
+										infoVisibility( _infoVisibility ),
+										outputFile( myStderr ),
+										errorCount( 0 )
+{
+}
+
+/*
+ *	M e s s a g e H a n d l i n g
+ */
+MessageHandling::MessageHandling( 	myFILE* _outputFile,
+									VisibilityStatus _errorVisibility,
+									VisibilityStatus _warningVisibility,
+		 							VisibilityStatus _infoVisibility
+									) :
+										errorVisibility( _errorVisibility ),
+										warningVisibility( _warningVisibility ),
+										infoVisibility( _infoVisibility ),
+										outputFile( _outputFile ),
+										errorCount( 0 )
+{
+}
+
+
+
+/*
+ *	M e s s a g e H a n d l i n g
+ */
+MessageHandling::MessageHandling( const MessageHandling& rhs ) :
+										errorVisibility( rhs.errorVisibility ),
+										warningVisibility( rhs.warningVisibility ),
+										infoVisibility( rhs.infoVisibility ),
+										outputFile( rhs.outputFile ),
+										errorCount( rhs.errorCount )
+{
+}
+
+
+/*
+ *	~ M e s s a g e H a n d l i n g
+ */
+MessageHandling::~MessageHandling( )
+{
+	#ifdef PC_DEBUG
+	if ( outputFile != 0 )
+		fclose( outputFile );
+	#endif
+}
+
+
+/*
+ *	o p e r a t o r =
+ */
+MessageHandling& MessageHandling::operator=( const MessageHandling& rhs )
+{
+	if ( this != &rhs )
+	{
+		errorVisibility = rhs.errorVisibility;
+		warningVisibility = rhs.warningVisibility;
+		infoVisibility = rhs.infoVisibility;
+		outputFile = rhs.outputFile;
+		errorCount = rhs.errorCount;
+	}
+
+	return *this;
+}
+
+
+/*
+ *	t h r o w E r r o r
+ */
+returnValue MessageHandling::throwError(
+	returnValue Enumber,
+	const char* additionaltext,
+	const char* functionname,
+	const char* filename,
+	const unsigned long linenumber,
+	VisibilityStatus localVisibilityStatus
+	)
+{
+	/* consistency check */
+	if ( Enumber <= SUCCESSFUL_RETURN )
+		return throwError( RET_ERROR_UNDEFINED,0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+
+	/* Call to common throwMessage function if error shall be displayed. */
+	if ( errorVisibility == VS_VISIBLE )
+		return throwMessage( Enumber,additionaltext,functionname,filename,linenumber,localVisibilityStatus,"ERROR" );
+	else
+		return Enumber;
+}
+
+
+/*
+ *	t h r o w W a r n i n g
+ */
+returnValue MessageHandling::throwWarning(
+	returnValue Wnumber,
+	const char* additionaltext,
+	const char* functionname,
+	const char* filename,
+	const unsigned long linenumber,
+	VisibilityStatus localVisibilityStatus
+  	)
+{
+	/* consistency check */
+  	if ( Wnumber <= SUCCESSFUL_RETURN )
+		return throwError( RET_WARNING_UNDEFINED,0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+
+	/* Call to common throwMessage function if warning shall be displayed. */
+	if ( warningVisibility == VS_VISIBLE )
+		return throwMessage( Wnumber,additionaltext,functionname,filename,linenumber,localVisibilityStatus,"WARNING" );
+  	else
+  		return Wnumber;
+}
+
+
+/*
+ *	t h r o w I n f o
+ */
+returnValue MessageHandling::throwInfo(
+  	returnValue Inumber,
+	const char* additionaltext,
+  	const char* functionname,
+	const char* filename,
+	const unsigned long linenumber,
+	VisibilityStatus localVisibilityStatus
+ 	)
+{
+	/* consistency check */
+	if ( Inumber < SUCCESSFUL_RETURN )
+		return throwError( RET_INFO_UNDEFINED,0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+
+	/* Call to common throwMessage function if info shall be displayed. */
+	if ( infoVisibility == VS_VISIBLE )
+		return throwMessage( Inumber,additionaltext,functionname,filename,linenumber,localVisibilityStatus,"INFO" );
+	else
+		return Inumber;
+}
+
+
+/*
+ *	r e s e t
+ */
+returnValue MessageHandling::reset( )
+{
+	setErrorVisibilityStatus(   VS_VISIBLE );
+	setWarningVisibilityStatus( VS_VISIBLE );
+	setInfoVisibilityStatus(    VS_VISIBLE );
+
+	setOutputFile( myStderr );
+	setErrorCount( 0 );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	l i s t A l l M e s s a g e s
+ */
+returnValue MessageHandling::listAllMessages( )
+{
+	#ifdef PC_DEBUG
+	int keypos = 0;
+	char myPrintfString[160];
+
+	/* Run through whole returnValueList and print each item. */
+	while ( returnValueList[keypos].key != TERMINAL_LIST_ELEMENT )
+	{
+		sprintf( myPrintfString," %d - %s \n",keypos,returnValueList[keypos].data );
+		myPrintf( myPrintfString );
+
+		++keypos;
+	}
+	#endif
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*****************************************************************************
+ *  P R O T E C T E D                                                        *
+ *****************************************************************************/
+
+
+#ifdef PC_DEBUG  /* Re-define throwMessage function for embedded code! */
+
+/*
+ *	t h r o w M e s s a g e
+ */
+returnValue MessageHandling::throwMessage(
+	returnValue RETnumber,
+	const char* additionaltext,
+	const char* functionname,
+	const char* filename,
+	const unsigned long linenumber,
+	VisibilityStatus localVisibilityStatus,
+	const char* RETstring
+ 	)
+{
+	int i;
+
+	int keypos = 0;
+	char myPrintfString[160];
+
+	/* 1) Determine number of whitespace for output. */
+	char whitespaces[41];
+	int numberOfWhitespaces = (errorCount-1)*2;
+
+	if ( numberOfWhitespaces < 0 )
+		numberOfWhitespaces = 0;
+
+	if ( numberOfWhitespaces > 40 )
+		numberOfWhitespaces = 40;
+
+	for( i=0; i<numberOfWhitespaces; ++i )
+		whitespaces[i] = ' ';
+	whitespaces[numberOfWhitespaces] = '\0';
+
+	/* 2) Find error/warning/info in list. */
+	while ( returnValueList[keypos].key != TERMINAL_LIST_ELEMENT )
+	{
+		if ( returnValueList[keypos].key == RETnumber )
+			break;
+		else
+			++keypos;
+	}
+
+	if ( returnValueList[keypos].key == TERMINAL_LIST_ELEMENT )
+	{
+		throwError( RET_EWI_UNDEFINED,0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		return RETnumber;
+	}
+
+	/* 3) Print error/warning/info. */
+	if ( ( returnValueList[keypos].globalVisibilityStatus == VS_VISIBLE ) && ( localVisibilityStatus == VS_VISIBLE ) )
+	{
+		if ( errorCount > 0 )
+		{
+			sprintf( myPrintfString,"%s->", whitespaces );
+			myPrintf( myPrintfString );
+		}
+
+		if ( additionaltext == 0 )
+		{
+			sprintf(	myPrintfString,"%s (%s, %s:%d): \t%s\n",
+						RETstring,functionname,filename,(int)linenumber,returnValueList[keypos].data
+						);
+			myPrintf( myPrintfString );
+		}
+		else
+		{
+			sprintf(	myPrintfString,"%s (%s, %s:%d): \t%s %s\n",
+						RETstring,functionname,filename,(int)linenumber,returnValueList[keypos].data,additionaltext
+						);
+			myPrintf( myPrintfString );
+		}
+
+		/* take care of proper indention for subsequent error messages */
+		if ( RETstring[0] == 'E' )
+		{
+			++errorCount;
+		}
+		else
+		{
+			if ( errorCount > 0 )
+				myPrintf( "\n" );
+			errorCount = 0;
+		}
+	}
+
+	return RETnumber;
+}
+
+#else  /* = PC_DEBUG not defined */
+
+/*
+ *	t h r o w M e s s a g e
+ */
+returnValue MessageHandling::throwMessage(
+	returnValue RETnumber,
+	const char* additionaltext,
+	const char* functionname,
+	const char* filename,
+	const unsigned long linenumber,
+	VisibilityStatus localVisibilityStatus,
+	const char* RETstring
+ 	)
+{
+	/* DUMMY CODE FOR PRETENDING USE OF ARGUMENTS
+	 * FOR SUPPRESSING COMPILER WARNINGS! */
+	int i = 0;
+	if ( additionaltext == 0 ) i++;
+	if ( functionname == 0 ) i++;
+	if ( filename == 0 ) i++;
+	if ( linenumber == 0 ) i++;
+	if ( localVisibilityStatus == VS_VISIBLE ) i++;
+	if ( RETstring == 0 ) i++;
+	/* END OF DUMMY CODE */
+
+	return RETnumber;
+}
+
+#endif  /* PC_DEBUG */
+
+
+
+/*****************************************************************************
+ *  G L O B A L  M E S S A G E  H A N D L E R                                *
+ *****************************************************************************/
+
+
+/** Global message handler for all qpOASES modules.*/
+MessageHandling globalMessageHandler( myStderr,VS_VISIBLE,VS_VISIBLE,VS_VISIBLE );
+
+
+/*
+ *	g e t G l o b a l M e s s a g e H a n d l e r
+ */
+MessageHandling* getGlobalMessageHandler( )
+{
+	return &globalMessageHandler;
+}
+
+const char* MessageHandling::getErrorString(int error)
+{
+	return returnValueList[ error ].data;
+}
+
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/MessageHandling.ipp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/MessageHandling.ipp
new file mode 100644
index 0000000000000000000000000000000000000000..033957b2842610c3cb1f80364eff9f3db8f7031b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/MessageHandling.ipp
@@ -0,0 +1,137 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/MessageHandling.ipp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of inlined member functions of the MessageHandling class. 
+ */
+
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+ 
+/*
+ *	g e t E r r o r V i s i b i l i t y S t a t u s
+ */
+inline VisibilityStatus MessageHandling::getErrorVisibilityStatus( ) const
+{
+ 	return errorVisibility;
+}
+
+
+/*
+ *	g e t W a r n i n g V i s i b i l i t y S t a t u s
+ */
+inline VisibilityStatus MessageHandling::getWarningVisibilityStatus( ) const
+{
+ 	return warningVisibility;
+}
+
+
+/*
+ *	g e t I n f o V i s i b i l i t y S t a t u s
+ */
+inline VisibilityStatus MessageHandling::getInfoVisibilityStatus( ) const
+{
+ 	return infoVisibility;
+}
+
+
+/*
+ *	g e t O u t p u t F i l e
+ */
+inline myFILE* MessageHandling::getOutputFile( ) const
+{
+ 	return outputFile;
+}
+
+
+/*
+ *	g e t E r r o r C o u n t
+ */
+inline int MessageHandling::getErrorCount( ) const
+{
+ 	return errorCount;
+}
+
+
+/*
+ *	s e t E r r o r V i s i b i l i t y S t a t u s
+ */
+inline void MessageHandling::setErrorVisibilityStatus( VisibilityStatus _errorVisibility ) 
+{
+ 	errorVisibility = _errorVisibility;
+}
+
+
+/*
+ *	s e t W a r n i n g V i s i b i l i t y S t a t u s
+ */
+inline void MessageHandling::setWarningVisibilityStatus( VisibilityStatus _warningVisibility ) 
+{
+ 	warningVisibility = _warningVisibility;
+}
+
+
+/*
+ *	s e t I n f o V i s i b i l i t y S t a t u s
+ */
+inline void MessageHandling::setInfoVisibilityStatus( VisibilityStatus _infoVisibility ) 
+{
+ 	infoVisibility = _infoVisibility;
+}
+
+
+/*
+ *	s e t O u t p u t F i l e
+ */
+inline void MessageHandling::setOutputFile( myFILE* _outputFile ) 
+{
+ 	outputFile = _outputFile;
+}
+
+
+/*
+ *	s e t E r r o r C o u n t
+ */
+inline returnValue MessageHandling::setErrorCount( int _errorCount )
+{
+	if ( _errorCount >= 0 ) 	
+	{
+		errorCount = _errorCount;
+		return SUCCESSFUL_RETURN;
+	}
+	else
+		return RET_INVALID_ARGUMENTS;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblem.cpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblem.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..75e2f324d567c5e466639cf4017cfaf0cd0dfe62
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblem.cpp
@@ -0,0 +1,3867 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/QProblem.cpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of the QProblem class which is able to use the newly
+ *	developed online active set strategy for parametric quadratic programming.
+ */
+
+
+#include <QProblem.hpp>
+
+#include <stdio.h>
+
+void printmatrix2(char *name, double *A, int m, int n) {
+  int i, j;
+
+  printf("%s = [...\n", name);
+  for (i = 0; i < m; i++) {
+    for (j = 0; j < n; j++)
+        printf("  % 9.4f", A[i*n+j]);
+    printf(",\n");
+  }
+  printf("];\n");
+}
+
+//#define __PERFORM_KKT_TEST__
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+
+/*
+ *	Q P r o b l e m
+ */
+QProblem::QProblem( ) : QProblemB( )
+{
+	constraints.init( 0 );
+
+	sizeT = 0;
+
+	cyclingManager.init( 0,0 );
+}
+
+
+/*
+ *	Q P r o b l e m
+ */
+QProblem::QProblem( int _nV, int _nC ) : QProblemB( _nV )
+{
+	/* consistency checks */
+	if ( _nV <= 0 )
+		_nV = 1;
+
+	if ( _nC < 0 )
+	{
+		_nC = 0;
+		THROWERROR( RET_INVALID_ARGUMENTS );
+	}
+
+	constraints.init( _nC );
+
+
+	sizeT = _nC;
+	if ( _nC > _nV )
+		sizeT = _nV;
+
+	cyclingManager.init( _nV,_nC );
+}
+
+
+/*
+ *	Q P r o b l e m
+ */
+QProblem::QProblem( const QProblem& rhs ) :	QProblemB( rhs )
+{
+	int i, j;
+
+	int _nV = rhs.bounds.getNV( );
+	int _nC = rhs.constraints.getNC( );
+
+	for( i=0; i<_nC; ++i )
+		for( j=0; j<_nV; ++j )
+			A[i*NVMAX + j] = rhs.A[i*NVMAX + j];
+
+	for( i=0; i<_nC; ++i )
+		lbA[i] = rhs.lbA[i];
+
+	for( i=0; i<_nC; ++i )
+			ubA[i] = rhs.ubA[i];
+
+	constraints = rhs.constraints;
+
+	for( i=0; i<(_nV+_nC); ++i )
+		y[i] = rhs.y[i];
+
+
+	sizeT = rhs.sizeT;
+
+	for( i=0; i<sizeT; ++i )
+		for( j=0; j<sizeT; ++j )
+			T[i*NVMAX + j] = rhs.T[i*NVMAX + j];
+
+	for( i=0; i<_nV; ++i )
+		for( j=0; j<_nV; ++j )
+			Q[i*NVMAX + j] = rhs.Q[i*NVMAX + j];
+
+	for( i=0; i<_nC; ++i )
+		Ax[i] = rhs.Ax[i];
+
+	cyclingManager = rhs.cyclingManager;
+}
+
+
+/*
+ *	~ Q P r o b l e m
+ */
+QProblem::~QProblem( )
+{
+}
+
+
+/*
+ *	o p e r a t o r =
+ */
+QProblem& QProblem::operator=( const QProblem& rhs )
+{
+	int i, j;
+
+	if ( this != &rhs )
+	{
+		QProblemB::operator=( rhs );
+
+
+		int _nV = rhs.bounds.getNV( );
+		int _nC = rhs.constraints.getNC( );
+
+		for( i=0; i<_nC; ++i )
+			for( j=0; j<_nV; ++j )
+				A[i*NVMAX + j] = rhs.A[i*NVMAX + j];
+
+		for( i=0; i<_nC; ++i )
+			lbA[i] = rhs.lbA[i];
+
+		for( i=0; i<_nC; ++i )
+			ubA[i] = rhs.ubA[i];
+
+		constraints = rhs.constraints;
+
+		for( i=0; i<(_nV+_nC); ++i )
+			y[i] = rhs.y[i];
+
+
+		sizeT = rhs.sizeT;
+
+		for( i=0; i<sizeT; ++i )
+			for( j=0; j<sizeT; ++j )
+				T[i*NVMAX + j] = rhs.T[i*NVMAX + j];
+
+		for( i=0; i<_nV; ++i )
+			for( j=0; j<_nV; ++j )
+				Q[i*NVMAX + j] = rhs.Q[i*NVMAX + j];
+
+		for( i=0; i<_nC; ++i )
+			Ax[i] = rhs.Ax[i];
+
+		cyclingManager = rhs.cyclingManager;
+	}
+
+	return *this;
+}
+
+
+/*
+ *	r e s e t
+ */
+returnValue QProblem::reset( )
+{
+	int i, j;
+	int nV = getNV( );
+	int nC = getNC( );
+
+
+	/* 1) Reset bounds, Cholesky decomposition and status flags. */
+	if ( QProblemB::reset( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_RESET_FAILED );
+
+	/* 2) Reset constraints. */
+	constraints.init( nC );
+
+	/* 3) Reset TQ factorisation. */
+	for( i=0; i<sizeT; ++i )
+		for( j=0; j<sizeT; ++j )
+			T[i*NVMAX + j] = 0.0;
+
+	for( i=0; i<nV; ++i )
+		for( j=0; j<nV; ++j )
+			Q[i*NVMAX + j] = 0.0;
+
+	/* 4) Reset cycling manager. */
+	if ( cyclingManager.clearCyclingData( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_RESET_FAILED );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	i n i t
+ */
+returnValue QProblem::init(	const real_t* const _H, const real_t* const _g, const real_t* const _A,
+							const real_t* const _lb, const real_t* const _ub,
+							const real_t* const _lbA, const real_t* const _ubA,
+							int& nWSR, const real_t* const yOpt, real_t* const cputime
+							)
+{
+	/* 1) Setup QP data. */
+	if (setupQPdata(_H, 0, _g, _A, _lb, _ub, _lbA, _ubA) != SUCCESSFUL_RETURN)
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	/* 2) Call to main initialisation routine (without any additional information). */
+	return solveInitialQP( 0,yOpt,0,0, nWSR,cputime );
+}
+
+returnValue QProblem::init(	const real_t* const _H, const real_t* const _R, const real_t* const _g, const real_t* const _A,
+							const real_t* const _lb, const real_t* const _ub,
+							const real_t* const _lbA, const real_t* const _ubA,
+							int& nWSR, const real_t* const yOpt, real_t* const cputime
+							)
+{
+	/* 1) Setup QP data. */
+	if (setupQPdata(_H, _R, _g, _A, _lb, _ub, _lbA, _ubA) != SUCCESSFUL_RETURN)
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	/* 2) Call to main initialisation routine (without any additional information). */
+	return solveInitialQP( 0,yOpt,0,0, nWSR,cputime );
+}
+
+
+/*
+ *	h o t s t a r t
+ */
+returnValue QProblem::hotstart(	const real_t* const g_new, const real_t* const lb_new, const real_t* const ub_new,
+								const real_t* const lbA_new, const real_t* const ubA_new,
+								int& nWSR, real_t* const cputime
+								)
+{
+	int l;
+
+	/* consistency check */
+	if ( ( getStatus( ) == QPS_NOTINITIALISED )       ||
+		 ( getStatus( ) == QPS_PREPARINGAUXILIARYQP ) ||
+		 ( getStatus( ) == QPS_PERFORMINGHOMOTOPY )   )
+	{
+		return THROWERROR( RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED );
+	}
+
+	/* start runtime measurement */
+	real_t starttime = 0.0;
+	if ( cputime != 0 )
+		starttime = getCPUtime( );
+
+
+	/* I) PREPARATIONS */
+	/* 1) Reset cycling and status flags and increase QP counter. */
+	cyclingManager.clearCyclingData( );
+
+	infeasible = BT_FALSE;
+	unbounded = BT_FALSE;
+
+	++count;
+
+	/* 2) Allocate delta vectors of gradient and (constraints') bounds. */
+	returnValue returnvalue;
+	BooleanType Delta_bC_isZero, Delta_bB_isZero;
+
+	int FR_idx[NVMAX];
+	int FX_idx[NVMAX];
+	int AC_idx[NCMAX_ALLOC];
+	int IAC_idx[NCMAX_ALLOC];
+
+	real_t delta_g[NVMAX];
+	real_t delta_lb[NVMAX];
+	real_t delta_ub[NVMAX];
+	real_t delta_lbA[NCMAX_ALLOC];
+	real_t delta_ubA[NCMAX_ALLOC];
+
+	real_t delta_xFR[NVMAX];
+	real_t delta_xFX[NVMAX];
+	real_t delta_yAC[NCMAX_ALLOC];
+	real_t delta_yFX[NVMAX];
+	real_t delta_Ax[NCMAX_ALLOC];
+
+	int BC_idx;
+	SubjectToStatus BC_status;
+	BooleanType BC_isBound;
+
+	#ifdef PC_DEBUG
+	char messageString[80];
+	#endif
+
+
+	/* II) MAIN HOMOTOPY LOOP */
+	for( l=0; l<nWSR; ++l )
+	{
+		status = QPS_PERFORMINGHOMOTOPY;
+
+		if ( printlevel == PL_HIGH )
+		{
+			#ifdef PC_DEBUG
+			sprintf( messageString,"%d ...",l );
+		  	getGlobalMessageHandler( )->throwInfo( RET_ITERATION_STARTED,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+			#endif
+		}
+
+		/* 1) Setup index arrays. */
+		if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_HOTSTART_FAILED );
+
+		if ( bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_HOTSTART_FAILED );
+
+		if ( constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_HOTSTART_FAILED );
+
+		if ( constraints.getInactive( )->getNumberArray( IAC_idx ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_HOTSTART_FAILED );
+
+		/* 2) Detemination of shift direction of the gradient and the (constraints') bounds. */
+		returnvalue = hotstart_determineDataShift(  FX_idx, AC_idx,
+													g_new,lbA_new,ubA_new,lb_new,ub_new,
+													delta_g,delta_lbA,delta_ubA,delta_lb,delta_ub,
+													Delta_bC_isZero, Delta_bB_isZero );
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			nWSR = l;
+			THROWERROR( RET_SHIFT_DETERMINATION_FAILED );
+			return returnvalue;
+		}
+
+		/* 3) Determination of step direction of X and Y. */
+		returnvalue = hotstart_determineStepDirection(	FR_idx,FX_idx,AC_idx,
+														delta_g,delta_lbA,delta_ubA,delta_lb,delta_ub,
+														Delta_bC_isZero, Delta_bB_isZero,
+														delta_xFX,delta_xFR,delta_yAC,delta_yFX
+														);
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			nWSR = l;
+			THROWERROR( RET_STEPDIRECTION_DETERMINATION_FAILED );
+			return returnvalue;
+		}
+
+		/* 4) Determination of step length TAU. */
+		returnvalue = hotstart_determineStepLength(	FR_idx,FX_idx,AC_idx,IAC_idx,
+													delta_lbA,delta_ubA,delta_lb,delta_ub,
+													delta_xFX,delta_xFR,delta_yAC,delta_yFX,delta_Ax,
+													BC_idx,BC_status,BC_isBound
+													);
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			nWSR = l;
+			THROWERROR( RET_STEPLENGTH_DETERMINATION_FAILED );
+			return returnvalue;
+		}
+
+		/* 5) Realisation of the homotopy step. */
+		returnvalue = hotstart_performStep(	FR_idx,FX_idx,AC_idx,IAC_idx,
+											delta_g,delta_lbA,delta_ubA,delta_lb,delta_ub,
+											delta_xFX,delta_xFR,delta_yAC,delta_yFX,delta_Ax,
+											BC_idx,BC_status,BC_isBound
+											);
+
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			nWSR = l;
+
+			/* stop runtime measurement */
+			if ( cputime != 0 )
+					*cputime = getCPUtime( ) - starttime;
+
+			/* optimal solution found? */
+			if ( returnvalue == RET_OPTIMAL_SOLUTION_FOUND )
+			{
+				status = QPS_SOLVED;
+
+				if ( printlevel == PL_HIGH )
+					THROWINFO( RET_OPTIMAL_SOLUTION_FOUND );
+
+				#ifdef PC_DEBUG
+	 			if ( printIteration( l,BC_idx,BC_status,BC_isBound ) != SUCCESSFUL_RETURN )
+					THROWERROR( RET_PRINT_ITERATION_FAILED ); /* do not pass this as return value! */
+				#endif
+
+				/* check KKT optimality conditions */
+				return checkKKTconditions( );
+			}
+			else
+			{
+				/* checks for infeasibility... */
+				if ( isInfeasible( ) == BT_TRUE )
+				{
+					status = QPS_HOMOTOPYQPSOLVED;
+					return THROWERROR( RET_HOTSTART_STOPPED_INFEASIBILITY );
+				}
+
+				/* ...unboundedness... */
+				if ( unbounded == BT_TRUE ) /* not necessary since objective function convex! */
+					return THROWERROR( RET_HOTSTART_STOPPED_UNBOUNDEDNESS );
+
+				/* ... and throw unspecific error otherwise */
+				THROWERROR( RET_HOMOTOPY_STEP_FAILED );
+				return returnvalue;
+			}
+		}
+
+		/* 6) Output information of successful QP iteration. */
+		status = QPS_HOMOTOPYQPSOLVED;
+
+		#ifdef PC_DEBUG
+		if ( printIteration( l,BC_idx,BC_status,BC_isBound ) != SUCCESSFUL_RETURN )
+			THROWERROR( RET_PRINT_ITERATION_FAILED ); /* do not pass this as return value! */
+		#endif
+	}
+
+
+	/* stop runtime measurement */
+	if ( cputime != 0 )
+		*cputime = getCPUtime( ) - starttime;
+
+
+	/* if programm gets to here, output information that QP could not be solved
+	 * within the given maximum numbers of working set changes */
+	if ( printlevel == PL_HIGH )
+	{
+		#ifdef PC_DEBUG
+		sprintf( messageString,"(nWSR = %d)",nWSR );
+		return getGlobalMessageHandler( )->throwWarning( RET_MAX_NWSR_REACHED,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		#endif
+	}
+
+	/* Finally check KKT optimality conditions. */
+	returnValue returnvalueKKTcheck = checkKKTconditions( );
+
+	if ( returnvalueKKTcheck != SUCCESSFUL_RETURN )
+		return returnvalueKKTcheck;
+	else
+		return RET_MAX_NWSR_REACHED;
+}
+
+
+/*
+ *	g e t N Z
+ */
+int QProblem::getNZ( )
+{
+	/* nZ = nFR - nAC */
+	return bounds.getFree( )->getLength( ) - constraints.getActive( )->getLength( );
+}
+
+
+/*
+ *	g e t D u a l S o l u t i o n
+ */
+returnValue QProblem::getDualSolution( real_t* const yOpt ) const
+{
+	int i;
+
+	/* return optimal dual solution vector
+	 * only if current QP has been solved */
+	if ( ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) ||
+		 ( getStatus( ) == QPS_HOMOTOPYQPSOLVED )  ||
+		 ( getStatus( ) == QPS_SOLVED ) )
+	{
+		for( i=0; i<getNV( )+getNC( ); ++i )
+			yOpt[i] = y[i];
+
+		return SUCCESSFUL_RETURN;
+	}
+	else
+	{
+		return RET_QP_NOT_SOLVED;
+	}
+}
+
+
+
+/*****************************************************************************
+ *  P R O T E C T E D                                                        *
+ *****************************************************************************/
+
+/*
+ *	s e t u p S u b j e c t T o T y p e
+ */
+returnValue QProblem::setupSubjectToType( )
+{
+	int i;
+	int nC = getNC( );
+
+
+	/* I) SETUP SUBJECTTOTYPE FOR BOUNDS */
+	if ( QProblemB::setupSubjectToType( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_SETUPSUBJECTTOTYPE_FAILED );
+
+
+	/* II) SETUP SUBJECTTOTYPE FOR CONSTRAINTS */
+	/* 1) Check if lower constraints' bounds are present. */
+	constraints.setNoLower( BT_TRUE );
+	for( i=0; i<nC; ++i )
+	{
+		if ( lbA[i] > -INFTY )
+		{
+			constraints.setNoLower( BT_FALSE );
+			break;
+		}
+	}
+
+	/* 2) Check if upper constraints' bounds are present. */
+	constraints.setNoUpper( BT_TRUE );
+	for( i=0; i<nC; ++i )
+	{
+		if ( ubA[i] < INFTY )
+		{
+			constraints.setNoUpper( BT_FALSE );
+			break;
+		}
+	}
+
+	/* 3) Determine implicit equality constraints and unbounded constraints. */
+	int nEC = 0;
+	int nUC = 0;
+
+	for( i=0; i<nC; ++i )
+	{
+		if ( ( lbA[i] < -INFTY + BOUNDTOL ) && ( ubA[i] > INFTY - BOUNDTOL ) )
+		{
+			constraints.setType( i,ST_UNBOUNDED );
+			++nUC;
+		}
+		else
+		{
+			if ( lbA[i] > ubA[i] - BOUNDTOL )
+			{
+				constraints.setType( i,ST_EQUALITY );
+				++nEC;
+			}
+			else
+			{
+				constraints.setType( i,ST_BOUNDED );
+			}
+		}
+	}
+
+	/* 4) Set dimensions of constraints structure. */
+	constraints.setNEC( nEC );
+	constraints.setNUC( nUC );
+	constraints.setNIC( nC - nEC - nUC );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	c h o l e s k y D e c o m p o s i t i o n P r o j e c t e d
+ */
+returnValue QProblem::setupCholeskyDecompositionProjected( )
+{
+	int i, j, k, ii, kk;
+	int nV  = getNV( );
+	int nFR = getNFR( );
+	int nZ  = getNZ( );
+
+	/* 1) Initialises R with all zeros. */
+	for( i=0; i<nV; ++i )
+		for( j=0; j<nV; ++j )
+			R[i*NVMAX + j] = 0.0;
+
+	/* 2) Calculate Cholesky decomposition of projected Hessian Z'*H*Z. */
+	if ( hessianType == HST_IDENTITY )
+	{
+		/* if Hessian is identity, so is its Cholesky factor. */
+		for( i=0; i<nV; ++i )
+			R[i*NVMAX + i] = 1.0;
+	}
+	else
+	{
+		if ( nZ > 0 )
+		{
+			int FR_idx[NVMAX];
+			if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_INDEXLIST_CORRUPTED );
+
+#if 0
+			real_t HZ[NVMAX*NVMAX];
+			real_t ZHZ[NVMAX*NVMAX];
+
+			/* calculate H*Z */
+			for ( i=0; i<nFR; ++i )
+			{
+				ii = FR_idx[i];
+
+				for ( j=0; j<nZ; ++j )
+				{
+					real_t sum = 0.0;
+					for ( k=0; k<nFR; ++k )
+					{
+						kk = FR_idx[k];
+						sum += H[ii*NVMAX + kk] * Q[kk*NVMAX + j];
+					}
+					HZ[i * NVMAX + j] = sum;
+				}
+			}
+
+			/* calculate Z'*H*Z */
+			for ( i=0; i<nZ; ++i )
+				for ( j=0; j<nZ; ++j )
+				{
+					real_t sum = 0.0;
+					for ( k=0; k<nFR; ++k )
+					{
+						kk = FR_idx[k];
+						sum += Q[kk*NVMAX + i] * HZ[k*NVMAX + j];
+					}
+					ZHZ[i * NVMAX + j] = sum;
+				}
+
+			/* R'*R = Z'*H*Z */
+			real_t sum, inv;
+
+			for( i=0; i<nZ; ++i )
+			{
+				/* j == i */
+				sum = ZHZ[i*NVMAX + i];
+
+				for( k=(i-1); k>=0; --k )
+					sum -= R[k*NVMAX + i] * R[k*NVMAX + i];
+
+				if ( sum > 0.0 )
+				{
+					R[i*NVMAX + i] = sqrt( sum );
+					inv = 1.0 / R[i * NVMAX + i];
+				}
+				else
+				{
+					hessianType = HST_SEMIDEF;
+					return THROWERROR( RET_HESSIAN_NOT_SPD );
+				}
+
+				for( j=(i+1); j<nZ; ++j )
+				{
+					sum = ZHZ[j*NVMAX + i];
+
+					for( k=(i-1); k>=0; --k )
+						sum -= R[k*NVMAX + i] * R[k*NVMAX + j];
+
+					R[i*NVMAX + j] = sum * inv;
+				}
+			}
+#else
+			real_t HZ[NVMAX];
+			real_t ZHZ[NVMAX];
+
+			real_t sum, inv;
+			for (j = 0; j < nZ; ++j)
+			{
+				/* Cache one column of Z. */
+				for (i = 0; i < NVMAX; ++i)
+					ZHZ[i] = Q[i * NVMAX + j];
+
+				/* Create one column of the product H * Z. */
+				for (i = 0; i < nFR; ++i)
+				{
+					ii = FR_idx[i];
+
+					sum = 0.0;
+					for (k = 0; k < nFR; ++k)
+					{
+						kk = FR_idx[k];
+						sum += H[ii * NVMAX + kk] * ZHZ[kk];
+					}
+					HZ[ii] = sum;
+				}
+
+				/* Create one column of the product Z^T * H * Z. */
+				for (i = j; i < nZ; ++i)
+					ZHZ[ i ] = 0.0;
+
+				for (k = 0; k < nFR; ++k)
+				{
+					kk = FR_idx[k];
+					real_t q = HZ[kk];
+					for (i = j; i < nZ; ++i)
+					{
+						ZHZ[i] += Q[kk * NVMAX + i] * q;
+					}
+				}
+
+				/* Use the computed column to update the factorization. */
+				/* j == i */
+				sum = ZHZ[j];
+
+				for (k = (j - 1); k >= 0; --k)
+					sum -= R[k * NVMAX + j] * R[k * NVMAX + j];
+
+				if (sum > 0.0)
+				{
+					R[j * NVMAX + j] = sqrt(sum);
+					inv = 1.0 / R[j * NVMAX + j];
+				}
+				else
+				{
+					hessianType = HST_SEMIDEF;
+					return THROWERROR( RET_HESSIAN_NOT_SPD );
+				}
+
+				for (i = (j + 1); i < nZ; ++i)
+				{
+					sum = ZHZ[i];
+
+					for (k = (j - 1); k >= 0; --k)
+						sum -= R[k * NVMAX + j] * R[k * NVMAX + i];
+
+					R[j * NVMAX + i] = sum * inv;
+				}
+			}
+#endif
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p T Q f a c t o r i s a t i o n
+ */
+returnValue QProblem::setupTQfactorisation( )
+{
+	int i, j, ii;
+	int nV  = getNV( );
+	int nFR = getNFR( );
+
+	int FR_idx[NVMAX];
+	if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INDEXLIST_CORRUPTED );
+
+	/* 1) Set Q to unity matrix. */
+	for( i=0; i<nV; ++i )
+		for( j=0; j<nV; ++j )
+			Q[i*NVMAX + j] = 0.0;
+
+	for( i=0; i<nFR; ++i )
+	{
+		ii = FR_idx[i];
+		Q[ii*NVMAX + i] = 1.0;
+	}
+
+ 	/* 2) Set T to zero matrix. */
+	for( i=0; i<sizeT; ++i )
+		for( j=0; j<sizeT; ++j )
+			T[i*NVMAX + j] = 0.0;
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s o l v e I n i t i a l Q P
+ */
+returnValue QProblem::solveInitialQP(	const real_t* const xOpt, const real_t* const yOpt,
+										const Bounds* const guessedBounds, const Constraints* const guessedConstraints,
+										int& nWSR, real_t* const cputime
+										)
+{
+	int i;
+
+	/* some definitions */
+	int nV = getNV( );
+	int nC = getNC( );
+
+
+	/* start runtime measurement */
+	real_t starttime = 0.0;
+	if ( cputime != 0 )
+		starttime = getCPUtime( );
+
+
+	status = QPS_NOTINITIALISED;
+
+	/* I) ANALYSE QP DATA: */
+	/* 1) Check if Hessian happens to be the identity matrix. */
+	if ( checkForIdentityHessian( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	/* 2) Setup type of bounds and constraints (i.e. unbounded, implicitly fixed etc.). */
+	if ( setupSubjectToType( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	/* 3) Initialise cycling manager. */
+	cyclingManager.clearCyclingData( );
+
+	status = QPS_PREPARINGAUXILIARYQP;
+
+
+	/* II) SETUP AUXILIARY QP WITH GIVEN OPTIMAL SOLUTION: */
+	/* 1) Setup bounds and constraints data structure. */
+	if ( bounds.setupAllFree( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	if ( constraints.setupAllInactive( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	/* 2) Setup optimal primal/dual solution for auxiliary QP. */
+	if ( setupAuxiliaryQPsolution( xOpt,yOpt ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	/* 3) Obtain linear independent working set for auxiliary QP. */
+
+	static Bounds auxiliaryBounds;
+
+	auxiliaryBounds.init( nV );
+
+	static Constraints auxiliaryConstraints;
+
+	auxiliaryConstraints.init( nC );
+
+	if ( obtainAuxiliaryWorkingSet(	xOpt,yOpt,guessedBounds,guessedConstraints,
+									&auxiliaryBounds,&auxiliaryConstraints ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	/* 4) Setup working set of auxiliary QP and setup matrix factorisations. */
+	if ( setupTQfactorisation( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED_TQ );
+
+	if ( setupAuxiliaryWorkingSet( &auxiliaryBounds,&auxiliaryConstraints,BT_TRUE ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	if ( ( getNAC( ) + getNFX( ) ) == 0 )
+	{
+		/* Factorise full Hessian if no bounds/constraints are active. */
+		if (hasCholesky == BT_FALSE)
+			if ( setupCholeskyDecomposition( ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_INIT_FAILED_CHOLESKY );
+		/* ... else we use user provided Cholesky factorization. At the moment
+		 * we can do that only for cold-started solver. */
+	}
+	else
+	{
+		/* Factorise projected Hessian if there active bounds/constraints. */
+		if ( setupCholeskyDecompositionProjected( ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_INIT_FAILED_CHOLESKY );
+		/* TODO: use user-supplied Hessian decomposition. R_Z = R * Z. */
+	}
+
+	/* 5) Store original QP formulation... */
+	real_t g_original[NVMAX];
+	real_t lb_original[NVMAX];
+	real_t ub_original[NVMAX];
+	real_t lbA_original[NCMAX_ALLOC];
+	real_t ubA_original[NCMAX_ALLOC];
+
+	for( i=0; i<nV; ++i )
+	{
+		g_original[i] = g[i];
+		lb_original[i] = lb[i];
+		ub_original[i] = ub[i];
+	}
+
+	for( i=0; i<nC; ++i )
+	{
+		lbA_original[i] = lbA[i];
+		ubA_original[i] = ubA[i];
+	}
+
+	/* ... and setup QP data of an auxiliary QP having an optimal solution
+	 * as specified by the user (or xOpt = yOpt = 0, by default). */
+	if ( setupAuxiliaryQPgradient( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	if ( setupAuxiliaryQPbounds( &auxiliaryBounds,&auxiliaryConstraints,BT_TRUE ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	status = QPS_AUXILIARYQPSOLVED;
+
+
+	/* III) SOLVE ACTUAL INITIAL QP: */
+	/* Use hotstart method to find the solution of the original initial QP,... */
+	returnValue returnvalue = hotstart( g_original,lb_original,ub_original,lbA_original,ubA_original, nWSR,0 );
+
+
+	/* ... check for infeasibility and unboundedness... */
+	if ( isInfeasible( ) == BT_TRUE )
+		return THROWERROR( RET_INIT_FAILED_INFEASIBILITY );
+
+	if ( isUnbounded( ) == BT_TRUE )
+		return THROWERROR( RET_INIT_FAILED_UNBOUNDEDNESS );
+
+	/* ... and internal errors. */
+	if ( ( returnvalue != SUCCESSFUL_RETURN ) && ( returnvalue != RET_MAX_NWSR_REACHED )  &&
+	     ( returnvalue != RET_INACCURATE_SOLUTION ) && ( returnvalue != RET_NO_SOLUTION ) )
+		return THROWERROR( RET_INIT_FAILED_HOTSTART );
+
+
+	/* stop runtime measurement */
+	if ( cputime != 0 )
+		*cputime = getCPUtime( ) - starttime;
+
+	if ( printlevel == PL_HIGH )
+		THROWINFO( RET_INIT_SUCCESSFUL );
+
+	return returnvalue;
+}
+
+
+/*
+ *	o b t a i n A u x i l i a r y W o r k i n g S e t
+ */
+returnValue QProblem::obtainAuxiliaryWorkingSet(	const real_t* const xOpt, const real_t* const yOpt,
+													const Bounds* const guessedBounds, const Constraints* const guessedConstraints,
+													Bounds* auxiliaryBounds, Constraints* auxiliaryConstraints
+													) const
+{
+	int i = 0;
+	int nV = getNV( );
+	int nC = getNC( );
+
+
+	/* 1) Ensure that desiredBounds is allocated (and different from guessedBounds). */
+	if ( ( auxiliaryBounds == 0 ) || ( auxiliaryBounds == guessedBounds ) )
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	if ( ( auxiliaryConstraints == 0 ) || ( auxiliaryConstraints == guessedConstraints ) )
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+
+	SubjectToStatus guessedStatus;
+
+	/* 2) Setup working set of bounds for auxiliary initial QP. */
+	if ( QProblemB::obtainAuxiliaryWorkingSet( xOpt,yOpt,guessedBounds, auxiliaryBounds ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+
+	/* 3) Setup working set of constraints for auxiliary initial QP. */
+	if ( guessedConstraints != 0 )
+	{
+		/* If an initial working set is specific, use it!
+		 * Moreover, add all equality constraints if specified. */
+		for( i=0; i<nC; ++i )
+		{
+			guessedStatus = guessedConstraints->getStatus( i );
+
+			if ( constraints.getType( i ) == ST_EQUALITY )
+			{
+				if ( auxiliaryConstraints->setupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+			}
+			else
+			{
+				if ( auxiliaryConstraints->setupConstraint( i,guessedStatus ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+			}
+		}
+	}
+	else	/* No initial working set specified. */
+	{
+		/* Obtain initial working set by "clipping". */
+		if ( ( xOpt != 0 ) && ( yOpt == 0 ) )
+		{
+			for( i=0; i<nC; ++i )
+			{
+				if ( Ax[i] <= lbA[i] + BOUNDTOL )
+				{
+					if ( auxiliaryConstraints->setupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+					continue;
+				}
+
+				if ( Ax[i] >= ubA[i] - BOUNDTOL )
+				{
+					if ( auxiliaryConstraints->setupConstraint( i,ST_UPPER ) != SUCCESSFUL_RETURN )
+							return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+					continue;
+				}
+
+				/* Moreover, add all equality constraints if specified. */
+				if ( constraints.getType( i ) == ST_EQUALITY )
+				{
+					if ( auxiliaryConstraints->setupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+				else
+				{
+					if ( auxiliaryConstraints->setupConstraint( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+			}
+		}
+
+		/* Obtain initial working set in accordance to sign of dual solution vector. */
+		if ( ( xOpt == 0 ) && ( yOpt != 0 ) )
+		{
+			for( i=0; i<nC; ++i )
+			{
+				if ( yOpt[nV+i] > ZERO )
+				{
+					if ( auxiliaryConstraints->setupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+					continue;
+				}
+
+				if ( yOpt[nV+i] < -ZERO )
+				{
+					if ( auxiliaryConstraints->setupConstraint( i,ST_UPPER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+					continue;
+				}
+
+				/* Moreover, add all equality constraints if specified. */
+				if ( constraints.getType( i ) == ST_EQUALITY )
+				{
+					if ( auxiliaryConstraints->setupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+				else
+				{
+					if ( auxiliaryConstraints->setupConstraint( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+			}
+		}
+
+		/* If xOpt and yOpt are null pointer and no initial working is specified,
+		 * start with empty working set (or implicitly fixed bounds and equality constraints only)
+		 * for auxiliary QP. */
+		if ( ( xOpt == 0 ) && ( yOpt == 0 ) )
+		{
+			for( i=0; i<nC; ++i )
+			{
+				/* Only add all equality constraints if specified. */
+				if ( constraints.getType( i ) == ST_EQUALITY )
+				{
+					if ( auxiliaryConstraints->setupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+				else
+				{
+					if ( auxiliaryConstraints->setupConstraint( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+			}
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*
+ *	s e t u p A u x i l i a r y W o r k i n g S e t
+ */
+returnValue QProblem::setupAuxiliaryWorkingSet(	const Bounds* const auxiliaryBounds,
+												const Constraints* const auxiliaryConstraints,
+												BooleanType setupAfresh
+												)
+{
+	int i;
+	int nV = getNV( );
+	int nC = getNC( );
+
+	/* consistency checks */
+	if ( auxiliaryBounds != 0 )
+	{
+		for( i=0; i<nV; ++i )
+			if ( ( bounds.getStatus( i ) == ST_UNDEFINED ) || ( auxiliaryBounds->getStatus( i ) == ST_UNDEFINED ) )
+				return THROWERROR( RET_UNKNOWN_BUG );
+	}
+	else
+	{
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+	}
+
+	if ( auxiliaryConstraints != 0 )
+	{
+		for( i=0; i<nC; ++i )
+			if ( ( constraints.getStatus( i ) == ST_UNDEFINED ) || ( auxiliaryConstraints->getStatus( i ) == ST_UNDEFINED ) )
+				return THROWERROR( RET_UNKNOWN_BUG );
+	}
+	else
+	{
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+	}
+
+
+	/* I) SETUP CHOLESKY FLAG:
+	 *    Cholesky decomposition shall only be updated if working set
+	 *    shall be updated (i.e. NOT setup afresh!) */
+	BooleanType updateCholesky;
+	if ( setupAfresh == BT_TRUE )
+		updateCholesky = BT_FALSE;
+	else
+		updateCholesky = BT_TRUE;
+
+
+	/* II) REMOVE FORMERLY ACTIVE (CONSTRAINTS') BOUNDS (IF NECESSARY): */
+	if ( setupAfresh == BT_FALSE )
+	{
+		/* 1) Remove all active constraints that shall be inactive AND
+		*    all active constraints that are active at the wrong bound. */
+		for( i=0; i<nC; ++i )
+		{
+			if ( ( constraints.getStatus( i ) == ST_LOWER ) && ( auxiliaryConstraints->getStatus( i ) != ST_LOWER ) )
+				if ( removeConstraint( i,updateCholesky ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_SETUP_WORKINGSET_FAILED );
+
+			if ( ( constraints.getStatus( i ) == ST_UPPER ) && ( auxiliaryConstraints->getStatus( i ) != ST_UPPER ) )
+				if ( removeConstraint( i,updateCholesky ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_SETUP_WORKINGSET_FAILED );
+		}
+
+		/* 2) Remove all active bounds that shall be inactive AND
+		*    all active bounds that are active at the wrong bound. */
+		for( i=0; i<nV; ++i )
+		{
+			if ( ( bounds.getStatus( i ) == ST_LOWER ) && ( auxiliaryBounds->getStatus( i ) != ST_LOWER ) )
+				if ( removeBound( i,updateCholesky ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_SETUP_WORKINGSET_FAILED );
+
+			if ( ( bounds.getStatus( i ) == ST_UPPER ) && ( auxiliaryBounds->getStatus( i ) != ST_UPPER ) )
+				if ( removeBound( i,updateCholesky ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_SETUP_WORKINGSET_FAILED );
+		}
+	}
+
+
+	/* III) ADD NEWLY ACTIVE (CONSTRAINTS') BOUNDS: */
+	/* 1) Add all inactive bounds that shall be active AND
+	 *    all formerly active bounds that have been active at the wrong bound. */
+	for( i=0; i<nV; ++i )
+	{
+		if ( ( bounds.getStatus( i ) == ST_INACTIVE ) && ( auxiliaryBounds->getStatus( i ) != ST_INACTIVE ) )
+		{
+			/* Add bound only if it is linearly independent from the current working set. */
+			if ( addBound_checkLI( i ) == RET_LINEARLY_INDEPENDENT )
+			{
+				if ( addBound( i,auxiliaryBounds->getStatus( i ),updateCholesky ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_SETUP_WORKINGSET_FAILED );
+			}
+		}
+	}
+
+	/* 2) Add all inactive constraints that shall be active AND
+	 *    all formerly active constraints that have been active at the wrong bound. */
+	for( i=0; i<nC; ++i )
+	{
+		if ( ( auxiliaryConstraints->getStatus( i ) == ST_LOWER ) || ( auxiliaryConstraints->getStatus( i ) == ST_UPPER ) )
+		{
+			/* formerly inactive */
+			if ( constraints.getStatus( i ) == ST_INACTIVE )
+			{
+				/* Add constraint only if it is linearly independent from the current working set. */
+				if ( addConstraint_checkLI( i ) == RET_LINEARLY_INDEPENDENT )
+				{
+					if ( addConstraint( i,auxiliaryConstraints->getStatus( i ),updateCholesky ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_SETUP_WORKINGSET_FAILED );
+				}
+			}
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p A u x i l i a r y Q P s o l u t i o n
+ */
+returnValue QProblem::setupAuxiliaryQPsolution(	const real_t* const xOpt, const real_t* const yOpt
+												)
+{
+	int i, j;
+	int nV = getNV( );
+	int nC = getNC( );
+
+
+	/* Setup primal/dual solution vector for auxiliary initial QP:
+	 * if a null pointer is passed, a zero vector is assigned;
+	 *  old solution vector is kept if pointer to internal solution vevtor is passed. */
+	if ( xOpt != 0 )
+	{
+		if ( xOpt != x )
+			for( i=0; i<nV; ++i )
+				x[i] = xOpt[i];
+
+		for ( j=0; j<nC; ++j )
+		{
+			Ax[j] = 0.0;
+
+			for( i=0; i<nV; ++i )
+				Ax[j] += A[j*NVMAX + i] * x[i];
+		}
+	}
+	else
+	{
+		for( i=0; i<nV; ++i )
+			x[i] = 0.0;
+
+		for ( j=0; j<nC; ++j )
+			Ax[j] = 0.0;
+	}
+
+	if ( yOpt != 0 )
+	{
+		if ( yOpt != y )
+			for( i=0; i<nV+nC; ++i )
+				y[i] = yOpt[i];
+	}
+	else
+	{
+		for( i=0; i<nV+nC; ++i )
+			y[i] = 0.0;
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p A u x i l i a r y Q P g r a d i e n t
+ */
+returnValue QProblem::setupAuxiliaryQPgradient( )
+{
+	int i, j;
+	int nV = getNV( );
+	int nC = getNC( );
+
+
+	/* Setup gradient vector: g = -H*x + [Id A]'*[yB yC]. */
+	for ( i=0; i<nV; ++i )
+	{
+		/* Id'*yB */
+		g[i] = y[i];
+
+		/* A'*yC */
+		for ( j=0; j<nC; ++j )
+			g[i] += A[j*NVMAX + i] * y[nV+j];
+
+		/* -H*x */
+		for ( j=0; j<nV; ++j )
+			g[i] -= H[i*NVMAX + j] * x[j];
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p A u x i l i a r y Q P b o u n d s
+ */
+returnValue QProblem::setupAuxiliaryQPbounds(	const Bounds* const auxiliaryBounds,
+												const Constraints* const auxiliaryConstraints,
+												BooleanType useRelaxation
+												)
+{
+	int i;
+	int nV = getNV( );
+	int nC = getNC( );
+
+
+	/* 1) Setup bound vectors. */
+	for ( i=0; i<nV; ++i )
+	{
+		switch ( bounds.getStatus( i ) )
+		{
+			case ST_INACTIVE:
+				if ( useRelaxation == BT_TRUE )
+				{
+					if ( bounds.getType( i ) == ST_EQUALITY )
+					{
+						lb[i] = x[i];
+						ub[i] = x[i];
+					}
+					else
+					{
+						/* If a bound is inactive although it was supposed to be
+						* active by the auxiliaryBounds, it could not be added
+						* due to linear dependence. Thus set it "strongly inactive". */
+						if ( auxiliaryBounds->getStatus( i ) == ST_LOWER )
+							lb[i] = x[i];
+						else
+							lb[i] = x[i] - BOUNDRELAXATION;
+
+						if ( auxiliaryBounds->getStatus( i ) == ST_UPPER )
+							ub[i] = x[i];
+						else
+							ub[i] = x[i] + BOUNDRELAXATION;
+					}
+				}
+				break;
+
+			case ST_LOWER:
+				lb[i] = x[i];
+				if ( bounds.getType( i ) == ST_EQUALITY )
+				{
+					ub[i] = x[i];
+				}
+				else
+				{
+					if ( useRelaxation == BT_TRUE )
+						ub[i] = x[i] + BOUNDRELAXATION;
+				}
+				break;
+
+			case ST_UPPER:
+				ub[i] = x[i];
+				if ( bounds.getType( i ) == ST_EQUALITY )
+				{
+					lb[i] = x[i];
+				}
+				else
+				{
+					if ( useRelaxation == BT_TRUE )
+						lb[i] = x[i] - BOUNDRELAXATION;
+				}
+				break;
+
+			default:
+				return THROWERROR( RET_UNKNOWN_BUG );
+		}
+	}
+
+	/* 2) Setup constraints vectors. */
+	for ( i=0; i<nC; ++i )
+	{
+		switch ( constraints.getStatus( i ) )
+		{
+			case ST_INACTIVE:
+				if ( useRelaxation == BT_TRUE )
+				{
+					if ( constraints.getType( i ) == ST_EQUALITY )
+					{
+						lbA[i] = Ax[i];
+						ubA[i] = Ax[i];
+					}
+					else
+					{
+						/* If a constraint is inactive although it was supposed to be
+						* active by the auxiliaryConstraints, it could not be added
+						* due to linear dependence. Thus set it "strongly inactive". */
+						if ( auxiliaryConstraints->getStatus( i ) == ST_LOWER )
+							lbA[i] = Ax[i];
+						else
+							lbA[i] = Ax[i] - BOUNDRELAXATION;
+
+						if ( auxiliaryConstraints->getStatus( i ) == ST_UPPER )
+							ubA[i] = Ax[i];
+						else
+							ubA[i] = Ax[i] + BOUNDRELAXATION;
+					}
+				}
+				break;
+
+			case ST_LOWER:
+				lbA[i] = Ax[i];
+				if ( constraints.getType( i ) == ST_EQUALITY )
+				{
+					ubA[i] = Ax[i];
+				}
+				else
+				{
+					if ( useRelaxation == BT_TRUE )
+						ubA[i] = Ax[i] + BOUNDRELAXATION;
+				}
+				break;
+
+			case ST_UPPER:
+				ubA[i] = Ax[i];
+				if ( constraints.getType( i ) == ST_EQUALITY )
+				{
+					lbA[i] = Ax[i];
+				}
+				else
+				{
+					if ( useRelaxation == BT_TRUE )
+						lbA[i] = Ax[i] - BOUNDRELAXATION;
+				}
+				break;
+
+			default:
+				return THROWERROR( RET_UNKNOWN_BUG );
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	a d d C o n s t r a i n t
+ */
+returnValue QProblem::addConstraint(	int number, SubjectToStatus C_status,
+										BooleanType updateCholesky
+										)
+{
+	int i, j, ii;
+
+	/* consistency checks */
+	if ( constraints.getStatus( number ) != ST_INACTIVE )
+		return THROWERROR( RET_CONSTRAINT_ALREADY_ACTIVE );
+
+	if ( ( constraints.getNC( ) - getNAC( ) ) == constraints.getNUC( ) )
+		return THROWERROR( RET_ALL_CONSTRAINTS_ACTIVE );
+
+	if ( ( getStatus( ) == QPS_NOTINITIALISED )    ||
+		 ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) ||
+		 ( getStatus( ) == QPS_HOMOTOPYQPSOLVED )  ||
+		 ( getStatus( ) == QPS_SOLVED )            )
+	{
+		return THROWERROR( RET_UNKNOWN_BUG );
+	}
+
+
+	/* I) ENSURE LINEAR INDEPENDENCE OF THE WORKING SET,
+	 *    i.e. remove a constraint or bound if linear dependence occurs. */
+	/* check for LI only if Cholesky decomposition shall be updated! */
+	if ( updateCholesky == BT_TRUE )
+	{
+		returnValue ensureLIreturnvalue = addConstraint_ensureLI( number,C_status );
+
+		switch ( ensureLIreturnvalue )
+		{
+			case SUCCESSFUL_RETURN:
+				break;
+
+			case RET_LI_RESOLVED:
+				break;
+
+			case RET_ENSURELI_FAILED_NOINDEX:
+				return THROWERROR( RET_ADDCONSTRAINT_FAILED_INFEASIBILITY );
+
+			case RET_ENSURELI_FAILED_CYCLING:
+				return THROWERROR( RET_ADDCONSTRAINT_FAILED_INFEASIBILITY );
+
+			default:
+				return THROWERROR( RET_ENSURELI_FAILED );
+		}
+	}
+
+	/* some definitions */
+	int nFR = getNFR( );
+	int nAC = getNAC( );
+	int nZ  = getNZ( );
+
+	int tcol = sizeT - nAC;
+
+
+	int FR_idx[NVMAX];
+	if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ADDCONSTRAINT_FAILED );
+
+	real_t aFR[NVMAX];
+	real_t wZ[NVMAX];
+	for( i=0; i<nZ; ++i )
+		wZ[i] = 0.0;
+
+
+	/* II) ADD NEW ACTIVE CONSTRAINT TO MATRIX T: */
+	/* 1) Add row [wZ wY] = aFR'*[Z Y] to the end of T: assign aFR. */
+	for( i=0; i<nFR; ++i )
+	{
+		ii = FR_idx[i];
+		aFR[i] = A[number*NVMAX + ii];
+	}
+
+	/* calculate wZ */
+	for( i=0; i<nFR; ++i )
+	{
+		ii = FR_idx[i];
+		for( j=0; j<nZ; ++j )
+			wZ[j] += aFR[i] * Q[ii*NVMAX + j];
+	}
+
+	/* 2) Calculate wY and store it directly into T. */
+	if ( nAC > 0 )
+	{
+		for( j=0; j<nAC; ++j )
+			T[nAC*NVMAX + tcol+j] = 0.0;
+		for( i=0; i<nFR; ++i )
+		{
+			ii = FR_idx[i];
+			for( j=0; j<nAC; ++j )
+				T[nAC*NVMAX + tcol+j] += aFR[i] * Q[ii*NVMAX + nZ+j];
+		}
+	}
+
+
+	real_t c, s;
+
+	if ( nZ > 0 )
+	{
+		/* II) RESTORE TRIANGULAR FORM OF T: */
+		/*     Use column-wise Givens rotations to restore reverse triangular form
+		*      of T, simultanenous change of Q (i.e. Z) and R. */
+		for( j=0; j<nZ-1; ++j )
+		{
+			computeGivens( wZ[j+1],wZ[j], wZ[j+1],wZ[j],c,s );
+
+			for( i=0; i<nFR; ++i )
+			{
+				ii = FR_idx[i];
+				applyGivens( c,s,Q[ii*NVMAX + 1+j],Q[ii*NVMAX + j], Q[ii*NVMAX + 1+j],Q[ii*NVMAX + j] );
+			}
+
+			if ( ( updateCholesky == BT_TRUE ) && ( hessianType != HST_IDENTITY ) )
+			{
+				for( i=0; i<=j+1; ++i )
+					applyGivens( c,s,R[i*NVMAX + 1+j],R[i*NVMAX + j], R[i*NVMAX + 1+j],R[i*NVMAX + j] );
+			}
+		}
+
+		T[nAC*NVMAX + tcol-1] = wZ[nZ-1];
+
+
+		if ( ( updateCholesky == BT_TRUE ) && ( hessianType != HST_IDENTITY ) )
+		{
+			/* III) RESTORE TRIANGULAR FORM OF R:
+			 *      Use row-wise Givens rotations to restore upper triangular form of R. */
+			for( i=0; i<nZ-1; ++i )
+			{
+				computeGivens( R[i*NVMAX + i],R[(1+i)*NVMAX + i], R[i*NVMAX + i],R[(1+i)*NVMAX + i],c,s );
+
+				for( j=(1+i); j<(nZ-1); ++j ) /* last column of R is thrown away */
+					applyGivens( c,s,R[i*NVMAX + j],R[(1+i)*NVMAX + j], R[i*NVMAX + j],R[(1+i)*NVMAX + j] );
+			}
+			/* last column of R is thrown away */
+			for( i=0; i<nZ; ++i )
+				R[i*NVMAX + nZ-1] = 0.0;
+		}
+	}
+
+
+	/* IV) UPDATE INDICES */
+	if ( constraints.moveInactiveToActive( number,C_status ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ADDCONSTRAINT_FAILED );
+
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*
+ *	a d d C o n s t r a i n t _ c h e c k L I
+ */
+returnValue QProblem::addConstraint_checkLI( int number )
+{
+	int i, j, jj;
+	int nFR = getNFR( );
+	int nZ  = getNZ( );
+
+	int FR_idx[NVMAX];
+	if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INDEXLIST_CORRUPTED );
+
+	/* Check if constraint <number> is linearly independent from the
+	   the active ones (<=> is element of null space of Afr). */
+	real_t sum;
+
+	for( i=0; i<nZ; ++i )
+	{
+		sum = 0.0;
+		for( j=0; j<nFR; ++j )
+		{
+			jj = FR_idx[j];
+			sum += Q[jj*NVMAX + i] * A[number*NVMAX + jj];
+		}
+
+		if ( getAbs( sum ) > 10.0*EPS )
+			return RET_LINEARLY_INDEPENDENT;
+	}
+
+	return RET_LINEARLY_DEPENDENT;
+}
+
+
+/*
+ *	a d d C o n s t r a i n t _ e n s u r e L I
+ */
+returnValue QProblem::addConstraint_ensureLI( int number, SubjectToStatus C_status )
+{
+	int i, j, ii, jj;
+	int nV  = getNV( );
+	int nFR = getNFR( );
+	int nFX = getNFX( );
+	int nAC = getNAC( );
+	int nZ  = getNZ( );
+
+
+	/* I) Check if new constraint is linearly independent from the active ones. */
+	returnValue returnvalueCheckLI = addConstraint_checkLI( number );
+
+	if ( returnvalueCheckLI == RET_INDEXLIST_CORRUPTED )
+		return THROWERROR( RET_ENSURELI_FAILED );
+
+	if ( returnvalueCheckLI == RET_LINEARLY_INDEPENDENT )
+		return SUCCESSFUL_RETURN;
+
+
+ 	/* II) NEW CONSTRAINT IS LINEARLY DEPENDENT: */
+	/* 1) Determine coefficients of linear combination,
+	 *    cf. M.J. Best. Applied Mathematics and Parallel Computing, chapter:
+	 *    An Algorithm for the Solution of the Parametric Quadratic Programming
+	 *    Problem, pages 57-76. Physica-Verlag, Heidelberg, 1996. */
+	int FR_idx[NVMAX];
+	if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ENSURELI_FAILED );
+
+	int FX_idx[NVMAX];
+	if ( bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ENSURELI_FAILED );
+
+	real_t xiC[NCMAX_ALLOC];
+	real_t xiC_TMP[NCMAX_ALLOC];
+	real_t xiB[NVMAX];
+
+	/* 2) Calculate xiC */
+	if ( nAC > 0 )
+	{
+		if ( C_status == ST_LOWER )
+		{
+			for( i=0; i<nAC; ++i )
+			{
+				xiC_TMP[i] = 0.0;
+				for( j=0; j<nFR; ++j )
+				{
+					jj = FR_idx[j];
+					xiC_TMP[i] += Q[jj*NVMAX + nZ+i] * A[number*NVMAX + jj];
+				}
+			}
+		}
+		else
+		{
+			for( i=0; i<nAC; ++i )
+			{
+				xiC_TMP[i] = 0.0;
+				for( j=0; j<nFR; ++j )
+				{
+					jj = FR_idx[j];
+					xiC_TMP[i] -= Q[jj*NVMAX + nZ+i] * A[number*NVMAX + jj];
+				}
+			}
+		}
+
+		if ( backsolveT( xiC_TMP, BT_TRUE, xiC ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_ENSURELI_FAILED_TQ );
+	}
+
+	/* 3) Calculate xiB. */
+	int AC_idx[NCMAX_ALLOC];
+	if ( constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ENSURELI_FAILED );
+
+	if ( C_status == ST_LOWER )
+	{
+		for( i=0; i<nFX; ++i )
+		{
+			ii = FX_idx[i];
+			xiB[i] = A[number*NVMAX + ii];
+
+			for( j=0; j<nAC; ++j )
+			{
+				jj = AC_idx[j];
+				xiB[i] -= A[jj*NVMAX + ii] * xiC[j];
+			}
+		}
+	}
+	else
+	{
+		for( i=0; i<nFX; ++i )
+		{
+			ii = FX_idx[i];
+			xiB[i] = -A[number*NVMAX + ii];
+
+			for( j=0; j<nAC; ++j )
+			{
+				jj = AC_idx[j];
+				xiB[i] -= A[jj*NVMAX + ii] * xiC[j];
+			}
+		}
+	}
+
+
+	/* III) DETERMINE CONSTRAINT/BOUND TO BE REMOVED. */
+	real_t y_min = INFTY * INFTY;
+	int y_min_number = -1;
+	BooleanType y_min_isBound = BT_FALSE;
+
+	/* 1) Constraints. */
+	for( i=0; i<nAC; ++i )
+	{
+		ii = AC_idx[i];
+
+		if ( constraints.getStatus( ii ) == ST_LOWER )
+		{
+			if ( ( xiC[i] > ZERO ) && ( y[nV+ii] >= 0.0 ) )
+			{
+				if ( y[nV+ii]/xiC[i] < y_min )
+				{
+					y_min = y[nV+ii]/xiC[i];
+					y_min_number = ii;
+				}
+			}
+		}
+		else
+		{
+			if ( ( xiC[i] < -ZERO ) && ( y[nV+ii] <= 0.0 ) )
+			{
+				if ( y[nV+ii]/xiC[i] < y_min )
+				{
+					y_min = y[nV+ii]/xiC[i];
+					y_min_number = ii;
+				}
+			}
+		}
+	}
+
+	/* 2) Bounds. */
+	for( i=0; i<nFX; ++i )
+	{
+		ii = FX_idx[i];
+
+		if ( bounds.getStatus( ii ) == ST_LOWER )
+		{
+			if ( ( xiB[i] > ZERO ) && ( y[ii] >= 0.0 ) )
+			{
+				if ( y[ii]/xiB[i] < y_min )
+				{
+					y_min = y[ii]/xiB[i];
+					y_min_number = ii;
+					y_min_isBound = BT_TRUE;
+				}
+			}
+		}
+		else
+		{
+			if ( ( xiB[i] < -ZERO ) && ( y[ii] <= 0.0 ) )
+			{
+				if ( y[ii]/xiB[i] < y_min )
+				{
+					y_min = y[ii]/xiB[i];
+					y_min_number = ii;
+					y_min_isBound = BT_TRUE;
+				}
+			}
+		}
+	}
+
+	/* setup output preferences */
+	#ifdef PC_DEBUG
+	char messageString[80];
+	VisibilityStatus visibilityStatus;
+
+	if ( printlevel == PL_HIGH )
+		visibilityStatus = VS_VISIBLE;
+	else
+		visibilityStatus = VS_HIDDEN;
+	#endif
+
+
+	/* IV) REMOVE CONSTRAINT/BOUND FOR RESOLVING LINEAR DEPENDENCE: */
+	if ( y_min_number >= 0 )
+	{
+		/* 1) Check for cycling due to infeasibility. */
+		if ( ( cyclingManager.getCyclingStatus( number,BT_FALSE ) == CYC_PREV_REMOVED ) &&
+			 ( cyclingManager.getCyclingStatus( y_min_number,y_min_isBound ) == CYC_PREV_ADDED ) )
+		{
+			infeasible = BT_TRUE;
+
+			return THROWERROR( RET_ENSURELI_FAILED_CYCLING );
+		}
+		else
+		{
+			/* set cycling data */
+			cyclingManager.clearCyclingData( );
+			cyclingManager.setCyclingStatus( number,BT_FALSE, CYC_PREV_ADDED );
+			cyclingManager.setCyclingStatus( y_min_number,y_min_isBound, CYC_PREV_REMOVED );
+		}
+
+		/* 2) Update Lagrange multiplier... */
+		for( i=0; i<nAC; ++i )
+		{
+			ii = AC_idx[i];
+			y[nV+ii] -= y_min * xiC[i];
+		}
+		for( i=0; i<nFX; ++i )
+		{
+			ii = FX_idx[i];
+			y[ii] -= y_min * xiB[i];
+		}
+
+		/* ... also for newly active constraint... */
+		if ( C_status == ST_LOWER )
+			y[nV+number] = y_min;
+		else
+			y[nV+number] = -y_min;
+
+		/* ... and for constraint to be removed. */
+		if ( y_min_isBound == BT_TRUE )
+		{
+			#ifdef PC_DEBUG
+			sprintf( messageString,"bound no. %d.",y_min_number );
+			getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus );
+			#endif
+
+			if ( removeBound( y_min_number,BT_TRUE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED );
+
+			y[y_min_number] = 0.0;
+		}
+		else
+		{
+			#ifdef PC_DEBUG
+			sprintf( messageString,"constraint no. %d.",y_min_number );
+			getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus );
+			#endif
+
+			if ( removeConstraint( y_min_number,BT_TRUE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED );
+
+			y[nV+y_min_number] = 0.0;
+		}
+	}
+	else
+	{
+		/* no constraint/bound can be removed => QP is infeasible! */
+		infeasible = BT_TRUE;
+
+		return THROWERROR( RET_ENSURELI_FAILED_NOINDEX );
+	}
+
+	return getGlobalMessageHandler( )->throwInfo( RET_LI_RESOLVED,0,__FUNCTION__,__FILE__,__LINE__,VS_HIDDEN );
+}
+
+
+
+/*
+ *	a d d B o u n d
+ */
+returnValue QProblem::addBound(	int number, SubjectToStatus B_status,
+								BooleanType updateCholesky
+								)
+{
+	int i, j, ii;
+
+	/* consistency checks */
+	if ( bounds.getStatus( number ) != ST_INACTIVE )
+		return THROWERROR( RET_BOUND_ALREADY_ACTIVE );
+
+	if ( getNFR( ) == bounds.getNUV( ) )
+		return THROWERROR( RET_ALL_BOUNDS_ACTIVE );
+
+	if ( ( getStatus( ) == QPS_NOTINITIALISED )    ||
+		 ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) ||
+		 ( getStatus( ) == QPS_HOMOTOPYQPSOLVED )  ||
+ 		 ( getStatus( ) == QPS_SOLVED )            )
+	{
+		return THROWERROR( RET_UNKNOWN_BUG );
+	}
+
+
+	/* I) ENSURE LINEAR INDEPENDENCE OF THE WORKING SET,
+	 *    i.e. remove a constraint or bound if linear dependence occurs. */
+	/* check for LI only if Cholesky decomposition shall be updated! */
+	if ( updateCholesky == BT_TRUE )
+	{
+		returnValue ensureLIreturnvalue = addBound_ensureLI( number,B_status );
+
+		switch ( ensureLIreturnvalue )
+		{
+			case SUCCESSFUL_RETURN:
+				break;
+
+			case RET_LI_RESOLVED:
+				break;
+
+			case RET_ENSURELI_FAILED_NOINDEX:
+				return THROWERROR( RET_ADDBOUND_FAILED_INFEASIBILITY );
+
+			case RET_ENSURELI_FAILED_CYCLING:
+				return THROWERROR( RET_ADDBOUND_FAILED_INFEASIBILITY );
+
+			default:
+				return THROWERROR( RET_ENSURELI_FAILED );
+		}
+	}
+
+
+	/* some definitions */
+	int nFR = getNFR( );
+	int nAC = getNAC( );
+	int nZ  = getNZ( );
+
+	int tcol = sizeT - nAC;
+
+
+	/* I) SWAP INDEXLIST OF FREE VARIABLES:
+	 *    move the variable to be fixed to the end of the list of free variables. */
+	int lastfreenumber = bounds.getFree( )->getLastNumber( );
+	if ( lastfreenumber != number )
+		if ( bounds.swapFree( number,lastfreenumber ) != SUCCESSFUL_RETURN )
+			THROWERROR( RET_ADDBOUND_FAILED );
+
+
+	int FR_idx[NVMAX];
+	if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ADDBOUND_FAILED );
+
+	real_t w[NVMAX];
+
+
+	/* II) ADD NEW ACTIVE BOUND TO TOP OF MATRIX T: */
+	/* 1) add row [wZ wY] = [Z Y](number) at the top of T: assign w */
+	for( i=0; i<nFR; ++i )
+		w[i] = Q[FR_idx[nFR-1]*NVMAX + i];
+
+
+	/* 2) Use column-wise Givens rotations to restore reverse triangular form
+	 *    of the first row of T, simultanenous change of Q (i.e. Z) and R. */
+	real_t c, s;
+
+	for( j=0; j<nZ-1; ++j )
+	{
+		computeGivens( w[j+1],w[j], w[j+1],w[j],c,s );
+
+		for( i=0; i<nFR; ++i )
+		{
+			ii = FR_idx[i];
+			applyGivens( c,s,Q[ii*NVMAX + 1+j],Q[ii*NVMAX + j], Q[ii*NVMAX + 1+j],Q[ii*NVMAX + j] );
+		}
+
+		if ( ( updateCholesky == BT_TRUE ) && ( hessianType != HST_IDENTITY ) )
+		{
+			for( i=0; i<=j+1; ++i )
+				applyGivens( c,s,R[i*NVMAX + 1+j],R[i*NVMAX + j], R[i*NVMAX + 1+j],R[i*NVMAX + j] );
+		}
+	}
+
+
+	if ( nAC > 0 )	  /* ( nAC == 0 ) <=> ( nZ == nFR ) <=> Y and T are empty => nothing to do */
+	{
+		/* store new column a in a temporary vector instead of shifting T one column to the left */
+		real_t tmp[NCMAX_ALLOC];
+		for( i=0; i<nAC; ++i )
+			tmp[i] = 0.0;
+
+		{
+			j = nZ-1;
+
+			computeGivens( w[j+1],w[j], w[j+1],w[j],c,s );
+
+			for( i=0; i<nFR; ++i )
+			{
+				ii = FR_idx[i];
+				applyGivens( c,s,Q[ii*NVMAX + 1+j],Q[ii*NVMAX + j], Q[ii*NVMAX + 1+j],Q[ii*NVMAX + j] );
+			}
+
+			applyGivens( c,s,T[(nAC-1)*NVMAX + tcol],tmp[nAC-1], tmp[nAC-1],T[(nAC-1)*NVMAX + tcol] );
+		}
+
+		for( j=nZ; j<nFR-1; ++j )
+		{
+			computeGivens( w[j+1],w[j], w[j+1],w[j],c,s );
+
+			for( i=0; i<nFR; ++i )
+			{
+				ii = FR_idx[i];
+				applyGivens( c,s,Q[ii*NVMAX + 1+j],Q[ii*NVMAX + j], Q[ii*NVMAX + 1+j],Q[ii*NVMAX + j] );
+			}
+
+			for( i=(nFR-2-j); i<nAC; ++i )
+				applyGivens( c,s,T[i*NVMAX + 1+tcol-nZ+j],tmp[i], tmp[i],T[i*NVMAX + 1+tcol-nZ+j] );
+		}
+
+	}
+
+
+	if ( ( updateCholesky == BT_TRUE ) && ( hessianType != HST_IDENTITY ) )
+	{
+		/* III) RESTORE TRIANGULAR FORM OF R:
+		 *      use row-wise Givens rotations to restore upper triangular form of R */
+		for( i=0; i<nZ-1; ++i )
+		{
+			computeGivens( R[i*NVMAX + i],R[(1+i)*NVMAX + i], R[i*NVMAX + i],R[(1+i)*NVMAX + i],c,s );
+
+			for( j=(1+i); j<nZ-1; ++j ) /* last column of R is thrown away */
+				applyGivens( c,s,R[i*NVMAX + j],R[(1+i)*NVMAX + j], R[i*NVMAX + j],R[(1+i)*NVMAX + j] );
+		}
+		/* last column of R is thrown away */
+		for( i=0; i<nZ; ++i )
+			R[i*NVMAX + nZ-1] = 0.0;
+	}
+
+
+	/* IV) UPDATE INDICES */
+	if ( bounds.moveFreeToFixed( number,B_status ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ADDBOUND_FAILED );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	a d d B o u n d _ c h e c k L I
+ */
+returnValue QProblem::addBound_checkLI( int number )
+{
+	int i;
+
+	/* some definitions */
+	int nZ  = getNZ( );
+
+	/* Check if constraint <number> is linearly independent from the
+	   the active ones (<=> is element of null space of Afr). */
+	for( i=0; i<nZ; ++i )
+	{
+		if ( getAbs( Q[number*NVMAX + i] ) > EPS )
+			return RET_LINEARLY_INDEPENDENT;
+	}
+
+	return RET_LINEARLY_DEPENDENT;
+}
+
+
+/*
+ *	a d d B o u n d _ e n s u r e L I
+ */
+returnValue QProblem::addBound_ensureLI( int number, SubjectToStatus B_status )
+{
+	int i, j, ii, jj;
+	int nV  = getNV( );
+	int nFX = getNFX( );
+	int nAC = getNAC( );
+	int nZ  = getNZ( );
+
+
+	/* I) Check if new constraint is linearly independent from the active ones. */
+	returnValue returnvalueCheckLI = addBound_checkLI( number );
+
+	if ( returnvalueCheckLI == RET_LINEARLY_INDEPENDENT )
+		return SUCCESSFUL_RETURN;
+
+
+ 	/* II) NEW BOUND IS LINEARLY DEPENDENT: */
+	/* 1) Determine coefficients of linear combination,
+	 *    cf. M.J. Best. Applied Mathematics and Parallel Computing, chapter:
+	 *    An Algorithm for the Solution of the Parametric Quadratic Programming
+	 *    Problem, pages 57-76. Physica-Verlag, Heidelberg, 1996. */
+	int FR_idx[NVMAX];
+	if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ENSURELI_FAILED );
+
+	int FX_idx[NVMAX];
+	if ( bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ENSURELI_FAILED );
+
+	int AC_idx[NCMAX_ALLOC];
+	if ( constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ENSURELI_FAILED );
+
+	real_t xiC[NCMAX_ALLOC];
+	real_t xiC_TMP[NCMAX_ALLOC];
+	real_t xiB[NVMAX];
+
+	/* 2) Calculate xiC. */
+	if ( nAC > 0 )
+	{
+		if ( B_status == ST_LOWER )
+		{
+			for( i=0; i<nAC; ++i )
+				xiC_TMP[i] = Q[number*NVMAX + nZ+i];
+		}
+		else
+		{
+			for( i=0; i<nAC; ++i )
+				xiC_TMP[i] = -Q[number*NVMAX + nZ+i];
+		}
+
+		if ( backsolveT( xiC_TMP, BT_TRUE, xiC ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_ENSURELI_FAILED_TQ );
+	}
+
+	/* 3) Calculate xiB. */
+	for( i=0; i<nFX; ++i )
+	{
+		ii = FX_idx[i];
+
+		xiB[i] = 0.0;
+		for( j=0; j<nAC; ++j )
+		{
+			jj = AC_idx[j];
+			xiB[i] -= A[jj*NVMAX + ii] * xiC[j];
+		}
+	}
+
+
+	/* III) DETERMINE CONSTRAINT/BOUND TO BE REMOVED. */
+	real_t y_min = INFTY * INFTY;
+	int y_min_number = -1;
+	BooleanType y_min_isBound = BT_FALSE;
+
+	/* 1) Constraints. */
+	for( i=0; i<nAC; ++i )
+	{
+		ii = AC_idx[i];
+
+		if ( constraints.getStatus( ii ) == ST_LOWER )
+		{
+			if ( ( xiC[i] > ZERO ) && ( y[nV+ii] >= 0.0 ) )
+			{
+				if ( y[nV+ii]/xiC[i] < y_min )
+				{
+					y_min = y[nV+ii]/xiC[i];
+					y_min_number = ii;
+				}
+			}
+		}
+		else
+		{
+			if ( ( xiC[i] < -ZERO ) && ( y[nV+ii] <= 0.0 ) )
+			{
+				if ( y[nV+ii]/xiC[i] < y_min )
+				{
+					y_min = y[nV+ii]/xiC[i];
+					y_min_number = ii;
+				}
+			}
+		}
+	}
+
+	/* 2) Bounds. */
+	for( i=0; i<nFX; ++i )
+	{
+		ii = FX_idx[i];
+
+		if ( bounds.getStatus( ii ) == ST_LOWER )
+		{
+			if ( ( xiB[i] > ZERO ) && ( y[ii] >= 0.0 ) )
+			{
+				if ( y[ii]/xiB[i] < y_min )
+				{
+					y_min = y[ii]/xiB[i];
+					y_min_number = ii;
+					y_min_isBound = BT_TRUE;
+				}
+			}
+		}
+		else
+		{
+			if ( ( xiB[i] < -ZERO ) && ( y[ii] <= 0.0 ) )
+			{
+				if ( y[ii]/xiB[i] < y_min )
+				{
+					y_min = y[ii]/xiB[i];
+					y_min_number = ii;
+					y_min_isBound = BT_TRUE;
+				}
+			}
+		}
+	}
+
+	/* setup output preferences */
+	#ifdef PC_DEBUG
+	char messageString[80];
+	VisibilityStatus visibilityStatus;
+
+	if ( printlevel == PL_HIGH )
+		visibilityStatus = VS_VISIBLE;
+	else
+		visibilityStatus = VS_HIDDEN;
+	#endif
+
+
+	/* IV) REMOVE CONSTRAINT/BOUND FOR RESOLVING LINEAR DEPENDENCE: */
+	if ( y_min_number >= 0 )
+	{
+		/* 1) Check for cycling due to infeasibility. */
+		if ( ( cyclingManager.getCyclingStatus( number,BT_TRUE ) == CYC_PREV_REMOVED ) &&
+			 ( cyclingManager.getCyclingStatus( y_min_number,y_min_isBound ) == CYC_PREV_ADDED ) )
+		{
+			infeasible = BT_TRUE;
+
+			return THROWERROR( RET_ENSURELI_FAILED_CYCLING );
+		}
+		else
+		{
+			/* set cycling data */
+			cyclingManager.clearCyclingData( );
+			cyclingManager.setCyclingStatus( number,BT_TRUE, CYC_PREV_ADDED );
+			cyclingManager.setCyclingStatus( y_min_number,y_min_isBound, CYC_PREV_REMOVED );
+		}
+
+
+		/* 2) Update Lagrange multiplier... */
+		for( i=0; i<nAC; ++i )
+		{
+			ii = AC_idx[i];
+			y[nV+ii] -= y_min * xiC[i];
+		}
+		for( i=0; i<nFX; ++i )
+		{
+			ii = FX_idx[i];
+			y[ii] -= y_min * xiB[i];
+		}
+
+		/* ... also for newly active bound ... */
+		if ( B_status == ST_LOWER )
+			y[number] = y_min;
+		else
+			y[number] = -y_min;
+
+		/* ... and for bound to be removed. */
+		if ( y_min_isBound == BT_TRUE )
+		{
+			#ifdef PC_DEBUG
+			sprintf( messageString,"bound no. %d.",y_min_number );
+			getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus );
+			#endif
+
+			if ( removeBound( y_min_number,BT_TRUE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED );
+
+			y[y_min_number] = 0.0;
+		}
+		else
+		{
+			#ifdef PC_DEBUG
+			sprintf( messageString,"constraint no. %d.",y_min_number );
+			getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus );
+			#endif
+
+			if ( removeConstraint( y_min_number,BT_TRUE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED );
+
+			y[nV+y_min_number] = 0.0;
+		}
+	}
+	else
+	{
+		/* no constraint/bound can be removed => QP is infeasible! */
+		infeasible = BT_TRUE;
+
+		return THROWERROR( RET_ENSURELI_FAILED_NOINDEX );
+	}
+
+	return getGlobalMessageHandler( )->throwInfo( RET_LI_RESOLVED,0,__FUNCTION__,__FILE__,__LINE__,VS_HIDDEN );
+}
+
+
+
+/*
+ *	r e m o v e C o n s t r a i n t
+ */
+returnValue QProblem::removeConstraint(	int number,
+										BooleanType updateCholesky
+										)
+{
+	int i, j, ii, jj;
+
+	/* consistency check */
+	if ( ( getStatus( ) == QPS_NOTINITIALISED )    ||
+		 ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) ||
+		 ( getStatus( ) == QPS_HOMOTOPYQPSOLVED )  ||
+ 		 ( getStatus( ) == QPS_SOLVED )            )
+	{
+		return THROWERROR( RET_UNKNOWN_BUG );
+	}
+
+	/* some definitions */
+	int nFR = getNFR( );
+	int nAC = getNAC( );
+	int nZ  = getNZ( );
+
+	int tcol = sizeT - nAC;
+	int number_idx = constraints.getActive( )->getIndex( number );
+
+
+	/* consistency checks */
+	if ( constraints.getStatus( number ) == ST_INACTIVE )
+		return THROWERROR( RET_CONSTRAINT_NOT_ACTIVE );
+
+	if ( ( number_idx < 0 ) || ( number_idx >= nAC ) )
+		return THROWERROR( RET_CONSTRAINT_NOT_ACTIVE );
+
+
+	int FR_idx[NVMAX];
+	if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_REMOVECONSTRAINT_FAILED );
+
+
+	/* I) REMOVE <number>th ROW FROM T,
+	 *    i.e. shift rows number+1 through nAC  upwards (instead of the actual
+	 *    constraint number its corresponding index within matrix A is used). */
+	if ( number_idx < nAC-1 )
+	{
+		for( i=(number_idx+1); i<nAC; ++i )
+			for( j=(nAC-i-1); j<nAC; ++j )
+				T[(i-1)*NVMAX + tcol+j] = T[i*NVMAX + tcol+j];
+		/* gimmick: write zeros into the last row of T */
+		for( j=0; j<nAC; ++j )
+			T[(nAC-1)*NVMAX + tcol+j] = 0.0;
+
+
+		/* II) RESTORE TRIANGULAR FORM OF T,
+		 *     use column-wise Givens rotations to restore reverse triangular form
+		 *     of T simultanenous change of Q (i.e. Y). */
+		real_t c, s;
+
+		for( j=(nAC-2-number_idx); j>=0; --j )
+		{
+			computeGivens( T[(nAC-2-j)*NVMAX + tcol+1+j],T[(nAC-2-j)*NVMAX + tcol+j], T[(nAC-2-j)*NVMAX + tcol+1+j],T[(nAC-2-j)*NVMAX + tcol+j],c,s );
+
+			for( i=(nAC-j-1); i<(nAC-1); ++i )
+				applyGivens( c,s,T[i*NVMAX + tcol+1+j],T[i*NVMAX + tcol+j], T[i*NVMAX + tcol+1+j],T[i*NVMAX + tcol+j] );
+
+			for( i=0; i<nFR; ++i )
+			{
+				ii = FR_idx[i];
+				applyGivens( c,s,Q[ii*NVMAX + nZ+1+j],Q[ii*NVMAX + nZ+j], Q[ii*NVMAX + nZ+1+j],Q[ii*NVMAX + nZ+j] );
+			}
+		}
+	}
+	else
+	{
+		/* gimmick: write zeros into the last row of T */
+		for( j=0; j<nAC; ++j )
+			T[(nAC-1)*NVMAX + tcol+j] = 0.0;
+	}
+
+
+	if ( ( updateCholesky == BT_TRUE ) && ( hessianType != HST_IDENTITY ) )
+	{
+		/* III) UPDATE CHOLESKY DECOMPOSITION,
+		 *      calculate new additional column (i.e. [r sqrt(rho2)]')
+		 *      of the Cholesky factor R. */
+		real_t Hz[NVMAX];
+		for ( i=0; i<nFR; ++i )
+			Hz[i] = 0.0;
+		real_t rho2 = 0.0;
+
+		/* 1) Calculate Hz = H*z, where z is the new rightmost column of Z
+		 *    (i.e. the old leftmost column of Y).  */
+		for( j=0; j<nFR; ++j )
+		{
+			jj = FR_idx[j];
+			for( i=0; i<nFR; ++i )
+				Hz[i] += H[jj*NVMAX + FR_idx[i]] * Q[jj*NVMAX + nZ];
+		}
+
+		if ( nZ > 0 )
+		{
+			real_t ZHz[NVMAX];
+			for ( i=0; i<nZ; ++i )
+				ZHz[i] = 0.0;
+			real_t r[NVMAX];
+
+			/* 2) Calculate ZHz = Z'*Hz (old Z). */
+			for( j=0; j<nFR; ++j )
+			{
+				jj = FR_idx[j];
+
+				for( i=0; i<nZ; ++i )
+					ZHz[i] += Q[jj*NVMAX + i] * Hz[j];
+			}
+
+			/* 3) Calculate r = R^-T * ZHz. */
+			if ( backsolveR( ZHz,BT_TRUE,r ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_REMOVECONSTRAINT_FAILED );
+
+			/* 4) Calculate rho2 = rho^2 = z'*Hz - r'*r
+			 *    and store r into R. */
+			for( i=0; i<nZ; ++i )
+			{
+				rho2 -= r[i]*r[i];
+				R[i*NVMAX + nZ] = r[i];
+			}
+		}
+
+		for( j=0; j<nFR; ++j )
+			rho2 += Q[FR_idx[j]*NVMAX + nZ] * Hz[j];
+
+		/* 5) Store rho into R. */
+		if ( rho2 > 0.0 )
+			R[nZ*NVMAX + nZ] = sqrt( rho2 );
+		else
+		{
+			hessianType = HST_SEMIDEF;
+			return THROWERROR( RET_HESSIAN_NOT_SPD );
+		}
+	}
+
+	/* IV) UPDATE INDICES */
+	if ( constraints.moveActiveToInactive( number ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_REMOVECONSTRAINT_FAILED );
+
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	r e m o v e B o u n d
+ */
+returnValue QProblem::removeBound(	int number,
+									BooleanType updateCholesky
+									)
+{
+	int i, j, ii, jj;
+
+	/* consistency checks */
+	if ( bounds.getStatus( number ) == ST_INACTIVE )
+		return THROWERROR( RET_BOUND_NOT_ACTIVE );
+
+	if ( ( getStatus( ) == QPS_NOTINITIALISED )    ||
+		 ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) ||
+		 ( getStatus( ) == QPS_HOMOTOPYQPSOLVED )  ||
+ 		 ( getStatus( ) == QPS_SOLVED )            )
+	{
+		return THROWERROR( RET_UNKNOWN_BUG );
+	}
+
+	/* some definitions */
+	int nFR = getNFR( );
+	int nAC = getNAC( );
+	int nZ  = getNZ( );
+
+	int tcol = sizeT - nAC;
+
+
+	/* I) UPDATE INDICES */
+	if ( bounds.moveFixedToFree( number ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_REMOVEBOUND_FAILED );
+
+
+	int FR_idx[NVMAX];
+	if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_REMOVEBOUND_FAILED );
+
+	/* I) APPEND <nFR+1>th UNITY VECOTR TO Q. */
+	int nnFRp1 = FR_idx[nFR];
+	for( i=0; i<nFR; ++i )
+	{
+		ii = FR_idx[i];
+		Q[ii*NVMAX + nFR] = 0.0;
+		Q[nnFRp1*NVMAX + i] = 0.0;
+	}
+	Q[nnFRp1*NVMAX + nFR] = 1.0;
+
+	if ( nAC > 0 )
+	{
+		/* store new column a in a temporary vector instead of shifting T one column to the left and appending a */
+		int AC_idx[NCMAX_ALLOC];
+		if ( constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_REMOVEBOUND_FAILED );
+
+		real_t tmp[NCMAX_ALLOC];
+		for( i=0; i<nAC; ++i )
+		{
+			ii = AC_idx[i];
+			tmp[i] =  A[ii*NVMAX + number];
+		}
+
+
+		/* II) RESTORE TRIANGULAR FORM OF T,
+		 *     use column-wise Givens rotations to restore reverse triangular form
+		 *     of T = [T A(:,number)], simultanenous change of Q (i.e. Y and Z). */
+		real_t c, s;
+
+		for( j=(nAC-1); j>=0; --j )
+		{
+			computeGivens( tmp[nAC-1-j],T[(nAC-1-j)*NVMAX + tcol+j],T[(nAC-1-j)*NVMAX + tcol+j],tmp[nAC-1-j],c,s );
+
+			for( i=(nAC-j); i<nAC; ++i )
+				applyGivens( c,s,tmp[i],T[i*NVMAX + tcol+j],T[i*NVMAX + tcol+j],tmp[i] );
+
+			for( i=0; i<=nFR; ++i )
+			{
+				ii = FR_idx[i];
+				/* nZ+1+nAC = nFR+1  /  nZ+(1) = nZ+1 */
+				applyGivens( c,s,Q[ii*NVMAX + nZ+1+j],Q[ii*NVMAX + nZ+j],Q[ii*NVMAX + nZ+1+j],Q[ii*NVMAX + nZ+j] );
+			}
+		}
+	}
+
+
+	if ( ( updateCholesky == BT_TRUE ) && ( hessianType != HST_IDENTITY ) )
+	{
+		/* III) UPDATE CHOLESKY DECOMPOSITION,
+		 *      calculate new additional column (i.e. [r sqrt(rho2)]')
+		 *      of the Cholesky factor R: */
+		real_t z2 = Q[nnFRp1*NVMAX + nZ];
+		real_t rho2 = H[nnFRp1*NVMAX + nnFRp1]*z2*z2; /* rho2 = h2*z2*z2 */
+
+		if ( nFR > 0 )
+		{
+			real_t Hz[NVMAX];
+			for( i=0; i<nFR; ++i )
+				Hz[i] = 0.0;
+			/* 1) Calculate R'*r = Zfr'*Hfr*z1 + z2*Zfr'*h1 =: Zfr'*Hz + z2*Zfr'*h1 =: rhs and
+			 *    rho2 = z1'*Hfr*z1 + 2*z2*h1'*z1 + h2*z2^2 - r'*r =: z1'*Hz + 2*z2*h1'*z1 + h2*z2^2 - r'r */
+			for( j=0; j<nFR; ++j )
+			{
+				jj = FR_idx[j];
+				for( i=0; i<nFR; ++i )
+				{
+					ii = FR_idx[i];
+					/*			   H * z1 */
+					Hz[i] += H[jj*NVMAX + ii] * Q[jj*NVMAX + nZ];
+				}
+			}
+
+			if ( nZ > 0 )
+			{
+				real_t r[NVMAX];
+				real_t rhs[NVMAX];
+				for( i=0; i<nZ; ++i )
+					rhs[i] = 0.0;
+
+				/* 2) Calculate rhs. */
+				for( j=0; j<nFR; ++j )
+				{
+					jj = FR_idx[j];
+					for( i=0; i<nZ; ++i )
+										/* Zfr' * ( Hz + z2*h1 ) */
+						rhs[i] += Q[jj*NVMAX + i] * ( Hz[j] + z2 * H[nnFRp1*NVMAX + jj] );
+				}
+
+				/* 3) Calculate r = R^-T * rhs. */
+				if ( backsolveR( rhs,BT_TRUE,BT_TRUE,r ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_REMOVEBOUND_FAILED );
+
+				/* 4) Calculate rho2 = rho^2 = z'*Hz - r'*r
+				 *    and store r into R. */
+				for( i=0; i<nZ; ++i )
+				{
+					rho2 -= r[i]*r[i];
+					R[i*NVMAX + nZ] = r[i];
+				}
+			}
+
+			for( j=0; j<nFR; ++j )
+			{
+				jj = FR_idx[j];
+							/* z1' * ( Hz + 2*z2*h1 ) */
+				rho2 += Q[jj*NVMAX + nZ] * ( Hz[j] + 2.0*z2*H[nnFRp1*NVMAX + jj] );
+			}
+		}
+
+
+		/* 5) Store rho into R. */
+		if ( rho2 > 0.0 )
+			R[nZ*NVMAX + nZ] = sqrt( rho2 );
+		else
+		{
+			hessianType = HST_SEMIDEF;
+			return THROWERROR( RET_HESSIAN_NOT_SPD );
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	b a c k s o l v e R  (CODE DUPLICATE OF QProblemB CLASS!!!)
+ */
+returnValue QProblem::backsolveR(	const real_t* const b, BooleanType transposed,
+									real_t* const a
+									)
+{
+	/* Call standard backsolve procedure (i.e. removingBound == BT_FALSE). */
+	return backsolveR( b,transposed,BT_FALSE,a );
+}
+
+
+/*
+ *	b a c k s o l v e R  (CODE DUPLICATE OF QProblemB CLASS!!!)
+ */
+returnValue QProblem::backsolveR(	const real_t* const b, BooleanType transposed,
+									BooleanType removingBound,
+									real_t* const a
+									)
+{
+	int i, j;
+	int nR = getNZ( );
+
+	real_t sum;
+
+	/* if backsolve is called while removing a bound, reduce nZ by one. */
+	if ( removingBound == BT_TRUE )
+		--nR;
+
+	/* nothing to do */
+	if ( nR <= 0 )
+		return SUCCESSFUL_RETURN;
+
+
+	/* Solve Ra = b, where R might be transposed. */
+	if ( transposed == BT_FALSE )
+	{
+		/* solve Ra = b */
+		for( i=(nR-1); i>=0; --i )
+		{
+			sum = b[i];
+			for( j=(i+1); j<nR; ++j )
+				sum -= R[i*NVMAX + j] * a[j];
+
+			if ( getAbs( R[i*NVMAX + i] ) > ZERO )
+				a[i] = sum / R[i*NVMAX + i];
+			else
+				return THROWERROR( RET_DIV_BY_ZERO );
+		}
+	}
+	else
+	{
+		/* solve R^T*a = b */
+		for( i=0; i<nR; ++i )
+		{
+			sum = b[i];
+
+			for( j=0; j<i; ++j )
+				sum -= R[j*NVMAX + i] * a[j];
+
+			if ( getAbs( R[i*NVMAX + i] ) > ZERO )
+				a[i] = sum / R[i*NVMAX + i];
+			else
+				return THROWERROR( RET_DIV_BY_ZERO );
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*
+ *	b a c k s o l v e T
+ */
+returnValue QProblem::backsolveT( const real_t* const b, BooleanType transposed, real_t* const a )
+{
+	int i, j;
+	int nT = getNAC( );
+	int tcol = sizeT - nT;
+
+	real_t sum;
+
+	/* nothing to do */
+	if ( nT <= 0 )
+		return SUCCESSFUL_RETURN;
+
+
+	/* Solve Ta = b, where T might be transposed. */
+	if ( transposed == BT_FALSE )
+	{
+		/* solve Ta = b */
+		for( i=0; i<nT; ++i )
+		{
+			sum = b[i];
+			for( j=0; j<i; ++j )
+				sum -= T[i*NVMAX + sizeT-1-j] * a[nT-1-j];
+
+			if ( getAbs( T[i*NVMAX + sizeT-1-i] ) > ZERO )
+				a[nT-1-i] = sum / T[i*NVMAX + sizeT-1-i];
+			else
+				return THROWERROR( RET_DIV_BY_ZERO );
+		}
+	}
+	else
+	{
+		/* solve T^T*a = b */
+		for( i=0; i<nT; ++i )
+		{
+			sum = b[i];
+			for( j=0; j<i; ++j )
+				sum -= T[(nT-1-j)*NVMAX + tcol+i] * a[nT-1-j];
+
+			if ( getAbs( T[(nT-1-i)*NVMAX + tcol+i] ) > ZERO )
+				a[nT-1-i] = sum / T[(nT-1-i)*NVMAX + tcol+i];
+			else
+				return THROWERROR( RET_DIV_BY_ZERO );
+		}
+	}
+
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	h o t s t a r t _ d e t e r m i n e D a t a S h i f t
+ */
+returnValue QProblem::hotstart_determineDataShift(  const int* const FX_idx, const int* const AC_idx,
+													const real_t* const g_new, const real_t* const lbA_new, const real_t* const ubA_new,
+													const real_t* const lb_new, const real_t* const ub_new,
+													real_t* const delta_g, real_t* const delta_lbA, real_t* const delta_ubA,
+													real_t* const delta_lb, real_t* const delta_ub,
+													BooleanType& Delta_bC_isZero, BooleanType& Delta_bB_isZero
+													)
+{
+	int i, ii;
+	int nC  = getNC( );
+	int nAC = getNAC( );
+
+
+	/* I) DETERMINE DATA SHIFT FOR BOUNDS */
+	QProblemB::hotstart_determineDataShift( FX_idx,g_new,lb_new,ub_new, delta_g,delta_lb,delta_ub, Delta_bB_isZero );
+
+
+	/* II) DETERMINE DATA SHIFT FOR CONSTRAINTS */
+	/* 1) Calculate shift directions. */
+	for( i=0; i<nC; ++i )
+	{
+		/* if lower constraints' bounds do not exist, shift them to -infinity */
+		if ( lbA_new != 0 )
+			delta_lbA[i] = lbA_new[i] - lbA[i];
+		else
+			delta_lbA[i] = -INFTY - lbA[i];
+	}
+
+	for( i=0; i<nC; ++i )
+	{
+		/* if upper constraints' bounds do not exist, shift them to infinity */
+		if ( ubA_new != 0 )
+			delta_ubA[i] = ubA_new[i] - ubA[i];
+		else
+			delta_ubA[i] = INFTY - ubA[i];
+	}
+
+	/* 2) Determine if active constraints' bounds are to be shifted. */
+	Delta_bC_isZero = BT_TRUE;
+
+	for ( i=0; i<nAC; ++i )
+	{
+		ii = AC_idx[i];
+
+		if ( ( getAbs( delta_lbA[ii] ) > EPS ) || ( getAbs( delta_ubA[ii] ) > EPS ) )
+		{
+			Delta_bC_isZero = BT_FALSE;
+			break;
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	h o t s t a r t _ d e t e r m i n e S t e p D i r e c t i o n
+ */
+returnValue QProblem::hotstart_determineStepDirection(	const int* const FR_idx, const int* const FX_idx, const int* const AC_idx,
+														const real_t* const delta_g, const real_t* const delta_lbA, const real_t* const delta_ubA,
+														const real_t* const delta_lb, const real_t* const delta_ub,
+														BooleanType Delta_bC_isZero, BooleanType Delta_bB_isZero,
+														real_t* const delta_xFX, real_t* const delta_xFR,
+														real_t* const delta_yAC, real_t* const delta_yFX
+														)
+{
+	int i, j, ii, jj;
+	int nFR = getNFR( );
+	int nFX = getNFX( );
+	int nAC = getNAC( );
+	int nZ  = getNZ( );
+
+	/* initialise auxiliary vectors */
+	real_t HMX_delta_xFX[NVMAX];
+	real_t YFR_delta_xFRy[NVMAX];
+	real_t ZFR_delta_xFRz[NVMAX];
+	real_t HFR_YFR_delta_xFRy[NVMAX];
+	for( i=0; i<nFR; ++i )
+	{
+		delta_xFR[i] = 0.0;
+		HMX_delta_xFX[i] = 0.0;
+		YFR_delta_xFRy[i] = 0.0;
+		ZFR_delta_xFRz[i] = 0.0;
+		HFR_YFR_delta_xFRy[i] = 0.0;
+	}
+
+	real_t delta_xFRy[NCMAX_ALLOC];
+	real_t delta_xFRz[NVMAX];
+	for( i=0; i<nZ; ++i )
+		delta_xFRz[i] = 0.0;
+
+
+	/* I) DETERMINE delta_xFX */
+	if ( nFX > 0 )
+	{
+		for( i=0; i<nFX; ++i )
+		{
+			ii = FX_idx[i];
+
+			if ( bounds.getStatus( ii ) == ST_LOWER )
+				delta_xFX[i] = delta_lb[ii];
+			else
+				delta_xFX[i] = delta_ub[ii];
+		}
+	}
+
+	/* II) DETERMINE delta_xFR */
+	if ( nFR > 0 )
+	{
+		/* 1) Determine delta_xFRy. */
+		if ( nAC > 0 )
+		{
+			if ( ( Delta_bC_isZero == BT_TRUE ) && ( Delta_bB_isZero == BT_TRUE ) )
+			{
+				for( i=0; i<nAC; ++i )
+					delta_xFRy[i] = 0.0;
+
+				for( i=0; i<nFR; ++i )
+					delta_xFR[i] = 0.0;
+			}
+			else
+			{
+				/* auxillary variable */
+				real_t delta_xFRy_TMP[NCMAX_ALLOC];
+
+				for( i=0; i<nAC; ++i )
+				{
+					ii = AC_idx[i];
+
+					if ( constraints.getStatus( ii ) == ST_LOWER )
+						delta_xFRy_TMP[i] = delta_lbA[ii];
+					else
+						delta_xFRy_TMP[i] = delta_ubA[ii];
+
+					if ( Delta_bB_isZero == BT_FALSE )
+					{
+						for( j=0; j<nFX; ++j )
+						{
+							jj = FX_idx[j];
+							delta_xFRy_TMP[i] -= A[ii*NVMAX + jj] * delta_xFX[j];
+						}
+					}
+				}
+
+				if ( backsolveT( delta_xFRy_TMP, BT_FALSE, delta_xFRy ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_STEPDIRECTION_FAILED_TQ );
+
+				for( i=0; i<nFR; ++i )
+				{
+					ii = FR_idx[i];
+					for( j=0; j<nAC; ++j )
+						YFR_delta_xFRy[i] += Q[ii*NVMAX + nZ+j] * delta_xFRy[j];
+
+					/* delta_xFR = YFR*delta_xFRy (+ ZFR*delta_xFRz) */
+					delta_xFR[i] = YFR_delta_xFRy[i];
+				}
+			}
+		}
+
+		/* 2) Determine delta_xFRz. */
+		if ( hessianType == HST_IDENTITY )
+		{
+			for( j=0; j<nFR; ++j )
+			{
+				jj = FR_idx[j];
+				for( i=0; i<nZ; ++i )
+					delta_xFRz[i] -= Q[jj*NVMAX + i] * delta_g[jj];
+			}
+
+			if ( nZ > 0 )
+			{
+				for( i=0; i<nFR; ++i )
+				{
+					ii = FR_idx[i];
+					for( j=0; j<nZ; ++j )
+						ZFR_delta_xFRz[i] += Q[ii*NVMAX + j] * delta_xFRz[j];
+
+					delta_xFR[i] += ZFR_delta_xFRz[i];
+				}
+			}
+		}
+		else
+		{
+			if ( Delta_bB_isZero == BT_FALSE )
+			{
+				for( i=0; i<nFR; ++i )
+				{
+					ii = FR_idx[i];
+					for( j=0; j<nFX; ++j )
+					{
+						jj = FX_idx[j];
+						HMX_delta_xFX[i] += H[ii*NVMAX + jj] * delta_xFX[j];
+					}
+				}
+			}
+
+			if ( nAC > 0 )
+			{
+				if ( ( Delta_bC_isZero == BT_FALSE ) || ( Delta_bB_isZero == BT_FALSE ) )
+				{
+					for( i=0; i<nFR; ++i )
+					{
+						ii = FR_idx[i];
+						for( j=0; j<nFR; ++j )
+						{
+							jj = FR_idx[j];
+							HFR_YFR_delta_xFRy[i] += H[ii*NVMAX + jj] * YFR_delta_xFRy[j];
+						}
+					}
+				}
+			}
+
+
+			if ( nZ > 0 )
+			{
+				/* auxiliary variable */
+				real_t delta_xFRz_TMP[NVMAX];
+				real_t delta_xFRz_RHS[NVMAX];
+
+
+				if ( ( nAC > 0 ) && ( nFX > 0 ) && ( Delta_bB_isZero == BT_FALSE ) )
+				{
+					for( j=0; j<nFR; ++j )
+					{
+						jj = FR_idx[j];
+						delta_xFRz_RHS[j] = delta_g[jj] + HFR_YFR_delta_xFRy[j] + HMX_delta_xFX[j];
+					}
+				}
+				else
+				{
+					if ( ( nAC == 0 ) && ( Delta_bB_isZero == BT_TRUE ) )
+					{
+						for( j=0; j<nFR; ++j )
+						{
+							jj = FR_idx[j];
+							delta_xFRz_RHS[j] = delta_g[jj];
+						}
+					}
+					else
+					{
+						if ( nAC > 0 ) /* => Delta_bB_isZero == BT_TRUE, as BT_FALSE would imply nFX>0 */
+						{
+							for( j=0; j<nFR; ++j )
+							{
+								jj = FR_idx[j];
+								delta_xFRz_RHS[j] = delta_g[jj] + HFR_YFR_delta_xFRy[j];
+							}
+						}
+						else /* Delta_bB_isZero == BT_FALSE, as nAC==0 */
+						{
+							for( j=0; j<nFR; ++j )
+							{
+								jj = FR_idx[j];
+								delta_xFRz_RHS[j] = delta_g[jj] + HMX_delta_xFX[j];
+							}
+						}
+					}
+				}
+
+				for( j=0; j<nFR; ++j )
+				{
+					jj = FR_idx[j];
+					for( i=0; i<nZ; ++i )
+						delta_xFRz[i] -= Q[jj*NVMAX + i] * delta_xFRz_RHS[j];
+				}
+
+
+				if ( backsolveR( delta_xFRz,BT_TRUE,delta_xFRz_TMP ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_STEPDIRECTION_FAILED_CHOLESKY );
+
+				if ( backsolveR( delta_xFRz_TMP,BT_FALSE,delta_xFRz ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_STEPDIRECTION_FAILED_CHOLESKY );
+
+
+				for( i=0; i<nFR; ++i )
+				{
+					ii = FR_idx[i];
+					for( j=0; j<nZ; ++j )
+						ZFR_delta_xFRz[i] += Q[ii*NVMAX + j] * delta_xFRz[j];
+
+					delta_xFR[i] += ZFR_delta_xFRz[i];
+				}
+			}
+		}
+	}
+
+	/* III) DETERMINE delta_yAC */
+	if ( nAC > 0 ) /* => ( nFR = nZ + nAC > 0 ) */
+	{
+		/* auxiliary variables */
+		real_t delta_yAC_TMP[NCMAX_ALLOC];
+		for( i=0; i<nAC; ++i )
+			delta_yAC_TMP[i] = 0.0;
+		real_t delta_yAC_RHS[NVMAX];
+		for( i=0; i<nFR; ++i )
+			delta_yAC_RHS[i] = 0.0;
+
+		if ( hessianType == HST_IDENTITY )
+		{
+			/* delta_yAC = (T')^-1 * ( Yfr*delta_gFR + delta_xFRy ) */
+			for( j=0; j<nAC; ++j )
+			{
+				for( i=0; i<nFR; ++i )
+				{
+					ii = FR_idx[i];
+					delta_yAC_TMP[j] += Q[ii*NVMAX + nZ+j] * delta_g[ii];
+				}
+
+				delta_yAC_TMP[j] += delta_xFRy[j];
+			}
+		}
+		else
+		{
+			if ( ( Delta_bC_isZero == BT_TRUE ) && ( Delta_bB_isZero == BT_TRUE ) )
+			{
+				for( i=0; i<nFR; ++i )
+				{
+					ii = FR_idx[i];
+					delta_yAC_RHS[i] = delta_g[ii];
+				}
+			}
+			else
+			{
+				for( i=0; i<nFR; ++i )
+				{
+					ii = FR_idx[i];
+					delta_yAC_RHS[i] = HFR_YFR_delta_xFRy[i] + delta_g[ii];
+				}
+			}
+
+			if ( nZ > 0 )
+			{
+				for( i=0; i<nFR; ++i )
+				{
+					ii = FR_idx[i];
+					for( j=0; j<nFR; ++j )
+					{
+						jj = FR_idx[j];
+						delta_yAC_RHS[i] += H[ii*NVMAX + jj] * ZFR_delta_xFRz[j];
+					}
+				}
+			}
+
+			if ( nFX > 0 )
+			{
+				if ( Delta_bB_isZero == BT_FALSE )
+				{
+					for( i=0; i<nFR; ++i )
+						delta_yAC_RHS[i] += HMX_delta_xFX[i];
+				}
+			}
+
+			for( i=0; i<nAC; ++i)
+			{
+				for( j=0; j<nFR; ++j )
+				{
+					jj = FR_idx[j];
+					delta_yAC_TMP[i] += Q[jj*NVMAX + nZ+i] * delta_yAC_RHS[j];
+				}
+			}
+		}
+
+		if ( backsolveT( delta_yAC_TMP,BT_TRUE,delta_yAC ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_STEPDIRECTION_FAILED_TQ );
+	}
+
+
+	/* IV) DETERMINE delta_yFX */
+	if ( nFX > 0 )
+	{
+		for( i=0; i<nFX; ++i )
+		{
+			ii = FX_idx[i];
+
+			delta_yFX[i] = delta_g[ii];
+
+			for( j=0; j<nAC; ++j )
+			{
+				jj = AC_idx[j];
+				delta_yFX[i] -= A[jj*NVMAX + ii] * delta_yAC[j];
+			}
+
+			if ( hessianType == HST_IDENTITY )
+			{
+				delta_yFX[i] += delta_xFX[i];
+			}
+			else
+			{
+				for( j=0; j<nFR; ++j )
+				{
+					jj = FR_idx[j];
+					delta_yFX[i] += H[ii*NVMAX + jj] * delta_xFR[j];
+				}
+
+				if ( Delta_bB_isZero == BT_FALSE )
+				{
+					for( j=0; j<nFX; ++j )
+					{
+						jj = FX_idx[j];
+						delta_yFX[i] += H[ii*NVMAX + jj] * delta_xFX[j];
+					}
+				}
+			}
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	h o t s t a r t _ d e t e r m i n e S t e p L e n g t h
+ */
+returnValue QProblem::hotstart_determineStepLength(	const int* const FR_idx, const int* const FX_idx, const int* const AC_idx, const int* const IAC_idx,
+													const real_t* const delta_lbA, const real_t* const delta_ubA,
+													const real_t* const delta_lb, const real_t* const delta_ub,
+													const real_t* const delta_xFX, const real_t* const delta_xFR,
+													const real_t* const delta_yAC, const real_t* const delta_yFX,
+													real_t* const delta_Ax, int& BC_idx, SubjectToStatus& BC_status, BooleanType& BC_isBound
+													)
+{
+	int i, j, ii, jj;
+	int nV  = getNV( );
+	int nC  = getNC( );
+	int nFR = getNFR( );
+	int nFX = getNFX( );
+	int nAC = getNAC( );
+	int nIAC = getNIAC( );
+
+	/* initialise maximum steplength array */
+	real_t maxStepLength[2*(NVMAX+NCMAX_ALLOC)];
+	for ( i=0; i<2*(nV+nC); ++i )
+		maxStepLength[i] = 1.0;
+
+
+	/* I) DETERMINE MAXIMUM DUAL STEPLENGTH: */
+	/* 1) Ensure that active dual constraints' bounds remain valid
+	 *    (ignoring inequality constraints).  */
+	for( i=0; i<nAC; ++i )
+	{
+		ii = AC_idx[i];
+
+		if ( constraints.getType( ii ) != ST_EQUALITY )
+		{
+			if ( constraints.getStatus( ii ) == ST_LOWER )
+			{
+				/* active lower constraints' bounds */
+				if ( delta_yAC[i] < -ZERO )
+				{
+					if ( y[nV+ii] > 0.0 )
+						maxStepLength[nV+ii] = y[nV+ii] / ( -delta_yAC[i] );
+					else
+						maxStepLength[nV+ii] = 0.0;
+				}
+			}
+			else
+			{
+				/* active upper constraints' bounds */
+				if ( delta_yAC[i] > ZERO )
+				{
+					if ( y[nV+ii] < 0.0 )
+						maxStepLength[nV+ii] = y[nV+ii] / ( -delta_yAC[i] );
+					else
+						maxStepLength[nV+ii] = 0.0;
+				}
+			}
+		}
+	}
+
+	/* 2) Ensure that active dual bounds remain valid
+	 *    (ignoring implicitly fixed variables). */
+	for( i=0; i<nFX; ++i )
+	{
+		ii = FX_idx[i];
+
+		if ( bounds.getType( ii ) != ST_EQUALITY )
+		{
+			if ( bounds.getStatus( ii ) == ST_LOWER )
+			{
+				/* active lower bounds */
+				if ( delta_yFX[i] < -ZERO )
+				{
+					if ( y[ii] > 0.0 )
+						maxStepLength[ii] = y[ii] / ( -delta_yFX[i] );
+					else
+						maxStepLength[ii] = 0.0;
+				}
+			}
+			else
+			{
+				/* active upper bounds */
+				if ( delta_yFX[i] > ZERO )
+				{
+					if ( y[ii] < 0.0 )
+						maxStepLength[ii] = y[ii] / ( -delta_yFX[i] );
+					else
+						maxStepLength[ii] = 0.0;
+				}
+			}
+		}
+	}
+
+
+	/* II) DETERMINE MAXIMUM PRIMAL STEPLENGTH */
+	/* 1) Ensure that inactive constraints' bounds remain valid
+	 *    (ignoring unbounded constraints). */
+	real_t delta_x[NVMAX];
+	for( j=0; j<nFR; ++j )
+	{
+		jj = FR_idx[j];
+		delta_x[jj] = delta_xFR[j];
+	}
+	for( j=0; j<nFX; ++j )
+	{
+		jj = FX_idx[j];
+		delta_x[jj] = delta_xFX[j];
+	}
+
+	for( i=0; i<nIAC; ++i )
+	{
+		ii = IAC_idx[i];
+
+		if ( constraints.getType( ii ) != ST_UNBOUNDED )
+		{
+			delta_Ax[ii] = 0.0;
+			for( j=0; j<nV; ++j )
+				delta_Ax[ii] += A[ii*NVMAX + j] * delta_x[j]; // POSSIBLE SPEEDUP!
+
+			/* inactive lower constraints' bounds */
+			if ( constraints.isNoLower( ) == BT_FALSE )
+			{
+				if ( delta_lbA[ii] > delta_Ax[ii] )
+				{
+					if ( Ax[ii] > lbA[ii] )
+						maxStepLength[nV+ii] = ( Ax[ii] - lbA[ii] ) / ( delta_lbA[ii] - delta_Ax[ii] );
+					else
+						maxStepLength[nV+ii] = 0.0;
+				}
+			}
+
+			/* inactive upper constraints' bounds */
+			if ( constraints.isNoUpper( ) == BT_FALSE )
+			{
+				if ( delta_ubA[ii] < delta_Ax[ii] )
+				{
+					if ( Ax[ii] < ubA[ii] )
+						maxStepLength[nV+nC+nV+ii] = ( Ax[ii] - ubA[ii] ) / ( delta_ubA[ii] - delta_Ax[ii] );
+					else
+						maxStepLength[nV+nC+nV+ii] = 0.0;
+				}
+			}
+		}
+	}
+
+
+	/* 2) Ensure that inactive bounds remain valid
+	 *    (ignoring unbounded variables). */
+	/* inactive lower bounds */
+	if ( bounds.isNoLower( ) == BT_FALSE )
+	{
+		for( i=0; i<nFR; ++i )
+		{
+			ii = FR_idx[i];
+			if ( bounds.getType( ii ) != ST_UNBOUNDED )
+				if ( delta_lb[ii] > delta_xFR[i] )
+				{
+					if ( x[ii] > lb[ii] )
+						maxStepLength[ii] = ( x[ii] - lb[ii] ) / ( delta_lb[ii] - delta_xFR[i] );
+					else
+						maxStepLength[ii] = 0.0;
+				}
+		}
+	}
+
+	/* inactive upper bounds */
+	if ( bounds.isNoUpper( ) == BT_FALSE )
+	{
+		for( i=0; i<nFR; ++i )
+		{
+			ii = FR_idx[i];
+			if ( bounds.getType( ii ) != ST_UNBOUNDED )
+				if ( delta_ub[ii] < delta_xFR[i] )
+				{
+					if ( x[ii] < ub[ii] )
+						maxStepLength[nV+nC+ii] = ( x[ii] - ub[ii] ) / ( delta_ub[ii] - delta_xFR[i] );
+					else
+						maxStepLength[nV+nC+ii] = 0.0;
+				}
+		}
+	}
+
+
+	/* III) DETERMINE MAXIMUM HOMOTOPY STEPLENGTH */
+	real_t tau_new = 1.0;
+
+	BC_idx = 0;
+	BC_status = ST_UNDEFINED;
+	BC_isBound = BT_FALSE;
+
+	for ( i=0; i<nV; ++i )
+	{
+		/* 1) Consider lower/dual blocking bounds. */
+		if ( maxStepLength[i] < tau_new )
+		{
+			tau_new = maxStepLength[i];
+			BC_idx = i;
+			BC_isBound = BT_TRUE;
+			if ( bounds.getStatus( i ) == ST_INACTIVE ) /* inactive? */
+				BC_status = ST_LOWER;
+			else
+				BC_status = ST_INACTIVE;
+		}
+
+		/* 2) Consider upper blocking bounds. */
+		if ( maxStepLength[nV+nC+i] < tau_new )
+		{
+			tau_new = maxStepLength[nV+nC+i];
+			BC_idx = i;
+			BC_isBound = BT_TRUE;
+			BC_status = ST_UPPER;
+		}
+	}
+
+	for ( i=nV; i<nV+nC; ++i )
+	{
+		/* 3) Consider lower/dual blocking constraints. */
+		if ( maxStepLength[i] < tau_new )
+		{
+			tau_new = maxStepLength[i];
+			BC_idx = i-nV;
+			BC_isBound = BT_FALSE;
+			if ( constraints.getStatus( i-nV ) == ST_INACTIVE ) /* inactive? */
+				BC_status = ST_LOWER;
+			else
+				BC_status = ST_INACTIVE;
+		}
+
+		/* 4) Consider upper blocking constraints. */
+		if ( maxStepLength[nV+nC+i] < tau_new )
+		{
+			tau_new = maxStepLength[nV+nC+i];
+			BC_idx = i-nV;
+			BC_isBound = BT_FALSE;
+			BC_status = ST_UPPER;
+		}
+	}
+
+
+	/* IV) CLEAR CYCLING DATA
+	 *     if a positive step can be taken */
+	if ( tau_new > EPS )
+		cyclingManager.clearCyclingData( );
+
+
+	/* V) SET MAXIMUM HOMOTOPY STEPLENGTH */
+	tau = tau_new;
+
+	#ifdef PC_DEBUG
+	if ( printlevel == PL_HIGH )
+	{
+
+	 	char messageString[80];
+
+		if ( BC_status == ST_UNDEFINED )
+			sprintf( messageString,"Stepsize is %.6e!",tau );
+		else
+			sprintf( messageString,"Stepsize is %.6e! (BC_idx = %d, BC_isBound = %d, BC_status = %d)",tau,BC_idx,BC_isBound,BC_status );
+
+		getGlobalMessageHandler( )->throwInfo( RET_STEPSIZE_NONPOSITIVE,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+	}
+	#endif
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	h o t s t a r t _ p e r f o r m S t e p
+ */
+returnValue QProblem::hotstart_performStep(	const int* const FR_idx, const int* const FX_idx, const int* const AC_idx, const int* const IAC_idx,
+											const real_t* const delta_g, const real_t* const delta_lbA, const real_t* const delta_ubA,
+											const real_t* const delta_lb, const real_t* const delta_ub,
+											const real_t* const delta_xFX, const real_t* const delta_xFR,
+											const real_t* const delta_yAC, const real_t* const delta_yFX,
+											const real_t* const delta_Ax, int BC_idx, SubjectToStatus BC_status, BooleanType BC_isBound
+											)
+{
+	int i, j, ii;
+	int nV  = getNV( );
+	int nC  = getNC( );
+	int nFR = getNFR( );
+	int nFX = getNFX( );
+	int nAC = getNAC( );
+	int nIAC = getNIAC( );
+
+
+	/* I) CHECK (CONSTRAINTS') BOUNDS' CONSISTENCY */
+	if ( areBoundsConsistent( delta_lb,delta_ub,delta_lbA,delta_ubA ) == BT_FALSE )
+	{
+		infeasible = BT_TRUE;
+		tau = 0.0;
+
+		return THROWERROR( RET_QP_INFEASIBLE );
+	}
+
+
+	/* II) GO TO ACTIVE SET CHANGE */
+	if ( tau > ZERO )
+	{
+		/* 1) Perform step in primal und dual space... */
+		for( i=0; i<nFR; ++i )
+		{
+			ii = FR_idx[i];
+			x[ii] += tau*delta_xFR[i];
+		}
+
+		for( i=0; i<nFX; ++i )
+		{
+			ii = FX_idx[i];
+			x[ii] += tau*delta_xFX[i];
+			y[ii] += tau*delta_yFX[i];
+		}
+
+		for( i=0; i<nAC; ++i )
+		{
+			ii = AC_idx[i];
+			y[nV+ii] += tau*delta_yAC[i];
+		}
+
+		/* ... also for Ax. */
+		for( i=0; i<nIAC; ++i )
+		{
+			ii = IAC_idx[i];
+			if ( constraints.getType( ii ) != ST_UNBOUNDED )
+				Ax[ii] += tau*delta_Ax[ii];
+		}
+		for( i=0; i<nAC; ++i )
+		{
+			ii = AC_idx[i];
+
+			Ax[ii] = 0.0;
+			for( j=0; j<nV; ++j )
+				Ax[ii] += A[ii*NVMAX + j] * x[j];
+		}
+
+		/* 2) Shift QP data. */
+		for( i=0; i<nV; ++i )
+		{
+			g[i]  += tau*delta_g[i];
+			lb[i] += tau*delta_lb[i];
+			ub[i] += tau*delta_ub[i];
+		}
+
+		for( i=0; i<nC; ++i )
+		{
+			lbA[i] += tau*delta_lbA[i];
+			ubA[i] += tau*delta_ubA[i];
+		}
+	}
+	else
+	{
+		/* print a stepsize warning if stepsize is zero */
+		#ifdef PC_DEBUG
+		char messageString[80];
+		sprintf( messageString,"Stepsize is %.6e",tau );
+		getGlobalMessageHandler( )->throwWarning( RET_STEPSIZE,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		#endif
+	}
+
+
+	/* setup output preferences */
+	#ifdef PC_DEBUG
+	char messageString[80];
+	VisibilityStatus visibilityStatus;
+
+	if ( printlevel == PL_HIGH )
+		visibilityStatus = VS_VISIBLE;
+	else
+		visibilityStatus = VS_HIDDEN;
+	#endif
+
+	
+	/* III) UPDATE ACTIVE SET */
+	switch ( BC_status )
+	{
+		/* Optimal solution found as no working set change detected. */
+		case ST_UNDEFINED:
+			return RET_OPTIMAL_SOLUTION_FOUND;
+
+
+		/* Remove one variable from active set. */
+		case ST_INACTIVE:
+			if ( BC_isBound == BT_TRUE )
+			{
+				#ifdef PC_DEBUG
+				sprintf( messageString,"bound no. %d.", BC_idx );
+				getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus );
+				#endif
+
+				if ( removeBound( BC_idx,BT_TRUE ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED );
+
+				y[BC_idx] = 0.0;
+			}
+			else
+			{
+				#ifdef PC_DEBUG
+				sprintf( messageString,"constraint no. %d.", BC_idx );
+				getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus );
+				#endif
+
+				if ( removeConstraint( BC_idx,BT_TRUE ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED );
+
+				y[nV+BC_idx] = 0.0;
+			}
+			break;
+
+
+		/* Add one variable to active set. */
+		default:
+			if ( BC_isBound == BT_TRUE )
+			{
+				#ifdef PC_DEBUG
+				if ( BC_status == ST_LOWER )
+					sprintf( messageString,"lower bound no. %d.", BC_idx );
+				else
+					sprintf( messageString,"upper bound no. %d.", BC_idx );
+				getGlobalMessageHandler( )->throwInfo( RET_ADD_TO_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus );
+				#endif
+
+				if ( addBound( BC_idx,BC_status,BT_TRUE ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_ADD_TO_ACTIVESET_FAILED );
+			}
+			else
+			{
+				#ifdef PC_DEBUG
+				if ( BC_status == ST_LOWER )
+					sprintf( messageString,"lower constraint's bound no. %d.", BC_idx );
+				else
+					sprintf( messageString,"upper constraint's bound no. %d.", BC_idx );
+				getGlobalMessageHandler( )->throwInfo( RET_ADD_TO_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus );
+				#endif
+
+				if ( addConstraint( BC_idx,BC_status,BT_TRUE ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_ADD_TO_ACTIVESET_FAILED );
+			}
+			break;
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	a r e B o u n d s C o n s i s t e n t
+ */
+BooleanType QProblem::areBoundsConsistent(	const real_t* const delta_lb, const real_t* const delta_ub,
+											const real_t* const delta_lbA, const real_t* const delta_ubA
+											) const
+{
+	int i;
+
+	/* 1) Check bounds' consistency. */
+	if ( QProblemB::areBoundsConsistent( delta_lb,delta_ub ) == BT_FALSE )
+		return BT_FALSE;
+
+	/* 2) Check constraints' consistency, i.e.
+	 *    check if delta_lb[i] is greater than delta_ub[i]
+	 *    for a component i whose bounds are already (numerically) equal. */
+	for( i=0; i<getNC( ); ++i )
+		if ( ( lbA[i] > ubA[i] - BOUNDTOL ) && ( delta_lbA[i] > delta_ubA[i] + EPS ) )
+			return BT_FALSE;
+
+	return BT_TRUE;
+}
+
+
+/*
+ *	s e t u p Q P d a t a
+ */
+returnValue QProblem::setupQPdata(	const real_t* const _H, const real_t* const _R, const real_t* const _g, const real_t* const _A,
+									const real_t* const _lb, const real_t* const _ub,
+									const real_t* const _lbA, const real_t* const _ubA
+									)
+{
+	int i, j;
+	int nV = getNV( );
+	int nC = getNC( );
+
+
+	/* 1) Load Hessian matrix as well as lower and upper bounds vectors. */
+	if (QProblemB::setupQPdata(_H, _R, _g, _lb, _ub) != SUCCESSFUL_RETURN)
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	/* 2) Load constraint matrix. */
+	if ( ( nC > 0 ) && ( _A == 0 ) )
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	if ( nC > 0 )
+	{
+		for( i=0; i<nC; ++i )
+			for( j=0; j<nV; ++j )
+				A[i*NVMAX + j] = _A[i*nV + j];
+
+		/* 3) Setup lower constraints' bounds vector. */
+		if ( _lbA != 0 )
+		{
+			for( i=0; i<nC; ++i )
+				lbA[i] = _lbA[i];
+		}
+		else
+		{
+			/* if no lower constraints' bounds are specified, set them to -infinity */
+			for( i=0; i<nC; ++i )
+				lbA[i] = -INFTY;
+		}
+
+		/* 4) Setup upper constraints' bounds vector. */
+		if ( _ubA != 0 )
+		{
+			for( i=0; i<nC; ++i )
+				ubA[i] = _ubA[i];
+		}
+		else
+		{
+			/* if no upper constraints' bounds are specified, set them to infinity */
+			for( i=0; i<nC; ++i )
+				ubA[i] = INFTY;
+		}
+	}
+
+// 	printmatrix2( "A",A,10,20 );
+	
+// 	printmatrix2( "lbA",lbA,1,nC );
+// 	printmatrix2( "ubA",ubA,1,nC );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+#ifdef PC_DEBUG  /* Define print functions only for debugging! */
+
+/*
+ *	p r i n t I t e r a t i o n
+ */
+returnValue QProblem::printIteration( 	int iteration,
+										int BC_idx,	SubjectToStatus BC_status, BooleanType BC_isBound
+		  								)
+{
+	char myPrintfString[160];
+
+	/* consistency check */
+	if ( iteration < 0 )
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	/* nothing to do */
+	if ( printlevel != PL_MEDIUM )
+		return SUCCESSFUL_RETURN;
+
+
+	/* 1) Print header at first iteration. */
+ 	if ( iteration == 0 )
+	{
+		sprintf( myPrintfString,"\n##############  qpOASES  --  QP NO.%4.1d  ###############\n", count );
+		myPrintf( myPrintfString );
+
+		sprintf( myPrintfString,"  Iter  |  StepLength   |     Info      |  nFX  |  nAC  \n" );
+		myPrintf( myPrintfString );
+	}
+
+	/* 2) Print iteration line. */
+	if ( BC_status == ST_UNDEFINED )
+	{
+		sprintf( myPrintfString,"  %4.1d  |  %1.5e  |   QP SOLVED   | %4.1d  | %4.1d  \n", iteration,tau,getNFX( ),getNAC( ) );
+		myPrintf( myPrintfString );
+	}
+	else
+	{
+		char info[8];
+
+		if ( BC_status == ST_INACTIVE )
+			sprintf( info,"REM " );
+		else
+			sprintf( info,"ADD " );
+
+		if ( BC_isBound == BT_TRUE )
+			sprintf( &(info[4]),"BND" );
+		else
+			sprintf( &(info[4]),"CON" );
+
+		sprintf( myPrintfString,"  %4.1d  |  %1.5e  |  %s%4.1d  | %4.1d  | %4.1d  \n", iteration,tau,info,BC_idx,getNFX( ),getNAC( ) );
+		myPrintf( myPrintfString );
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	p r i n t I t e r a t i o n
+ */
+returnValue QProblem::printIteration( 	int iteration,
+										int BC_idx,	SubjectToStatus BC_status
+		  								)
+{
+	return printIteration( iteration,BC_idx,BC_status,BT_TRUE );
+}
+
+#endif  /* PC_DEBUG */
+
+
+
+/*
+ *	c h e c k K K T c o n d i t i o n s
+ */
+returnValue QProblem::checkKKTconditions( )
+{
+	#ifdef __PERFORM_KKT_TEST__
+
+	int i, j, jj;
+	int nV  = getNV( );
+	int nC  = getNC( );
+	int nAC = getNAC( );
+
+	real_t tmp;
+	real_t maxKKTviolation = 0.0;
+
+	int AC_idx[NCMAX_ALLOC];
+	constraints.getActive( )->getNumberArray( AC_idx );
+
+	/* 1) check for Hx + g - [yFX yAC]*[Id A]' = 0. */
+	for( i=0; i<nV; ++i )
+	{
+		tmp = g[i];
+
+		for( j=0; j<nV; ++j )
+			tmp += H[i*NVMAX + j] * x[j];
+
+		tmp -= y[i];
+
+		/* Only sum over active constraints as y is zero for all inactive ones. */
+		for( j=0; j<nAC; ++j )
+		{
+			jj = AC_idx[j];
+			tmp -= A[jj*NVMAX + i] * y[nV+jj];
+		}
+
+		if ( getAbs( tmp ) > maxKKTviolation )
+			maxKKTviolation = getAbs( tmp );
+	}
+
+	/* 2) Check for [lb lbA] <= [Id A]*x <= [ub ubA]. */
+	/* lbA <= Ax <= ubA */
+	for( i=0; i<nC; ++i )
+	{
+		if ( lbA[i] - Ax[i] > maxKKTviolation )
+			maxKKTviolation = lbA[i] - Ax[i];
+
+		if ( Ax[i] - ubA[i] > maxKKTviolation )
+			maxKKTviolation = Ax[i] - ubA[i];
+	}
+
+	/* lb <= x <= ub */
+	for( i=0; i<nV; ++i )
+	{
+		if ( lb[i] - x[i] > maxKKTviolation )
+			maxKKTviolation = lb[i] - x[i];
+
+		if ( x[i] - ub[i] > maxKKTviolation )
+			maxKKTviolation = x[i] - ub[i];
+	}
+
+	/* 3) Check for correct sign of y and for complementary slackness. */
+	/* bounds */
+	for( i=0; i<nV; ++i )
+	{
+		switch ( bounds.getStatus( i ) )
+		{
+			case ST_LOWER:
+				if ( -y[i] > maxKKTviolation )
+					maxKKTviolation = -y[i];
+				if ( getAbs( x[i] - lb[i] ) > maxKKTviolation )
+					maxKKTviolation = getAbs( x[i] - lb[i] );
+				break;
+
+			case ST_UPPER:
+				if ( y[i] > maxKKTviolation )
+					maxKKTviolation = y[i];
+				if ( getAbs( ub[i] - x[i] ) > maxKKTviolation )
+					maxKKTviolation = getAbs( ub[i] - x[i] );
+				break;
+
+			default: /* inactive */
+			if ( getAbs( y[i] ) > maxKKTviolation )
+					maxKKTviolation = getAbs( y[i] );
+				break;
+		}
+	}
+
+	/* constraints */
+	for( i=0; i<nC; ++i )
+	{
+		switch ( constraints.getStatus( i ) )
+		{
+			case ST_LOWER:
+				if ( -y[nV+i] > maxKKTviolation )
+					maxKKTviolation = -y[nV+i];
+				if ( getAbs( Ax[i] - lbA[i] ) > maxKKTviolation )
+					maxKKTviolation = getAbs( Ax[i] - lbA[i] );
+				break;
+
+			case ST_UPPER:
+				if ( y[nV+i] > maxKKTviolation )
+					maxKKTviolation = y[nV+i];
+				if ( getAbs( ubA[i] - Ax[i] ) > maxKKTviolation )
+					maxKKTviolation = getAbs( ubA[i] - Ax[i] );
+				break;
+
+			default: /* inactive */
+			if ( getAbs( y[nV+i] ) > maxKKTviolation )
+					maxKKTviolation = getAbs( y[nV+i] );
+				break;
+		}
+	}
+
+	if ( maxKKTviolation > CRITICALACCURACY )
+		return RET_NO_SOLUTION;
+
+	if ( maxKKTviolation > DESIREDACCURACY )
+		return RET_INACCURATE_SOLUTION;
+
+	#endif /* __PERFORM_KKT_TEST__ */
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblem.ipp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblem.ipp
new file mode 100644
index 0000000000000000000000000000000000000000..e98ada6330fb22ecdd37799e4b52d5e31b645dd0
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblem.ipp
@@ -0,0 +1,299 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/QProblem.ipp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of inlined member functions of the QProblem class which 
+ *	is able to use the newly developed online active set strategy for 
+ *	parametric quadratic programming.
+ */
+
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+/*
+ *	g e t A
+ */
+inline returnValue QProblem::getA( real_t* const _A ) const
+{
+	int i;
+
+	for ( i=0; i<getNV( )*getNC( ); ++i )
+		_A[i] = A[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t A
+ */
+inline returnValue QProblem::getA( int number, real_t* const row ) const
+{
+	int nV = getNV( );
+		
+	if ( ( number >= 0 ) && ( number < getNC( ) ) )
+	{
+		for ( int i=0; i<nV; ++i )
+			row[i] = A[number*NVMAX + i];
+
+		return SUCCESSFUL_RETURN;
+	}
+	else
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+}
+
+
+/*
+ *	g e t L B A
+ */
+inline returnValue QProblem::getLBA( real_t* const _lbA ) const
+{
+	int i;
+
+	for ( i=0; i<getNC( ); ++i )
+		_lbA[i] = lbA[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t L B A
+ */
+inline returnValue QProblem::getLBA( int number, real_t& value ) const
+{
+	if ( ( number >= 0 ) && ( number < getNC( ) ) )
+	{
+		value = lbA[number];
+		return SUCCESSFUL_RETURN;
+	}
+	else
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+}
+
+
+/*
+ *	g e t U B A
+ */
+inline returnValue QProblem::getUBA( real_t* const _ubA ) const
+{
+	int i;
+
+	for ( i=0; i<getNC( ); ++i )
+		_ubA[i] = ubA[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t U B A
+ */
+inline returnValue QProblem::getUBA( int number, real_t& value ) const
+{
+	if ( ( number >= 0 ) && ( number < getNC( ) ) )
+	{
+		value = ubA[number];
+		return SUCCESSFUL_RETURN;
+	}
+	else
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+}
+
+
+/*
+ *	g e t C o n s t r a i n t s
+ */
+inline returnValue QProblem::getConstraints( Constraints* const _constraints ) const
+{
+	*_constraints = constraints;
+	
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*
+ *	g e t N C
+ */
+inline int QProblem::getNC( ) const
+{
+	return constraints.getNC( );
+}
+
+
+/*
+ *	g e t N E C
+ */
+inline int QProblem::getNEC( ) const
+{
+	return constraints.getNEC( );
+}
+
+
+/*
+ *	g e t N A C
+ */
+inline int QProblem::getNAC( )
+{
+	return constraints.getNAC( );
+}
+
+
+/*
+ *	g e t N I A C
+ */
+inline int QProblem::getNIAC( )
+{
+	return constraints.getNIAC( );
+}
+
+
+
+/*****************************************************************************
+ *  P R O T E C T E D                                                        *
+ *****************************************************************************/
+ 
+
+/*
+ *	s e t A
+ */
+inline returnValue QProblem::setA( const real_t* const A_new )
+{
+	int i, j;
+	int nV = getNV( );
+	int nC = getNC( );
+
+	/* Set constraint matrix AND update member AX. */
+	for( j=0; j<nC; ++j )
+	{
+		Ax[j] = 0.0;
+
+		for( i=0; i<nV; ++i )
+		{	
+			A[j*NVMAX + i] = A_new[j*nV + i];
+			Ax[j] += A[j*NVMAX + i] * x[i];
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t A
+ */
+inline returnValue QProblem::setA( int number, const real_t* const row )
+{
+	int i;
+	int nV = getNV( );
+
+	/* Set constraint matrix AND update member AX. */
+	if ( ( number >= 0 ) && ( number < getNC( ) ) )
+	{
+		Ax[number] = 0.0;
+
+		for( i=0; i<nV; ++i )
+		{
+			A[number*NVMAX + i] = row[i];
+			Ax[number] += A[number*NVMAX + i] * x[i];
+		}
+
+		return SUCCESSFUL_RETURN;
+	}
+	else
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+}
+
+
+/*
+ *	s e t L B A
+ */
+inline returnValue QProblem::setLBA( const real_t* const lbA_new )
+{
+	int i;
+	int nC = getNC();
+
+	for( i=0; i<nC; ++i )
+		lbA[i] = lbA_new[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t L B A
+ */
+inline returnValue QProblem::setLBA( int number, real_t value )
+{
+	if ( ( number >= 0 ) && ( number < getNC( ) ) )
+	{
+		lbA[number] = value;
+		return SUCCESSFUL_RETURN;
+	}
+	else
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+}
+
+
+/*
+ *	s e t U B A
+ */
+inline returnValue QProblem::setUBA( const real_t* const ubA_new )
+{
+	int i;
+	int nC = getNC();
+
+	for( i=0; i<nC; ++i )
+		ubA[i] = ubA_new[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t U B A
+ */
+inline returnValue QProblem::setUBA( int number, real_t value )
+{
+	if ( ( number >= 0 ) && ( number < getNC( ) ) )
+	{
+		ubA[number] = value;
+		return SUCCESSFUL_RETURN;
+	}
+	else
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblemB.cpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblemB.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..47ac3536f35cf50b28803550fc6409a4a7f96a12
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblemB.cpp
@@ -0,0 +1,2151 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/QProblemB.cpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of the QProblemB class which is able to use the newly
+ *	developed online active set strategy for parametric quadratic programming.
+ */
+
+
+#include <QProblemB.hpp>
+
+#include <stdio.h>
+
+void printmatrix(char *name, double *A, int m, int n) {
+  int i, j;
+
+  printf("%s = [...\n", name);
+  for (i = 0; i < m; i++) {
+    for (j = 0; j < n; j++)
+        printf("  % 9.4f", A[i*n+j]);
+    printf(",\n");
+  }
+  printf("];\n");
+}
+
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+
+/*
+ *	Q P r o b l e m B
+ */
+QProblemB::QProblemB( )
+{
+	/* reset global message handler */
+	getGlobalMessageHandler( )->reset( );
+
+	hasHessian = BT_FALSE;
+
+	bounds.init( 0 );
+
+	hasCholesky = BT_FALSE;
+
+	tau = 0.0;
+
+	hessianType = HST_POSDEF_NULLSPACE; /* Hessian is assumed to be positive definite by default */
+	infeasible = BT_FALSE;
+	unbounded = BT_FALSE;
+
+	status = QPS_NOTINITIALISED;
+
+	#ifdef PC_DEBUG
+	printlevel = PL_MEDIUM;
+	setPrintLevel( PL_MEDIUM );
+	#else
+	printlevel = QPOASES_PRINTLEVEL;
+	#endif
+
+	count = 0;
+}
+
+
+/*
+ *	Q P r o b l e m B
+ */
+QProblemB::QProblemB( int _nV )
+{
+	/* consistency check */
+	if ( _nV <= 0 )
+	{
+		_nV = 1;
+		THROWERROR( RET_INVALID_ARGUMENTS );
+	}
+
+	hasHessian = BT_FALSE;
+
+	/* reset global message handler */
+	getGlobalMessageHandler( )->reset( );
+
+	bounds.init( _nV );
+
+	hasCholesky = BT_FALSE;
+
+	tau = 0.0;
+
+	hessianType = HST_POSDEF_NULLSPACE; /* Hessian is assumed to be positive definite by default */
+	infeasible = BT_FALSE;
+	unbounded = BT_FALSE;
+
+	status = QPS_NOTINITIALISED;
+
+	#ifdef PC_DEBUG
+	printlevel = PL_MEDIUM;
+	setPrintLevel( PL_MEDIUM );
+	#else
+	printlevel = QPOASES_PRINTLEVEL;
+	#endif
+
+	count = 0;
+}
+
+
+/*
+ *	Q P r o b l e m B
+ */
+QProblemB::QProblemB( const QProblemB& rhs )
+{
+	int i, j;
+
+	int _nV = rhs.bounds.getNV( );
+
+	for( i=0; i<_nV; ++i )
+		for( j=0; j<_nV; ++j )
+			H[i*NVMAX + j] = rhs.H[i*NVMAX + j];
+
+	hasHessian = rhs.hasHessian;
+
+	for( i=0; i<_nV; ++i )
+		g[i] = rhs.g[i];
+
+	for( i=0; i<_nV; ++i )
+		lb[i] = rhs.lb[i];
+
+	for( i=0; i<_nV; ++i )
+		ub[i] = rhs.ub[i];
+
+
+	bounds = rhs.bounds;
+
+	for( i=0; i<_nV; ++i )
+		for( j=0; j<_nV; ++j )
+			R[i*NVMAX + j] = rhs.R[i*NVMAX + j];
+	hasCholesky = rhs.hasCholesky;
+
+	for( i=0; i<_nV; ++i )
+		x[i] = rhs.x[i];
+
+	for( i=0; i<_nV; ++i )
+		y[i] = rhs.y[i];
+
+	tau = rhs.tau;
+
+	hessianType = rhs.hessianType;
+	infeasible = rhs.infeasible;
+	unbounded = rhs.unbounded;
+
+	status = rhs.status;
+
+	printlevel = rhs.printlevel;
+
+	count = rhs.count;
+}
+
+
+/*
+ *	~ Q P r o b l e m B
+ */
+QProblemB::~QProblemB( )
+{
+}
+
+
+/*
+ *	o p e r a t o r =
+ */
+QProblemB& QProblemB::operator=( const QProblemB& rhs )
+{
+	int i, j;
+
+	if ( this != &rhs )
+	{
+		int _nV = rhs.bounds.getNV( );
+
+		for( i=0; i<_nV; ++i )
+			for( j=0; j<_nV; ++j )
+				H[i*NVMAX + j] = rhs.H[i*NVMAX + j];
+
+		hasHessian = rhs.hasHessian;
+
+		for( i=0; i<_nV; ++i )
+			g[i] = rhs.g[i];
+
+		for( i=0; i<_nV; ++i )
+			lb[i] = rhs.lb[i];
+
+		for( i=0; i<_nV; ++i )
+			ub[i] = rhs.ub[i];
+
+		bounds = rhs.bounds;
+
+		for( i=0; i<_nV; ++i )
+			for( j=0; j<_nV; ++j )
+				R[i*NVMAX + j] = rhs.R[i*NVMAX + j];
+		hasCholesky = rhs.hasCholesky;
+
+
+		for( i=0; i<_nV; ++i )
+			x[i] = rhs.x[i];
+
+		for( i=0; i<_nV; ++i )
+			y[i] = rhs.y[i];
+
+		tau = rhs.tau;
+
+		hessianType = rhs.hessianType;
+		infeasible = rhs.infeasible;
+		unbounded = rhs.unbounded;
+
+		status = rhs.status;
+
+		printlevel = rhs.printlevel;
+		setPrintLevel( rhs.printlevel );
+
+		count = rhs.count;
+	}
+
+	return *this;
+}
+
+
+/*
+ *	r e s e t
+ */
+returnValue QProblemB::reset( )
+{
+	int i, j;
+	int nV = getNV( );
+
+	/** 0) Reset has Hessian flag. */
+	hasHessian = BT_FALSE;
+
+	/* 1) Reset bounds. */
+	bounds.init( nV );
+
+	/* 2) Reset Cholesky decomposition. */
+	for( i=0; i<nV; ++i )
+		for( j=0; j<nV; ++j )
+			R[i*NVMAX + j] = 0.0;
+	hasCholesky = BT_FALSE;
+
+	/* 3) Reset steplength and status flags. */
+	tau = 0.0;
+
+	hessianType = HST_POSDEF_NULLSPACE; /* Hessian is assumed to be positive definite by default */
+	infeasible = BT_FALSE;
+	unbounded = BT_FALSE;
+
+	status = QPS_NOTINITIALISED;
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	i n i t
+ */
+returnValue QProblemB::init(	const real_t* const _H, const real_t* const _g,
+								const real_t* const _lb, const real_t* const _ub,
+								int& nWSR, const real_t* const yOpt, real_t* const cputime
+								)
+{
+	/* 1) Setup QP data. */
+	if (setupQPdata(_H, 0, _g, _lb, _ub) != SUCCESSFUL_RETURN)
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	/* 2) Call to main initialisation routine (without any additional information). */
+	return solveInitialQP(0, yOpt, 0, nWSR, cputime);
+}
+
+returnValue QProblemB::init(	const real_t* const _H, const real_t* const _R, const real_t* const _g,
+								const real_t* const _lb, const real_t* const _ub,
+								int& nWSR, const real_t* const yOpt, real_t* const cputime
+								)
+{
+	/* 1) Setup QP data. */
+	if (setupQPdata(_H, _R, _g, _lb, _ub) != SUCCESSFUL_RETURN)
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	/* 2) Call to main initialisation routine (without any additional information). */
+	return solveInitialQP(0, yOpt, 0, nWSR, cputime);
+}
+
+
+/*
+ *	h o t s t a r t
+ */
+returnValue QProblemB::hotstart(	const real_t* const g_new, const real_t* const lb_new, const real_t* const ub_new,
+									int& nWSR, real_t* const cputime
+									)
+{
+	int l;
+
+	/* consistency check */
+	if ( ( getStatus( ) == QPS_NOTINITIALISED )       ||
+		 ( getStatus( ) == QPS_PREPARINGAUXILIARYQP ) ||
+		 ( getStatus( ) == QPS_PERFORMINGHOMOTOPY )   )
+	{
+		return THROWERROR( RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED );
+	}
+
+	/* start runtime measurement */
+	real_t starttime = 0.0;
+	if ( cputime != 0 )
+		starttime = getCPUtime( );
+
+
+	/* I) PREPARATIONS */
+	/* 1) Reset status flags and increase QP counter. */
+	infeasible = BT_FALSE;
+	unbounded = BT_FALSE;
+
+	++count;
+
+	/* 2) Allocate delta vectors of gradient and bounds. */
+	returnValue returnvalue;
+	BooleanType Delta_bB_isZero;
+
+	int FR_idx[NVMAX];
+	int FX_idx[NVMAX];
+
+	real_t delta_g[NVMAX];
+	real_t delta_lb[NVMAX];
+	real_t delta_ub[NVMAX];
+
+	real_t delta_xFR[NVMAX];
+	real_t delta_xFX[NVMAX];
+	real_t delta_yFX[NVMAX];
+
+	int BC_idx;
+	SubjectToStatus BC_status;
+
+	#ifdef PC_DEBUG
+	char messageString[80];
+	#endif
+
+	/* II) MAIN HOMOTOPY LOOP */
+	for( l=0; l<nWSR; ++l )
+	{
+		status = QPS_PERFORMINGHOMOTOPY;
+
+		if ( printlevel == PL_HIGH )
+		{
+			#ifdef PC_DEBUG
+			sprintf( messageString,"%d ...",l );
+			getGlobalMessageHandler( )->throwInfo( RET_ITERATION_STARTED,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+			#endif
+		}
+
+		/* 1) Setup index arrays. */
+		if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_HOTSTART_FAILED );
+
+		if ( bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_HOTSTART_FAILED );
+
+		/* 2) Initialize shift direction of the gradient and the bounds. */
+		returnvalue = hotstart_determineDataShift(  FX_idx,
+													g_new,lb_new,ub_new,
+													delta_g,delta_lb,delta_ub,
+													Delta_bB_isZero
+													);
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			nWSR = l;
+			THROWERROR( RET_SHIFT_DETERMINATION_FAILED );
+			return returnvalue;
+		}
+
+		/* 3) Determination of step direction of X and Y. */
+		returnvalue = hotstart_determineStepDirection(	FR_idx,FX_idx,
+														delta_g,delta_lb,delta_ub,
+														Delta_bB_isZero,
+														delta_xFX,delta_xFR,delta_yFX
+														);
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			nWSR = l;
+			THROWERROR( RET_STEPDIRECTION_DETERMINATION_FAILED );
+			return returnvalue;
+		}
+
+
+		/* 4) Determination of step length TAU. */
+		returnvalue = hotstart_determineStepLength(	FR_idx,FX_idx,
+													delta_lb,delta_ub,
+													delta_xFR,delta_yFX,
+													BC_idx,BC_status );
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			nWSR = l;
+			THROWERROR( RET_STEPLENGTH_DETERMINATION_FAILED );
+			return returnvalue;
+		}
+
+		/* 5) Realization of the homotopy step. */
+		returnvalue = hotstart_performStep(	FR_idx,FX_idx,
+											delta_g,delta_lb,delta_ub,
+											delta_xFX,delta_xFR,delta_yFX,
+											BC_idx,BC_status
+											);
+
+
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			nWSR = l;
+
+			/* stop runtime measurement */
+			if ( cputime != 0 )
+				*cputime = getCPUtime( ) - starttime;
+
+			/* optimal solution found? */
+			if ( returnvalue == RET_OPTIMAL_SOLUTION_FOUND )
+			{
+				status = QPS_SOLVED;
+
+				if ( printlevel == PL_HIGH )
+					THROWINFO( RET_OPTIMAL_SOLUTION_FOUND );
+
+				#ifdef PC_DEBUG
+	 			if ( printIteration( l,BC_idx,BC_status ) != SUCCESSFUL_RETURN )
+					THROWERROR( RET_PRINT_ITERATION_FAILED ); /* do not pass this as return value! */
+				#endif
+
+				/* check KKT optimality conditions */
+				return checkKKTconditions( );
+			}
+			else
+			{
+				/* checks for infeasibility... */
+				if ( infeasible == BT_TRUE )
+				{
+					status = QPS_HOMOTOPYQPSOLVED;
+					return THROWERROR( RET_HOTSTART_STOPPED_INFEASIBILITY );
+				}
+
+				/* ...unboundedness... */
+				if ( unbounded == BT_TRUE ) /* not necessary since objective function convex! */
+					return THROWERROR( RET_HOTSTART_STOPPED_UNBOUNDEDNESS );
+
+				/* ... and throw unspecific error otherwise */
+				THROWERROR( RET_HOMOTOPY_STEP_FAILED );
+				return returnvalue;
+			}
+		}
+
+		/* 6) Output information of successful QP iteration. */
+		status = QPS_HOMOTOPYQPSOLVED;
+
+		#ifdef PC_DEBUG
+		if ( printIteration( l,BC_idx,BC_status ) != SUCCESSFUL_RETURN )
+			THROWERROR( RET_PRINT_ITERATION_FAILED ); /* do not pass this as return value! */
+		#endif
+	}
+
+
+	/* stop runtime measurement */
+	if ( cputime != 0 )
+		*cputime = getCPUtime( ) - starttime;
+
+
+	/* if programm gets to here, output information that QP could not be solved
+	 * within the given maximum numbers of working set changes */
+	if ( printlevel == PL_HIGH )
+	{
+		#ifdef PC_DEBUG
+		sprintf( messageString,"(nWSR = %d)",nWSR );
+		return getGlobalMessageHandler( )->throwWarning( RET_MAX_NWSR_REACHED,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		#endif
+	}
+
+	/* Finally check KKT optimality conditions. */
+	returnValue returnvalueKKTcheck = checkKKTconditions( );
+
+	if ( returnvalueKKTcheck != SUCCESSFUL_RETURN )
+		return returnvalueKKTcheck;
+	else
+		return RET_MAX_NWSR_REACHED;
+}
+
+
+/*
+ *	g e t N Z
+ */
+int QProblemB::getNZ( )
+{
+	/* if no constraints are present: nZ=nFR */
+	return bounds.getFree( )->getLength( );
+}
+
+
+/*
+ *	g e t O b j V a l
+ */
+real_t QProblemB::getObjVal( ) const
+{
+	real_t objVal;
+
+	/* calculated optimal objective function value
+	 * only if current QP has been solved */
+	if ( ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) ||
+		 ( getStatus( ) == QPS_HOMOTOPYQPSOLVED )  ||
+		 ( getStatus( ) == QPS_SOLVED ) )
+	{
+		objVal = getObjVal( x );
+	}
+	else
+	{
+		objVal = INFTY;
+	}
+
+	return objVal;
+}
+
+
+/*
+ *	g e t O b j V a l
+ */
+real_t QProblemB::getObjVal( const real_t* const _x ) const
+{
+	int i, j;
+	int nV = getNV( );
+
+	real_t obj_tmp = 0.0;
+
+	for( i=0; i<nV; ++i )
+	{
+		obj_tmp += _x[i]*g[i];
+
+		for( j=0; j<nV; ++j )
+			obj_tmp += 0.5*_x[i]*H[i*NVMAX + j]*_x[j];
+	}
+
+	return obj_tmp;
+}
+
+
+/*
+ *	g e t P r i m a l S o l u t i o n
+ */
+returnValue QProblemB::getPrimalSolution( real_t* const xOpt ) const
+{
+	int i;
+
+	/* return optimal primal solution vector
+	 * only if current QP has been solved */
+	if ( ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) ||
+		 ( getStatus( ) == QPS_HOMOTOPYQPSOLVED )  ||
+		 ( getStatus( ) == QPS_SOLVED ) )
+	{
+		for( i=0; i<getNV( ); ++i )
+			xOpt[i] = x[i];
+
+		return SUCCESSFUL_RETURN;
+	}
+	else
+	{
+		return RET_QP_NOT_SOLVED;
+	}
+}
+
+
+/*
+ *	g e t D u a l S o l u t i o n
+ */
+returnValue QProblemB::getDualSolution( real_t* const yOpt ) const
+{
+	int i;
+
+	/* return optimal dual solution vector
+	 * only if current QP has been solved */
+	if ( ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) ||
+		 ( getStatus( ) == QPS_HOMOTOPYQPSOLVED )  ||
+		 ( getStatus( ) == QPS_SOLVED ) )
+	{
+		for( i=0; i<getNV( ); ++i )
+			yOpt[i] = y[i];
+
+		return SUCCESSFUL_RETURN;
+	}
+	else
+	{
+		return RET_QP_NOT_SOLVED;
+	}
+}
+
+
+/*
+ *	s e t P r i n t L e v e l
+ */
+returnValue QProblemB::setPrintLevel( PrintLevel _printlevel )
+{
+	#ifndef __MATLAB__
+	if ( ( printlevel >= PL_MEDIUM ) && ( printlevel != _printlevel ) )
+		THROWINFO( RET_PRINTLEVEL_CHANGED );
+	#endif
+
+	printlevel = _printlevel;
+
+	/* update message handler preferences */
+ 	switch ( printlevel )
+ 	{
+ 		case PL_NONE:
+ 			getGlobalMessageHandler( )->setErrorVisibilityStatus( VS_HIDDEN );
+			getGlobalMessageHandler( )->setWarningVisibilityStatus( VS_HIDDEN );
+			getGlobalMessageHandler( )->setInfoVisibilityStatus( VS_HIDDEN );
+			break;
+
+		case PL_LOW:
+ 			getGlobalMessageHandler( )->setErrorVisibilityStatus( VS_VISIBLE );
+			getGlobalMessageHandler( )->setWarningVisibilityStatus( VS_HIDDEN );
+			getGlobalMessageHandler( )->setInfoVisibilityStatus( VS_HIDDEN );
+			break;
+
+ 		default: /* PL_MEDIUM, PL_HIGH */
+ 			getGlobalMessageHandler( )->setErrorVisibilityStatus( VS_VISIBLE );
+			getGlobalMessageHandler( )->setWarningVisibilityStatus( VS_VISIBLE );
+			getGlobalMessageHandler( )->setInfoVisibilityStatus( VS_VISIBLE );
+			break;
+ 	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*****************************************************************************
+ *  P R O T E C T E D                                                        *
+ *****************************************************************************/
+
+/*
+ *	c h e c k F o r I d e n t i t y H e s s i a n
+ */
+returnValue QProblemB::checkForIdentityHessian( )
+{
+	int i, j;
+	int nV = getNV( );
+
+	/* nothing to do as status flag remains unaltered
+	 * if Hessian differs from identity matrix */
+	if ( hessianType == HST_IDENTITY )
+		return SUCCESSFUL_RETURN;
+
+	/* 1) If Hessian differs from identity matrix,
+	 *    return without changing the internal HessianType. */
+	for ( i=0; i<nV; ++i )
+		if ( getAbs( H[i*NVMAX + i] - 1.0 ) > EPS )
+			return SUCCESSFUL_RETURN;
+
+	for ( i=0; i<nV; ++i )
+	{
+		for ( j=0; j<i; ++j )
+			if ( ( getAbs( H[i*NVMAX + j] ) > EPS ) || ( getAbs( H[j*NVMAX + i] ) > EPS ) )
+				return SUCCESSFUL_RETURN;
+	}
+
+	/* 2) If this point is reached, Hessian equals the idetity matrix. */
+	hessianType = HST_IDENTITY;
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p S u b j e c t T o T y p e
+ */
+returnValue QProblemB::setupSubjectToType( )
+{
+	int i;
+	int nV = getNV( );
+
+
+	/* 1) Check if lower bounds are present. */
+	bounds.setNoLower( BT_TRUE );
+	for( i=0; i<nV; ++i )
+		if ( lb[i] > -INFTY )
+		{
+			bounds.setNoLower( BT_FALSE );
+			break;
+		}
+
+	/* 2) Check if upper bounds are present. */
+	bounds.setNoUpper( BT_TRUE );
+	for( i=0; i<nV; ++i )
+		if ( ub[i] < INFTY )
+		{
+			bounds.setNoUpper( BT_FALSE );
+			break;
+		}
+
+	/* 3) Determine implicitly fixed and unbounded variables. */
+	int nFV = 0;
+	int nUV = 0;
+
+	for( i=0; i<nV; ++i )
+		if ( ( lb[i] < -INFTY + BOUNDTOL ) && ( ub[i] > INFTY - BOUNDTOL ) )
+		{
+			bounds.setType( i,ST_UNBOUNDED );
+			++nUV;
+		}
+		else
+		{
+			if ( lb[i] > ub[i] - BOUNDTOL )
+			{
+				bounds.setType( i,ST_EQUALITY );
+				++nFV;
+			}
+			else
+			{
+				bounds.setType( i,ST_BOUNDED );
+			}
+		}
+
+	/* 4) Set dimensions of bounds structure. */
+	bounds.setNFV( nFV );
+	bounds.setNUV( nUV );
+	bounds.setNBV( nV - nFV - nUV );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	c h o l e s k y D e c o m p o s i t i o n
+ */
+returnValue QProblemB::setupCholeskyDecomposition( )
+{
+	int i, j, k, ii, jj;
+	int nV  = getNV( );
+	int nFR = getNFR( );
+
+	/* If Hessian flag is false, it means that H & R already contain Cholesky
+	 * factorization -- provided from outside. */
+	if (hasHessian == BT_FALSE)
+		return SUCCESSFUL_RETURN;
+
+	/* 1) Initialises R with all zeros. */
+	for( i=0; i<nV; ++i )
+		for( j=0; j<nV; ++j )
+			R[i*NVMAX + j] = 0.0;
+
+	/* 2) Calculate Cholesky decomposition of H (projected to free variables). */
+	if ( hessianType == HST_IDENTITY )
+	{
+		/* if Hessian is identity, so is its Cholesky factor. */
+		for( i=0; i<nFR; ++i )
+			R[i*NVMAX + i] = 1.0;
+	}
+	else
+	{
+		if ( nFR > 0 )
+		{
+			int FR_idx[NVMAX];
+			if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_INDEXLIST_CORRUPTED );
+
+			/* R'*R = H */
+			real_t sum;
+			real_t inv;
+
+			for( i=0; i<nFR; ++i )
+			{
+				/* j == i */
+				ii = FR_idx[i];
+				sum = H[ii*NVMAX + ii];
+
+				for( k=(i-1); k>=0; --k )
+					sum -= R[k*NVMAX + i] * R[k*NVMAX + i];
+
+				if ( sum > 0.0 )
+				{
+					R[i*NVMAX + i] = sqrt( sum );
+					inv = 1.0 / R[i*NVMAX + i];
+				}
+				else
+				{
+					hessianType = HST_SEMIDEF;
+					return THROWERROR( RET_HESSIAN_NOT_SPD );
+				}
+
+				/* j > i */
+				for( j=(i+1); j<nFR; ++j )
+				{
+					jj = FR_idx[j];
+					sum = H[jj*NVMAX + ii];
+
+					for( k=(i-1); k>=0; --k )
+						sum -= R[k*NVMAX + i] * R[k*NVMAX + j];
+
+					R[i*NVMAX + j] = sum * inv;
+				}
+			}
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s o l v e I n i t i a l Q P
+ */
+returnValue QProblemB::solveInitialQP(	const real_t* const xOpt, const real_t* const yOpt,
+										const Bounds* const guessedBounds,
+										int& nWSR, real_t* const cputime
+										)
+{
+	int i, nFR;
+	int nV = getNV( );
+
+
+	/* start runtime measurement */
+	real_t starttime = 0.0;
+	if ( cputime != 0 )
+		starttime = getCPUtime( );
+
+
+	status = QPS_NOTINITIALISED;
+
+	/* I) ANALYSE QP DATA: */
+	/* 1) Check if Hessian happens to be the identity matrix. */
+	if ( checkForIdentityHessian( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	/* 2) Setup type of bounds (i.e. unbounded, implicitly fixed etc.). */
+	if ( setupSubjectToType( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	status = QPS_PREPARINGAUXILIARYQP;
+
+
+	/* II) SETUP AUXILIARY QP WITH GIVEN OPTIMAL SOLUTION: */
+	/* 1) Setup bounds data structure. */
+	if ( bounds.setupAllFree( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	/* 2) Setup optimal primal/dual solution for auxiliary QP. */
+	if ( setupAuxiliaryQPsolution( xOpt,yOpt ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	/* 3) Obtain linear independent working set for auxiliary QP. */
+
+	static Bounds auxiliaryBounds;
+
+	auxiliaryBounds.init( nV );
+
+	if ( obtainAuxiliaryWorkingSet( xOpt,yOpt,guessedBounds, &auxiliaryBounds ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	/* 4) Setup working set of auxiliary QP and setup cholesky decomposition. */
+	if ( setupAuxiliaryWorkingSet( &auxiliaryBounds,BT_TRUE ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	nFR = getNFR();
+	/* At the moment we can only provide a Cholesky of the Hessian if
+	 * the solver is cold-started. */
+	if (hasCholesky == BT_FALSE || nFR != nV)
+		if (setupCholeskyDecomposition() != SUCCESSFUL_RETURN)
+			return THROWERROR( RET_INIT_FAILED_CHOLESKY );
+
+	/* 5) Store original QP formulation... */
+	real_t g_original[NVMAX];
+	real_t lb_original[NVMAX];
+	real_t ub_original[NVMAX];
+
+	for( i=0; i<nV; ++i )
+		g_original[i] = g[i];
+	for( i=0; i<nV; ++i )
+		lb_original[i] = lb[i];
+	for( i=0; i<nV; ++i )
+		ub_original[i] = ub[i];
+
+	/* ... and setup QP data of an auxiliary QP having an optimal solution
+	 * as specified by the user (or xOpt = yOpt = 0, by default). */
+	if ( setupAuxiliaryQPgradient( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	if ( setupAuxiliaryQPbounds( BT_TRUE ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	status = QPS_AUXILIARYQPSOLVED;
+
+
+	/* III) SOLVE ACTUAL INITIAL QP: */
+	/* Use hotstart method to find the solution of the original initial QP,... */
+	returnValue returnvalue = hotstart( g_original,lb_original,ub_original, nWSR,0 );
+
+
+	/* ... check for infeasibility and unboundedness... */
+	if ( isInfeasible( ) == BT_TRUE )
+		return THROWERROR( RET_INIT_FAILED_INFEASIBILITY );
+
+	if ( isUnbounded( ) == BT_TRUE )
+		return THROWERROR( RET_INIT_FAILED_UNBOUNDEDNESS );
+
+	/* ... and internal errors. */
+	if ( ( returnvalue != SUCCESSFUL_RETURN ) && ( returnvalue != RET_MAX_NWSR_REACHED )  &&
+	     ( returnvalue != RET_INACCURATE_SOLUTION ) && ( returnvalue != RET_NO_SOLUTION ) )
+		return THROWERROR( RET_INIT_FAILED_HOTSTART );
+
+
+	/* stop runtime measurement */
+	if ( cputime != 0 )
+		*cputime = getCPUtime( ) - starttime;
+
+	if ( printlevel == PL_HIGH )
+		THROWINFO( RET_INIT_SUCCESSFUL );
+
+	return returnvalue;
+}
+
+
+/*
+ *	o b t a i n A u x i l i a r y W o r k i n g S e t
+ */
+returnValue QProblemB::obtainAuxiliaryWorkingSet(	const real_t* const xOpt, const real_t* const yOpt,
+													const Bounds* const guessedBounds, Bounds* auxiliaryBounds
+													) const
+{
+	int i = 0;
+	int nV = getNV( );
+
+
+	/* 1) Ensure that desiredBounds is allocated (and different from guessedBounds). */
+	if ( ( auxiliaryBounds == 0 ) || ( auxiliaryBounds == guessedBounds ) )
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+
+	/* 2) Setup working set for auxiliary initial QP. */
+	if ( guessedBounds != 0 )
+	{
+		/* If an initial working set is specific, use it!
+		 * Moreover, add all implictly fixed variables if specified. */
+		for( i=0; i<nV; ++i )
+		{
+			if ( bounds.getType( i ) == ST_EQUALITY )
+			{
+				if ( auxiliaryBounds->setupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+			}
+			else
+			{
+				if ( auxiliaryBounds->setupBound( i,guessedBounds->getStatus( i ) ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+			}
+		}
+	}
+	else	/* No initial working set specified. */
+	{
+		if ( ( xOpt != 0 ) && ( yOpt == 0 ) )
+		{
+			/* Obtain initial working set by "clipping". */
+			for( i=0; i<nV; ++i )
+			{
+				if ( xOpt[i] <= lb[i] + BOUNDTOL )
+				{
+					if ( auxiliaryBounds->setupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+					continue;
+				}
+
+				if ( xOpt[i] >= ub[i] - BOUNDTOL )
+				{
+					if ( auxiliaryBounds->setupBound( i,ST_UPPER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+					continue;
+				}
+
+				/* Moreover, add all implictly fixed variables if specified. */
+				if ( bounds.getType( i ) == ST_EQUALITY )
+				{
+					if ( auxiliaryBounds->setupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+				else
+				{
+					if ( auxiliaryBounds->setupBound( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+			}
+		}
+
+		if ( ( xOpt == 0 ) && ( yOpt != 0 ) )
+		{
+			/* Obtain initial working set in accordance to sign of dual solution vector. */
+			for( i=0; i<nV; ++i )
+			{
+				if ( yOpt[i] > ZERO )
+				{
+					if ( auxiliaryBounds->setupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+					continue;
+				}
+
+				if ( yOpt[i] < -ZERO )
+				{
+					if ( auxiliaryBounds->setupBound( i,ST_UPPER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+					continue;
+				}
+
+				/* Moreover, add all implictly fixed variables if specified. */
+				if ( bounds.getType( i ) == ST_EQUALITY )
+				{
+					if ( auxiliaryBounds->setupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+				else
+				{
+					if ( auxiliaryBounds->setupBound( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+			}
+		}
+
+		/* If xOpt and yOpt are null pointer and no initial working is specified,
+		 * start with empty working set (or implicitly fixed bounds only)
+		 * for auxiliary QP. */
+		if ( ( xOpt == 0 ) && ( yOpt == 0 ) )
+		{
+			for( i=0; i<nV; ++i )
+			{
+				/* Only add all implictly fixed variables if specified. */
+				if ( bounds.getType( i ) == ST_EQUALITY )
+				{
+					if ( auxiliaryBounds->setupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+				else
+				{
+					if ( auxiliaryBounds->setupBound( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+			}
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p A u x i l i a r y W o r k i n g S e t
+ */
+returnValue QProblemB::setupAuxiliaryWorkingSet( 	const Bounds* const auxiliaryBounds,
+													BooleanType setupAfresh
+													)
+{
+	int i;
+	int nV = getNV( );
+
+	/* consistency checks */
+	if ( auxiliaryBounds != 0 )
+	{
+		for( i=0; i<nV; ++i )
+			if ( ( bounds.getStatus( i ) == ST_UNDEFINED ) || ( auxiliaryBounds->getStatus( i ) == ST_UNDEFINED ) )
+				return THROWERROR( RET_UNKNOWN_BUG );
+	}
+	else
+	{
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+	}
+
+
+	/* I) SETUP CHOLESKY FLAG:
+	 *    Cholesky decomposition shall only be updated if working set
+	 *    shall be updated (i.e. NOT setup afresh!) */
+	BooleanType updateCholesky;
+	if ( setupAfresh == BT_TRUE )
+		updateCholesky = BT_FALSE;
+	else
+		updateCholesky = BT_TRUE;
+
+
+	/* II) REMOVE FORMERLY ACTIVE BOUNDS (IF NECESSARY): */
+	if ( setupAfresh == BT_FALSE )
+	{
+		/* Remove all active bounds that shall be inactive AND
+		*  all active bounds that are active at the wrong bound. */
+		for( i=0; i<nV; ++i )
+		{
+			if ( ( bounds.getStatus( i ) == ST_LOWER ) && ( auxiliaryBounds->getStatus( i ) != ST_LOWER ) )
+				if ( removeBound( i,updateCholesky ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_SETUP_WORKINGSET_FAILED );
+
+			if ( ( bounds.getStatus( i ) == ST_UPPER ) && ( auxiliaryBounds->getStatus( i ) != ST_UPPER ) )
+				if ( removeBound( i,updateCholesky ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_SETUP_WORKINGSET_FAILED );
+		}
+	}
+
+
+	/* III) ADD NEWLY ACTIVE BOUNDS: */
+	/*      Add all inactive bounds that shall be active AND
+	 *      all formerly active bounds that have been active at the wrong bound. */
+	for( i=0; i<nV; ++i )
+	{
+		if ( ( bounds.getStatus( i ) == ST_INACTIVE ) && ( auxiliaryBounds->getStatus( i ) != ST_INACTIVE ) )
+		{
+			if ( addBound( i,auxiliaryBounds->getStatus( i ),updateCholesky ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_WORKINGSET_FAILED );
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p A u x i l i a r y Q P s o l u t i o n
+ */
+returnValue QProblemB::setupAuxiliaryQPsolution(	const real_t* const xOpt, const real_t* const yOpt
+													)
+{
+	int i;
+	int nV = getNV( );
+
+
+	/* Setup primal/dual solution vectors for auxiliary initial QP:
+	 * if a null pointer is passed, a zero vector is assigned;
+	 * old solution vector is kept if pointer to internal solution vector is passed. */
+	if ( xOpt != 0 )
+	{
+		if ( xOpt != x )
+			for( i=0; i<nV; ++i )
+				x[i] = xOpt[i];
+	}
+	else
+	{
+		for( i=0; i<nV; ++i )
+			x[i] = 0.0;
+	}
+
+	if ( yOpt != 0 )
+	{
+		if ( yOpt != y )
+			for( i=0; i<nV; ++i )
+				y[i] = yOpt[i];
+	}
+	else
+	{
+		for( i=0; i<nV; ++i )
+			y[i] = 0.0;
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p A u x i l i a r y Q P g r a d i e n t
+ */
+returnValue QProblemB::setupAuxiliaryQPgradient( )
+{
+	int i, j;
+	int nV = getNV( );
+
+
+	/* Setup gradient vector: g = -H*x + y'*Id. */
+	for ( i=0; i<nV; ++i )
+	{
+		/* y'*Id */
+		g[i] = y[i];
+
+		/* -H*x */
+		for ( j=0; j<nV; ++j )
+			g[i] -= H[i*NVMAX + j] * x[j];
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p A u x i l i a r y Q P b o u n d s
+ */
+returnValue QProblemB::setupAuxiliaryQPbounds( BooleanType useRelaxation )
+{
+	int i;
+	int nV = getNV( );
+
+
+	/* Setup bound vectors. */
+	for ( i=0; i<nV; ++i )
+	{
+		switch ( bounds.getStatus( i ) )
+		{
+			case ST_INACTIVE:
+				if ( useRelaxation == BT_TRUE )
+				{
+					if ( bounds.getType( i ) == ST_EQUALITY )
+					{
+						lb[i] = x[i];
+						ub[i] = x[i];
+					}
+					else
+					{
+						lb[i] = x[i] - BOUNDRELAXATION;
+						ub[i] = x[i] + BOUNDRELAXATION;
+					}
+				}
+				break;
+
+			case ST_LOWER:
+				lb[i] = x[i];
+				if ( bounds.getType( i ) == ST_EQUALITY )
+				{
+					ub[i] = x[i];
+				}
+				else
+				{
+					if ( useRelaxation == BT_TRUE )
+						ub[i] = x[i] + BOUNDRELAXATION;
+				}
+				break;
+
+			case ST_UPPER:
+				ub[i] = x[i];
+				if ( bounds.getType( i ) == ST_EQUALITY )
+				{
+					lb[i] = x[i];
+				}
+				else
+				{
+					if ( useRelaxation == BT_TRUE )
+						lb[i] = x[i] - BOUNDRELAXATION;
+				}
+				break;
+
+			default:
+				return THROWERROR( RET_UNKNOWN_BUG );
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	a d d B o u n d
+ */
+returnValue QProblemB::addBound(	int number, SubjectToStatus B_status,
+									BooleanType updateCholesky
+									)
+{
+	int i, j;
+	int nFR = getNFR( );
+
+
+	/* consistency check */
+	if ( ( getStatus( ) == QPS_NOTINITIALISED )    ||
+		 ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) ||
+		 ( getStatus( ) == QPS_HOMOTOPYQPSOLVED )  ||
+		 ( getStatus( ) == QPS_SOLVED )            )
+	{
+		return THROWERROR( RET_UNKNOWN_BUG );
+	}
+
+	/* Perform cholesky updates only if QProblemB has been initialised! */
+	if ( ( getStatus( ) == QPS_PREPARINGAUXILIARYQP ) || ( updateCholesky == BT_FALSE ) )
+	{
+		/* UPDATE INDICES */
+		if ( bounds.moveFreeToFixed( number,B_status ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_ADDBOUND_FAILED );
+
+		return SUCCESSFUL_RETURN;
+	}
+
+
+	/* I) PERFORM CHOLESKY UPDATE: */
+	/* 1) Index of variable to be added within the list of free variables. */
+	int number_idx = bounds.getFree( )->getIndex( number );
+
+	real_t c, s;
+
+	/* 2) Use row-wise Givens rotations to restore upper triangular form of R. */
+	for( i=number_idx+1; i<nFR; ++i )
+	{
+		computeGivens( R[(i-1)*NVMAX + i],R[i*NVMAX + i], R[(i-1)*NVMAX + i],R[i*NVMAX + i],c,s );
+
+		for( j=(1+i); j<nFR; ++j ) /* last column of R is thrown away */
+			applyGivens( c,s,R[(i-1)*NVMAX + j],R[i*NVMAX + j], R[(i-1)*NVMAX + j],R[i*NVMAX + j] );
+	}
+
+	/* 3) Delete <number_idx>th column and ... */
+	for( i=0; i<nFR-1; ++i )
+		for( j=number_idx+1; j<nFR; ++j )
+			R[i*NVMAX + j-1] = R[i*NVMAX + j];
+	/* ... last column of R. */
+	for( i=0; i<nFR; ++i )
+		R[i*NVMAX + nFR-1] = 0.0;
+
+
+	/* II) UPDATE INDICES */
+	if ( bounds.moveFreeToFixed( number,B_status ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ADDBOUND_FAILED );
+
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+returnValue QProblemB::removeBound(	int number,
+									BooleanType updateCholesky
+									)
+{
+	int i, ii;
+	int nFR = getNFR( );
+
+
+	/* consistency check */
+	if ( ( getStatus( ) == QPS_NOTINITIALISED )    ||
+		 ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) ||
+		 ( getStatus( ) == QPS_HOMOTOPYQPSOLVED )  ||
+		 ( getStatus( ) == QPS_SOLVED )            )
+	{
+		return THROWERROR( RET_UNKNOWN_BUG );
+	}
+
+
+	/* I) UPDATE INDICES */
+	if ( bounds.moveFixedToFree( number ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_REMOVEBOUND_FAILED );
+
+	/* Perform cholesky updates only if QProblemB has been initialised! */
+	if ( ( getStatus( ) == QPS_PREPARINGAUXILIARYQP ) || ( updateCholesky == BT_FALSE ) )
+		return SUCCESSFUL_RETURN;
+
+
+	/* II) PERFORM CHOLESKY UPDATE */
+	int FR_idx[NVMAX];
+	if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_REMOVEBOUND_FAILED );
+
+	/* 1) Calculate new column of cholesky decomposition. */
+	real_t rhs[NVMAX];
+	real_t r[NVMAX];
+	real_t r0 = H[number*NVMAX + number];
+
+	for( i=0; i<nFR; ++i )
+	{
+		ii = FR_idx[i];
+		rhs[i] = H[number*NVMAX + ii];
+	}
+
+	if ( backsolveR( rhs,BT_TRUE,BT_TRUE,r ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_REMOVEBOUND_FAILED );
+
+	for( i=0; i<nFR; ++i )
+		r0 -= r[i]*r[i];
+
+	/* 2) Store new column into R. */
+	for( i=0; i<nFR; ++i )
+		R[i*NVMAX + nFR] = r[i];
+
+	if ( r0 > 0.0 )
+		R[nFR*NVMAX + nFR] = sqrt( r0 );
+	else
+	{
+		hessianType = HST_SEMIDEF;
+		return THROWERROR( RET_HESSIAN_NOT_SPD );
+	}
+
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	b a c k s o l v e R  (CODE DUPLICATED IN QProblem CLASS!!!)
+ */
+returnValue QProblemB::backsolveR(	const real_t* const b, BooleanType transposed,
+									real_t* const a
+									)
+{
+	/* Call standard backsolve procedure (i.e. removingBound == BT_FALSE). */
+	return backsolveR( b,transposed,BT_FALSE,a );
+}
+
+
+/*
+ *	b a c k s o l v e R  (CODE DUPLICATED IN QProblem CLASS!!!)
+ */
+returnValue QProblemB::backsolveR(	const real_t* const b, BooleanType transposed,
+									BooleanType removingBound,
+									real_t* const a
+									)
+{
+	int i, j;
+	int nR = getNZ( );
+
+	real_t sum;
+
+	/* if backsolve is called while removing a bound, reduce nZ by one. */
+	if ( removingBound == BT_TRUE )
+		--nR;
+
+	/* nothing to do */
+	if ( nR <= 0 )
+		return SUCCESSFUL_RETURN;
+
+
+	/* Solve Ra = b, where R might be transposed. */
+	if ( transposed == BT_FALSE )
+	{
+		/* solve Ra = b */
+		for( i=(nR-1); i>=0; --i )
+		{
+			sum = b[i];
+			for( j=(i+1); j<nR; ++j )
+				sum -= R[i*NVMAX + j] * a[j];
+
+			if ( getAbs( R[i*NVMAX + i] ) > ZERO )
+				a[i] = sum / R[i*NVMAX + i];
+			else
+				return THROWERROR( RET_DIV_BY_ZERO );
+		}
+	}
+	else
+	{
+		/* solve R^T*a = b */
+		for( i=0; i<nR; ++i )
+		{
+			sum = b[i];
+
+			for( j=0; j<i; ++j )
+				sum -= R[j*NVMAX + i] * a[j];
+
+			if ( getAbs( R[i*NVMAX + i] ) > ZERO )
+				a[i] = sum / R[i*NVMAX + i];
+			else
+				return THROWERROR( RET_DIV_BY_ZERO );
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	h o t s t a r t _ d e t e r m i n e D a t a S h i f t
+ */
+returnValue QProblemB::hotstart_determineDataShift(	const int* const FX_idx,
+													const real_t* const g_new, const real_t* const lb_new, const real_t* const ub_new,
+													real_t* const delta_g, real_t* const delta_lb, real_t* const delta_ub,
+													BooleanType& Delta_bB_isZero
+													)
+{
+	int i, ii;
+	int nV  = getNV( );
+	int nFX = getNFX( );
+
+
+	/* 1) Calculate shift directions. */
+	for( i=0; i<nV; ++i )
+		delta_g[i]  = g_new[i]  - g[i];
+
+	if ( lb_new != 0 )
+	{
+		for( i=0; i<nV; ++i )
+			delta_lb[i] = lb_new[i] - lb[i];
+	}
+	else
+	{
+		/* if no lower bounds exist, assume the new lower bounds to be -infinity */
+		for( i=0; i<nV; ++i )
+			delta_lb[i] = -INFTY - lb[i];
+	}
+
+	if ( ub_new != 0 )
+	{
+		for( i=0; i<nV; ++i )
+			delta_ub[i] = ub_new[i] - ub[i];
+	}
+	else
+	{
+		/* if no upper bounds exist, assume the new upper bounds to be infinity */
+		for( i=0; i<nV; ++i )
+			delta_ub[i] = INFTY - ub[i];
+	}
+
+	/* 2) Determine if active bounds are to be shifted. */
+	Delta_bB_isZero = BT_TRUE;
+
+	for ( i=0; i<nFX; ++i )
+	{
+		ii = FX_idx[i];
+
+		if ( ( getAbs( delta_lb[ii] ) > EPS ) || ( getAbs( delta_ub[ii] ) > EPS ) )
+		{
+			Delta_bB_isZero = BT_FALSE;
+			break;
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	a r e B o u n d s C o n s i s t e n t
+ */
+BooleanType QProblemB::areBoundsConsistent(	const real_t* const delta_lb, const real_t* const delta_ub
+											) const
+{
+	int i;
+
+	/* Check if delta_lb[i] is greater than delta_ub[i]
+	 * for a component i whose bounds are already (numerically) equal. */
+	for( i=0; i<getNV( ); ++i )
+		if ( ( lb[i] > ub[i] - BOUNDTOL ) && ( delta_lb[i] > delta_ub[i] + EPS ) )
+			return BT_FALSE;
+
+	return BT_TRUE;
+}
+
+
+/*
+ *	s e t u p Q P d a t a
+ */
+returnValue QProblemB::setupQPdata(	const real_t* const _H, const real_t* const _R, const real_t* const _g,
+									const real_t* const _lb, const real_t* const _ub
+									)
+{
+	int i, j;
+	int nV = getNV( );
+
+	/* 1) Setup Hessian matrix and it's Cholesky factorization. */
+	if (_H != 0)
+	{
+		for( i=0; i<nV; ++i )
+			for( j=0; j<nV; ++j )
+				H[i*NVMAX + j] = _H[i*nV + j];
+		hasHessian = BT_TRUE;
+	}
+	else
+		hasHessian = BT_FALSE;
+
+	if (_R != 0)
+	{
+		for( i=0; i<nV; ++i )
+			for( j=0; j<nV; ++j )
+				R[i*NVMAX + j] = _R[i*nV + j];
+		hasCholesky = BT_TRUE;
+
+		/* If Hessian is not provided, store it's factorization in H, and that guy
+		 * is going to be used for H * x products (R^T * R * x in this case). */
+		if (hasHessian == BT_FALSE)
+			for( i=0; i<nV; ++i )
+				for( j=0; j<nV; ++j )
+					H[i*NVMAX + j] = _R[i*nV + j];
+	}
+	else
+		hasCholesky = BT_FALSE;
+
+	if (hasHessian == BT_FALSE && hasCholesky == BT_FALSE)
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	/* 2) Setup gradient vector. */
+	if ( _g == 0 )
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	for( i=0; i<nV; ++i )
+		g[i] = _g[i];
+
+	/* 3) Setup lower bounds vector. */
+	if ( _lb != 0 )
+	{
+		for( i=0; i<nV; ++i )
+			lb[i] = _lb[i];
+	}
+	else
+	{
+		/* if no lower bounds are specified, set them to -infinity */
+		for( i=0; i<nV; ++i )
+			lb[i] = -INFTY;
+	}
+
+	/* 4) Setup upper bounds vector. */
+	if ( _ub != 0 )
+	{
+		for( i=0; i<nV; ++i )
+			ub[i] = _ub[i];
+	}
+	else
+	{
+		/* if no upper bounds are specified, set them to infinity */
+		for( i=0; i<nV; ++i )
+			ub[i] = INFTY;
+	}
+
+	//printmatrix( "H",H,nV,nV );
+	//printmatrix( "R",R,nV,nV );
+	//printmatrix( "g",g,1,nV );
+	//printmatrix( "lb",lb,1,nV );
+	//printmatrix( "ub",ub,1,nV );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*****************************************************************************
+ *  P R I V A T E                                                            *
+ *****************************************************************************/
+
+/*
+ *	h o t s t a r t _ d e t e r m i n e S t e p D i r e c t i o n
+ */
+returnValue QProblemB::hotstart_determineStepDirection(	const int* const FR_idx, const int* const FX_idx,
+														const real_t* const delta_g, const real_t* const delta_lb, const real_t* const delta_ub,
+														BooleanType Delta_bB_isZero,
+														real_t* const delta_xFX, real_t* const delta_xFR,
+														real_t* const delta_yFX
+														)
+{
+	int i, j, ii, jj;
+	int nFR = getNFR( );
+	int nFX = getNFX( );
+
+
+	/* initialise auxiliary vectors */
+	real_t HMX_delta_xFX[NVMAX];
+	for( i=0; i<nFR; ++i )
+		HMX_delta_xFX[i] = 0.0;
+
+
+	/* I) DETERMINE delta_xFX */
+	if ( nFX > 0 )
+	{
+		for( i=0; i<nFX; ++i )
+		{
+			ii = FX_idx[i];
+
+			if ( bounds.getStatus( ii ) == ST_LOWER )
+				delta_xFX[i] = delta_lb[ii];
+			else
+				delta_xFX[i] = delta_ub[ii];
+		}
+	}
+
+
+	/* II) DETERMINE delta_xFR */
+	if ( nFR > 0 )
+	{
+		/* auxiliary variables */
+		real_t delta_xFRz_TMP[NVMAX];
+		real_t delta_xFRz_RHS[NVMAX];
+
+		/* Determine delta_xFRz. */
+		if ( Delta_bB_isZero == BT_FALSE )
+		{
+			for( i=0; i<nFR; ++i )
+			{
+				ii = FR_idx[i];
+				for( j=0; j<nFX; ++j )
+				{
+					jj = FX_idx[j];
+					HMX_delta_xFX[i] += H[ii*NVMAX + jj] * delta_xFX[j];
+				}
+			}
+		}
+
+		if ( Delta_bB_isZero == BT_TRUE )
+		{
+			for( j=0; j<nFR; ++j )
+			{
+				jj = FR_idx[j];
+				delta_xFRz_RHS[j] = delta_g[jj];
+			}
+		}
+		else
+		{
+			for( j=0; j<nFR; ++j )
+			{
+				jj = FR_idx[j];
+				delta_xFRz_RHS[j] = delta_g[jj] + HMX_delta_xFX[j]; /* *ZFR */
+			}
+		}
+
+		for( i=0; i<nFR; ++i )
+			delta_xFR[i] = -delta_xFRz_RHS[i];
+
+		if ( backsolveR( delta_xFR,BT_TRUE,delta_xFRz_TMP ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_STEPDIRECTION_FAILED_CHOLESKY );
+
+		if ( backsolveR( delta_xFRz_TMP,BT_FALSE,delta_xFR ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_STEPDIRECTION_FAILED_CHOLESKY );
+	}
+
+
+	/* III) DETERMINE delta_yFX */
+	if ( nFX > 0 )
+	{
+		for( i=0; i<nFX; ++i )
+		{
+			ii = FX_idx[i];
+
+			delta_yFX[i] = 0.0;
+			for( j=0; j<nFR; ++j )
+			{
+				jj = FR_idx[j];
+				delta_yFX[i] += H[ii*NVMAX + jj] * delta_xFR[j];
+			}
+
+			if ( Delta_bB_isZero == BT_FALSE )
+			{
+				for( j=0; j<nFX; ++j )
+				{
+					jj = FX_idx[j];
+					delta_yFX[i] += H[ii*NVMAX + jj] * delta_xFX[j];
+				}
+			}
+
+			delta_yFX[i] += delta_g[ii];
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	h o t s t a r t _ d e t e r m i n e S t e p L e n g t h
+ */
+returnValue QProblemB::hotstart_determineStepLength(	const int* const FR_idx, const int* const FX_idx,
+														const real_t* const delta_lb, const real_t* const delta_ub,
+														const real_t* const delta_xFR,
+														const real_t* const delta_yFX,
+														int& BC_idx, SubjectToStatus& BC_status
+														)
+{
+	int i, ii;
+	int nFR = getNFR( );
+	int nFX = getNFX( );
+
+	real_t tau_tmp;
+	real_t tau_new = 1.0;
+
+	BC_idx = 0;
+	BC_status = ST_UNDEFINED;
+
+
+	/* I) DETERMINE MAXIMUM DUAL STEPLENGTH, i.e. ensure that
+	 *    active dual bounds remain valid (ignoring implicitly fixed variables): */
+	for( i=0; i<nFX; ++i )
+	{
+		ii = FX_idx[i];
+
+		if ( bounds.getType( ii ) != ST_EQUALITY )
+		{
+			if ( bounds.getStatus( ii ) == ST_LOWER )
+			{
+				/* 1) Active lower bounds. */
+				if ( ( delta_yFX[i] < -ZERO ) && ( y[ii] >= 0.0 ) )
+				{
+					tau_tmp = y[ii] / ( -delta_yFX[i] );
+					if ( tau_tmp < tau_new )
+					{
+						if ( tau_tmp >= 0.0 )
+						{
+							tau_new = tau_tmp;
+							BC_idx = ii;
+							BC_status = ST_INACTIVE;
+						}
+					}
+				}
+			}
+			else
+			{
+				/* 2) Active upper bounds. */
+				if ( ( delta_yFX[i] > ZERO ) && ( y[ii] <= 0.0 ) )
+				{
+					tau_tmp = y[ii] / ( -delta_yFX[i] );
+					if ( tau_tmp < tau_new )
+					{
+						if ( tau_tmp >= 0.0 )
+						{
+							tau_new = tau_tmp;
+							BC_idx = ii;
+							BC_status = ST_INACTIVE;
+						}
+					}
+				}
+			}
+		}
+	}
+
+
+	/* II) DETERMINE MAXIMUM PRIMAL STEPLENGTH, i.e. ensure that
+	 *     inactive bounds remain valid (ignoring unbounded variables). */
+	/* 1) Inactive lower bounds. */
+	if ( bounds.isNoLower( ) == BT_FALSE )
+	{
+		for( i=0; i<nFR; ++i )
+		{
+			ii = FR_idx[i];
+
+			if ( bounds.getType( ii ) != ST_UNBOUNDED )
+			{
+				if ( delta_lb[ii] > delta_xFR[i] )
+				{
+					if ( x[ii] > lb[ii] )
+						tau_tmp = ( x[ii] - lb[ii] ) / ( delta_lb[ii] - delta_xFR[i] );
+					else
+						tau_tmp = 0.0;
+
+					if ( tau_tmp < tau_new )
+					{
+						if ( tau_tmp >= 0.0 )
+						{
+							tau_new = tau_tmp;
+							BC_idx = ii;
+							BC_status = ST_LOWER;
+						}
+					}
+				}
+			}
+		}
+	}
+
+	/* 2) Inactive upper bounds. */
+	if ( bounds.isNoUpper( ) == BT_FALSE )
+	{
+		for( i=0; i<nFR; ++i )
+		{
+			ii = FR_idx[i];
+
+			if ( bounds.getType( ii ) != ST_UNBOUNDED )
+			{
+				if ( delta_ub[ii] < delta_xFR[i] )
+				{
+					if ( x[ii] < ub[ii] )
+						tau_tmp = ( x[ii] - ub[ii] ) / ( delta_ub[ii] - delta_xFR[i] );
+					else
+						tau_tmp = 0.0;
+
+					if ( tau_tmp < tau_new )
+					{
+						if ( tau_tmp >= 0.0 )
+						{
+							tau_new = tau_tmp;
+							BC_idx = ii;
+							BC_status = ST_UPPER;
+						}
+					}
+				}
+			}
+		}
+	}
+
+
+	/* III) SET MAXIMUM HOMOTOPY STEPLENGTH */
+	tau = tau_new;
+
+	if ( printlevel ==  PL_HIGH )
+	{
+		#ifdef PC_DEBUG
+		char messageString[80];
+
+		if ( BC_status == ST_UNDEFINED )
+			sprintf( messageString,"Stepsize is %.6e!",tau );
+		else
+			sprintf( messageString,"Stepsize is %.6e! (BC_idx = %d, BC_status = %d)",tau,BC_idx,BC_status );
+
+		getGlobalMessageHandler( )->throwInfo( RET_STEPSIZE_NONPOSITIVE,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		#endif
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	h o t s t a r t _ p e r f o r m S t e p
+ */
+returnValue QProblemB::hotstart_performStep(	const int* const FR_idx, const int* const FX_idx,
+												const real_t* const delta_g, const real_t* const  delta_lb, const real_t* const delta_ub,
+												const real_t* const delta_xFX, const real_t* const delta_xFR,
+												const real_t* const delta_yFX,
+												int BC_idx, SubjectToStatus BC_status
+												)
+{
+	int i, ii;
+	int nV  = getNV( );
+	int nFR = getNFR( );
+	int nFX = getNFX( );
+
+
+	/* I) CHECK BOUNDS' CONSISTENCY */
+	if ( areBoundsConsistent( delta_lb,delta_ub ) == BT_FALSE )
+	{
+		infeasible = BT_TRUE;
+		tau = 0.0;
+
+		return THROWERROR( RET_QP_INFEASIBLE );
+	}
+
+
+	/* II) GO TO ACTIVE SET CHANGE */
+	if ( tau > ZERO )
+	{
+		/* 1) Perform step in primal und dual space. */
+		for( i=0; i<nFR; ++i )
+		{
+			ii = FR_idx[i];
+			x[ii] += tau*delta_xFR[i];
+		}
+
+		for( i=0; i<nFX; ++i )
+		{
+			ii = FX_idx[i];
+			x[ii] += tau*delta_xFX[i];
+			y[ii] += tau*delta_yFX[i];
+		}
+
+		/* 2) Shift QP data. */
+		for( i=0; i<nV; ++i )
+		{
+			g[i]  += tau*delta_g[i];
+			lb[i] += tau*delta_lb[i];
+			ub[i] += tau*delta_ub[i];
+		}
+	}
+	else
+	{
+		/* print a stepsize warning if stepsize is zero */
+		#ifdef PC_DEBUG
+		char messageString[80];
+		sprintf( messageString,"Stepsize is %.6e",tau );
+		getGlobalMessageHandler( )->throwWarning( RET_STEPSIZE,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		#endif
+	}
+
+
+	/* setup output preferences */
+	#ifdef PC_DEBUG
+	char messageString[80];
+  	VisibilityStatus visibilityStatus;
+
+  	if ( printlevel == PL_HIGH )
+		visibilityStatus = VS_VISIBLE;
+	else
+		visibilityStatus = VS_HIDDEN;
+	#endif
+
+
+	/* III) UPDATE ACTIVE SET */
+	switch ( BC_status )
+	{
+		/* Optimal solution found as no working set change detected. */
+		case ST_UNDEFINED:
+			return RET_OPTIMAL_SOLUTION_FOUND;
+
+
+		/* Remove one variable from active set. */
+		case ST_INACTIVE:
+			#ifdef PC_DEBUG
+			sprintf( messageString,"bound no. %d.", BC_idx );
+			getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus );
+			#endif
+
+			if ( removeBound( BC_idx,BT_TRUE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED );
+
+			y[BC_idx] = 0.0;
+			break;
+
+
+		/* Add one variable to active set. */
+		default:
+			#ifdef PC_DEBUG
+			if ( BC_status == ST_LOWER )
+				sprintf( messageString,"lower bound no. %d.", BC_idx );
+			else
+				sprintf( messageString,"upper bound no. %d.", BC_idx );
+				getGlobalMessageHandler( )->throwInfo( RET_ADD_TO_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus );
+			#endif
+
+			if ( addBound( BC_idx,BC_status,BT_TRUE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_ADD_TO_ACTIVESET_FAILED );
+			break;
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+#ifdef PC_DEBUG  /* Define print functions only for debugging! */
+
+/*
+ *	p r i n t I t e r a t i o n
+ */
+returnValue QProblemB::printIteration( 	int iteration,
+										int BC_idx,	SubjectToStatus BC_status
+		  								)
+{
+	char myPrintfString[160];
+
+	/* consistency check */
+	if ( iteration < 0 )
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	/* nothing to do */
+	if ( printlevel != PL_MEDIUM )
+		return SUCCESSFUL_RETURN;
+
+
+	/* 1) Print header at first iteration. */
+ 	if ( iteration == 0 )
+	{
+		sprintf( myPrintfString,"\n##############  qpOASES  --  QP NO.%4.1d  ###############\n", count );
+		myPrintf( myPrintfString );
+
+		sprintf( myPrintfString,"   Iter   |   StepLength    |       Info      |   nFX   \n" );
+		myPrintf( myPrintfString );
+	}
+
+	/* 2) Print iteration line. */
+	if ( BC_status == ST_UNDEFINED )
+	{
+		sprintf( myPrintfString,"   %4.1d   |   %1.5e   |    QP SOLVED    |  %4.1d   \n", iteration,tau,getNFX( ) );
+		myPrintf( myPrintfString );
+	}
+	else
+	{
+		char info[8];
+
+		if ( BC_status == ST_INACTIVE )
+			sprintf( info,"REM BND" );
+		else
+			sprintf( info,"ADD BND" );
+
+		sprintf( myPrintfString,"   %4.1d   |   %1.5e   |   %s%4.1d   |  %4.1d   \n", iteration,tau,info,BC_idx,getNFX( ) );
+		myPrintf( myPrintfString );
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+#endif  /* PC_DEBUG */
+
+
+
+/*
+ *	c h e c k K K T c o n d i t i o n s
+ */
+returnValue QProblemB::checkKKTconditions( )
+{
+	#ifdef __PERFORM_KKT_TEST__
+
+	int i, j;
+	int nV = getNV( );
+
+	real_t tmp;
+	real_t maxKKTviolation = 0.0;
+
+
+	/* 1) Check for Hx + g - y*A' = 0  (here: A = Id). */
+	for( i=0; i<nV; ++i )
+	{
+		tmp = g[i];
+
+		for( j=0; j<nV; ++j )
+			tmp += H[i*nV + j] * x[j];
+
+		tmp -= y[i];
+
+		if ( getAbs( tmp ) > maxKKTviolation )
+			maxKKTviolation = getAbs( tmp );
+	}
+
+	/* 2) Check for lb <= x <= ub. */
+	for( i=0; i<nV; ++i )
+	{
+		if ( lb[i] - x[i] > maxKKTviolation )
+			maxKKTviolation = lb[i] - x[i];
+
+		if ( x[i] - ub[i] > maxKKTviolation )
+			maxKKTviolation = x[i] - ub[i];
+	}
+
+	/* 3) Check for correct sign of y and for complementary slackness. */
+	for( i=0; i<nV; ++i )
+	{
+		switch ( bounds.getStatus( i ) )
+		{
+			case ST_LOWER:
+				if ( -y[i] > maxKKTviolation )
+					maxKKTviolation = -y[i];
+				if ( getAbs( ( x[i] - lb[i] ) * y[i] ) > maxKKTviolation )
+					maxKKTviolation = getAbs( ( x[i] - lb[i] ) * y[i] );
+				break;
+
+			case ST_UPPER:
+				if ( y[i] > maxKKTviolation )
+					maxKKTviolation = y[i];
+				if ( getAbs( ( ub[i] - x[i] ) * y[i] ) > maxKKTviolation )
+					maxKKTviolation = getAbs( ( ub[i] - x[i] ) * y[i] );
+				break;
+
+			default: /* inactive */
+			if ( getAbs( y[i] ) > maxKKTviolation )
+					maxKKTviolation = getAbs( y[i] );
+				break;
+		}
+	}
+
+	if ( maxKKTviolation > CRITICALACCURACY )
+		return RET_NO_SOLUTION;
+
+	if ( maxKKTviolation > DESIREDACCURACY )
+		return RET_INACCURATE_SOLUTION;
+
+	#endif /* __PERFORM_KKT_TEST__ */
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblemB.ipp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblemB.ipp
new file mode 100644
index 0000000000000000000000000000000000000000..0b031301e6c41531e9a7f25bf888c1d20e62c371
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/QProblemB.ipp
@@ -0,0 +1,425 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/QProblemB.ipp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of inlined member functions of the QProblemB class which 
+ *	is able to use the newly developed online active set strategy for 
+ *	parametric quadratic programming.
+ */
+
+
+
+#include <math.h>
+
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+/*
+ *	g e t H
+ */
+inline returnValue QProblemB::getH( real_t* const _H ) const
+{
+	int i;
+
+	for ( i=0; i<getNV( )*getNV( ); ++i )
+		_H[i] = H[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t G
+ */
+inline returnValue QProblemB::getG( real_t* const _g ) const
+{
+	int i;
+
+	for ( i=0; i<getNV( ); ++i )
+		_g[i] = g[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t L B
+ */
+inline returnValue QProblemB::getLB( real_t* const _lb ) const
+{
+	int i;
+
+	for ( i=0; i<getNV( ); ++i )
+		_lb[i] = lb[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t L B
+ */
+inline returnValue QProblemB::getLB( int number, real_t& value ) const
+{
+	if ( ( number >= 0 ) && ( number < getNV( ) ) )
+	{
+		value = lb[number];
+		return SUCCESSFUL_RETURN;
+	}
+	else
+	{
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+	}
+}
+
+
+/*
+ *	g e t U B
+ */
+inline returnValue QProblemB::getUB( real_t* const _ub ) const
+{
+	int i;
+
+	for ( i=0; i<getNV( ); ++i )
+		_ub[i] = ub[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t U B
+ */
+inline returnValue QProblemB::getUB( int number, real_t& value ) const
+{
+	if ( ( number >= 0 ) && ( number < getNV( ) ) )
+	{
+		value = ub[number];
+		return SUCCESSFUL_RETURN;
+	}
+	else
+	{
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+	}
+}
+
+
+/*
+ *	g e t B o u n d s
+ */
+inline returnValue QProblemB::getBounds( Bounds* const _bounds ) const
+{
+	*_bounds = bounds;
+	
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t N V
+ */
+inline int QProblemB::getNV( ) const
+{
+	return bounds.getNV( );
+}
+
+
+/*
+ *	g e t N F R
+ */
+inline int QProblemB::getNFR( )
+{
+	return bounds.getNFR( );
+}
+
+
+/*
+ *	g e t N F X
+ */
+inline int QProblemB::getNFX( )
+{
+	return bounds.getNFX( );
+}
+
+
+/*
+ *	g e t N F V
+ */
+inline int QProblemB::getNFV( ) const
+{
+	return bounds.getNFV( );
+}
+
+
+/*
+ *	g e t S t a t u s
+ */
+inline QProblemStatus QProblemB::getStatus( ) const
+{
+	return status;
+}
+
+
+/*
+ *	i s I n i t i a l i s e d
+ */
+inline BooleanType QProblemB::isInitialised( ) const
+{
+	if ( status == QPS_NOTINITIALISED )
+		return BT_FALSE;
+	else
+		return BT_TRUE;
+}
+
+
+/*
+ *	i s S o l v e d
+ */
+inline BooleanType QProblemB::isSolved( ) const
+{
+	if ( status == QPS_SOLVED )
+		return BT_TRUE;
+	else
+		return BT_FALSE;
+}
+
+
+/*
+ *	i s I n f e a s i b l e
+ */
+inline BooleanType QProblemB::isInfeasible( ) const
+{
+	return infeasible;
+}
+
+
+/*
+ *	i s U n b o u n d e d
+ */
+inline BooleanType QProblemB::isUnbounded( ) const
+{
+	return unbounded;
+}
+
+
+/*
+ *	g e t P r i n t L e v e l
+ */
+inline PrintLevel QProblemB::getPrintLevel( ) const
+{
+	return printlevel;
+}
+
+
+/*
+ *	g e t H e s s i a n T y p e
+ */
+inline HessianType QProblemB::getHessianType( ) const
+{
+	return hessianType;
+}
+
+
+/*
+ *	s e t H e s s i a n T y p e
+ */
+inline returnValue QProblemB::setHessianType( HessianType _hessianType )
+{
+	hessianType = _hessianType;
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*****************************************************************************
+ *  P R O T E C T E D                                                        *
+ *****************************************************************************/
+
+/*
+ *	s e t H
+ */
+inline returnValue QProblemB::setH( const real_t* const H_new )
+{
+	int i, j;
+
+	int nV = getNV();
+
+	for( i=0; i<nV; ++i )
+		for( j=0; j<nV; ++j )
+			H[i*NVMAX + j] = H_new[i*nV + j];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t G
+ */
+inline returnValue QProblemB::setG( const real_t* const g_new )
+{
+	int i;
+
+	int nV = getNV();
+
+	for( i=0; i<nV; ++i )
+		g[i] = g_new[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t L B
+ */
+inline returnValue QProblemB::setLB( const real_t* const lb_new )
+{
+	int i;
+
+	int nV = getNV();
+
+	for( i=0; i<nV; ++i )
+		lb[i] = lb_new[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t L B
+ */
+inline returnValue QProblemB::setLB( int number, real_t value )
+{
+	if ( ( number >= 0 ) && ( number < getNV( ) ) )
+	{
+		lb[number] = value;
+		return SUCCESSFUL_RETURN;
+	}
+	else
+	{
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+	}
+}
+
+
+/*
+ *	s e t U B
+ */
+inline returnValue QProblemB::setUB( const real_t* const ub_new )
+{
+	int i;
+
+	int nV = getNV();
+
+	for( i=0; i<nV; ++i )
+		ub[i] = ub_new[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t U B
+ */
+inline returnValue QProblemB::setUB( int number, real_t value )
+{
+	if ( ( number >= 0 ) && ( number < getNV( ) ) )
+	{
+		ub[number] = value;
+
+		return SUCCESSFUL_RETURN;
+	}
+	else
+	{
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+	}
+}
+
+
+/*
+ *	c o m p u t e G i v e n s
+ */
+inline void QProblemB::computeGivens(	real_t xold, real_t yold, real_t& xnew, real_t& ynew,
+										real_t& c, real_t& s 
+										) const
+{
+    if ( getAbs( yold ) <= ZERO )
+	{
+        c = 1.0;
+        s = 0.0;
+		
+		xnew = xold;
+		ynew = yold;
+	}
+    else
+	{
+		real_t t, mu;
+
+        mu = getAbs( xold );
+		if ( getAbs( yold ) > mu )
+			mu = getAbs( yold );
+		
+        t = mu * sqrt( (xold/mu)*(xold/mu) + (yold/mu)*(yold/mu) );
+		
+		if ( xold < 0.0 )
+            t = -t;
+		
+        c = xold/t;
+        s = yold/t;
+        xnew = t;
+        ynew = 0.0;
+	}
+	
+	return;
+}
+
+		
+/*
+ *	a p p l y G i v e n s
+ */
+inline void QProblemB::applyGivens(	real_t c, real_t s, real_t xold, real_t yold,
+									real_t& xnew, real_t& ynew 
+									) const
+{
+	/* Usual Givens plane rotation requiring four multiplications. */
+	xnew =  c*xold + s*yold;
+	ynew = -s*xold + c*yold;
+// 	double nu = s/(1.0+c);
+// 
+// 	xnew = xold*c + yold*s;
+// 	ynew = (xnew+xold)*nu - yold;
+	
+	return;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/SubjectTo.cpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/SubjectTo.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..371f0d76d3278143bcdcd786bfb7b755d49de50d
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/SubjectTo.cpp
@@ -0,0 +1,200 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/SubjectTo.cpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of the SubjectTo class designed to manage working sets of
+ *	constraints and bounds within a QProblem.
+ */
+
+
+#include <SubjectTo.hpp>
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+
+/*
+ *	S u b j e c t T o
+ */
+SubjectTo::SubjectTo( ) :	noLower( BT_TRUE ),
+							noUpper( BT_TRUE ),
+							size( 0 )
+{
+	int i;
+
+	for( i=0; i<size; ++i )
+	{
+		type[i] = ST_UNKNOWN;
+		status[i] = ST_UNDEFINED;
+	}
+}
+
+
+/*
+ *	S u b j e c t T o
+ */
+SubjectTo::SubjectTo( const SubjectTo& rhs ) :	noLower( rhs.noLower ),
+												noUpper( rhs.noUpper ),
+												size( rhs.size )
+{
+	int i;
+
+	for( i=0; i<size; ++i )
+	{
+		type[i] = rhs.type[i];
+		status[i] = rhs.status[i];
+	}
+}
+
+
+/*
+ *	~ S u b j e c t T o
+ */
+SubjectTo::~SubjectTo( )
+{
+}
+
+
+/*
+ *	o p e r a t o r =
+ */
+SubjectTo& SubjectTo::operator=( const SubjectTo& rhs )
+{
+	int i;
+
+	if ( this != &rhs )
+	{
+		size = rhs.size;
+
+		for( i=0; i<size; ++i )
+		{
+			type[i] = rhs.type[i];
+			status[i] = rhs.status[i];
+		}
+
+		noLower = rhs.noLower;
+		noUpper = rhs.noUpper;
+	}
+
+	return *this;
+}
+
+
+
+/*
+ *	i n i t
+ */
+returnValue SubjectTo::init( int n )
+{
+	int i;
+
+	size = n;
+
+	noLower = BT_TRUE;
+	noUpper = BT_TRUE;
+
+	for( i=0; i<size; ++i )
+	{
+		type[i] = ST_UNKNOWN;
+		status[i] = ST_UNDEFINED;
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*****************************************************************************
+ *  P R O T E C T E D                                                        *
+ *****************************************************************************/
+
+/*
+ *	a d d I n d e x
+ */
+returnValue SubjectTo::addIndex(	Indexlist* const indexlist,
+									int newnumber, SubjectToStatus newstatus
+									)
+{
+	/* consistency check */
+	if ( status[newnumber] == newstatus )
+		return THROWERROR( RET_INDEX_ALREADY_OF_DESIRED_STATUS );
+
+	status[newnumber] = newstatus;
+
+	if ( indexlist->addNumber( newnumber ) == RET_INDEXLIST_EXCEEDS_MAX_LENGTH )
+		return THROWERROR( RET_ADDINDEX_FAILED );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	r e m o v e I n d e x
+ */
+returnValue SubjectTo::removeIndex(	Indexlist* const indexlist, 
+									int removenumber
+									)
+{
+	status[removenumber] = ST_UNDEFINED;
+
+	if ( indexlist->removeNumber( removenumber ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_UNKNOWN_BUG );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s w a p I n d e x
+ */
+returnValue SubjectTo::swapIndex(	Indexlist* const indexlist,
+									int number1, int number2
+									)
+{
+	/* consistency checks */
+	if ( status[number1] != status[number2] )
+		return THROWERROR( RET_SWAPINDEX_FAILED );
+
+	if ( number1 == number2 )
+	{
+		THROWWARNING( RET_NOTHING_TO_DO );
+		return SUCCESSFUL_RETURN;
+	}
+
+	if ( indexlist->swapNumbers( number1,number2 ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_SWAPINDEX_FAILED );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/SubjectTo.ipp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/SubjectTo.ipp
new file mode 100644
index 0000000000000000000000000000000000000000..32215ba7e458552ffa734b57b59d220ee11bc02d
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/SubjectTo.ipp
@@ -0,0 +1,132 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/SubjectTo.ipp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of the inlined member functions of the SubjectTo class 
+ *	designed to manage working sets of constraints and bounds within a QProblem.
+ */
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+ 
+
+/*
+ *	g e t T y p e
+ */
+inline SubjectToType SubjectTo::getType( int i ) const
+{
+	if ( ( i >= 0 ) && ( i < size ) )
+		return type[i];
+	else
+		return ST_UNKNOWN;
+}
+
+
+/*
+ *	g e t S t a t u s
+ */
+inline SubjectToStatus SubjectTo::getStatus( int i ) const
+{
+	if ( ( i >= 0 ) && ( i < size ) )
+		return status[i];
+	else
+		return ST_UNDEFINED;
+}
+
+
+/*
+ *	s e t T y p e
+ */
+inline returnValue SubjectTo::setType( int i, SubjectToType value )
+{
+	if ( ( i >= 0 ) && ( i < size ) )
+	{
+		type[i] = value;
+		return SUCCESSFUL_RETURN;
+	}
+	else
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+}
+
+
+/*
+ *	s e t S t a t u s
+ */
+inline returnValue SubjectTo::setStatus( int i, SubjectToStatus value )
+{
+	if ( ( i >= 0 ) && ( i < size ) )
+	{
+		status[i] = value;
+		return SUCCESSFUL_RETURN;
+	}
+	else
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+}
+
+
+/*
+ *	s e t N o L o w e r
+ */
+inline void SubjectTo::setNoLower( BooleanType _status )
+{
+	noLower = _status;
+}
+ 
+
+/*
+ *	s e t N o U p p e r
+ */
+inline void SubjectTo::setNoUpper( BooleanType _status )
+{
+	noUpper = _status;
+}
+
+
+/*
+ *	i s N o L o w e r
+ */
+inline BooleanType SubjectTo::isNoLower( ) const
+{
+	return noLower;
+}
+
+ 
+/*
+ *	i s N o L o w e r
+ */
+inline BooleanType SubjectTo::isNoUpper( ) const
+{
+	return noUpper;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Utils.cpp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Utils.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..c11722c4797d99c4dd90f794eb3d880a54eb14d2
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Utils.cpp
@@ -0,0 +1,471 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/Utils.cpp
+ *	\author Hans Joachim Ferreau, Eckhard Arnold
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of some inlined utilities for working with the different QProblem
+ *  classes.
+ */
+
+
+#include <math.h>
+
+#if defined(__WIN32__) || defined(WIN32)
+  #include <windows.h>
+#elif defined(LINUX)
+  #include <sys/stat.h>
+  #include <sys/time.h>
+#endif
+
+#ifdef __MATLAB__
+  #include <mex.h>
+#endif
+
+
+#include <Utils.hpp>
+
+
+
+#ifdef PC_DEBUG  /* Define print functions only for debugging! */
+/*
+ *	p r i n t
+ */
+returnValue print( const real_t* const v, int n )
+{
+	int i;
+	char myPrintfString[160];
+
+	/* Print a vector. */
+	myPrintf( "[\t" );
+	for( i=0; i<n; ++i )
+	{
+		sprintf( myPrintfString," %.16e\t", v[i] );
+		myPrintf( myPrintfString );
+	}
+	myPrintf( "]\n" );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	p r i n t
+ */
+returnValue print(	const real_t* const v, int n,
+					const int* const V_idx
+					)
+{
+	int i;
+	char myPrintfString[160];
+
+	/* Print a permuted vector. */
+	myPrintf( "[\t" );
+	for( i=0; i<n; ++i )
+	{
+		sprintf( myPrintfString," %.16e\t", v[ V_idx[i] ] );
+		myPrintf( myPrintfString );
+	}
+	myPrintf( "]\n" );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	p r i n t
+ */
+returnValue print(	const real_t* const v, int n,
+					const char* name
+					)
+{
+	char myPrintfString[160];
+
+	/* Print vector name ... */
+	sprintf( myPrintfString,"%s = ", name );
+	myPrintf( myPrintfString );
+
+	/* ... and the vector itself. */
+	return print( v, n );
+}
+
+
+/*
+ *	p r i n t
+ */
+returnValue print( const real_t* const M, int nrow, int ncol )
+{
+	int i;
+
+	/* Print a matrix as a collection of row vectors. */
+	for( i=0; i<nrow; ++i )
+		print( &(M[i*ncol]), ncol );
+	myPrintf( "\n" );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	p r i n t
+ */
+returnValue print(	const real_t* const M, int nrow, int ncol,
+					const int* const ROW_idx, const int* const COL_idx
+					)
+{
+	int i;
+
+	/* Print a permuted matrix as a collection of permuted row vectors. */
+	for( i=0; i<nrow; ++i )
+		print( &( M[ ROW_idx[i]*ncol ] ), ncol, COL_idx );
+	myPrintf( "\n" );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	p r i n t
+ */
+returnValue print(	const real_t* const M, int nrow, int ncol,
+					const char* name
+					)
+{
+	char myPrintfString[160];
+
+	/* Print matrix name ... */
+	sprintf( myPrintfString,"%s = ", name );
+	myPrintf( myPrintfString );
+
+	/* ... and the matrix itself. */
+	return print( M, nrow, ncol );
+}
+
+
+/*
+ *	p r i n t
+ */
+returnValue print( const int* const index, int n )
+{
+	int i;
+	char myPrintfString[160];
+
+	/* Print a indexlist. */
+	myPrintf( "[\t" );
+	for( i=0; i<n; ++i )
+	{
+		sprintf( myPrintfString," %d\t", index[i] );
+		myPrintf( myPrintfString );
+	}
+	myPrintf( "]\n" );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	p r i n t
+ */
+returnValue print(	const int* const index, int n,
+					const char* name
+					)
+{
+	char myPrintfString[160];
+
+	/* Print indexlist name ... */
+	sprintf( myPrintfString,"%s = ", name );
+	myPrintf( myPrintfString );
+
+	/* ... and the indexlist itself. */
+	return print( index, n );
+}
+
+
+/*
+ *	m y P r i n t f
+ */
+returnValue myPrintf( const char* s )
+{
+	#ifdef __MATLAB__
+	mexPrintf( s );
+	#else
+	myFILE* outputfile = getGlobalMessageHandler( )->getOutputFile( );
+	if ( outputfile == 0 )
+		return THROWERROR( RET_NO_GLOBAL_MESSAGE_OUTPUTFILE );
+
+	fprintf( outputfile, "%s", s );
+	#endif
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	p r i n t C o p y r i g h t N o t i c e
+ */
+returnValue printCopyrightNotice( )
+{
+	return myPrintf( "\nqpOASES -- An Implementation of the Online Active Set Strategy.\nCopyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.\n\nqpOASES is distributed under the terms of the \nGNU Lesser General Public License 2.1 in the hope that it will be \nuseful, but WITHOUT ANY WARRANTY; without even the implied warranty \nof MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. \nSee the GNU Lesser General Public License for more details.\n\n" );
+}
+
+
+/*
+ *	r e a d F r o m F i l e
+ */
+returnValue readFromFile(	real_t* data, int nrow, int ncol,
+							const char* datafilename
+							)
+{
+	int i, j;
+	float float_data;
+	myFILE* datafile;
+
+	/* 1) Open file. */
+	if ( ( datafile = fopen( datafilename, "r" ) ) == 0 )
+	{
+		char errstr[80];
+		sprintf( errstr,"(%s)",datafilename );
+		return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+	}
+
+	/* 2) Read data from file. */
+	for( i=0; i<nrow; ++i )
+	{
+		for( j=0; j<ncol; ++j )
+		{
+			if ( fscanf( datafile, "%f ", &float_data ) == 0 )
+			{
+				fclose( datafile );
+				char errstr[80];
+				sprintf( errstr,"(%s)",datafilename );
+				return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_READ_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+			}
+			data[i*ncol + j] = ( (real_t) float_data );
+		}
+	}
+
+	/* 3) Close file. */
+	fclose( datafile );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	r e a d F r o m F i l e
+ */
+returnValue readFromFile(	real_t* data, int n,
+							const char* datafilename
+							)
+{
+	return readFromFile( data, n, 1, datafilename );
+}
+
+
+
+/*
+ *	r e a d F r o m F i l e
+ */
+returnValue readFromFile(	int* data, int n,
+							const char* datafilename
+							)
+{
+	int i;
+	myFILE* datafile;
+
+	/* 1) Open file. */
+	if ( ( datafile = fopen( datafilename, "r" ) ) == 0 )
+	{
+		char errstr[80];
+		sprintf( errstr,"(%s)",datafilename );
+		return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+	}
+
+	/* 2) Read data from file. */
+	for( i=0; i<n; ++i )
+	{
+		if ( fscanf( datafile, "%d\n", &(data[i]) ) == 0 )
+		{
+			fclose( datafile );
+			char errstr[80];
+			sprintf( errstr,"(%s)",datafilename );
+			return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_READ_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		}
+	}
+
+	/* 3) Close file. */
+	fclose( datafile );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	w r i t e I n t o F i l e
+ */
+returnValue writeIntoFile(	const real_t* const data, int nrow, int ncol,
+							const char* datafilename, BooleanType append
+							)
+{
+	int i, j;
+	myFILE* datafile;
+
+	/* 1) Open file. */
+	if ( append == BT_TRUE )
+	{
+		/* append data */
+		if ( ( datafile = fopen( datafilename, "a" ) ) == 0 )
+		{
+			char errstr[80];
+			sprintf( errstr,"(%s)",datafilename );
+			return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		}
+	}
+	else
+	{
+		/* do not append data */
+		if ( ( datafile = fopen( datafilename, "w" ) ) == 0 )
+		{
+			char errstr[80];
+			sprintf( errstr,"(%s)",datafilename );
+			return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		}
+	}
+
+	/* 2) Write data into file. */
+	for( i=0; i<nrow; ++i )
+	{
+		for( j=0; j<ncol; ++j )
+		 	fprintf( datafile, "%.16e ", data[i*ncol+j] );
+
+		fprintf( datafile, "\n" );
+	}
+
+	/* 3) Close file. */
+	fclose( datafile );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	w r i t e I n t o F i l e
+ */
+returnValue writeIntoFile(	const real_t* const data, int n,
+							const char* datafilename, BooleanType append
+							)
+{
+	return writeIntoFile( data,1,n,datafilename,append );
+}
+
+
+/*
+ *	w r i t e I n t o F i l e
+ */
+returnValue writeIntoFile(	const int* const data, int n,
+							const char* datafilename, BooleanType append
+							)
+{
+	int i;
+
+	myFILE* datafile;
+
+	/* 1) Open file. */
+	if ( append == BT_TRUE )
+	{
+		/* append data */
+		if ( ( datafile = fopen( datafilename, "a" ) ) == 0 )
+		{
+			char errstr[80];
+			sprintf( errstr,"(%s)",datafilename );
+			return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		}
+	}
+	else
+	{
+		/* do not append data */
+		if ( ( datafile = fopen( datafilename, "w" ) ) == 0 )
+		{
+			char errstr[80];
+			sprintf( errstr,"(%s)",datafilename );
+			return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		}
+	}
+
+	/* 2) Write data into file. */
+	for( i=0; i<n; ++i )
+		fprintf( datafile, "%d\n", data[i] );
+
+	/* 3) Close file. */
+	fclose( datafile );
+
+	return SUCCESSFUL_RETURN;
+}
+#endif  /* PC_DEBUG */
+
+
+/*
+ *	g e t C P U t i m e
+ */
+real_t getCPUtime( )
+{
+	real_t current_time = -1.0;
+
+	#if defined(__WIN32__) || defined(WIN32)
+	LARGE_INTEGER counter, frequency;
+	QueryPerformanceFrequency(&frequency);
+	QueryPerformanceCounter(&counter);
+	current_time = ((real_t) counter.QuadPart) / ((real_t) frequency.QuadPart);
+	#elif defined(LINUX)
+	struct timeval theclock;
+	gettimeofday( &theclock,0 );
+	current_time = 1.0*theclock.tv_sec + 1.0e-6*theclock.tv_usec;
+	#endif
+
+	return current_time;
+}
+
+
+/*
+ *	g e t N o r m
+ */
+real_t getNorm( const real_t* const v, int n )
+{
+	int i;
+
+	real_t norm = 0.0;
+
+	for( i=0; i<n; ++i )
+		norm += v[i]*v[i];
+
+	return sqrt( norm );
+}
+
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Utils.ipp b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Utils.ipp
new file mode 100644
index 0000000000000000000000000000000000000000..861bdb3726717da533849c02f0e16f516d182ce7
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/SRC/Utils.ipp
@@ -0,0 +1,51 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+
+/**
+ *	\file SRC/Utils.ipp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of some inlined utilities for working with the different QProblem 
+ *  classes.
+ */
+
+
+
+/*
+ *	g e t A b s
+ */
+inline real_t getAbs( real_t x )
+{
+	if ( x < 0.0 )
+		return -x;
+	else
+		return x;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/VERSIONS.txt b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/VERSIONS.txt
new file mode 100644
index 0000000000000000000000000000000000000000..35a6740b142fb59d8bef519dfbd5457301189a0b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/qpoases/VERSIONS.txt
@@ -0,0 +1,87 @@
+##
+##	qpOASES -- An Implementation of the Online Active Set Strategy.
+##	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+##
+##	qpOASES is free software; you can redistribute it and/or
+##	modify it under the terms of the GNU Lesser General Public
+##	License as published by the Free Software Foundation; either
+##	version 2.1 of the License, or (at your option) any later version.
+##
+##	qpOASES is distributed in the hope that it will be useful,
+##	but WITHOUT ANY WARRANTY; without even the implied warranty of
+##	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+##	Lesser General Public License for more details.
+##
+##	You should have received a copy of the GNU Lesser General Public
+##	License along with qpOASES; if not, write to the Free Software
+##	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+##
+
+
+
+VERSION HISTORY
+===============
+
+1.3embedded (last updated on 30th April 2009):
+-----------------------------------------------------------------------
+
++ Re-programming of internal memory management to avoid dynamic memory allocations 
++ Most #ifdef directives removed
++ Almost all type definitions gathered within INCLUDE/Types.hpp
++ Irrelevant functionality removed (like the SQProblem class, functionality 
+  for loading data from files or the SCILAB interface)
++ Replacement of all doubles by real_t
++ Introduction of define "PC_DEBUG" for switching off all print functions
++ stdio.h was made optional, string.h is no longer needed
++ relative paths removed from #include directives
++ made auxiliary objects locally static within solveInitialQP()
++ Matlab interface fixed for single precision
++ New return value -2 from Legacy wrapper added to Matlab/Simulink interfaces
++ KKT optimality check moved into QProblem(B) class, SolutionAnalysis class removed
+
+
+1.3 (released on 2nd June 2008, last updated on 19th June 2008):
+-----------------------------------------------------------------------
+
++ Implementation of "initialised homotopy" concept
++ Addition of the SolutionAnalysis class
++ Utility functions for solving test problems in OQP format added
++ Flexibility of Matlab(R) interface enhanced
++ Major source code cleanup
+  (Attention: a few class names and calling interfaces have changed!)
+
+
+
+1.2 (released on 9th October 2007):
+-----------------------------------------------------------------------
+
++ Special treatment of diagonal Hessians
++ Improved infeasibility detection
++ Further improved Matlab(R) interface
++ Extended Simulink(R) interface
++ scilab interface added
++ Code cleanup and several bugfixes
+
+
+
+1.1 (released on 8th July 2007):
+--------------------------------
+
++ Implementation of the QProblemB class
++ Basic implementation of the SQProblem class
++ Improved Matlab(R) interface
++ Enabling/Disabling of constraints introduced
++ Several bugfixes
+
+
+
+1.0 (released on 17th April 2007):
+----------------------------------
+
+Initial release.
+
+
+
+##
+##	end of file
+##
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/setup_custom_pythonpath.sh b/mav_control_rw/mav_nonlinear_mpc/solver/setup_custom_pythonpath.sh
new file mode 100644
index 0000000000000000000000000000000000000000..52176962e1d4df9f6535229f15878fe0445a8a56
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/setup_custom_pythonpath.sh
@@ -0,0 +1,5 @@
+#!/usr/bin/env sh
+# generated from dynamic_reconfigure/cmake/setup_custom_pythonpath.sh.in
+
+PYTHONPATH=/home/simhe502/catkin_ws/src/mav_control_rw/mav_nonlinear_mpc/solver/devel/lib/python3/dist-packages:$PYTHONPATH
+exec /usr/bin/python3 "$@"
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/test b/mav_control_rw/mav_nonlinear_mpc/solver/test
new file mode 100644
index 0000000000000000000000000000000000000000..7f40bcc80315c0692ef3ed8079c190a2b94751a9
Binary files /dev/null and b/mav_control_rw/mav_nonlinear_mpc/solver/test differ
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver/test.c b/mav_control_rw/mav_nonlinear_mpc/solver/test.c
new file mode 100644
index 0000000000000000000000000000000000000000..399953183a1300c3ad77c1c0d230c3b146bf1455
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver/test.c
@@ -0,0 +1,119 @@
+/*
+ *    This file was auto-generated using the ACADO Toolkit.
+ *    
+ *    While ACADO Toolkit is free software released under the terms of
+ *    the GNU Lesser General Public License (LGPL), the generated code
+ *    as such remains the property of the user who used ACADO Toolkit
+ *    to generate this code. In particular, user dependent data of the code
+ *    do not inherit the GNU LGPL license. On the other hand, parts of the
+ *    generated code that are a direct copy of source code from the
+ *    ACADO Toolkit or the software tools it is based on, remain, as derived
+ *    work, automatically covered by the LGPL license.
+ *    
+ *    ACADO Toolkit is distributed in the hope that it will be useful,
+ *    but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ *    
+ */
+
+
+
+/*
+
+IMPORTANT: This file should serve as a starting point to develop the user
+code for the OCP solver. The code below is for illustration purposes. Most
+likely you will not get good results if you execute this code without any
+modification(s).
+
+Please read the examples in order to understand how to write user code how
+to run the OCP solver. You can find more info on the website:
+www.acadotoolkit.org
+
+*/
+
+#include "acado_common.h"
+#include "acado_auxiliary_functions.h"
+
+#include <stdio.h>
+
+/* Some convenient definitions. */
+#define NX          ACADO_NX  /* Number of differential state variables.  */
+#define NXA         ACADO_NXA /* Number of algebraic variables. */
+#define NU          ACADO_NU  /* Number of control inputs. */
+#define NOD         ACADO_NOD  /* Number of online data values. */
+
+#define NY          ACADO_NY  /* Number of measurements/references on nodes 0..N - 1. */
+#define NYN         ACADO_NYN /* Number of measurements/references on node N. */
+
+#define N           ACADO_N   /* Number of intervals in the horizon. */
+
+#define NUM_STEPS   10        /* Number of real-time iterations. */
+#define VERBOSE     1         /* Show iterations: 1, silent: 0.  */
+
+/* Global variables used by the solver. */
+ACADOvariables acadoVariables;
+ACADOworkspace acadoWorkspace;
+
+/* A template for testing of the solver. */
+int main( )
+{
+	/* Some temporary variables. */
+	int    i, iter;
+	acado_timer t;
+
+	/* Initialize the solver. */
+	acado_initializeSolver();
+
+	/* Initialize the states and controls. */
+	for (i = 0; i < NX * (N + 1); ++i)  acadoVariables.x[ i ] = 0.0;
+	for (i = 0; i < NU * N; ++i)  acadoVariables.u[ i ] = 0.0;
+
+	/* Initialize the measurements/reference. */
+	for (i = 0; i < NY * N; ++i)  acadoVariables.y[ i ] = 0.0;
+	for (i = 0; i < NYN; ++i)  acadoVariables.yN[ i ] = 0.0;
+
+	/* MPC: initialize the current state feedback. */
+#if ACADO_INITIAL_STATE_FIXED
+	for (i = 0; i < NX; ++i) acadoVariables.x0[ i ] = 0.1;
+#endif
+
+	if( VERBOSE ) acado_printHeader();
+
+	/* Prepare first step */
+	acado_preparationStep();
+
+	/* Get the time before start of the loop. */
+	acado_tic( &t );
+
+	/* The "real-time iterations" loop. */
+	for(iter = 0; iter < NUM_STEPS; ++iter)
+	{
+        /* Perform the feedback step. */
+		acado_feedbackStep( );
+
+		/* Apply the new control immediately to the process, first NU components. */
+
+		if( VERBOSE ) printf("\tReal-Time Iteration %d:  KKT Tolerance = %.3e\n\n", iter, acado_getKKT() );
+
+		/* Optional: shift the initialization (look at acado_common.h). */
+        /* acado_shiftStates(2, 0, 0); */
+		/* acado_shiftControls( 0 ); */
+
+		/* Prepare for the next step. */
+		acado_preparationStep();
+	}
+	/* Read the elapsed time. */
+	real_t te = acado_toc( &t );
+
+	if( VERBOSE ) printf("\n\nEnd of the RTI loop. \n\n\n");
+
+	/* Eye-candy. */
+
+	if( !VERBOSE )
+	printf("\n\n Average time of one real-time iteration:   %.3g microseconds\n\n", 1e6 * te / NUM_STEPS);
+
+	acado_printDifferentialVariables();
+	acado_printControlVariables();
+
+    return 0;
+}
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/CMakeLists.txt b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/CMakeLists.txt
new file mode 100644
index 0000000000000000000000000000000000000000..679dcbea067e9cd5f63bbd8b617fdced708e8b9d
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/CMakeLists.txt
@@ -0,0 +1,27 @@
+CMAKE_MINIMUM_REQUIRED(VERSION 2.8.4)
+PROJECT(nmpc_solver)
+
+# CMake module(s) path
+set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_SOURCE_DIR}/cmake/")
+set (CMAKE_CXX_FLAGS  "-std=c++11 -g")
+#
+# Prerequisites
+#
+FIND_PACKAGE(ACADO REQUIRED)
+
+#
+# Include directories
+#
+INCLUDE_DIRECTORIES( ${ACADO_INCLUDE_DIRS} )
+
+#
+# Build an executable
+#
+ADD_EXECUTABLE(../solver/nmpc_solver_setup nmpc_solver_setup.cpp )
+
+TARGET_LINK_LIBRARIES(../solver/nmpc_solver_setup 
+  ${ACADO_SHARED_LIBRARIES}
+)
+
+SET_TARGET_PROPERTIES(../solver/nmpc_solver_setup PROPERTIES RUNTIME_OUTPUT_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} )
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/README.md b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/README.md
new file mode 100644
index 0000000000000000000000000000000000000000..bd175fa372466614c40d6e795f89e4413cc0c69c
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/README.md
@@ -0,0 +1,35 @@
+Author: Oskar Ljungqvist
+Date: 2017-11-23
+Description:
+
+This folder contains code to Automatically generate an MPC controller using ACADO toolkit.
+
+The file nmpc_solver_setup.cpp is what defines the MPC controller and it is this you should change in order the change the controller. Then build/install it using the explanation below. As an example it easy to change the prediction horizon if that is prefered.
+
+Prerequests: 
+
+ACADO toolkit needs to be properly installed. Follow the instructions here: http://acado.github.io/install_linux.html
+
+In your ~/.bashrc add the line:
+source [pathToAcado]/build/acado_env.sh
+
+Build/Install: 
+
+From this folder do:
+
+mkdir build
+cd build
+cmake ..
+make
+
+The executable is now placed in the folder ../solver
+
+Execute it by running the following commands:
+
+cd ../../solver
+./nmpc_solver_setup
+
+Then the controller is generated.
+
+
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/cmake/FindACADO.cmake b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/cmake/FindACADO.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..19fa7d4bbfa40d516a37d9b16b7434fc3c779117
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/cmake/FindACADO.cmake
@@ -0,0 +1,157 @@
+################################################################################
+#
+# Description:
+#	ACADO Toolkit package configuration file
+#
+#	Defines:
+#		- Variable: ACADO_INCLUDE_DIRS
+#		- Variable: ACADO_LIBRARY_DIRS
+#		- Variable: ACADO_STATIC_LIBS_FOUND
+#		- Variable: ACADO_STATIC_LIBRARIES
+#		- Variable: ACADO_SHARED_LIBS_FOUND
+#		- Variable: ACADO_SHARED_LIBRARIES
+#
+# Authors:
+#	Milan Vukov, milan.vukov@esat.kuleuven.be
+#
+# Year:
+#	2011 - 2013.
+#
+# NOTE:
+#	- This script is for Linux/Unix use only.
+#	- Use this script only (and only :)) if you do not want to install ACADO
+#		toolkit. If you install ACADO toolkit you do not need this script.
+#
+#	- PREREQUISITE: sourced acado_env.sh in your ~/.bashrc file. This script
+#		will try to find ACADO folders, libraries etc., but looking for them
+#		in enviromental variables.
+#
+# Usage:
+#	- Linux/Unix: TODO
+#
+################################################################################
+
+################################################################################
+#
+# Search for package components
+#
+################################################################################
+
+MESSAGE( STATUS "********************************************************************************" )
+MESSAGE( STATUS "---> Looking for ACADO toolkit:" )
+
+#
+# Include folders
+#
+SET( ACADO_INCLUDE_DIRS $ENV{ACADO_ENV_INCLUDE_DIRS} )
+IF( ACADO_INCLUDE_DIRS )
+	MESSAGE( STATUS "Found ACADO toolkit include directories: ${ACADO_INCLUDE_DIRS}" )
+	SET( ACADO_INCLUDE_DIRS_FOUND TRUE )
+ELSE( ACADO_INCLUDE_DIRS )
+	MESSAGE( STATUS "Could not find ACADO toolkit include directories" )
+ENDIF( ACADO_INCLUDE_DIRS )
+
+#
+# Library folders
+#
+SET( ACADO_LIBRARY_DIRS $ENV{ACADO_ENV_LIBRARY_DIRS} )
+IF( ACADO_LIBRARY_DIRS )
+	MESSAGE( STATUS "Found ACADO toolkit library directories: ${ACADO_LIBRARY_DIRS}" )
+	SET( ACADO_LIBRARY_DIRS_FOUND TRUE )
+ELSE( ACADO_LIBRARY_DIRS )
+	MESSAGE( STATUS "Could not find ACADO toolkit library directories" )
+ENDIF( ACADO_LIBRARY_DIRS )
+
+#
+# Static libs
+#
+
+SET ( STATIC_TMP $ENV{ACADO_ENV_STATIC_LIBRARIES})
+IF ( NOT STATIC_TMP )
+	MESSAGE( STATUS "Could not find ACADO static library." )
+	SET( ACADO_STATIC_LIBS_FOUND FALSE )
+ELSE()
+	SET( ACADO_STATIC_LIBS_FOUND TRUE )
+	UNSET( ACADO_STATIC_LIBRARIES )
+	FOREACH( LIB $ENV{ACADO_ENV_STATIC_LIBRARIES} )
+		UNSET( ACADO_TOOLKIT_STATIC_${LIB} )
+	
+		FIND_LIBRARY( ACADO_TOOLKIT_STATIC_${LIB}
+			NAMES ${LIB}
+			PATHS ${ACADO_LIBRARY_DIRS}
+			NO_DEFAULT_PATH
+		)
+	
+		IF( ACADO_TOOLKIT_STATIC_${LIB} )
+			MESSAGE( STATUS "Found ACADO static library: ${LIB}" )
+			SET( ACADO_STATIC_LIBRARIES
+				${ACADO_STATIC_LIBRARIES} ${ACADO_TOOLKIT_STATIC_${LIB}}
+			)
+		ELSE( )
+			MESSAGE( STATUS "Could not find ACADO static library: ${LIB}" )
+ 			SET( ACADO_STATIC_LIBS_FOUND FALSE )
+		ENDIF( )
+	ENDFOREACH()
+ENDIF()
+
+SET( ACADO_BUILD_STATIC ${ACADO_STATIC_LIBS_FOUND} )
+
+IF( VERBOSE )
+	MESSAGE( STATUS "Static libraries: ${ACADO_STATIC_LIBRARIES}\n" )
+ENDIF()
+
+#
+# Shared libs
+#
+SET( SHARED_TMP $ENV{ACADO_ENV_SHARED_LIBRARIES} )
+IF ( NOT SHARED_TMP )
+	MESSAGE( STATUS "Could not find ACADO shared library." )
+	SET( ACADO_SHARED_LIBS_FOUND FALSE )
+ELSE()
+SET( ACADO_SHARED_LIBS_FOUND TRUE )
+	UNSET( ACADO_SHARED_LIBRARIES )
+	FOREACH( LIB $ENV{ACADO_ENV_SHARED_LIBRARIES} )
+		UNSET( ACADO_TOOLKIT_SHARED_${LIB} )
+	
+		FIND_LIBRARY( ACADO_TOOLKIT_SHARED_${LIB}
+			NAMES ${LIB}
+			PATHS ${ACADO_LIBRARY_DIRS}
+			NO_DEFAULT_PATH
+		)
+	
+		IF( ACADO_TOOLKIT_SHARED_${LIB} )
+			MESSAGE( STATUS "Found ACADO shared library: ${LIB}" )
+			SET( ACADO_SHARED_LIBRARIES
+				${ACADO_SHARED_LIBRARIES} ${ACADO_TOOLKIT_SHARED_${LIB}}
+			)
+		ELSE( )
+			MESSAGE( STATUS "Could not find ACADO shared library: ${LIB}" )
+ 			SET( ACADO_SHARED_LIBS_FOUND FALSE )
+		ENDIF( )
+	ENDFOREACH()
+ENDIF()
+
+SET( ACADO_BUILD_SHARED ${ACADO_SHARED_LIBS_FOUND} )
+
+IF( VERBOSE )
+	MESSAGE( STATUS "${ACADO_SHARED_LIBRARIES}\n" )
+ENDIF()
+
+#
+# qpOASES embedded source files and include folders
+# TODO: checks
+#
+SET( ACADO_QPOASES_EMBEDDED_SOURCES $ENV{ACADO_ENV_QPOASES_EMBEDDED_SOURCES} )
+SET( ACADO_QPOASES_EMBEDDED_INC_DIRS $ENV{ACADO_ENV_QPOASES_EMBEDDED_INC_DIRS} )
+
+
+#
+# And finally set found flag...
+#
+IF( ACADO_INCLUDE_DIRS_FOUND AND ACADO_LIBRARY_DIRS_FOUND 
+		AND (ACADO_STATIC_LIBS_FOUND OR ACADO_SHARED_LIBS_FOUND) )
+	SET( ACADO_FOUND TRUE )
+ENDIF()
+
+MESSAGE( STATUS "********************************************************************************" )
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/nmpc_solver_setup.cpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/nmpc_solver_setup.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..d81c8095ab776200b623821f81fc4c08e4a684de
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/nmpc_solver_setup.cpp
@@ -0,0 +1,107 @@
+#include <acado_code_generation.hpp>
+#include <acado_toolkit.hpp>
+#include <acado_optimal_control.hpp>
+#include <acado_gnuplot.hpp>
+#include <matrix_vector/vector.hpp>
+
+USING_NAMESPACE_ACADO
+
+int main()
+{
+    double Ts = 0.3;  // Prediction sampling time
+    double N  = 20;   // Prediction horizon
+    double margin = 1.0;
+
+    DifferentialState x, y;                     // Position of robot
+    DifferentialState heading;                  // Heading of robot
+    DifferentialState vel_forward, vel_angular; // Velocity forward and angular
+
+    Control acc_forward, acc_angular;           // Control variables
+
+    // Online scan data, contains position instead of only range, so mpc can solve it
+    OnlineData scan_x1, scan_x2, scan_x3, scan_x4, scan_x5, scan_x6, scan_x7, scan_x8, scan_x9, scan_x10;
+    OnlineData scan_y1, scan_y2, scan_y3, scan_y4, scan_y5, scan_y6, scan_y7, scan_y8, scan_y9, scan_y10;
+
+    // Proximity IntermediateState variables
+    IntermediateState proximity1 = sqrt((x-scan_x1)*(x-scan_x1) + (y-scan_y1)*(y-scan_y1));
+    IntermediateState proximity2 = sqrt((x-scan_x2)*(x-scan_x2) + (y-scan_y2)*(y-scan_y2));
+    IntermediateState proximity3 = sqrt((x-scan_x3)*(x-scan_x3) + (y-scan_y3)*(y-scan_y3));
+    IntermediateState proximity4 = sqrt((x-scan_x4)*(x-scan_x4) + (y-scan_y4)*(y-scan_y4));
+    IntermediateState proximity5 = sqrt((x-scan_x5)*(x-scan_x5) + (y-scan_y5)*(y-scan_y5));
+    IntermediateState proximity6 = sqrt((x-scan_x6)*(x-scan_x6) + (y-scan_y6)*(y-scan_y6));
+    IntermediateState proximity7 = sqrt((x-scan_x7)*(x-scan_x7) + (y-scan_y7)*(y-scan_y7));
+    IntermediateState proximity8 = sqrt((x-scan_x8)*(x-scan_x8) + (y-scan_y8)*(y-scan_y8));
+    IntermediateState proximity9 = sqrt((x-scan_x9)*(x-scan_x9) + (y-scan_y9)*(y-scan_y9));
+    IntermediateState proximity10 = sqrt((x-scan_x10)*(x-scan_x10) + (y-scan_y10)*(y-scan_y10));
+
+    IntermediateState general_proximity = exp(2*margin-proximity1) + exp(2*margin-proximity2)
+                                        + exp(2*margin-proximity3) + exp(2*margin-proximity4)
+                                        + exp(2*margin-proximity5) + exp(2*margin-proximity6)
+                                        + exp(2*margin-proximity7) + exp(2*margin-proximity8)
+                                        + exp(2*margin-proximity9) + exp(2*margin-proximity10);
+
+    // Define OCP problem:
+    OCP ocp(0.0, N*Ts, N);
+
+    // Model equations
+    DifferentialEquation f(0.0, N);
+    f << dot(x)           == cos(heading) * vel_forward;
+    f << dot(y)           == sin(heading) * vel_forward;
+    f << dot(heading)     == vel_angular;
+    f << dot(vel_forward) == acc_forward;
+    f << dot(vel_angular) == acc_angular;
+    ocp.subjectTo(f);
+
+    // Constraints taken from Husky docs
+    ocp.subjectTo(-1.0 <= vel_forward <= 1.0); // m/s
+    ocp.subjectTo(-3.0 <= acc_forward <= 3.0); // m/s^2
+    ocp.subjectTo(-3.0 <= vel_angular <= 3.0); // rad/s
+    ocp.subjectTo(-3.0 <= acc_angular <= 3.0); // rad/s^2
+
+    // Constraints for obstacle avoidance
+    ocp.subjectTo(proximity1 >= margin);
+    ocp.subjectTo(proximity2 >= margin);
+    ocp.subjectTo(proximity3 >= margin);
+    ocp.subjectTo(proximity4 >= margin);
+    ocp.subjectTo(proximity5 >= margin);
+    ocp.subjectTo(proximity6 >= margin);
+    ocp.subjectTo(proximity7 >= margin);
+    ocp.subjectTo(proximity8 >= margin);
+    ocp.subjectTo(proximity9 >= margin);
+    ocp.subjectTo(proximity10 >= margin);
+
+    // Weight matrices
+    BMatrix W = eye<bool>(8);
+    BMatrix WN = eye<bool>(5);
+
+    Function h, hN;
+    h << x << y << heading << vel_forward << vel_angular << acc_forward << acc_angular << general_proximity;
+    hN << x << y << heading << vel_forward << vel_angular;
+
+    ocp.minimizeLSQ(W, h);
+    ocp.minimizeLSQEndTerm(WN, hN);
+    ocp.setNOD(20);
+
+    // Export the code:
+    OCPexport mpc(ocp);
+
+    mpc.set(HESSIAN_APPROXIMATION, GAUSS_NEWTON);
+    mpc.set(DISCRETIZATION_TYPE, MULTIPLE_SHOOTING);
+    mpc.set(SPARSE_QP_SOLUTION, FULL_CONDENSING_N2);
+    mpc.set(INTEGRATOR_TYPE, INT_IRK_GL2);
+    mpc.set(QP_SOLVER, QP_QPOASES);
+    mpc.set(HOTSTART_QP, NO);
+    mpc.set(LEVENBERG_MARQUARDT, 1e-10);
+    mpc.set(LINEAR_ALGEBRA_SOLVER, GAUSS_LU);
+    mpc.set(IMPLICIT_INTEGRATOR_NUM_ITS, 2);
+    mpc.set(CG_USE_OPENMP, YES);
+    mpc.set(CG_HARDCODE_CONSTRAINT_VALUES, NO);
+    mpc.set(CG_USE_VARIABLE_WEIGHTING_MATRIX, YES);
+
+    if (mpc.exportCode( "." ) != SUCCESSFUL_RETURN)
+        exit( EXIT_FAILURE );
+
+    mpc.printDimensionsQP();
+
+    return EXIT_SUCCESS;
+}
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/EXAMPLES/example1.cpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/EXAMPLES/example1.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..92b47fc93798d2601ffc8c1810c187f94ac93df9
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/EXAMPLES/example1.cpp
@@ -0,0 +1,74 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file EXAMPLES/example1.cpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Very simple example for testing qpOASES (using QProblem class).
+ */
+
+
+#include <QProblem.hpp>
+
+
+/** Example for qpOASES main function using the QProblem class. */
+int main( )
+{
+	/* Setup data of first QP. */
+	real_t H[2*2] = { 1.0, 0.0, 0.0, 0.5 };
+	real_t A[1*2] = { 1.0, 1.0 };
+	real_t g[2] = { 1.5, 1.0 };
+	real_t lb[2] = { 0.5, -2.0 };
+	real_t ub[2] = { 5.0, 2.0 };
+	real_t lbA[1] = { -1.0 };
+	real_t ubA[1] = { 2.0 };
+
+	/* Setup data of second QP. */
+	real_t g_new[2] = { 1.0, 1.5 };
+	real_t lb_new[2] = { 0.0, -1.0 };
+	real_t ub_new[2] = { 5.0, -0.5 };
+	real_t lbA_new[1] = { -2.0 };
+	real_t ubA_new[1] = { 1.0 };
+
+
+	/* Setting up QProblem object. */
+	QProblem example( 2,1 );
+
+	/* Solve first QP. */
+	int nWSR = 10;
+	example.init( H,g,A,lb,ub,lbA,ubA, nWSR,0 );
+
+	/* Solve second QP. */
+	nWSR = 10;
+	example.hotstart( g_new,lb_new,ub_new,lbA_new,ubA_new, nWSR,0 );
+
+	return 0;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/EXAMPLES/example1b.cpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/EXAMPLES/example1b.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..331f19d8da0cbc8a530d9f6a36c5e0f57577e7ea
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/EXAMPLES/example1b.cpp
@@ -0,0 +1,69 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file EXAMPLES/example1b.cpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3
+ *	\date 2007-2008
+ *
+ *	Very simple example for testing qpOASES using the QProblemB class.
+ */
+
+
+#include <QProblemB.hpp>
+
+
+/** Example for qpOASES main function using the QProblemB class. */
+int main( )
+{
+	/* Setup data of first QP. */
+	real_t H[2*2] = { 1.0, 0.0, 0.0, 0.5 };
+	real_t g[2] = { 1.5, 1.0 };
+	real_t lb[2] = { 0.5, -2.0 };
+	real_t ub[2] = { 5.0, 2.0 };
+
+	/* Setup data of second QP. */
+	real_t g_new[2] = { 1.0, 1.5 };
+	real_t lb_new[2] = { 0.0, -1.0 };
+	real_t ub_new[2] = { 5.0, -0.5 };
+
+
+	/* Setting up QProblemB object. */
+	QProblemB example( 2 );
+
+	/* Solve first QP. */
+	int nWSR = 10;
+	example.init( H,g,lb,ub, nWSR,0 );
+
+	/* Solve second QP. */
+	nWSR = 10;
+	example.hotstart( g_new,lb_new,ub_new, nWSR,0 );
+
+	return 0;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/Bounds.hpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/Bounds.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..7260756da07b5b698599dd08077f6320cac7f4a8
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/Bounds.hpp
@@ -0,0 +1,189 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/Bounds.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Declaration of the Bounds class designed to manage working sets of
+ *	bounds within a QProblem.
+ */
+
+
+#ifndef QPOASES_BOUNDS_HPP
+#define QPOASES_BOUNDS_HPP
+
+
+#include <SubjectTo.hpp>
+
+
+
+/** This class manages working sets of bounds by storing
+ *	index sets and other status information.
+ *
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ */
+class Bounds : public SubjectTo
+{
+	/*
+	 *	PUBLIC MEMBER FUNCTIONS
+	 */
+	public:
+		/** Default constructor. */
+		Bounds( );
+
+		/** Copy constructor (deep copy). */
+		Bounds(	const Bounds& rhs	/**< Rhs object. */
+				);
+
+		/** Destructor. */
+		~Bounds( );
+
+		/** Assignment operator (deep copy). */
+		Bounds& operator=(	const Bounds& rhs	/**< Rhs object. */
+							);
+
+
+		/** Pseudo-constructor takes the number of bounds.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue init(	int n	/**< Number of bounds. */
+							);
+
+
+		/** Initially adds number of a new (i.e. not yet in the list) bound to
+		 *  given index set.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_SETUP_BOUND_FAILED \n
+					RET_INDEX_OUT_OF_BOUNDS \n
+					RET_INVALID_ARGUMENTS */
+		returnValue setupBound(	int _number,					/**< Number of new bound. */
+								SubjectToStatus _status			/**< Status of new bound. */
+								);
+
+		/** Initially adds all numbers of new (i.e. not yet in the list) bounds to
+		 *  to the index set of free bounds; the order depends on the SujectToType
+		 *  of each index.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_SETUP_BOUND_FAILED */
+		returnValue setupAllFree( );
+
+
+		/** Moves index of a bound from index list of fixed to that of free bounds.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_MOVING_BOUND_FAILED \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		returnValue moveFixedToFree(	int _number				/**< Number of bound to be freed. */
+										);
+
+		/** Moves index of a bound from index list of free to that of fixed bounds.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_MOVING_BOUND_FAILED \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		returnValue moveFreeToFixed(	int _number,			/**< Number of bound to be fixed. */
+										SubjectToStatus _status	/**< Status of bound to be fixed. */
+										);
+
+		/** Swaps the indices of two free bounds within the index set.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_SWAPINDEX_FAILED */
+		returnValue swapFree(	int number1,					/**< Number of first constraint or bound. */
+								int number2						/**< Number of second constraint or bound. */
+								);
+
+
+		/** Returns number of variables.
+		 *	\return Number of variables. */
+		inline int getNV( ) const;
+
+		/** Returns number of implicitly fixed variables.
+		 *	\return Number of implicitly fixed variables. */
+		inline int getNFV( ) const;
+
+		/** Returns number of bounded (but possibly free) variables.
+		 *	\return Number of bounded (but possibly free) variables. */
+		inline int getNBV( ) const;
+
+		/** Returns number of unbounded variables.
+		 *	\return Number of unbounded variables. */
+		inline int getNUV( ) const;
+
+
+		/** Sets number of implicitly fixed variables.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setNFV(	int n	/**< Number of implicitly fixed variables. */
+									);
+
+		/** Sets number of bounded (but possibly free) variables.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setNBV(	int n	/**< Number of bounded (but possibly free) variables. */
+									);
+
+		/** Sets number of unbounded variables.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setNUV(	int n	/**< Number of unbounded variables */
+									);
+
+
+		/** Returns number of free variables.
+		 *	\return Number of free variables. */
+		inline int getNFR( );
+
+		/** Returns number of fixed variables.
+		 *	\return Number of fixed variables. */
+		inline int getNFX( );
+
+
+		/** Returns a pointer to free variables index list.
+		 *	\return Pointer to free variables index list. */
+		inline Indexlist* getFree( );
+
+		/** Returns a pointer to fixed variables index list.
+		 *	\return Pointer to fixed variables index list. */
+		inline Indexlist* getFixed( );
+
+
+	/*
+	 *	PROTECTED MEMBER VARIABLES
+	 */
+	protected:
+		int nV;					/**< Number of variables (nV = nFV + nBV + nUV). */
+		int nFV;				/**< Number of implicitly fixed variables. */
+		int	nBV;				/**< Number of bounded (but possibly free) variables. */
+		int nUV;				/**< Number of unbounded variables. */
+
+		Indexlist free;			/**< Index list of free variables. */
+		Indexlist fixed;		/**< Index list of fixed variables. */
+};
+
+#include <Bounds.ipp>
+
+#endif	/* QPOASES_BOUNDS_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/Constants.hpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/Constants.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..92ee812295bf3746c1ebaf4899c851fa79f36aaf
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/Constants.hpp
@@ -0,0 +1,108 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/Constants.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2008
+ *
+ *	Definition of all global constants.
+ */
+
+
+#ifndef QPOASES_CONSTANTS_HPP
+#define QPOASES_CONSTANTS_HPP
+
+#ifndef QPOASES_CUSTOM_INTERFACE
+#include "acado_qpoases_interface.hpp"
+#else
+  #define XSTR(x) #x
+  #define STR(x) XSTR(x)
+  #include STR(QPOASES_CUSTOM_INTERFACE)
+#endif
+
+/** Maximum number of variables within a QP formulation.
+	Note: this value has to be positive! */
+const int NVMAX = QPOASES_NVMAX;
+
+/** Maximum number of constraints within a QP formulation.
+	Note: this value has to be positive! */
+const int NCMAX = QPOASES_NCMAX;
+
+/** Redefinition of NCMAX used for memory allocation, to avoid zero sized arrays
+    and compiler errors. */
+const int NCMAX_ALLOC = (NCMAX == 0) ? 1 : NCMAX;
+
+/**< Maximum number of working set recalculations.
+	Note: this value has to be positive! */
+const int NWSRMAX = QPOASES_NWSRMAX;
+
+/** Desired KKT tolerance of QP solution; a warning RET_INACCURATE_SOLUTION is
+ *  issued if this tolerance is not met.
+ *	Note: this value has to be positive! */
+const real_t DESIREDACCURACY = (real_t) 1.0e-3;
+
+/** Critical KKT tolerance of QP solution; an error is issued if this
+ *  tolerance is not met.
+ *	Note: this value has to be positive! */
+const real_t CRITICALACCURACY = (real_t) 1.0e-2;
+
+
+
+/** Numerical value of machine precision (min eps, s.t. 1+eps > 1).
+	Note: this value has to be positive! */
+const real_t EPS = (real_t) QPOASES_EPS;
+
+/** Numerical value of zero (for situations in which it would be
+ *	unreasonable to compare with 0.0).
+ *	Note: this value has to be positive! */
+const real_t ZERO = (real_t) 1.0e-50;
+
+/** Numerical value of infinity (e.g. for non-existing bounds).
+ *	Note: this value has to be positive! */
+const real_t INFTY = (real_t) 1.0e12;
+
+
+/** Lower/upper (constraints') bound tolerance (an inequality constraint
+ *	whose lower and upper bound differ by less than BOUNDTOL is regarded
+ *	to be an equality constraint).
+ *	Note: this value has to be positive! */
+const real_t BOUNDTOL = (real_t) 1.0e-10;
+
+/** Offset for relaxing (constraints') bounds at beginning of an initial homotopy.
+ *	Note: this value has to be positive! */
+const real_t BOUNDRELAXATION = (real_t) 1.0e3;
+
+
+/** Factor that determines physical lengths of index lists.
+ *	Note: this value has to be greater than 1! */
+const int INDEXLISTFACTOR = 5;
+
+
+#endif	/* QPOASES_CONSTANTS_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/Constraints.hpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/Constraints.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..899167942a7dd3637513c89c14ce4346358d275a
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/Constraints.hpp
@@ -0,0 +1,181 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/Constraints.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Declaration of the Constraints class designed to manage working sets of
+ *	constraints within a QProblem.
+ */
+
+
+#ifndef QPOASES_CONSTRAINTS_HPP
+#define QPOASES_CONSTRAINTS_HPP
+
+
+#include <SubjectTo.hpp>
+
+
+
+/** This class manages working sets of constraints by storing
+ *	index sets and other status information.
+ *
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ */
+class Constraints : public SubjectTo
+{
+	/*
+	 *	PUBLIC MEMBER FUNCTIONS
+	 */
+	public:
+		/** Default constructor. */
+		Constraints( );
+
+		/** Copy constructor (deep copy). */
+		Constraints(	const Constraints& rhs	/**< Rhs object. */
+						);
+
+		/** Destructor. */
+		~Constraints( );
+
+		/** Assignment operator (deep copy). */
+		Constraints& operator=(	const Constraints& rhs	/**< Rhs object. */
+								);
+
+
+		/** Pseudo-constructor takes the number of constraints.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue init(	int n	/**< Number of constraints. */
+							);
+
+
+		/** Initially adds number of a new (i.e. not yet in the list) constraint to
+		 *  a given index set.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_SETUP_CONSTRAINT_FAILED \n
+					RET_INDEX_OUT_OF_BOUNDS \n
+					RET_INVALID_ARGUMENTS */
+		returnValue setupConstraint(	int _number,				/**< Number of new constraint. */
+										SubjectToStatus _status		/**< Status of new constraint. */
+										);
+
+		/** Initially adds all enabled numbers of new (i.e. not yet in the list) constraints to
+		 *  to the index set of inactive constraints; the order depends on the SujectToType
+		 *  of each index. Only disabled constraints are added to index set of disabled constraints!
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_SETUP_CONSTRAINT_FAILED */
+		returnValue setupAllInactive( );
+
+
+		/** Moves index of a constraint from index list of active to that of inactive constraints.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_MOVING_CONSTRAINT_FAILED */
+		returnValue moveActiveToInactive(	int _number				/**< Number of constraint to become inactive. */
+											);
+
+		/** Moves index of a constraint from index list of inactive to that of active constraints.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_MOVING_CONSTRAINT_FAILED */
+		returnValue moveInactiveToActive(	int _number,			/**< Number of constraint to become active. */
+											SubjectToStatus _status	/**< Status of constraint to become active. */
+											);
+
+
+		/** Returns the number of constraints.
+		 *	\return Number of constraints. */
+		inline int getNC( ) const;
+
+		/** Returns the number of implicit equality constraints.
+		 *	\return Number of implicit equality constraints. */
+		inline int getNEC( ) const;
+
+		/** Returns the number of "real" inequality constraints.
+		 *	\return Number of "real" inequality constraints. */
+		inline int getNIC( ) const;
+
+		/** Returns the number of unbounded constraints (i.e. without any bounds).
+		 *	\return Number of unbounded constraints (i.e. without any bounds). */
+		inline int getNUC( ) const;
+
+
+		/** Sets number of implicit equality constraints.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setNEC(	int n	/**< Number of implicit equality constraints. */
+							);
+
+		/** Sets number of "real" inequality constraints.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setNIC(	int n	/**< Number of "real" inequality constraints. */
+									);
+
+		/** Sets number of unbounded constraints (i.e. without any bounds).
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setNUC(	int n	/**< Number of unbounded constraints (i.e. without any bounds). */
+									);
+
+
+		/** Returns the number of active constraints.
+		 *	\return Number of constraints. */
+		inline int getNAC( );
+
+		/** Returns the number of inactive constraints.
+		 *	\return Number of constraints. */
+		inline int getNIAC( );
+
+
+		/** Returns a pointer to active constraints index list.
+		 *	\return Pointer to active constraints index list. */
+		inline Indexlist* getActive( );
+
+		/** Returns a pointer to inactive constraints index list.
+		 *	\return Pointer to inactive constraints index list. */
+		inline Indexlist* getInactive( );
+
+
+	/*
+	 *	PROTECTED MEMBER VARIABLES
+	 */
+	protected:
+		int nC;					/**< Number of constraints (nC = nEC + nIC + nUC). */
+		int nEC;				/**< Number of implicit equality constraints. */
+		int	nIC;				/**< Number of "real" inequality constraints. */
+		int nUC;				/**< Number of unbounded constraints (i.e. without any bounds). */
+
+		Indexlist active;		/**< Index list of active constraints. */
+		Indexlist inactive;		/**< Index list of inactive constraints. */
+};
+
+
+#include <Constraints.ipp>
+
+#endif	/* QPOASES_CONSTRAINTS_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/CyclingManager.hpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/CyclingManager.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..b4410b106e61eade36587f56b5ccbadc1ed6a9a4
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/CyclingManager.hpp
@@ -0,0 +1,126 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/CyclingManager.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Declaration of the CyclingManager class designed to detect
+ *	and handle possible cycling during QP iterations.
+ */
+
+
+#ifndef QPOASES_CYCLINGMANAGER_HPP
+#define QPOASES_CYCLINGMANAGER_HPP
+
+
+#include <Utils.hpp>
+
+
+
+/** This class is intended to detect and handle possible cycling during QP iterations.
+ *	As cycling seems to occur quite rarely, this class is NOT FULLY IMPLEMENTED YET!
+ *
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ */
+class CyclingManager
+{
+	/*
+	 *	PUBLIC MEMBER FUNCTIONS
+	 */
+	public:
+		/** Default constructor. */
+		CyclingManager( );
+
+		/** Copy constructor (deep copy). */
+		CyclingManager(	const CyclingManager& rhs	/**< Rhs object. */
+						);
+
+		/** Destructor. */
+		~CyclingManager( );
+
+		/** Copy asingment operator (deep copy). */
+		CyclingManager& operator=(	const CyclingManager& rhs	/**< Rhs object. */
+									);
+
+
+		/** Pseudo-constructor which takes the number of bounds/constraints.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue init(	int _nV,	/**< Number of bounds to be managed. */
+							int _nC		/**< Number of constraints to be managed. */
+							);
+
+
+		/** Stores index of a bound/constraint that might cause cycling.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		returnValue setCyclingStatus(	int number,				/**< Number of bound/constraint. */
+										BooleanType isBound,	/**< Flag that indicates if given number corresponds to a
+																 *   bound (BT_TRUE) or a constraint (BT_FALSE). */
+										CyclingStatus _status	/**< Cycling status of bound/constraint. */
+										);
+
+		/** Returns if bound/constraint might cause cycling.
+		 *	\return BT_TRUE: bound/constraint might cause cycling \n
+		 			BT_FALSE: otherwise */
+		CyclingStatus getCyclingStatus(	int number,			/**< Number of bound/constraint. */
+										BooleanType isBound	/**< Flag that indicates if given number corresponds to
+															 *   a bound (BT_TRUE) or a constraint (BT_FALSE). */
+										) const;
+
+
+		/** Clears all previous cycling information.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue clearCyclingData( );
+
+
+		/** Returns if cycling was detected.
+		 *	\return BT_TRUE iff cycling was detected. */
+		inline BooleanType isCyclingDetected( ) const;
+
+
+	/*
+	 *	PROTECTED MEMBER VARIABLES
+	 */
+	protected:
+		int	nV;									/**< Number of managed bounds. */
+		int	nC;									/**< Number of managed constraints. */
+
+		CyclingStatus status[NVMAX+NCMAX];		/**< Array to store cycling status of all bounds/constraints. */
+
+		BooleanType cyclingDetected;			/**< Flag if cycling was detected. */
+};
+
+
+#include <CyclingManager.ipp>
+
+#endif	/* QPOASES_CYCLINGMANAGER_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..056bb26f02d09dab6949e9e25a9f0e87f67597e2
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp
@@ -0,0 +1,107 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/EXTRAS/SolutionAnalysis.hpp
+ *	\author Milan Vukov, Boris Houska, Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2012
+ *
+ *	Solution analysis class, based on a class in the standard version of the qpOASES
+ */
+
+
+//
+
+#ifndef QPOASES_SOLUTIONANALYSIS_HPP
+#define QPOASES_SOLUTIONANALYSIS_HPP
+
+#include <QProblem.hpp>
+
+/** Enables the computation of variance as is in the standard version of qpOASES */
+#define QPOASES_USE_OLD_VERSION 0
+
+#if QPOASES_USE_OLD_VERSION
+#define KKT_DIM (2 * NVMAX + NCMAX)
+#endif
+
+class SolutionAnalysis
+{
+public:
+	
+	/** Default constructor. */
+	SolutionAnalysis( );
+	
+	/** Copy constructor (deep copy). */
+	SolutionAnalysis( 	const SolutionAnalysis& rhs	/**< Rhs object. */
+						);
+	
+	/** Destructor. */
+	~SolutionAnalysis( );
+	
+	/** Copy asingment operator (deep copy). */
+	SolutionAnalysis& operator=(	const SolutionAnalysis& rhs	/**< Rhs object. */
+									);
+	
+	/** A routine for computation of inverse of the Hessian matrix. */
+	returnValue getHessianInverse(
+									QProblem* qp,			/** QP */
+									real_t* hessianInverse	/** Inverse of the Hessian matrix*/
+									);
+	
+	/** A routine for computation of inverse of the Hessian matrix. */
+	returnValue getHessianInverse(	QProblemB* qp,			/** QP */
+									real_t* hessianInverse	/** Inverse of the Hessian matrix*/
+									);
+
+#if QPOASES_USE_OLD_VERSION
+	returnValue getVarianceCovariance(
+										QProblem* qp,
+										real_t* g_b_bA_VAR,
+										real_t* Primal_Dual_VAR
+										);
+#endif
+	
+private:
+	
+	real_t delta_g_cov[ NVMAX ];		/** A covariance-vector of g */
+	real_t delta_lb_cov[ NVMAX ];		/** A covariance-vector of lb */
+	real_t delta_ub_cov[ NVMAX ];		/** A covariance-vector of ub */
+	real_t delta_lbA_cov[ NCMAX_ALLOC ];		/** A covariance-vector of lbA */
+	real_t delta_ubA_cov[ NCMAX_ALLOC ];		/** A covariance-vector of ubA */
+	
+#if QPOASES_USE_OLD_VERSION
+	real_t K[KKT_DIM * KKT_DIM];		/** A matrix to store an intermediate result */
+#endif
+	
+	int FR_idx[ NVMAX ];				/** Index array for free variables */
+	int FX_idx[ NVMAX ];				/** Index array for fixed variables */
+	int AC_idx[ NCMAX_ALLOC ];				/** Index array for active constraints */
+	
+	real_t delta_xFR[ NVMAX ];			/** QP reaction, primal, w.r.t. free */
+	real_t delta_xFX[ NVMAX ];			/** QP reaction, primal, w.r.t. fixed */
+	real_t delta_yAC[ NVMAX ];			/** QP reaction, dual, w.r.t. active */
+	real_t delta_yFX[ NVMAX ];			/** QP reaction, dual, w.r.t. fixed*/
+};
+
+#endif // QPOASES_SOLUTIONANALYSIS_HPP
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/Indexlist.hpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/Indexlist.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..21c31ddb9215bb98c59788986fff8db7ce92888d
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/Indexlist.hpp
@@ -0,0 +1,154 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/Indexlist.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Declaration of the Indexlist class designed to manage index lists of
+ *	constraints and bounds within a SubjectTo object.
+ */
+
+
+#ifndef QPOASES_INDEXLIST_HPP
+#define QPOASES_INDEXLIST_HPP
+
+
+#include <Utils.hpp>
+
+
+/** This class manages index lists.
+ *
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ */
+class Indexlist
+{
+	/*
+	 *	PUBLIC MEMBER FUNCTIONS
+	 */
+	public:
+		/** Default constructor. */
+		Indexlist( );
+
+		/** Copy constructor (deep copy). */
+		Indexlist(	const Indexlist& rhs	/**< Rhs object. */
+					);
+
+		/** Destructor. */
+		~Indexlist( );
+
+		/** Assingment operator (deep copy). */
+		Indexlist& operator=(	const Indexlist& rhs	/**< Rhs object. */
+								);
+
+		/** Pseudo-constructor.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue init( );
+
+
+		/** Creates an array of all numbers within the index set in correct order.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_INDEXLIST_CORRUPTED */
+		returnValue	getNumberArray(	int* const numberarray	/**< Output: Array of numbers (NULL on error). */
+									) const;
+
+
+		/** Determines the index within the index list at with a given number is stored.
+		 *	\return >= 0: Index of given number. \n
+		 			-1: Number not found. */
+		int	getIndex(	int givennumber	/**< Number whose index shall be determined. */
+						) const;
+
+		/** Determines the physical index within the index list at with a given number is stored.
+		 *	\return >= 0: Index of given number. \n
+		 			-1: Number not found. */
+		int	getPhysicalIndex(	int givennumber	/**< Number whose physical index shall be determined. */
+								) const;
+
+		/** Returns the number stored at a given physical index.
+		 *	\return >= 0: Number stored at given physical index. \n
+		 			-RET_INDEXLIST_OUTOFBOUNDS */
+		int	getNumber(	int physicalindex	/**< Physical index of the number to be returned. */
+						) const;
+
+
+		/** Returns the current length of the index list.
+		 *	\return Current length of the index list. */
+		inline int getLength( );
+
+		/** Returns last number within the index list.
+		 *	\return Last number within the index list. */
+		inline int getLastNumber( ) const;
+
+
+		/** Adds number to index list.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_INDEXLIST_MUST_BE_REORDERD \n
+		 			RET_INDEXLIST_EXCEEDS_MAX_LENGTH */
+		returnValue addNumber(	int addnumber	/**< Number to be added. */
+								);
+
+		/** Removes number from index list.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue removeNumber(	int removenumber	/**< Number to be removed. */
+									);
+
+		/** Swaps two numbers within index list.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue swapNumbers(	int number1,/**< First number for swapping. */
+									int number2	/**< Second number for swapping. */
+									);
+
+		/** Determines if a given number is contained in the index set.
+		 *	\return BT_TRUE iff number is contain in the index set */
+		inline BooleanType isMember(	int _number	/**< Number to be tested for membership. */
+										) const;
+
+
+	/*
+	 *	PROTECTED MEMBER VARIABLES
+	 */
+	protected:
+		int number[INDEXLISTFACTOR*(NVMAX+NCMAX)];		/**< Array to store numbers of constraints or bounds. */
+		int next[INDEXLISTFACTOR*(NVMAX+NCMAX)];		/**< Array to store physical index of successor. */
+		int previous[INDEXLISTFACTOR*(NVMAX+NCMAX)];	/**< Array to store physical index of predecossor. */
+		int	length;										/**< Length of index list. */
+		int	first;										/**< Physical index of first element. */
+		int	last;										/**< Physical index of last element. */
+		int	lastusedindex;								/**< Physical index of last entry in index list. */
+		int	physicallength;								/**< Physical length of index list. */
+};
+
+
+#include <Indexlist.ipp>
+
+#endif	/* QPOASES_INDEXLIST_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/MessageHandling.hpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/MessageHandling.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..3d17498ade0738c5fa356bbe56446ebfb6f3ada9
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/MessageHandling.hpp
@@ -0,0 +1,415 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/MessageHandling.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Declaration of the MessageHandling class including global return values.
+ */
+
+
+#ifndef QPOASES_MESSAGEHANDLING_HPP
+#define QPOASES_MESSAGEHANDLING_HPP
+
+// #define PC_DEBUG
+
+#ifdef PC_DEBUG
+  #include <stdio.h>
+
+  /** Defines an alias for  FILE  from stdio.h. */
+  #define myFILE FILE
+  /** Defines an alias for  stderr  from stdio.h. */
+  #define myStderr stderr
+  /** Defines an alias for  stdout  from stdio.h. */
+  #define myStdout stdout
+#else
+  /** Defines an alias for  FILE  from stdio.h. */
+  #define myFILE int
+  /** Defines an alias for  stderr  from stdio.h. */
+  #define myStderr 0
+  /** Defines an alias for  stdout  from stdio.h. */
+  #define myStdout 0
+#endif
+
+
+#include <Types.hpp>
+#include <Constants.hpp>
+
+
+/** Defines symbols for global return values. \n
+ *  Important: All return values are assumed to be nonnegative! */
+enum returnValue
+{
+TERMINAL_LIST_ELEMENT = -1,						/**< Terminal list element, internal usage only! */
+/* miscellaneous */
+SUCCESSFUL_RETURN = 0,							/**< Successful return. */
+RET_DIV_BY_ZERO,		   						/**< Division by zero. */
+RET_INDEX_OUT_OF_BOUNDS,						/**< Index out of bounds. */
+RET_INVALID_ARGUMENTS,							/**< At least one of the arguments is invalid. */
+RET_ERROR_UNDEFINED,							/**< Error number undefined. */
+RET_WARNING_UNDEFINED,							/**< Warning number undefined. */
+RET_INFO_UNDEFINED,								/**< Info number undefined. */
+RET_EWI_UNDEFINED,								/**< Error/warning/info number undefined. */
+RET_AVAILABLE_WITH_LINUX_ONLY,					/**< This function is available under Linux only. */
+RET_UNKNOWN_BUG,								/**< The error occured is not yet known. */
+RET_PRINTLEVEL_CHANGED,							/**< 10 Print level changed. */
+RET_NOT_YET_IMPLEMENTED,						/**< Requested function is not yet implemented in this version of qpOASES. */
+/* Indexlist */
+RET_INDEXLIST_MUST_BE_REORDERD,					/**< Index list has to be reordered. */
+RET_INDEXLIST_EXCEEDS_MAX_LENGTH,				/**< Index list exceeds its maximal physical length. */
+RET_INDEXLIST_CORRUPTED,						/**< Index list corrupted. */
+RET_INDEXLIST_OUTOFBOUNDS,						/**< Physical index is out of bounds. */
+RET_INDEXLIST_ADD_FAILED,						/**< Adding indices from another index set failed. */
+RET_INDEXLIST_INTERSECT_FAILED,					/**< Intersection with another index set failed. */
+/* SubjectTo / Bounds / Constraints */
+RET_INDEX_ALREADY_OF_DESIRED_STATUS,			/**< Index is already of desired status. */
+RET_ADDINDEX_FAILED,							/**< Cannot swap between different indexsets. */
+RET_SWAPINDEX_FAILED,							/**< 20 Adding index to index set failed. */
+RET_NOTHING_TO_DO,								/**< Nothing to do. */
+RET_SETUP_BOUND_FAILED,							/**< Setting up bound index failed. */
+RET_SETUP_CONSTRAINT_FAILED,					/**< Setting up constraint index failed. */
+RET_MOVING_BOUND_FAILED,						/**< Moving bound between index sets failed. */
+RET_MOVING_CONSTRAINT_FAILED,					/**< Moving constraint between index sets failed. */
+/* QProblem */
+RET_QP_ALREADY_INITIALISED,						/**< QProblem has already been initialised. */
+RET_NO_INIT_WITH_STANDARD_SOLVER,				/**< Initialisation via extern QP solver is not yet implemented. */
+RET_RESET_FAILED,								/**< Reset failed. */
+RET_INIT_FAILED,								/**< Initialisation failed. */
+RET_INIT_FAILED_TQ,								/**< 30 Initialisation failed due to TQ factorisation. */
+RET_INIT_FAILED_CHOLESKY,						/**< Initialisation failed due to Cholesky decomposition. */
+RET_INIT_FAILED_HOTSTART,						/**< Initialisation failed! QP could not be solved! */
+RET_INIT_FAILED_INFEASIBILITY,					/**< Initial QP could not be solved due to infeasibility! */
+RET_INIT_FAILED_UNBOUNDEDNESS,					/**< Initial QP could not be solved due to unboundedness! */
+RET_INIT_SUCCESSFUL,							/**< Initialisation done. */
+RET_OBTAINING_WORKINGSET_FAILED,				/**< Failed to obtain working set for auxiliary QP. */
+RET_SETUP_WORKINGSET_FAILED,					/**< Failed to setup working set for auxiliary QP. */
+RET_SETUP_AUXILIARYQP_FAILED,					/**< Failed to setup auxiliary QP for initialised homotopy. */
+RET_NO_EXTERN_SOLVER,							/**< No extern QP solver available. */
+RET_QP_UNBOUNDED,								/**< 40 QP is unbounded. */
+RET_QP_INFEASIBLE,								/**< QP is infeasible. */
+RET_QP_NOT_SOLVED,								/**< Problems occured while solving QP with standard solver. */
+RET_QP_SOLVED,									/**< QP successfully solved. */
+RET_UNABLE_TO_SOLVE_QP,							/**< Problems occured while solving QP. */
+RET_INITIALISATION_STARTED,						/**< Starting problem initialisation. */
+RET_HOTSTART_FAILED,							/**< Unable to perform homotopy due to internal error. */
+RET_HOTSTART_FAILED_TO_INIT,					/**< Unable to initialise problem. */
+RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED,		/**< Unable to perform homotopy as previous QP is not solved. */
+RET_ITERATION_STARTED,							/**< Iteration... */
+RET_SHIFT_DETERMINATION_FAILED,					/**< 50 Determination of shift of the QP data failed. */
+RET_STEPDIRECTION_DETERMINATION_FAILED,			/**< Determination of step direction failed. */
+RET_STEPLENGTH_DETERMINATION_FAILED,			/**< Determination of step direction failed. */
+RET_OPTIMAL_SOLUTION_FOUND,						/**< Optimal solution of neighbouring QP found. */
+RET_HOMOTOPY_STEP_FAILED,						/**< Unable to perform homotopy step. */
+RET_HOTSTART_STOPPED_INFEASIBILITY,				/**< Premature homotopy termination because QP is infeasible. */
+RET_HOTSTART_STOPPED_UNBOUNDEDNESS,				/**< Premature homotopy termination because QP is unbounded. */
+RET_WORKINGSET_UPDATE_FAILED,					/**< Unable to update working sets according to initial guesses. */
+RET_MAX_NWSR_REACHED,							/**< Maximum number of working set recalculations performed. */
+RET_CONSTRAINTS_NOT_SPECIFIED,					/**< Problem does comprise constraints! You also have to specify new constraints' bounds. */
+RET_INVALID_FACTORISATION_FLAG,					/**< 60 Invalid factorisation flag. */
+RET_UNABLE_TO_SAVE_QPDATA,						/**< Unable to save QP data. */
+RET_STEPDIRECTION_FAILED_TQ,					/**< Abnormal termination due to TQ factorisation. */
+RET_STEPDIRECTION_FAILED_CHOLESKY,				/**< Abnormal termination due to Cholesky factorisation. */
+RET_CYCLING_DETECTED,							/**< Cycling detected. */
+RET_CYCLING_NOT_RESOLVED,						/**< Cycling cannot be resolved, QP probably infeasible. */
+RET_CYCLING_RESOLVED,							/**< Cycling probably resolved. */
+RET_STEPSIZE,									/**< For displaying performed stepsize. */
+RET_STEPSIZE_NONPOSITIVE,						/**< For displaying non-positive stepsize. */
+RET_SETUPSUBJECTTOTYPE_FAILED,					/**< Setup of SubjectToTypes failed. */
+RET_ADDCONSTRAINT_FAILED,						/**< 70 Addition of constraint to working set failed. */
+RET_ADDCONSTRAINT_FAILED_INFEASIBILITY,			/**< Addition of constraint to working set failed (due to QP infeasibility). */
+RET_ADDBOUND_FAILED,							/**< Addition of bound to working set failed. */
+RET_ADDBOUND_FAILED_INFEASIBILITY,				/**< Addition of bound to working set failed (due to QP infeasibility). */
+RET_REMOVECONSTRAINT_FAILED,					/**< Removal of constraint from working set failed. */
+RET_REMOVEBOUND_FAILED,							/**< Removal of bound from working set failed. */
+RET_REMOVE_FROM_ACTIVESET,						/**< Removing from active set... */
+RET_ADD_TO_ACTIVESET,							/**< Adding to active set... */
+RET_REMOVE_FROM_ACTIVESET_FAILED,				/**< Removing from active set failed. */
+RET_ADD_TO_ACTIVESET_FAILED,					/**< Adding to active set failed. */
+RET_CONSTRAINT_ALREADY_ACTIVE,					/**< 80 Constraint is already active. */
+RET_ALL_CONSTRAINTS_ACTIVE,						/**< All constraints are active, no further constraint can be added. */
+RET_LINEARLY_DEPENDENT,							/**< New bound/constraint is linearly dependent. */
+RET_LINEARLY_INDEPENDENT,						/**< New bound/constraint is linearly independent. */
+RET_LI_RESOLVED,								/**< Linear independence of active contraint matrix successfully resolved. */
+RET_ENSURELI_FAILED,							/**< Failed to ensure linear indepence of active contraint matrix. */
+RET_ENSURELI_FAILED_TQ,							/**< Abnormal termination due to TQ factorisation. */
+RET_ENSURELI_FAILED_NOINDEX,					/**< No index found, QP probably infeasible. */
+RET_ENSURELI_FAILED_CYCLING,					/**< Cycling detected, QP probably infeasible. */
+RET_BOUND_ALREADY_ACTIVE,						/**< Bound is already active. */
+RET_ALL_BOUNDS_ACTIVE,							/**< 90 All bounds are active, no further bound can be added. */
+RET_CONSTRAINT_NOT_ACTIVE,						/**< Constraint is not active. */
+RET_BOUND_NOT_ACTIVE,							/**< Bound is not active. */
+RET_HESSIAN_NOT_SPD,							/**< Projected Hessian matrix not positive definite. */
+RET_MATRIX_SHIFT_FAILED,						/**< Unable to update matrices or to transform vectors. */
+RET_MATRIX_FACTORISATION_FAILED,				/**< Unable to calculate new matrix factorisations. */
+RET_PRINT_ITERATION_FAILED,						/**< Unable to print information on current iteration. */
+RET_NO_GLOBAL_MESSAGE_OUTPUTFILE,				/**< No global message output file initialised. */
+/* Utils */
+RET_UNABLE_TO_OPEN_FILE,						/**< Unable to open file. */
+RET_UNABLE_TO_WRITE_FILE,						/**< Unable to write into file. */
+RET_UNABLE_TO_READ_FILE,						/**< 100 Unable to read from file. */
+RET_FILEDATA_INCONSISTENT,						/**< File contains inconsistent data. */
+/* SolutionAnalysis */
+RET_NO_SOLUTION, 								/**< QP solution does not satisfy KKT optimality conditions. */
+RET_INACCURATE_SOLUTION							/**< KKT optimality conditions not satisfied to sufficient accuracy. */
+};
+
+
+
+/** This class handles all kinds of messages (errors, warnings, infos) initiated
+ *  by qpOASES modules and stores the correspoding global preferences.
+ *
+ *	\author Hans Joachim Ferreau (special thanks to Leonard Wirsching)
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ */
+class MessageHandling
+{
+	/*
+	 *	INTERNAL DATA STRUCTURES
+	 */
+	public:
+		/** Data structure for entries in global message list. */
+		typedef struct {
+			returnValue key;							/**< Global return value. */
+			const char* data;							/**< Corresponding message. */
+			VisibilityStatus globalVisibilityStatus; 	/**< Determines if message can be printed.
+														* 	 If this value is set to VS_HIDDEN, no message is printed! */
+		} ReturnValueList;
+
+
+	/*
+	 *	PUBLIC MEMBER FUNCTIONS
+	 */
+	public:
+		/** Default constructor. */
+		MessageHandling( );
+
+		/** Constructor which takes the desired output file. */
+		MessageHandling(  myFILE* _outputFile					/**< Output file. */
+						  );
+
+		/** Constructor which takes the desired visibility states. */
+		MessageHandling(	VisibilityStatus _errorVisibility,	/**< Visibility status for error messages. */
+							VisibilityStatus _warningVisibility,/**< Visibility status for warning messages. */
+							VisibilityStatus _infoVisibility	/**< Visibility status for info messages. */
+							);
+
+		/** Constructor which takes the desired output file and desired visibility states. */
+		MessageHandling(	myFILE* _outputFile,				/**< Output file. */
+							VisibilityStatus _errorVisibility,	/**< Visibility status for error messages. */
+							VisibilityStatus _warningVisibility,/**< Visibility status for warning messages. */
+							VisibilityStatus _infoVisibility	/**< Visibility status for info messages. */
+							);
+
+		/** Copy constructor (deep copy). */
+		MessageHandling(	const MessageHandling& rhs	/**< Rhs object. */
+							);
+
+		/** Destructor. */
+		~MessageHandling( );
+
+		/** Assignment operator (deep copy). */
+		MessageHandling& operator=(	const MessageHandling& rhs	/**< Rhs object. */
+									);
+
+
+		/** Prints an error message(a simplified macro THROWERROR is also provided). \n
+		 *  Errors are definied as abnormal events which cause an immediate termination of the current (sub) function.
+		 *  Errors of a sub function should be commented by the calling function by means of a warning message
+		 *  (if this error does not cause an error of the calling function, either)!
+		 *  \return Error number returned by sub function call
+		 */
+		returnValue throwError(
+			returnValue Enumber,					/**< Error number returned by sub function call. */
+			const char* additionaltext,				/**< Additional error text (0, if none). */
+			const char* functionname,				/**< Name of function which caused the error. */
+			const char* filename,					/**< Name of file which caused the error. */
+			const unsigned long linenumber,			/**< Number of line which caused the error.incompatible binary file */
+			VisibilityStatus localVisibilityStatus	/**< Determines (locally) if error message can be printed to myStderr.
+			   									 *   If GLOBAL visibility status of the message is set to VS_HIDDEN,
+	   			 								 *   no message is printed, anyway! */
+		);
+
+		/** Prints a warning message (a simplified macro THROWWARNING is also provided).
+		 *  Warnings are definied as abnormal events which does NOT cause an immediate termination of the current (sub) function.
+		 *  \return Warning number returned by sub function call
+		 */
+		returnValue throwWarning(
+			returnValue Wnumber,	 				/**< Warning number returned by sub function call. */
+			const char* additionaltext,				/**< Additional warning text (0, if none). */
+			const char* functionname,				/**< Name of function which caused the warning. */
+			const char* filename,   				/**< Name of file which caused the warning. */
+			const unsigned long linenumber,	 		/**< Number of line which caused the warning. */
+			VisibilityStatus localVisibilityStatus	/**< Determines (locally) if warning message can be printed to myStderr.
+		   		  									 *   If GLOBAL visibility status of the message is set to VS_HIDDEN,
+					 								 *   no message is printed, anyway! */
+			);
+
+	   /** Prints a info message (a simplified macro THROWINFO is also provided).
+		 *  \return Info number returned by sub function call
+		 */
+		returnValue throwInfo(
+			returnValue Inumber,	 				/**< Info number returned by sub function call. */
+			const char* additionaltext,	 			/**< Additional warning text (0, if none). */
+			const char* functionname,				/**< Name of function which submitted the info. */
+			const char* filename,   				/**< Name of file which submitted the info. */
+			const unsigned long linenumber,			/**< Number of line which submitted the info. */
+			VisibilityStatus localVisibilityStatus	/**< Determines (locally) if info message can be printed to myStderr.
+				  									 *   If GLOBAL visibility status of the message is set to VS_HIDDEN,
+				   									 *   no message is printed, anyway! */
+			);
+
+
+		/** Resets all preferences to default values.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue reset( );
+
+
+		/** Prints a complete list of all messages to output file.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue listAllMessages( );
+
+
+		/** Returns visibility status for error messages.
+		 *	\return Visibility status for error messages. */
+		inline VisibilityStatus getErrorVisibilityStatus( ) const;
+
+		/** Returns visibility status for warning messages.
+		 *	\return Visibility status for warning messages. */
+		inline VisibilityStatus getWarningVisibilityStatus( ) const;
+
+		/** Returns visibility status for info messages.
+		 *	\return Visibility status for info messages. */
+		inline VisibilityStatus getInfoVisibilityStatus( ) const;
+
+		/** Returns pointer to output file.
+		 *	\return Pointer to output file. */
+		inline myFILE* getOutputFile( ) const;
+
+		/** Returns error count value.
+		 *	\return Error count value. */
+		inline int getErrorCount( ) const;
+
+
+		/** Changes visibility status for error messages. */
+		inline void setErrorVisibilityStatus(	VisibilityStatus _errorVisibility	/**< New visibility status for error messages. */
+												);
+
+		/** Changes visibility status for warning messages. */
+		inline void setWarningVisibilityStatus(	VisibilityStatus _warningVisibility	/**< New visibility status for warning messages. */
+												);
+
+		/** Changes visibility status for info messages. */
+		inline void setInfoVisibilityStatus(	VisibilityStatus _infoVisibility	/**< New visibility status for info messages. */
+												);
+
+		/** Changes output file for messages. */
+		inline void setOutputFile(	myFILE* _outputFile	/**< New output file for messages. */
+									);
+
+		/** Changes error count.
+		 * \return SUCCESSFUL_RETURN \n
+		 *		   RET_INVALID_ARGUMENT */
+		inline returnValue setErrorCount(	int _errorCount	/**< New error count value. */
+											);
+
+		/** Return the error code string. */
+		static const char* getErrorString(int error);
+
+	/*
+	 *	PROTECTED MEMBER FUNCTIONS
+	 */
+	protected:
+		/** Prints a info message to myStderr (auxiliary function).
+		 *  \return Error/warning/info number returned by sub function call
+		 */
+		returnValue throwMessage(
+			returnValue RETnumber,	 				/**< Error/warning/info number returned by sub function call. */
+			const char* additionaltext,				/**< Additional warning text (0, if none). */
+			const char* functionname,				/**< Name of function which caused the error/warning/info. */
+			const char* filename,   				/**< Name of file which caused the error/warning/info. */
+			const unsigned long linenumber,			/**< Number of line which caused the error/warning/info. */
+			VisibilityStatus localVisibilityStatus,	/**< Determines (locally) if info message can be printed to myStderr.
+					  								 *   If GLOBAL visibility status of the message is set to VS_HIDDEN,
+				   									 *   no message is printed, anyway! */
+			const char* RETstring					/**< Leading string of error/warning/info message. */
+			);
+
+
+	/*
+	 *	PROTECTED MEMBER VARIABLES
+	 */
+	protected:
+		VisibilityStatus errorVisibility;		/**< Error messages visible? */
+		VisibilityStatus warningVisibility;		/**< Warning messages visible? */
+		VisibilityStatus infoVisibility;		/**< Info messages visible? */
+
+		myFILE* outputFile;						/**< Output file for messages. */
+
+		int errorCount; 						/**< Counts number of errors (for nicer output only). */
+};
+
+
+#ifndef __FUNCTION__
+  /** Ensures that __FUNCTION__ macro is defined. */
+  #define __FUNCTION__ 0
+#endif
+
+#ifndef __FILE__
+  /** Ensures that __FILE__ macro is defined. */
+  #define __FILE__ 0
+#endif
+
+#ifndef __LINE__
+  /** Ensures that __LINE__ macro is defined. */
+  #define __LINE__ 0
+#endif
+
+
+/** Short version of throwError with default values, only returnValue is needed */
+#define THROWERROR(retval) ( getGlobalMessageHandler( )->throwError((retval),0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE) )
+
+/** Short version of throwWarning with default values, only returnValue is needed */
+#define THROWWARNING(retval) ( getGlobalMessageHandler( )->throwWarning((retval),0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE) )
+
+/** Short version of throwInfo with default values, only returnValue is needed */
+#define THROWINFO(retval) ( getGlobalMessageHandler( )->throwInfo((retval),0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE) )
+
+
+/** Returns a pointer to global message handler.
+ *  \return Pointer to global message handler.
+ */
+MessageHandling* getGlobalMessageHandler( );
+
+
+#include <MessageHandling.ipp>
+
+#endif /* QPOASES_MESSAGEHANDLING_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/QProblem.hpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/QProblem.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..91dc43417542a5eb5091e3d6d6cd942482c5bd0a
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/QProblem.hpp
@@ -0,0 +1,666 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/QProblem.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Declaration of the QProblem class which is able to use the newly
+ *	developed online active set strategy for parametric quadratic programming.
+ */
+
+
+
+#ifndef QPOASES_QPROBLEM_HPP
+#define QPOASES_QPROBLEM_HPP
+
+
+#include <QProblemB.hpp>
+#include <Constraints.hpp>
+#include <CyclingManager.hpp>
+
+
+/** A class for setting up and solving quadratic programs. The main feature is
+ *	the possibily to use the newly developed online active set strategy for
+ * 	parametric quadratic programming.
+ *
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ */
+class QProblem : public QProblemB
+{
+	/* allow SolutionAnalysis class to access private members */
+	friend class SolutionAnalysis;
+	
+	/*
+	 *	PUBLIC MEMBER FUNCTIONS
+	 */
+	public:
+		/** Default constructor. */
+		QProblem( );
+
+		/** Constructor which takes the QP dimensions only. */
+		QProblem(	int _nV,	  				/**< Number of variables. */
+					int _nC  					/**< Number of constraints. */
+					);
+
+		/** Copy constructor (deep copy). */
+		QProblem(	const QProblem& rhs	/**< Rhs object. */
+					);
+
+		/** Destructor. */
+		~QProblem( );
+
+		/** Assignment operator (deep copy). */
+		QProblem& operator=(	const QProblem& rhs		/**< Rhs object. */
+								);
+
+
+		/** Clears all data structures of QProblemB except for QP data.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_RESET_FAILED */
+		returnValue reset( );
+
+
+		/** Initialises a QProblem with given QP data and solves it
+		 *	using an initial homotopy with empty working set (at most nWSR iterations).
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_INIT_FAILED \n
+					RET_INIT_FAILED_CHOLESKY \n
+					RET_INIT_FAILED_TQ \n
+					RET_INIT_FAILED_HOTSTART \n
+					RET_INIT_FAILED_INFEASIBILITY \n
+					RET_INIT_FAILED_UNBOUNDEDNESS \n
+					RET_MAX_NWSR_REACHED \n
+					RET_INVALID_ARGUMENTS \n
+					RET_INACCURATE_SOLUTION \n
+		 			RET_NO_SOLUTION */
+		returnValue init(	const real_t* const _H, 		/**< Hessian matrix. */
+							const real_t* const _g, 		/**< Gradient vector. */
+							const real_t* const _A,  		/**< Constraint matrix. */
+							const real_t* const _lb,		/**< Lower bound vector (on variables). \n
+																If no lower bounds exist, a NULL pointer can be passed. */
+							const real_t* const _ub,		/**< Upper bound vector (on variables). \n
+																If no upper bounds exist, a NULL pointer can be passed. */
+							const real_t* const _lbA,		/**< Lower constraints' bound vector. \n
+																If no lower constraints' bounds exist, a NULL pointer can be passed. */
+							const real_t* const _ubA,		/**< Upper constraints' bound vector. \n
+																If no lower constraints' bounds exist, a NULL pointer can be passed. */
+							int& nWSR,						/**< Input: Maximum number of working set recalculations when using initial homotopy.
+																Output: Number of performed working set recalculations. */
+							const real_t* const yOpt = 0,	/**< Initial guess for dual solution vector. */
+							real_t* const cputime = 0		/**< Output: CPU time required to initialise QP. */
+							);
+
+
+		/** Initialises a QProblem with given QP data and solves it
+		 *	using an initial homotopy with empty working set (at most nWSR iterations).
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_INIT_FAILED \n
+					RET_INIT_FAILED_CHOLESKY \n
+					RET_INIT_FAILED_TQ \n
+					RET_INIT_FAILED_HOTSTART \n
+					RET_INIT_FAILED_INFEASIBILITY \n
+					RET_INIT_FAILED_UNBOUNDEDNESS \n
+					RET_MAX_NWSR_REACHED \n
+					RET_INVALID_ARGUMENTS \n
+					RET_INACCURATE_SOLUTION \n
+		 			RET_NO_SOLUTION */
+		returnValue init(	const real_t* const _H, 		/**< Hessian matrix. */
+							const real_t* const _R, 		/**< Cholesky factorization of the Hessian matrix. */
+							const real_t* const _g, 		/**< Gradient vector. */
+							const real_t* const _A,  		/**< Constraint matrix. */
+							const real_t* const _lb,		/**< Lower bound vector (on variables). \n
+																If no lower bounds exist, a NULL pointer can be passed. */
+							const real_t* const _ub,		/**< Upper bound vector (on variables). \n
+																If no upper bounds exist, a NULL pointer can be passed. */
+							const real_t* const _lbA,		/**< Lower constraints' bound vector. \n
+																If no lower constraints' bounds exist, a NULL pointer can be passed. */
+							const real_t* const _ubA,		/**< Upper constraints' bound vector. \n
+																If no lower constraints' bounds exist, a NULL pointer can be passed. */
+							int& nWSR,						/**< Input: Maximum number of working set recalculations when using initial homotopy.
+																Output: Number of performed working set recalculations. */
+							const real_t* const yOpt = 0,	/**< Initial guess for dual solution vector. */
+							real_t* const cputime = 0		/**< Output: CPU time required to initialise QP. */
+							);
+
+
+		/** Solves QProblem using online active set strategy.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_MAX_NWSR_REACHED \n
+		 			RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n
+					RET_HOTSTART_FAILED \n
+					RET_SHIFT_DETERMINATION_FAILED \n
+					RET_STEPDIRECTION_DETERMINATION_FAILED \n
+					RET_STEPLENGTH_DETERMINATION_FAILED \n
+					RET_HOMOTOPY_STEP_FAILED \n
+					RET_HOTSTART_STOPPED_INFEASIBILITY \n
+					RET_HOTSTART_STOPPED_UNBOUNDEDNESS \n
+					RET_INACCURATE_SOLUTION \n
+		 			RET_NO_SOLUTION */
+		returnValue hotstart(	const real_t* const g_new,		/**< Gradient of neighbouring QP to be solved. */
+								const real_t* const lb_new,		/**< Lower bounds of neighbouring QP to be solved. \n
+													 			 	 If no lower bounds exist, a NULL pointer can be passed. */
+								const real_t* const ub_new,		/**< Upper bounds of neighbouring QP to be solved. \n
+													 			 	 If no upper bounds exist, a NULL pointer can be passed. */
+								const real_t* const lbA_new,	/**< Lower constraints' bounds of neighbouring QP to be solved. \n
+													 			 	 If no lower constraints' bounds exist, a NULL pointer can be passed. */
+								const real_t* const ubA_new,	/**< Upper constraints' bounds of neighbouring QP to be solved. \n
+													 			 	 If no upper constraints' bounds exist, a NULL pointer can be passed. */
+								int& nWSR,						/**< Input: Maximum number of working set recalculations; \n
+															 		 Output: Number of performed working set recalculations. */
+								real_t* const cputime			/**< Output: CPU time required to solve QP (or to perform nWSR iterations). */
+								);
+
+
+		/** Returns constraint matrix of the QP (deep copy).
+		  *	\return SUCCESSFUL_RETURN */
+		inline returnValue getA(	real_t* const _A	/**< Array of appropriate dimension for copying constraint matrix.*/
+									) const;
+
+		/** Returns a single row of constraint matrix of the QP (deep copy).
+		  *	\return SUCCESSFUL_RETURN \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue getA(	int number,			/**< Number of entry to be returned. */
+									real_t* const row	/**< Array of appropriate dimension for copying (number)th constraint. */
+									) const;
+
+		/** Returns lower constraints' bound vector of the QP (deep copy).
+		  *	\return SUCCESSFUL_RETURN */
+		inline returnValue getLBA(	real_t* const _lbA	/**< Array of appropriate dimension for copying lower constraints' bound vector.*/
+									) const;
+
+		/** Returns single entry of lower constraints' bound vector of the QP.
+		  *	\return SUCCESSFUL_RETURN \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue getLBA(	int number,		/**< Number of entry to be returned. */
+									real_t& value	/**< Output: lbA[number].*/
+									) const;
+
+		/** Returns upper constraints' bound vector of the QP (deep copy).
+		  *	\return SUCCESSFUL_RETURN */
+		inline returnValue getUBA(	real_t* const _ubA	/**< Array of appropriate dimension for copying upper constraints' bound vector.*/
+									) const;
+
+		/** Returns single entry of upper constraints' bound vector of the QP.
+		  *	\return SUCCESSFUL_RETURN \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue getUBA(	int number,		/**< Number of entry to be returned. */
+									real_t& value	/**< Output: ubA[number].*/
+									) const;
+
+
+		/** Returns current constraints object of the QP (deep copy).
+		  *	\return SUCCESSFUL_RETURN */
+		inline returnValue getConstraints(	Constraints* const _constraints	/** Output: Constraints object. */
+											) const;
+
+
+		/** Returns the number of constraints.
+		 *	\return Number of constraints. */
+		inline int getNC( ) const;
+
+		/** Returns the number of (implicitly defined) equality constraints.
+		 *	\return Number of (implicitly defined) equality constraints. */
+		inline int getNEC( ) const;
+
+		/** Returns the number of active constraints.
+		 *	\return Number of active constraints. */
+		inline int getNAC( );
+
+		/** Returns the number of inactive constraints.
+		 *	\return Number of inactive constraints. */
+		inline int getNIAC( );
+
+		/** Returns the dimension of null space.
+		 *	\return Dimension of null space. */
+		int getNZ( );
+
+
+		/** Returns the dual solution vector (deep copy).
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_QP_NOT_SOLVED */
+		returnValue getDualSolution(	real_t* const yOpt	/**< Output: Dual solution vector (if QP has been solved). */
+										) const;
+
+
+	/*
+	 *	PROTECTED MEMBER FUNCTIONS
+	 */
+	protected:
+		/** Determines type of constraints and bounds (i.e. implicitly fixed, unbounded etc.).
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_SETUPSUBJECTTOTYPE_FAILED */
+		returnValue setupSubjectToType( );
+
+		/** Computes the Cholesky decomposition R of the projected Hessian (i.e. R^T*R = Z^T*H*Z).
+		 *	\return SUCCESSFUL_RETURN \n
+		 *			RET_INDEXLIST_CORRUPTED */
+		returnValue setupCholeskyDecompositionProjected( );
+
+		/** Initialises TQ factorisation of A (i.e. A*Q = [0 T]) if NO constraint is active.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_INDEXLIST_CORRUPTED */
+		returnValue setupTQfactorisation( );
+
+
+		/** Solves a QProblem whose QP data is assumed to be stored in the member variables.
+		 *  A guess for its primal/dual optimal solution vectors and the corresponding
+		 *  working sets of bounds and constraints can be provided.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_INIT_FAILED \n
+					RET_INIT_FAILED_CHOLESKY \n
+					RET_INIT_FAILED_TQ \n
+					RET_INIT_FAILED_HOTSTART \n
+					RET_INIT_FAILED_INFEASIBILITY \n
+					RET_INIT_FAILED_UNBOUNDEDNESS \n
+					RET_MAX_NWSR_REACHED */
+		returnValue solveInitialQP(	const real_t* const xOpt,						/**< Optimal primal solution vector.
+																					 *	 A NULL pointer can be passed. */
+									const real_t* const yOpt,						/**< Optimal dual solution vector.
+																					 *	 A NULL pointer can be passed. */
+									const Bounds* const guessedBounds,				/**< Guessed working set of bounds for solution (xOpt,yOpt).
+																		 			 *	 A NULL pointer can be passed. */
+									const Constraints* const guessedConstraints,	/**< Optimal working set of constraints for solution (xOpt,yOpt).
+																		 			 *	 A NULL pointer can be passed. */
+									int& nWSR, 										/**< Input: Maximum number of working set recalculations; \n
+																 					 *	 Output: Number of performed working set recalculations. */
+									real_t* const cputime							/**< Output: CPU time required to solve QP (or to perform nWSR iterations). */
+									);
+
+		/** Obtains the desired working set for the auxiliary initial QP in
+		 *  accordance with the user specifications
+		 *  (assumes that member AX has already been initialised!)
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_OBTAINING_WORKINGSET_FAILED \n
+					RET_INVALID_ARGUMENTS */
+		returnValue obtainAuxiliaryWorkingSet(	const real_t* const xOpt,						/**< Optimal primal solution vector.
+																								 *	 If a NULL pointer is passed, all entries are assumed to be zero. */
+												const real_t* const yOpt,						/**< Optimal dual solution vector.
+																								 *	 If a NULL pointer is passed, all entries are assumed to be zero. */
+												const Bounds* const guessedBounds,				/**< Guessed working set of bounds for solution (xOpt,yOpt). */
+												const Constraints* const guessedConstraints,	/**< Guessed working set for solution (xOpt,yOpt). */
+												Bounds* auxiliaryBounds,						/**< Input: Allocated bound object. \n
+																								 *	 Ouput: Working set of constraints for auxiliary QP. */
+												Constraints* auxiliaryConstraints				/**< Input: Allocated bound object. \n
+																								 *	 Ouput: Working set for auxiliary QP. */
+												) const;
+
+		/** Setups bound and constraints data structures according to auxiliaryBounds/Constraints.
+		 *  (If the working set shall be setup afresh, make sure that
+		 *  bounds and constraints data structure have been resetted
+		 *  and the TQ factorisation has been initialised!)
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_SETUP_WORKINGSET_FAILED \n
+					RET_INVALID_ARGUMENTS \n
+					RET_UNKNOWN BUG */
+		returnValue setupAuxiliaryWorkingSet(	const Bounds* const auxiliaryBounds,			/**< Working set of bounds for auxiliary QP. */
+												const Constraints* const auxiliaryConstraints,	/**< Working set of constraints for auxiliary QP. */
+												BooleanType setupAfresh							/**< Flag indicating if given working set shall be
+																								 *    setup afresh or by updating the current one. */
+												);
+
+		/** Setups the optimal primal/dual solution of the auxiliary initial QP.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue setupAuxiliaryQPsolution(	const real_t* const xOpt,			/**< Optimal primal solution vector.
+																				 	*	 If a NULL pointer is passed, all entries are set to zero. */
+												const real_t* const yOpt			/**< Optimal dual solution vector.
+																					 *	 If a NULL pointer is passed, all entries are set to zero. */
+												);
+
+		/** Setups gradient of the auxiliary initial QP for given
+		 *  optimal primal/dual solution and given initial working set
+		 *  (assumes that members X, Y and BOUNDS, CONSTRAINTS have already been initialised!).
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue setupAuxiliaryQPgradient( );
+
+		/** Setups (constraints') bounds of the auxiliary initial QP for given
+		 *  optimal primal/dual solution and given initial working set
+		 *  (assumes that members X, Y and BOUNDS, CONSTRAINTS have already been initialised!).
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_UNKNOWN BUG */
+		returnValue setupAuxiliaryQPbounds(	const Bounds* const auxiliaryBounds,			/**< Working set of bounds for auxiliary QP. */
+											const Constraints* const auxiliaryConstraints,	/**< Working set of constraints for auxiliary QP. */
+											BooleanType useRelaxation						/**< Flag indicating if inactive (constraints') bounds shall be relaxed. */
+											);
+
+
+		/** Adds a constraint to active set.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_ADDCONSTRAINT_FAILED \n
+					RET_ADDCONSTRAINT_FAILED_INFEASIBILITY \n
+					RET_ENSURELI_FAILED */
+		returnValue addConstraint(	int number,					/**< Number of constraint to be added to active set. */
+									SubjectToStatus C_status,	/**< Status of new active constraint. */
+									BooleanType updateCholesky	/**< Flag indicating if Cholesky decomposition shall be updated. */
+									);
+
+		/** Checks if new active constraint to be added is linearly dependent from
+		 *	from row of the active constraints matrix.
+		 *	\return	 RET_LINEARLY_DEPENDENT \n
+		 			 RET_LINEARLY_INDEPENDENT \n
+					 RET_INDEXLIST_CORRUPTED */
+		returnValue addConstraint_checkLI(	int number			/**< Number of constraint to be added to active set. */
+											);
+
+		/** Ensures linear independence of constraint matrix when a new constraint is added.
+		 * 	To this end a bound or constraint is removed simultaneously if necessary.
+		 *	\return	 SUCCESSFUL_RETURN \n
+		 			 RET_LI_RESOLVED \n
+					 RET_ENSURELI_FAILED \n
+					 RET_ENSURELI_FAILED_TQ \n
+					 RET_ENSURELI_FAILED_NOINDEX \n
+					 RET_REMOVE_FROM_ACTIVESET */
+		returnValue addConstraint_ensureLI(	int number,					/**< Number of constraint to be added to active set. */
+											SubjectToStatus C_status	/**< Status of new active bound. */
+											);
+
+		/** Adds a bound to active set.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_ADDBOUND_FAILED \n
+					RET_ADDBOUND_FAILED_INFEASIBILITY \n
+					RET_ENSURELI_FAILED */
+		returnValue addBound(	int number,					/**< Number of bound to be added to active set. */
+								SubjectToStatus B_status,	/**< Status of new active bound. */
+								BooleanType updateCholesky	/**< Flag indicating if Cholesky decomposition shall be updated. */
+								);
+
+		/** Checks if new active bound to be added is linearly dependent from
+		 *	from row of the active constraints matrix.
+		 *	\return	 RET_LINEARLY_DEPENDENT \n
+		 			 RET_LINEARLY_INDEPENDENT */
+		returnValue addBound_checkLI(	int number			/**< Number of bound to be added to active set. */
+										);
+
+		/** Ensures linear independence of constraint matrix when a new bound is added.
+		 *	To this end a bound or constraint is removed simultaneously if necessary.
+		 *	\return	 SUCCESSFUL_RETURN \n
+		 			 RET_LI_RESOLVED \n
+					 RET_ENSURELI_FAILED \n
+					 RET_ENSURELI_FAILED_TQ \n
+					 RET_ENSURELI_FAILED_NOINDEX \n
+					 RET_REMOVE_FROM_ACTIVESET */
+		returnValue addBound_ensureLI(	int number,					/**< Number of bound to be added to active set. */
+										SubjectToStatus B_status	/**< Status of new active bound. */
+										);
+
+		/** Removes a constraint from active set.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_CONSTRAINT_NOT_ACTIVE \n
+					RET_REMOVECONSTRAINT_FAILED \n
+					RET_HESSIAN_NOT_SPD */
+		returnValue removeConstraint(	int number,					/**< Number of constraint to be removed from active set. */
+										BooleanType updateCholesky	/**< Flag indicating if Cholesky decomposition shall be updated. */
+										);
+
+		/** Removes a bounds from active set.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_BOUND_NOT_ACTIVE \n
+					RET_HESSIAN_NOT_SPD \n
+					RET_REMOVEBOUND_FAILED */
+		returnValue removeBound(	int number,					/**< Number of bound to be removed from active set. */
+									BooleanType updateCholesky	/**< Flag indicating if Cholesky decomposition shall be updated. */
+									);
+
+
+		/** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_DIV_BY_ZERO */
+		returnValue backsolveR(	const real_t* const b,	/**< Right hand side vector. */
+								BooleanType transposed,	/**< Indicates if the transposed system shall be solved. */
+								real_t* const a 		/**< Output: Solution vector */
+								);
+
+		/** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix. \n
+		 *  Special variant for the case that this function is called from within "removeBound()".
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_DIV_BY_ZERO */
+		returnValue backsolveR(	const real_t* const b,		/**< Right hand side vector. */
+								BooleanType transposed,		/**< Indicates if the transposed system shall be solved. */
+								BooleanType removingBound,	/**< Indicates if function is called from "removeBound()". */
+								real_t* const a 			/**< Output: Solution vector */
+								);
+
+
+		/** Solves the system Ta = b or T^Ta = b where T is a reverse upper triangular matrix.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_DIV_BY_ZERO */
+		returnValue backsolveT(	const real_t* const b,	/**< Right hand side vector. */
+								BooleanType transposed,	/**< Indicates if the transposed system shall be solved. */
+								real_t* const a 		/**< Output: Solution vector */
+								);
+
+
+		/** Determines step direction of the shift of the QP data.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue hotstart_determineDataShift(const int* const FX_idx, 	/**< Index array of fixed variables. */
+												const int* const AC_idx, 	/**< Index array of active constraints. */
+												const real_t* const g_new,	/**< New gradient vector. */
+												const real_t* const lbA_new,/**< New lower constraints' bounds. */
+												const real_t* const ubA_new,/**< New upper constraints' bounds. */
+												const real_t* const lb_new,	/**< New lower bounds. */
+												const real_t* const ub_new,	/**< New upper bounds. */
+												real_t* const delta_g,	 	/**< Output: Step direction of gradient vector. */
+												real_t* const delta_lbA,	/**< Output: Step direction of lower constraints' bounds. */
+												real_t* const delta_ubA,	/**< Output: Step direction of upper constraints' bounds. */
+												real_t* const delta_lb,	 	/**< Output: Step direction of lower bounds. */
+												real_t* const delta_ub,	 	/**< Output: Step direction of upper bounds. */
+												BooleanType& Delta_bC_isZero,/**< Output: Indicates if active constraints' bounds are to be shifted. */
+												BooleanType& Delta_bB_isZero/**< Output: Indicates if active bounds are to be shifted. */
+												);
+
+		/** Determines step direction of the homotopy path.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_STEPDIRECTION_FAILED_TQ \n
+					RET_STEPDIRECTION_FAILED_CHOLESKY */
+		returnValue hotstart_determineStepDirection(const int* const FR_idx, 		/**< Index array of free variables. */
+													const int* const FX_idx, 		/**< Index array of fixed variables. */
+													const int* const AC_idx, 		/**< Index array of active constraints. */
+													const real_t* const delta_g,	/**< Step direction of gradient vector. */
+													const real_t* const delta_lbA,	/**< Step direction of lower constraints' bounds. */
+													const real_t* const delta_ubA,	/**< Step direction of upper constraints' bounds. */
+													const real_t* const delta_lb,	/**< Step direction of lower bounds. */
+													const real_t* const delta_ub,	/**< Step direction of upper bounds. */
+													BooleanType Delta_bC_isZero, 	/**< Indicates if active constraints' bounds are to be shifted. */
+													BooleanType Delta_bB_isZero,	/**< Indicates if active bounds are to be shifted. */
+													real_t* const delta_xFX, 		/**< Output: Primal homotopy step direction of fixed variables. */
+													real_t* const delta_xFR,	 	/**< Output: Primal homotopy step direction of free variables. */
+													real_t* const delta_yAC, 		/**< Output: Dual homotopy step direction of active constraints' multiplier. */
+													real_t* const delta_yFX 		/**< Output: Dual homotopy step direction of fixed variables' multiplier. */
+													);
+
+		/** Determines the maximum possible step length along the homotopy path.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue hotstart_determineStepLength(	const int* const FR_idx, 			/**< Index array of free variables. */
+													const int* const FX_idx, 			/**< Index array of fixed variables. */
+													const int* const AC_idx, 			/**< Index array of active constraints. */
+													const int* const IAC_idx, 			/**< Index array of inactive constraints. */
+													const real_t* const delta_lbA,		/**< Step direction of lower constraints' bounds. */
+													const real_t* const delta_ubA,		/**< Step direction of upper constraints' bounds. */
+													const real_t* const delta_lb,	 	/**< Step direction of lower bounds. */
+													const real_t* const delta_ub,	 	/**< Step direction of upper bounds. */
+													const real_t* const delta_xFX, 		/**< Primal homotopy step direction of fixed variables. */
+													const real_t* const delta_xFR,		/**< Primal homotopy step direction of free variables. */
+													const real_t* const delta_yAC,		/**< Dual homotopy step direction of active constraints' multiplier. */
+													const real_t* const delta_yFX,		/**< Dual homotopy step direction of fixed variables' multiplier. */
+													real_t* const delta_Ax,				/**< Output: Step in vector Ax. */
+													int& BC_idx, 						/**< Output: Index of blocking constraint. */
+													SubjectToStatus& BC_status,			/**< Output: Status of blocking constraint. */
+													BooleanType& BC_isBound 			/**< Output: Indicates if blocking constraint is a bound. */
+													);
+
+		/** Performs a step along the homotopy path (and updates active set).
+		 *	\return  SUCCESSFUL_RETURN \n
+		 			 RET_OPTIMAL_SOLUTION_FOUND \n
+		 			 RET_REMOVE_FROM_ACTIVESET_FAILED \n
+					 RET_ADD_TO_ACTIVESET_FAILED \n
+					 RET_QP_INFEASIBLE */
+		returnValue hotstart_performStep(	const int* const FR_idx, 			/**< Index array of free variables. */
+											const int* const FX_idx, 			/**< Index array of fixed variables. */
+											const int* const AC_idx, 			/**< Index array of active constraints. */
+											const int* const IAC_idx, 			/**< Index array of inactive constraints. */
+											const real_t* const delta_g,	 	/**< Step direction of gradient vector. */
+											const real_t* const delta_lbA,	 	/**< Step direction of lower constraints' bounds. */
+											const real_t* const delta_ubA,	 	/**< Step direction of upper constraints' bounds. */
+											const real_t* const delta_lb,	 	/**< Step direction of lower bounds. */
+											const real_t* const delta_ub,	 	/**< Step direction of upper bounds. */
+											const real_t* const delta_xFX, 		/**< Primal homotopy step direction of fixed variables. */
+											const real_t* const delta_xFR,	 	/**< Primal homotopy step direction of free variables. */
+											const real_t* const delta_yAC,	 	/**< Dual homotopy step direction of active constraints' multiplier. */
+											const real_t* const delta_yFX, 		/**< Dual homotopy step direction of fixed variables' multiplier. */
+											const real_t* const delta_Ax, 		/**< Step in vector Ax. */
+											int BC_idx, 						/**< Index of blocking constraint. */
+											SubjectToStatus BC_status,			/**< Status of blocking constraint. */
+											BooleanType BC_isBound 				/**< Indicates if blocking constraint is a bound. */
+											);
+
+
+		/** Checks if lower/upper (constraints') bounds remain consistent
+		 *  (i.e. if lb <= ub and lbA <= ubA ) during the current step.
+		 *	\return BT_TRUE iff (constraints") bounds remain consistent
+		 */
+		BooleanType areBoundsConsistent(	const real_t* const delta_lb,	/**< Step direction of lower bounds. */
+											const real_t* const delta_ub,	/**< Step direction of upper bounds. */
+											const real_t* const delta_lbA,	/**< Step direction of lower constraints' bounds. */
+											const real_t* const delta_ubA	/**< Step direction of upper constraints' bounds. */
+											) const;
+
+
+		/** Setups internal QP data.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_INVALID_ARGUMENTS */
+		returnValue setupQPdata(	const real_t* const _H, 	/**< Hessian matrix. */
+									const real_t* const _R, 	/**< Cholesky factorization of the Hessian matrix. */
+									const real_t* const _g, 	/**< Gradient vector. */
+									const real_t* const _A,  	/**< Constraint matrix. */
+									const real_t* const _lb,	/**< Lower bound vector (on variables). \n
+																	 If no lower bounds exist, a NULL pointer can be passed. */
+									const real_t* const _ub,	/**< Upper bound vector (on variables). \n
+																	 If no upper bounds exist, a NULL pointer can be passed. */
+									const real_t* const _lbA,	/**< Lower constraints' bound vector. \n
+																	 If no lower constraints' bounds exist, a NULL pointer can be passed. */
+									const real_t* const _ubA	/**< Upper constraints' bound vector. \n
+																	 If no lower constraints' bounds exist, a NULL pointer can be passed. */
+									);
+
+
+		#ifdef PC_DEBUG  /* Define print functions only for debugging! */
+
+		/** Prints concise information on the current iteration.
+		 *	\return  SUCCESSFUL_RETURN \n */
+		returnValue printIteration(	int iteration,				/**< Number of current iteration. */
+									int BC_idx, 				/**< Index of blocking constraint. */
+									SubjectToStatus BC_status,	/**< Status of blocking constraint. */
+									BooleanType BC_isBound 		/**< Indicates if blocking constraint is a bound. */
+									);
+
+		/** Prints concise information on the current iteration.
+		 *  NOTE: ONLY DEFINED FOR SUPPRESSING A COMPILER WARNING!!
+		 *	\return  SUCCESSFUL_RETURN \n */
+		returnValue printIteration(	int iteration,				/**< Number of current iteration. */
+									int BC_idx, 				/**< Index of blocking bound. */
+									SubjectToStatus BC_status	/**< Status of blocking bound. */
+									);
+
+		#endif  /* PC_DEBUG */
+
+
+		/** Determines the maximum violation of the KKT optimality conditions
+		 *  of the current iterate within the QProblem object.
+		 *	\return SUCCESSFUL_RETURN \n
+		 * 			RET_INACCURATE_SOLUTION \n
+		 * 			RET_NO_SOLUTION */
+		returnValue checkKKTconditions( );
+
+
+		/** Sets constraint matrix of the QP. \n
+			(Remark: Also internal vector Ax is recomputed!)
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setA(	const real_t* const A_new	/**< New constraint matrix (with correct dimension!). */
+									);
+
+		/** Changes single row of constraint matrix of the QP. \n
+			(Remark: Also correponding component of internal vector Ax is recomputed!)
+		 *	\return SUCCESSFUL_RETURN  \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue setA(	int number,					/**< Number of row to be changed. */
+									const real_t* const value	/**< New (number)th constraint (with correct dimension!). */
+									);
+
+
+		/** Sets constraints' lower bound vector of the QP.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setLBA(	const real_t* const lbA_new	/**< New constraints' lower bound vector (with correct dimension!). */
+									);
+
+		/** Changes single entry of lower constraints' bound vector of the QP.
+		 *	\return SUCCESSFUL_RETURN  \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue setLBA(	int number,		/**< Number of entry to be changed. */
+									real_t value	/**< New value for entry of lower constraints' bound vector (with correct dimension!). */
+									);
+
+		/** Sets constraints' upper bound vector of the QP.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setUBA(	const real_t* const ubA_new	/**< New constraints' upper bound vector (with correct dimension!). */
+									);
+
+		/** Changes single entry of upper constraints' bound vector of the QP.
+		 *	\return SUCCESSFUL_RETURN  \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue setUBA(	int number,		/**< Number of entry to be changed. */
+									real_t value	/**< New value for entry of upper constraints' bound vector (with correct dimension!). */
+									);
+
+
+	/*
+	 *	PROTECTED MEMBER VARIABLES
+	 */
+	protected:
+		real_t A[NCMAX_ALLOC*NVMAX];		/**< Constraint matrix. */
+		real_t lbA[NCMAX_ALLOC];			/**< Lower constraints' bound vector. */
+		real_t ubA[NCMAX_ALLOC];			/**< Upper constraints' bound vector. */
+
+		Constraints constraints;			/**< Data structure for problem's constraints. */
+
+		real_t T[NVMAX*NVMAX];				/**< Reverse triangular matrix, A = [0 T]*Q'. */
+		real_t Q[NVMAX*NVMAX];				/**< Orthonormal quadratic matrix, A = [0 T]*Q'. */
+		int sizeT;							/**< Matrix T is stored in a (sizeT x sizeT) array. */
+
+		real_t Ax[NCMAX_ALLOC];				/**< Stores the current product A*x (for increased efficiency only). */
+
+		CyclingManager cyclingManager;		/**< Data structure for storing (possible) cycling information (NOT YET IMPLEMENTED!). */
+};
+
+
+#include <QProblem.ipp>
+
+#endif	/* QPOASES_QPROBLEM_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/QProblemB.hpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/QProblemB.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..49ace9ef9d00472edfdc167df71d920842f712bd
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/QProblemB.hpp
@@ -0,0 +1,628 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/QProblemB.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Declaration of the QProblemB class which is able to use the newly
+ *	developed online active set strategy for parametric quadratic programming
+ *	for problems with (simple) bounds only.
+ */
+
+
+
+#ifndef QPOASES_QPROBLEMB_HPP
+#define QPOASES_QPROBLEMB_HPP
+
+
+#include <Bounds.hpp>
+
+
+
+class SolutionAnalysis;
+
+/** Class for setting up and solving quadratic programs with (simple) bounds only.
+ *	The main feature is the possibily to use the newly developed online active set strategy
+ *	for parametric quadratic programming.
+ *
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ */
+class QProblemB
+{
+	/* allow SolutionAnalysis class to access private members */
+	friend class SolutionAnalysis;
+	
+	/*
+	 *	PUBLIC MEMBER FUNCTIONS
+	 */
+	public:
+		/** Default constructor. */
+		QProblemB( );
+
+		/** Constructor which takes the QP dimension only. */
+		QProblemB(	int _nV						/**< Number of variables. */
+					);
+
+		/** Copy constructor (deep copy). */
+		QProblemB(	const QProblemB& rhs	/**< Rhs object. */
+					);
+
+		/** Destructor. */
+		~QProblemB( );
+
+		/** Assignment operator (deep copy). */
+		QProblemB& operator=(	const QProblemB& rhs	/**< Rhs object. */
+								);
+
+
+		/** Clears all data structures of QProblemB except for QP data.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_RESET_FAILED */
+		returnValue reset( );
+
+
+		/** Initialises a QProblemB with given QP data and solves it
+		 *	using an initial homotopy with empty working set (at most nWSR iterations).
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_INIT_FAILED \n
+					RET_INIT_FAILED_CHOLESKY \n
+					RET_INIT_FAILED_HOTSTART \n
+					RET_INIT_FAILED_INFEASIBILITY \n
+					RET_INIT_FAILED_UNBOUNDEDNESS \n
+					RET_MAX_NWSR_REACHED \n
+					RET_INVALID_ARGUMENTS \n
+					RET_INACCURATE_SOLUTION \n
+		 			RET_NO_SOLUTION */
+		returnValue init(	const real_t* const _H, 		/**< Hessian matrix. */
+							const real_t* const _g,			/**< Gradient vector. */
+							const real_t* const _lb,		/**< Lower bounds (on variables). \n
+																If no lower bounds exist, a NULL pointer can be passed. */
+							const real_t* const _ub,		/**< Upper bounds (on variables). \n
+																If no upper bounds exist, a NULL pointer can be passed. */
+							int& nWSR, 						/**< Input: Maximum number of working set recalculations when using initial homotopy. \n
+																Output: Number of performed working set recalculations. */
+							const real_t* const yOpt = 0,	/**< Initial guess for dual solution vector. */
+				 			real_t* const cputime = 0		/**< Output: CPU time required to initialise QP. */
+							);
+
+
+		/** Initialises a QProblemB with given QP data and solves it
+		 *	using an initial homotopy with empty working set (at most nWSR iterations).
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_INIT_FAILED \n
+					RET_INIT_FAILED_CHOLESKY \n
+					RET_INIT_FAILED_HOTSTART \n
+					RET_INIT_FAILED_INFEASIBILITY \n
+					RET_INIT_FAILED_UNBOUNDEDNESS \n
+					RET_MAX_NWSR_REACHED \n
+					RET_INVALID_ARGUMENTS \n
+					RET_INACCURATE_SOLUTION \n
+		 			RET_NO_SOLUTION */
+		returnValue init(	const real_t* const _H, 		/**< Hessian matrix. */
+							const real_t* const _R, 		/**< Cholesky factorization of the Hessian matrix. */
+							const real_t* const _g,			/**< Gradient vector. */
+							const real_t* const _lb,		/**< Lower bounds (on variables). \n
+																If no lower bounds exist, a NULL pointer can be passed. */
+							const real_t* const _ub,		/**< Upper bounds (on variables). \n
+																If no upper bounds exist, a NULL pointer can be passed. */
+							int& nWSR, 						/**< Input: Maximum number of working set recalculations when using initial homotopy. \n
+																Output: Number of performed working set recalculations. */
+							const real_t* const yOpt = 0,	/**< Initial guess for dual solution vector. */
+				 			real_t* const cputime = 0		/**< Output: CPU time required to initialise QP. */
+							);
+
+
+		/** Solves an initialised QProblemB using online active set strategy.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_MAX_NWSR_REACHED \n
+					RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n
+					RET_HOTSTART_FAILED \n
+					RET_SHIFT_DETERMINATION_FAILED \n
+					RET_STEPDIRECTION_DETERMINATION_FAILED \n
+					RET_STEPLENGTH_DETERMINATION_FAILED \n
+					RET_HOMOTOPY_STEP_FAILED \n
+					RET_HOTSTART_STOPPED_INFEASIBILITY \n
+					RET_HOTSTART_STOPPED_UNBOUNDEDNESS \n
+					RET_INACCURATE_SOLUTION \n
+		 			RET_NO_SOLUTION */
+		returnValue hotstart(	const real_t* const g_new,	/**< Gradient of neighbouring QP to be solved. */
+								const real_t* const lb_new,	/**< Lower bounds of neighbouring QP to be solved. \n
+													 			 If no lower bounds exist, a NULL pointer can be passed. */
+								const real_t* const ub_new,	/**< Upper bounds of neighbouring QP to be solved. \n
+													 			 If no upper bounds exist, a NULL pointer can be passed. */
+								int& nWSR,					/**< Input: Maximum number of working set recalculations; \n
+																 Output: Number of performed working set recalculations. */
+								real_t* const cputime		/**< Output: CPU time required to solve QP (or to perform nWSR iterations). */
+								);
+
+
+		/** Returns Hessian matrix of the QP (deep copy).
+		  *	\return SUCCESSFUL_RETURN */
+		inline returnValue getH(	real_t* const _H	/**< Array of appropriate dimension for copying Hessian matrix.*/
+									) const;
+
+		/** Returns gradient vector of the QP (deep copy).
+		  *	\return SUCCESSFUL_RETURN */
+		inline returnValue getG(	real_t* const _g	/**< Array of appropriate dimension for copying gradient vector.*/
+									) const;
+
+		/** Returns lower bound vector of the QP (deep copy).
+		  *	\return SUCCESSFUL_RETURN */
+		inline returnValue getLB(	real_t* const _lb	/**< Array of appropriate dimension for copying lower bound vector.*/
+									) const;
+
+		/** Returns single entry of lower bound vector of the QP.
+		  *	\return SUCCESSFUL_RETURN \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue getLB(	int number,		/**< Number of entry to be returned. */
+									real_t& value	/**< Output: lb[number].*/
+									) const;
+
+		/** Returns upper bound vector of the QP (deep copy).
+		  *	\return SUCCESSFUL_RETURN */
+		inline returnValue getUB(	real_t* const _ub	/**< Array of appropriate dimension for copying upper bound vector.*/
+									) const;
+
+		/** Returns single entry of upper bound vector of the QP.
+		  *	\return SUCCESSFUL_RETURN \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue getUB(	int number,		/**< Number of entry to be returned. */
+									real_t& value	/**< Output: ub[number].*/
+									) const;
+
+
+		/** Returns current bounds object of the QP (deep copy).
+		  *	\return SUCCESSFUL_RETURN */
+		inline returnValue getBounds(	Bounds* const _bounds	/** Output: Bounds object. */
+										) const;
+
+
+		/** Returns the number of variables.
+		 *	\return Number of variables. */
+		inline int getNV( ) const;
+
+		/** Returns the number of free variables.
+		 *	\return Number of free variables. */
+		inline int getNFR( );
+
+		/** Returns the number of fixed variables.
+		 *	\return Number of fixed variables. */
+		inline int getNFX( );
+
+		/** Returns the number of implicitly fixed variables.
+		 *	\return Number of implicitly fixed variables. */
+		inline int getNFV( ) const;
+
+		/** Returns the dimension of null space.
+		 *	\return Dimension of null space. */
+		int getNZ( );
+
+
+		/** Returns the optimal objective function value.
+		 *	\return finite value: Optimal objective function value (QP was solved) \n
+		 			+infinity:	  QP was not yet solved */
+		real_t getObjVal( ) const;
+
+		/** Returns the objective function value at an arbitrary point x.
+		 *	\return Objective function value at point x */
+		real_t getObjVal(	const real_t* const _x	/**< Point at which the objective function shall be evaluated. */
+							) const;
+
+		/** Returns the primal solution vector.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_QP_NOT_SOLVED */
+		returnValue getPrimalSolution(	real_t* const xOpt			/**< Output: Primal solution vector (if QP has been solved). */
+										) const;
+
+		/** Returns the dual solution vector.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_QP_NOT_SOLVED */
+		returnValue getDualSolution(	real_t* const yOpt	/**< Output: Dual solution vector (if QP has been solved). */
+										) const;
+
+
+		/** Returns status of the solution process.
+		 *	\return Status of solution process. */
+		inline QProblemStatus getStatus( ) const;
+
+
+		/** Returns if the QProblem object is initialised.
+		 *	\return BT_TRUE:  QProblemB initialised \n
+		 			BT_FALSE: QProblemB not initialised */
+		inline BooleanType isInitialised( ) const;
+
+		/** Returns if the QP has been solved.
+		 *	\return BT_TRUE:  QProblemB solved \n
+		 			BT_FALSE: QProblemB not solved */
+		inline BooleanType isSolved( ) const;
+
+		/** Returns if the QP is infeasible.
+		 *	\return BT_TRUE:  QP infeasible \n
+		 			BT_FALSE: QP feasible (or not known to be infeasible!) */
+		inline BooleanType isInfeasible( ) const;
+
+		/** Returns if the QP is unbounded.
+		 *	\return BT_TRUE:  QP unbounded \n
+		 			BT_FALSE: QP unbounded (or not known to be unbounded!) */
+		inline BooleanType isUnbounded( ) const;
+
+
+		/** Returns the print level.
+		 *	\return Print level. */
+		inline PrintLevel getPrintLevel( ) const;
+
+		/** Changes the print level.
+ 		 *	\return SUCCESSFUL_RETURN */
+		returnValue setPrintLevel(	PrintLevel _printlevel	/**< New print level. */
+									);
+
+
+		/** Returns Hessian type flag (type is not determined due to this call!).
+		 *	\return Hessian type. */
+		inline HessianType getHessianType( ) const;
+
+		/** Changes the print level.
+ 		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setHessianType(	HessianType _hessianType /**< New Hessian type. */
+											);
+
+
+	/*
+	 *	PROTECTED MEMBER FUNCTIONS
+	 */
+	protected:
+		/** Checks if Hessian happens to be the identity matrix,
+		 *  and sets corresponding status flag (otherwise the flag remains unaltered!).
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue checkForIdentityHessian( );
+
+		/** Determines type of constraints and bounds (i.e. implicitly fixed, unbounded etc.).
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_SETUPSUBJECTTOTYPE_FAILED */
+		returnValue setupSubjectToType( );
+
+		/** Computes the Cholesky decomposition R of the (simply projected) Hessian (i.e. R^T*R = Z^T*H*Z).
+		 *  It only works in the case where Z is a simple projection matrix!
+		 *	\return SUCCESSFUL_RETURN \n
+		 *			RET_INDEXLIST_CORRUPTED */
+		returnValue setupCholeskyDecomposition( );
+
+
+		/** Solves a QProblemB whose QP data is assumed to be stored in the member variables.
+		 *  A guess for its primal/dual optimal solution vectors and the corresponding
+		 *  optimal working set can be provided.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_INIT_FAILED \n
+					RET_INIT_FAILED_CHOLESKY \n
+					RET_INIT_FAILED_HOTSTART \n
+					RET_INIT_FAILED_INFEASIBILITY \n
+					RET_INIT_FAILED_UNBOUNDEDNESS \n
+					RET_MAX_NWSR_REACHED */
+		returnValue solveInitialQP(	const real_t* const xOpt,			/**< Optimal primal solution vector.
+																		 *	 A NULL pointer can be passed. */
+									const real_t* const yOpt,			/**< Optimal dual solution vector.
+																		 *	 A NULL pointer can be passed. */
+									const Bounds* const guessedBounds,	/**< Guessed working set for solution (xOpt,yOpt).
+																		 *	 A NULL pointer can be passed. */
+									int& nWSR, 							/**< Input: Maximum number of working set recalculations; \n
+																 		 *	 Output: Number of performed working set recalculations. */
+									real_t* const cputime				/**< Output: CPU time required to solve QP (or to perform nWSR iterations). */
+									);
+
+
+		/** Obtains the desired working set for the auxiliary initial QP in
+		 *  accordance with the user specifications
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_OBTAINING_WORKINGSET_FAILED \n
+					RET_INVALID_ARGUMENTS */
+		returnValue obtainAuxiliaryWorkingSet(	const real_t* const xOpt,			/**< Optimal primal solution vector.
+																					 *	 If a NULL pointer is passed, all entries are assumed to be zero. */
+												const real_t* const yOpt,			/**< Optimal dual solution vector.
+																					 *	 If a NULL pointer is passed, all entries are assumed to be zero. */
+												const Bounds* const guessedBounds,	/**< Guessed working set for solution (xOpt,yOpt). */
+												Bounds* auxiliaryBounds				/**< Input: Allocated bound object. \n
+																					 *	 Ouput: Working set for auxiliary QP. */
+												) const;
+
+		/** Setups bound data structure according to auxiliaryBounds.
+		 *  (If the working set shall be setup afresh, make sure that
+		 *  bounds data structure has been resetted!)
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_SETUP_WORKINGSET_FAILED \n
+					RET_INVALID_ARGUMENTS \n
+					RET_UNKNOWN BUG */
+		returnValue setupAuxiliaryWorkingSet(	const Bounds* const auxiliaryBounds,	/**< Working set for auxiliary QP. */
+												BooleanType setupAfresh					/**< Flag indicating if given working set shall be
+																						 *    setup afresh or by updating the current one. */
+												);
+
+		/** Setups the optimal primal/dual solution of the auxiliary initial QP.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue setupAuxiliaryQPsolution(	const real_t* const xOpt,			/**< Optimal primal solution vector.
+																				 	*	 If a NULL pointer is passed, all entries are set to zero. */
+												const real_t* const yOpt			/**< Optimal dual solution vector.
+																					 *	 If a NULL pointer is passed, all entries are set to zero. */
+												);
+
+		/** Setups gradient of the auxiliary initial QP for given
+		 *  optimal primal/dual solution and given initial working set
+		 *  (assumes that members X, Y and BOUNDS have already been initialised!).
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue setupAuxiliaryQPgradient( );
+
+		/** Setups bounds of the auxiliary initial QP for given
+		 *  optimal primal/dual solution and given initial working set
+		 *  (assumes that members X, Y and BOUNDS have already been initialised!).
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_UNKNOWN BUG */
+		returnValue setupAuxiliaryQPbounds( BooleanType useRelaxation	/**< Flag indicating if inactive bounds shall be relaxed. */
+											);
+
+
+		/** Adds a bound to active set (specialised version for the case where no constraints exist).
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_ADDBOUND_FAILED */
+		returnValue addBound(	int number,					/**< Number of bound to be added to active set. */
+								SubjectToStatus B_status,	/**< Status of new active bound. */
+								BooleanType updateCholesky	/**< Flag indicating if Cholesky decomposition shall be updated. */
+								);
+
+		/** Removes a bounds from active set (specialised version for the case where no constraints exist).
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_HESSIAN_NOT_SPD \n
+					RET_REMOVEBOUND_FAILED */
+		returnValue removeBound(	int number,					/**< Number of bound to be removed from active set. */
+									BooleanType updateCholesky	/**< Flag indicating if Cholesky decomposition shall be updated. */
+									);
+
+
+		/** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_DIV_BY_ZERO */
+		returnValue backsolveR(	const real_t* const b,	/**< Right hand side vector. */
+								BooleanType transposed,	/**< Indicates if the transposed system shall be solved. */
+								real_t* const a 		/**< Output: Solution vector */
+								);
+
+		/** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix. \n
+		 *  Special variant for the case that this function is called from within "removeBound()".
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_DIV_BY_ZERO */
+		returnValue backsolveR(	const real_t* const b,		/**< Right hand side vector. */
+								BooleanType transposed,		/**< Indicates if the transposed system shall be solved. */
+								BooleanType removingBound,	/**< Indicates if function is called from "removeBound()". */
+								real_t* const a 			/**< Output: Solution vector */
+								);
+
+
+		/** Determines step direction of the shift of the QP data.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue hotstart_determineDataShift(const int* const FX_idx, 	/**< Index array of fixed variables. */
+												const real_t* const g_new,	/**< New gradient vector. */
+												const real_t* const lb_new,	/**< New lower bounds. */
+												const real_t* const ub_new,	/**< New upper bounds. */
+												real_t* const delta_g,	 	/**< Output: Step direction of gradient vector. */
+												real_t* const delta_lb,	 	/**< Output: Step direction of lower bounds. */
+												real_t* const delta_ub,	 	/**< Output: Step direction of upper bounds. */
+												BooleanType& Delta_bB_isZero/**< Output: Indicates if active bounds are to be shifted. */
+												);
+
+
+		/** Checks if lower/upper bounds remain consistent
+		 *  (i.e. if lb <= ub) during the current step.
+		 *	\return BT_TRUE iff bounds remain consistent
+		 */
+		BooleanType areBoundsConsistent(	const real_t* const delta_lb,		/**< Step direction of lower bounds. */
+											const real_t* const delta_ub		/**< Step direction of upper bounds. */
+											) const;
+
+
+		/** Setups internal QP data.
+		 *	\return SUCCESSFUL_RETURN \n
+					RET_INVALID_ARGUMENTS */
+		returnValue setupQPdata(	const real_t* const _H, 	/**< Hessian matrix. */
+									const real_t* const _R, 	/**< Cholesky factorization of the Hessian matrix. */
+									const real_t* const _g,		/**< Gradient vector. */
+									const real_t* const _lb,	/**< Lower bounds (on variables). \n
+																	 If no lower bounds exist, a NULL pointer can be passed. */
+									const real_t* const _ub		/**< Upper bounds (on variables). \n
+																	 If no upper bounds exist, a NULL pointer can be passed. */
+									);
+
+
+		/** Sets Hessian matrix of the QP.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setH(	const real_t* const H_new	/**< New Hessian matrix (with correct dimension!). */
+									);
+
+		/** Changes gradient vector of the QP.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setG(	const real_t* const g_new	/**< New gradient vector (with correct dimension!). */
+									);
+
+		/** Changes lower bound vector of the QP.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setLB(	const real_t* const lb_new	/**< New lower bound vector (with correct dimension!). */
+									);
+
+		/** Changes single entry of lower bound vector of the QP.
+		 *	\return SUCCESSFUL_RETURN  \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue setLB(	int number,		/**< Number of entry to be changed. */
+									real_t value	/**< New value for entry of lower bound vector. */
+									);
+
+		/** Changes upper bound vector of the QP.
+		 *	\return SUCCESSFUL_RETURN */
+		inline returnValue setUB(	const real_t* const ub_new	/**< New upper bound vector (with correct dimension!). */
+									);
+
+		/** Changes single entry of upper bound vector of the QP.
+		 *	\return SUCCESSFUL_RETURN  \n
+					RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue setUB(	int number,		/**< Number of entry to be changed. */
+									real_t value	/**< New value for entry of upper bound vector. */
+									);
+
+
+		/** Computes parameters for the Givens matrix G for which [x,y]*G = [z,0]
+		 *	\return SUCCESSFUL_RETURN */
+		inline void computeGivens(	real_t xold,	/**< Matrix entry to be normalised. */
+									real_t yold,	/**< Matrix entry to be annihilated. */
+									real_t& xnew,	/**< Output: Normalised matrix entry. */
+									real_t& ynew,	/**< Output: Annihilated matrix entry. */
+									real_t& c,		/**< Output: Cosine entry of Givens matrix. */
+									real_t& s 		/**< Output: Sine entry of Givens matrix. */
+									) const;
+
+		/** Applies Givens matrix determined by c and s (cf. computeGivens).
+		 *	\return SUCCESSFUL_RETURN */
+		inline void applyGivens(	real_t c,		/**< Cosine entry of Givens matrix. */
+									real_t s,		/**< Sine entry of Givens matrix. */
+									real_t xold,	/**< Matrix entry to be transformed corresponding to
+													 *	 the normalised entry of the original matrix. */
+									real_t yold, 	/**< Matrix entry to be transformed corresponding to
+													 *	 the annihilated entry of the original matrix. */
+									real_t& xnew,	/**< Output: Transformed matrix entry corresponding to
+													 *	 the normalised entry of the original matrix. */
+									real_t& ynew	/**< Output: Transformed matrix entry corresponding to
+													 *	 the annihilated entry of the original matrix. */
+									) const;
+
+
+	/*
+	 *	PRIVATE MEMBER FUNCTIONS
+	 */
+	private:
+		/** Determines step direction of the homotopy path.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_STEPDIRECTION_FAILED_CHOLESKY */
+		returnValue hotstart_determineStepDirection(const int* const FR_idx, 		/**< Index array of free variables. */
+													const int* const FX_idx, 		/**< Index array of fixed variables. */
+													const real_t* const delta_g,	/**< Step direction of gradient vector. */
+													const real_t* const delta_lb,	/**< Step direction of lower bounds. */
+													const real_t* const delta_ub,	/**< Step direction of upper bounds. */
+													BooleanType Delta_bB_isZero,	/**< Indicates if active bounds are to be shifted. */
+													real_t* const delta_xFX, 		/**< Output: Primal homotopy step direction of fixed variables. */
+													real_t* const delta_xFR,	 	/**< Output: Primal homotopy step direction of free variables. */
+													real_t* const delta_yFX 		/**< Output: Dual homotopy step direction of fixed variables' multiplier. */
+													);
+
+		/** Determines the maximum possible step length along the homotopy path.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue hotstart_determineStepLength(	const int* const FR_idx, 		/**< Index array of free variables. */
+													const int* const FX_idx, 		/**< Index array of fixed variables. */
+													const real_t* const delta_lb,	/**< Step direction of lower bounds. */
+													const real_t* const delta_ub,	/**< Step direction of upper bounds. */
+													const real_t* const delta_xFR,	/**< Primal homotopy step direction of free variables. */
+													const real_t* const delta_yFX,	/**< Dual homotopy step direction of fixed variables' multiplier. */
+													int& BC_idx, 					/**< Output: Index of blocking constraint. */
+													SubjectToStatus& BC_status		/**< Output: Status of blocking constraint. */
+													);
+
+		/** Performs a step along the homotopy path (and updates active set).
+		 *	\return  SUCCESSFUL_RETURN \n
+		 			 RET_OPTIMAL_SOLUTION_FOUND \n
+		 			 RET_REMOVE_FROM_ACTIVESET_FAILED \n
+					 RET_ADD_TO_ACTIVESET_FAILED \n
+					 RET_QP_INFEASIBLE */
+		returnValue hotstart_performStep(	const int* const FR_idx, 			/**< Index array of free variables. */
+											const int* const FX_idx, 			/**< Index array of fixed variables. */
+											const real_t* const delta_g,	 	/**< Step direction of gradient vector. */
+											const real_t* const delta_lb,	 	/**< Step direction of lower bounds. */
+											const real_t* const delta_ub,	 	/**< Step direction of upper bounds. */
+											const real_t* const delta_xFX, 		/**< Primal homotopy step direction of fixed variables. */
+											const real_t* const delta_xFR,	 	/**< Primal homotopy step direction of free variables. */
+											const real_t* const delta_yFX, 		/**< Dual homotopy step direction of fixed variables' multiplier. */
+											int BC_idx, 						/**< Index of blocking constraint. */
+											SubjectToStatus BC_status 			/**< Status of blocking constraint. */
+											);
+
+
+		#ifdef PC_DEBUG  /* Define print functions only for debugging! */
+
+		/** Prints concise information on the current iteration.
+		 *	\return  SUCCESSFUL_RETURN \n */
+		returnValue printIteration(	int iteration,				/**< Number of current iteration. */
+									int BC_idx, 				/**< Index of blocking bound. */
+									SubjectToStatus BC_status	/**< Status of blocking bound. */
+									);
+
+		#endif  /* PC_DEBUG */
+
+
+		/** Determines the maximum violation of the KKT optimality conditions
+		 *  of the current iterate within the QProblemB object.
+		 *	\return SUCCESSFUL_RETURN \n
+		 * 			RET_INACCURATE_SOLUTION \n
+		 * 			RET_NO_SOLUTION */
+		returnValue checkKKTconditions( );
+
+
+	/*
+	 *	PROTECTED MEMBER VARIABLES
+	 */
+	protected:
+		real_t H[NVMAX*NVMAX];		/**< Hessian matrix. */
+		BooleanType hasHessian;		/**< Flag indicating whether H contains Hessian or corresponding Cholesky factor R; \sa init. */
+
+		real_t g[NVMAX];			/**< Gradient. */
+		real_t lb[NVMAX];			/**< Lower bound vector (on variables). */
+		real_t ub[NVMAX];			/**< Upper bound vector (on variables). */
+
+		Bounds bounds;				/**< Data structure for problem's bounds. */
+
+		real_t R[NVMAX*NVMAX];		/**< Cholesky decomposition of H (i.e. H = R^T*R). */
+		BooleanType hasCholesky;	/**< Flag indicating whether Cholesky decomposition has already been setup. */
+
+		real_t x[NVMAX];			/**< Primal solution vector. */
+		real_t y[NVMAX+NCMAX];		/**< Dual solution vector. */
+
+		real_t tau;					/**< Last homotopy step length. */
+
+		QProblemStatus status;		/**< Current status of the solution process. */
+
+		BooleanType infeasible;		/**< QP infeasible? */
+		BooleanType unbounded;		/**< QP unbounded? */
+
+		HessianType hessianType;	/**< Type of Hessian matrix. */
+
+		PrintLevel printlevel;		/**< Print level. */
+
+		int count;					/**< Counts the number of hotstart function calls (internal usage only!). */
+};
+
+
+#include <QProblemB.ipp>
+
+#endif	/* QPOASES_QPROBLEMB_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/SubjectTo.hpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/SubjectTo.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..e07bf0421ec799492637834acaee6f53730ae88b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/SubjectTo.hpp
@@ -0,0 +1,178 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/SubjectTo.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Declaration of the SubjectTo class designed to manage working sets of
+ *	constraints and bounds within a QProblem.
+ */
+
+
+#ifndef QPOASES_SUBJECTTO_HPP
+#define QPOASES_SUBJECTTO_HPP
+
+
+#include <Indexlist.hpp>
+
+
+
+/** This class manages working sets of constraints and bounds by storing
+ *	index sets and other status information.
+ *
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ */
+class SubjectTo
+{
+	/*
+	 *	PUBLIC MEMBER FUNCTIONS
+	 */
+	public:
+		/** Default constructor. */
+		SubjectTo( );
+
+		/** Copy constructor (deep copy). */
+		SubjectTo(	const SubjectTo& rhs	/**< Rhs object. */
+					);
+
+		/** Destructor. */
+		~SubjectTo( );
+
+		/** Assignment operator (deep copy). */
+		SubjectTo& operator=(	const SubjectTo& rhs	/**< Rhs object. */
+								);
+
+
+		/** Pseudo-constructor takes the number of constraints or bounds.
+		 *	\return SUCCESSFUL_RETURN */
+		returnValue init(	int n 	/**< Number of constraints or bounds. */
+							);
+
+
+		/** Returns type of (constraints') bound.
+		 *	\return Type of (constraints') bound \n
+		 			RET_INDEX_OUT_OF_BOUNDS */
+		inline SubjectToType getType(	int i		/**< Number of (constraints') bound. */
+										) const ;
+
+		/** Returns status of (constraints') bound.
+		 *	\return Status of (constraints') bound \n
+		 			ST_UNDEFINED */
+		inline SubjectToStatus getStatus(	int i		/**< Number of (constraints') bound. */
+											) const;
+
+
+		/** Sets type of (constraints') bound.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue setType(	int i,				/**< Number of (constraints') bound. */
+									SubjectToType value	/**< Type of (constraints') bound. */
+									);
+
+		/** Sets status of (constraints') bound.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_INDEX_OUT_OF_BOUNDS */
+		inline returnValue setStatus(	int i,					/**< Number of (constraints') bound. */
+										SubjectToStatus value	/**< Status of (constraints') bound. */
+										);
+
+
+		/** Sets status of lower (constraints') bounds. */
+		inline void setNoLower(	BooleanType _status		/**< Status of lower (constraints') bounds. */
+								);
+
+		/** Sets status of upper (constraints') bounds. */
+		inline void setNoUpper(	BooleanType _status		/**< Status of upper (constraints') bounds. */
+								);
+
+
+		/** Returns status of lower (constraints') bounds.
+		 *	\return BT_TRUE if there is no lower (constraints') bound on any variable. */
+		inline BooleanType isNoLower( ) const;
+
+		/** Returns status of upper bounds.
+		 *	\return BT_TRUE if there is no upper (constraints') bound on any variable. */
+		inline BooleanType isNoUpper( ) const;
+
+
+	/*
+	 *	PROTECTED MEMBER FUNCTIONS
+	 */
+	protected:
+		/** Adds the index of a new constraint or bound to index set.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_ADDINDEX_FAILED */
+		returnValue addIndex(	Indexlist* const indexlist,	/**< Index list to which the new index shall be added. */
+								int newnumber,				/**< Number of new constraint or bound. */
+								SubjectToStatus newstatus	/**< Status of new constraint or bound. */
+								);
+
+		/** Removes the index of a constraint or bound from index set.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_UNKNOWN_BUG */
+		returnValue removeIndex(	Indexlist* const indexlist,	/**< Index list from which the new index shall be removed. */
+									int removenumber			/**< Number of constraint or bound to be removed. */
+									);
+
+		/** Swaps the indices of two constraints or bounds within the index set.
+		 *	\return SUCCESSFUL_RETURN \n
+		 			RET_SWAPINDEX_FAILED */
+		returnValue swapIndex(	Indexlist* const indexlist,	/**< Index list in which the indices shold be swapped. */
+								int number1,				/**< Number of first constraint or bound. */
+								int number2					/**< Number of second constraint or bound. */
+								);
+
+
+	/*
+	 *	PROTECTED MEMBER VARIABLES
+	 */
+	protected:
+		SubjectToType type[NVMAX+NCMAX]; 		/**< Type of constraints/bounds. */
+		SubjectToStatus status[NVMAX+NCMAX];	/**< Status of constraints/bounds. */
+
+		BooleanType noLower;				 	/**< This flag indicates if there is no lower bound on any variable. */
+		BooleanType noUpper;	 				/**< This flag indicates if there is no upper bound on any variable. */
+
+
+	/*
+	 *	PRIVATE MEMBER VARIABLES
+	 */
+	private:
+		int size;
+};
+
+
+
+#include <SubjectTo.ipp>
+
+#endif	/* QPOASES_SUBJECTTO_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/Types.hpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/Types.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..5b873ad070a875bb5e6a82b8371ea145202ed3d4
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/Types.hpp
@@ -0,0 +1,131 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/Types.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2008
+ *
+ *	Declaration of all non-built-in types (except for classes).
+ */
+
+
+#ifndef QPOASES_TYPES_HPP
+#define QPOASES_TYPES_HPP
+
+
+
+/** Define real_t for facilitating switching between double and float. */
+// typedef double real_t;
+
+
+/** Summarises all possible logical values. */
+enum BooleanType
+{
+	BT_FALSE,					/**< Logical value for "false". */
+	BT_TRUE						/**< Logical value for "true". */
+};
+
+
+/** Summarises all possible print levels. Print levels are used to describe
+ *	the desired amount of output during runtime of qpOASES. */
+enum PrintLevel
+{
+	PL_NONE,					/**< No output. */
+	PL_LOW,						/**< Print error messages only. */
+	PL_MEDIUM,					/**< Print error and warning messages as well as concise info messages. */
+	PL_HIGH						/**< Print all messages with full details. */
+};
+
+
+/** Defines visibility status of a message. */
+enum VisibilityStatus
+{
+	VS_VISIBLE,					/**< Message visible. */
+	VS_HIDDEN					/**< Message not visible. */
+};
+
+
+/** Summarises all possible states of the (S)QProblem(B) object during the
+solution process of a QP sequence. */
+enum QProblemStatus
+{
+	QPS_NOTINITIALISED,			/**< QProblem object is freshly instantiated or reset. */
+	QPS_PREPARINGAUXILIARYQP,	/**< An auxiliary problem is currently setup, either at the very beginning
+								 *   via an initial homotopy or after changing the QP matrices. */
+	QPS_AUXILIARYQPSOLVED,		/**< An auxilary problem was solved, either at the very beginning
+								 *   via an initial homotopy or after changing the QP matrices. */
+	QPS_PERFORMINGHOMOTOPY,		/**< A homotopy according to the main idea of the online active
+								 *   set strategy is performed. */
+	QPS_HOMOTOPYQPSOLVED,		/**< An intermediate QP along the homotopy path was solved. */
+	QPS_SOLVED					/**< The solution of the actual QP was found. */
+};
+
+
+/** Summarises all possible types of bounds and constraints. */
+enum SubjectToType
+{
+	ST_UNBOUNDED,				/**< Bound/constraint is unbounded. */
+	ST_BOUNDED,					/**< Bound/constraint is bounded but not fixed. */
+	ST_EQUALITY,				/**< Bound/constraint is fixed (implicit equality bound/constraint). */
+	ST_UNKNOWN					/**< Type of bound/constraint unknown. */
+};
+
+
+/** Summarises all possible states of bounds and constraints. */
+enum SubjectToStatus
+{
+	ST_INACTIVE,				/**< Bound/constraint is inactive. */
+	ST_LOWER,					/**< Bound/constraint is at its lower bound. */
+	ST_UPPER,					/**< Bound/constraint is at its upper bound. */
+	ST_UNDEFINED				/**< Status of bound/constraint undefined. */
+};
+
+
+/** Summarises all possible cycling states of bounds and constraints. */
+enum CyclingStatus
+{
+	CYC_NOT_INVOLVED,			/**< Bound/constraint is not involved in current cycling. */
+	CYC_PREV_ADDED,				/**< Bound/constraint has previously been added during the current cycling. */
+	CYC_PREV_REMOVED			/**< Bound/constraint has previously been removed during the current cycling. */
+};
+
+
+/** Summarises all possible types of the QP's Hessian matrix. */
+enum HessianType
+{
+	HST_SEMIDEF,				/**< Hessian is positive semi-definite. */
+	HST_POSDEF_NULLSPACE,		/**< Hessian is positive definite on null space of active bounds/constraints. */
+	HST_POSDEF,					/**< Hessian is (strictly) positive definite. */
+	HST_IDENTITY				/**< Hessian is identity matrix. */
+};
+
+
+
+#endif	/* QPOASES_TYPES_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/Utils.hpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/Utils.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..a91ee78ccb5cd724efbabc393f257f2cd293f863
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/INCLUDE/Utils.hpp
@@ -0,0 +1,197 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file INCLUDE/Utils.hpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Declaration of global utility functions for working with qpOASES.
+ */
+
+
+#ifndef QPOASES_UTILS_HPP
+#define QPOASES_UTILS_HPP
+
+
+#include <MessageHandling.hpp>
+
+
+#ifdef PC_DEBUG  /* Define print functions only for debugging! */
+
+/** Prints a vector.
+ * \return SUCCESSFUL_RETURN */
+returnValue print(	const real_t* const v,	/**< Vector to be printed. */
+					int n					/**< Length of vector. */
+					);
+
+/** Prints a permuted vector.
+ * \return SUCCESSFUL_RETURN */
+returnValue print(	const real_t* const v,		/**< Vector to be printed. */
+					int n,						/**< Length of vector. */
+					const int* const V_idx		/**< Pemutation vector. */
+					);
+
+/** Prints a named vector.
+ * \return SUCCESSFUL_RETURN */
+returnValue print(	const real_t* const v,	/**< Vector to be printed. */
+					int n,					/**< Length of vector. */
+					const char* name		/** Name of vector. */
+					);
+
+/** Prints a matrix.
+ * \return SUCCESSFUL_RETURN */
+returnValue print(	const real_t* const M,	/**< Matrix to be printed. */
+					int nrow,				/**< Row number of matrix. */
+					int ncol				/**< Column number of matrix. */
+					);
+
+/** Prints a permuted matrix.
+ * \return SUCCESSFUL_RETURN */
+returnValue print(	const real_t* const M,		/**< Matrix to be printed. */
+					int nrow,					/**< Row number of matrix. */
+					int ncol	,				/**< Column number of matrix. */
+					const int* const ROW_idx,	/**< Row pemutation vector. */
+					const int* const COL_idx	/**< Column pemutation vector. */
+					);
+
+/** Prints a named matrix.
+ * \return SUCCESSFUL_RETURN */
+returnValue print(	const real_t* const M,	/**< Matrix to be printed. */
+					int nrow,				/**< Row number of matrix. */
+					int ncol,				/**< Column number of matrix. */
+					const char* name		/** Name of matrix. */
+					);
+
+/** Prints an index array.
+ * \return SUCCESSFUL_RETURN */
+returnValue print(	const int* const index,	/**< Index array to be printed. */
+					int n					/**< Length of index array. */
+					);
+
+/** Prints a named index array.
+ * \return SUCCESSFUL_RETURN */
+returnValue print(	const int* const index,	/**< Index array to be printed. */
+					int n,					/**< Length of index array. */
+					const char* name		/**< Name of index array. */
+					);
+
+
+/** Prints a string to desired output target (useful also for MATLAB output!).
+ * \return SUCCESSFUL_RETURN */
+returnValue myPrintf(	const char* s	/**< String to be written. */
+						);
+
+
+/** Prints qpOASES copyright notice.
+ * \return SUCCESSFUL_RETURN */
+returnValue printCopyrightNotice( );
+
+
+/** Reads a real_t matrix from file.
+ * \return SUCCESSFUL_RETURN \n
+ 		   RET_UNABLE_TO_OPEN_FILE \n
+		   RET_UNABLE_TO_READ_FILE */
+returnValue readFromFile(	real_t* data,				/**< Matrix to be read from file. */
+							int nrow,					/**< Row number of matrix. */
+							int ncol,					/**< Column number of matrix. */
+							const char* datafilename	/**< Data file name. */
+							);
+
+/** Reads a real_t vector from file.
+ * \return SUCCESSFUL_RETURN \n
+ 		   RET_UNABLE_TO_OPEN_FILE \n
+		   RET_UNABLE_TO_READ_FILE */
+returnValue readFromFile(	real_t* data,				/**< Vector to be read from file. */
+							int n,						/**< Length of vector. */
+							const char* datafilename	/**< Data file name. */
+							);
+
+/** Reads an integer (column) vector from file.
+ * \return SUCCESSFUL_RETURN \n
+ 		   RET_UNABLE_TO_OPEN_FILE \n
+		   RET_UNABLE_TO_READ_FILE */
+returnValue readFromFile(	int* data,					/**< Vector to be read from file. */
+							int n,						/**< Length of vector. */
+							const char* datafilename	/**< Data file name. */
+							);
+
+
+/** Writes a real_t matrix into a file.
+ * \return SUCCESSFUL_RETURN \n
+ 		   RET_UNABLE_TO_OPEN_FILE  */
+returnValue writeIntoFile(	const real_t* const data,	/**< Matrix to be written into file. */
+							int nrow,					/**< Row number of matrix. */
+							int ncol,					/**< Column number of matrix. */
+							const char* datafilename,	/**< Data file name. */
+							BooleanType append			/**< Indicates if data shall be appended if the file already exists (otherwise it is overwritten). */
+							);
+
+/** Writes a real_t vector into a file.
+ * \return SUCCESSFUL_RETURN \n
+ 		   RET_UNABLE_TO_OPEN_FILE  */
+returnValue writeIntoFile(	const real_t* const data,	/**< Vector to be written into file. */
+							int n,						/**< Length of vector. */
+							const char* datafilename,	/**< Data file name. */
+							BooleanType append			/**< Indicates if data shall be appended if the file already exists (otherwise it is overwritten). */
+							);
+
+/** Writes an integer (column) vector into a file.
+ * \return SUCCESSFUL_RETURN \n
+ 		   RET_UNABLE_TO_OPEN_FILE */
+returnValue writeIntoFile(	const int* const integer,	/**< Integer vector to be written into file. */
+							int n,						/**< Length of vector. */
+							const char* datafilename,	/**< Data file name. */
+							BooleanType append			/**< Indicates if integer shall be appended if the file already exists (otherwise it is overwritten). */
+							);
+
+#endif  /* PC_DEBUG */
+
+
+/** Returns the current system time.
+ * \return current system time */
+real_t getCPUtime( );
+
+
+/** Returns the Euclidean norm of a vector.
+ * \return 0: successful */
+real_t getNorm(	const real_t* const v,	/**< Vector. */
+				int n					/**< Vector's dimension. */
+				);
+
+/** Returns the absolute value of a real_t.
+ * \return Absolute value of a real_t */
+inline real_t getAbs(	real_t x		/**< Input argument. */
+						);
+
+
+
+#include <Utils.ipp>
+
+#endif	/* QPOASES_UTILS_HPP */
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/LICENSE.txt b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/LICENSE.txt
new file mode 100644
index 0000000000000000000000000000000000000000..5ab7695ab8cabe0c5c8a814bb0ab1e8066578fbb
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/LICENSE.txt
@@ -0,0 +1,504 @@
+		  GNU LESSER GENERAL PUBLIC LICENSE
+		       Version 2.1, February 1999
+
+ Copyright (C) 1991, 1999 Free Software Foundation, Inc.
+ 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ Everyone is permitted to copy and distribute verbatim copies
+ of this license document, but changing it is not allowed.
+
+[This is the first released version of the Lesser GPL.  It also counts
+ as the successor of the GNU Library Public License, version 2, hence
+ the version number 2.1.]
+
+			    Preamble
+
+  The licenses for most software are designed to take away your
+freedom to share and change it.  By contrast, the GNU General Public
+Licenses are intended to guarantee your freedom to share and change
+free software--to make sure the software is free for all its users.
+
+  This license, the Lesser General Public License, applies to some
+specially designated software packages--typically libraries--of the
+Free Software Foundation and other authors who decide to use it.  You
+can use it too, but we suggest you first think carefully about whether
+this license or the ordinary General Public License is the better
+strategy to use in any particular case, based on the explanations below.
+
+  When we speak of free software, we are referring to freedom of use,
+not price.  Our General Public Licenses are designed to make sure that
+you have the freedom to distribute copies of free software (and charge
+for this service if you wish); that you receive source code or can get
+it if you want it; that you can change the software and use pieces of
+it in new free programs; and that you are informed that you can do
+these things.
+
+  To protect your rights, we need to make restrictions that forbid
+distributors to deny you these rights or to ask you to surrender these
+rights.  These restrictions translate to certain responsibilities for
+you if you distribute copies of the library or if you modify it.
+
+  For example, if you distribute copies of the library, whether gratis
+or for a fee, you must give the recipients all the rights that we gave
+you.  You must make sure that they, too, receive or can get the source
+code.  If you link other code with the library, you must provide
+complete object files to the recipients, so that they can relink them
+with the library after making changes to the library and recompiling
+it.  And you must show them these terms so they know their rights.
+
+  We protect your rights with a two-step method: (1) we copyright the
+library, and (2) we offer you this license, which gives you legal
+permission to copy, distribute and/or modify the library.
+
+  To protect each distributor, we want to make it very clear that
+there is no warranty for the free library.  Also, if the library is
+modified by someone else and passed on, the recipients should know
+that what they have is not the original version, so that the original
+author's reputation will not be affected by problems that might be
+introduced by others.
+
+  Finally, software patents pose a constant threat to the existence of
+any free program.  We wish to make sure that a company cannot
+effectively restrict the users of a free program by obtaining a
+restrictive license from a patent holder.  Therefore, we insist that
+any patent license obtained for a version of the library must be
+consistent with the full freedom of use specified in this license.
+
+  Most GNU software, including some libraries, is covered by the
+ordinary GNU General Public License.  This license, the GNU Lesser
+General Public License, applies to certain designated libraries, and
+is quite different from the ordinary General Public License.  We use
+this license for certain libraries in order to permit linking those
+libraries into non-free programs.
+
+  When a program is linked with a library, whether statically or using
+a shared library, the combination of the two is legally speaking a
+combined work, a derivative of the original library.  The ordinary
+General Public License therefore permits such linking only if the
+entire combination fits its criteria of freedom.  The Lesser General
+Public License permits more lax criteria for linking other code with
+the library.
+
+  We call this license the "Lesser" General Public License because it
+does Less to protect the user's freedom than the ordinary General
+Public License.  It also provides other free software developers Less
+of an advantage over competing non-free programs.  These disadvantages
+are the reason we use the ordinary General Public License for many
+libraries.  However, the Lesser license provides advantages in certain
+special circumstances.
+
+  For example, on rare occasions, there may be a special need to
+encourage the widest possible use of a certain library, so that it becomes
+a de-facto standard.  To achieve this, non-free programs must be
+allowed to use the library.  A more frequent case is that a free
+library does the same job as widely used non-free libraries.  In this
+case, there is little to gain by limiting the free library to free
+software only, so we use the Lesser General Public License.
+
+  In other cases, permission to use a particular library in non-free
+programs enables a greater number of people to use a large body of
+free software.  For example, permission to use the GNU C Library in
+non-free programs enables many more people to use the whole GNU
+operating system, as well as its variant, the GNU/Linux operating
+system.
+
+  Although the Lesser General Public License is Less protective of the
+users' freedom, it does ensure that the user of a program that is
+linked with the Library has the freedom and the wherewithal to run
+that program using a modified version of the Library.
+
+  The precise terms and conditions for copying, distribution and
+modification follow.  Pay close attention to the difference between a
+"work based on the library" and a "work that uses the library".  The
+former contains code derived from the library, whereas the latter must
+be combined with the library in order to run.
+
+		  GNU LESSER GENERAL PUBLIC LICENSE
+   TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION
+
+  0. This License Agreement applies to any software library or other
+program which contains a notice placed by the copyright holder or
+other authorized party saying it may be distributed under the terms of
+this Lesser General Public License (also called "this License").
+Each licensee is addressed as "you".
+
+  A "library" means a collection of software functions and/or data
+prepared so as to be conveniently linked with application programs
+(which use some of those functions and data) to form executables.
+
+  The "Library", below, refers to any such software library or work
+which has been distributed under these terms.  A "work based on the
+Library" means either the Library or any derivative work under
+copyright law: that is to say, a work containing the Library or a
+portion of it, either verbatim or with modifications and/or translated
+straightforwardly into another language.  (Hereinafter, translation is
+included without limitation in the term "modification".)
+
+  "Source code" for a work means the preferred form of the work for
+making modifications to it.  For a library, complete source code means
+all the source code for all modules it contains, plus any associated
+interface definition files, plus the scripts used to control compilation
+and installation of the library.
+
+  Activities other than copying, distribution and modification are not
+covered by this License; they are outside its scope.  The act of
+running a program using the Library is not restricted, and output from
+such a program is covered only if its contents constitute a work based
+on the Library (independent of the use of the Library in a tool for
+writing it).  Whether that is true depends on what the Library does
+and what the program that uses the Library does.
+  
+  1. You may copy and distribute verbatim copies of the Library's
+complete source code as you receive it, in any medium, provided that
+you conspicuously and appropriately publish on each copy an
+appropriate copyright notice and disclaimer of warranty; keep intact
+all the notices that refer to this License and to the absence of any
+warranty; and distribute a copy of this License along with the
+Library.
+
+  You may charge a fee for the physical act of transferring a copy,
+and you may at your option offer warranty protection in exchange for a
+fee.
+
+  2. You may modify your copy or copies of the Library or any portion
+of it, thus forming a work based on the Library, and copy and
+distribute such modifications or work under the terms of Section 1
+above, provided that you also meet all of these conditions:
+
+    a) The modified work must itself be a software library.
+
+    b) You must cause the files modified to carry prominent notices
+    stating that you changed the files and the date of any change.
+
+    c) You must cause the whole of the work to be licensed at no
+    charge to all third parties under the terms of this License.
+
+    d) If a facility in the modified Library refers to a function or a
+    table of data to be supplied by an application program that uses
+    the facility, other than as an argument passed when the facility
+    is invoked, then you must make a good faith effort to ensure that,
+    in the event an application does not supply such function or
+    table, the facility still operates, and performs whatever part of
+    its purpose remains meaningful.
+
+    (For example, a function in a library to compute square roots has
+    a purpose that is entirely well-defined independent of the
+    application.  Therefore, Subsection 2d requires that any
+    application-supplied function or table used by this function must
+    be optional: if the application does not supply it, the square
+    root function must still compute square roots.)
+
+These requirements apply to the modified work as a whole.  If
+identifiable sections of that work are not derived from the Library,
+and can be reasonably considered independent and separate works in
+themselves, then this License, and its terms, do not apply to those
+sections when you distribute them as separate works.  But when you
+distribute the same sections as part of a whole which is a work based
+on the Library, the distribution of the whole must be on the terms of
+this License, whose permissions for other licensees extend to the
+entire whole, and thus to each and every part regardless of who wrote
+it.
+
+Thus, it is not the intent of this section to claim rights or contest
+your rights to work written entirely by you; rather, the intent is to
+exercise the right to control the distribution of derivative or
+collective works based on the Library.
+
+In addition, mere aggregation of another work not based on the Library
+with the Library (or with a work based on the Library) on a volume of
+a storage or distribution medium does not bring the other work under
+the scope of this License.
+
+  3. You may opt to apply the terms of the ordinary GNU General Public
+License instead of this License to a given copy of the Library.  To do
+this, you must alter all the notices that refer to this License, so
+that they refer to the ordinary GNU General Public License, version 2,
+instead of to this License.  (If a newer version than version 2 of the
+ordinary GNU General Public License has appeared, then you can specify
+that version instead if you wish.)  Do not make any other change in
+these notices.
+
+  Once this change is made in a given copy, it is irreversible for
+that copy, so the ordinary GNU General Public License applies to all
+subsequent copies and derivative works made from that copy.
+
+  This option is useful when you wish to copy part of the code of
+the Library into a program that is not a library.
+
+  4. You may copy and distribute the Library (or a portion or
+derivative of it, under Section 2) in object code or executable form
+under the terms of Sections 1 and 2 above provided that you accompany
+it with the complete corresponding machine-readable source code, which
+must be distributed under the terms of Sections 1 and 2 above on a
+medium customarily used for software interchange.
+
+  If distribution of object code is made by offering access to copy
+from a designated place, then offering equivalent access to copy the
+source code from the same place satisfies the requirement to
+distribute the source code, even though third parties are not
+compelled to copy the source along with the object code.
+
+  5. A program that contains no derivative of any portion of the
+Library, but is designed to work with the Library by being compiled or
+linked with it, is called a "work that uses the Library".  Such a
+work, in isolation, is not a derivative work of the Library, and
+therefore falls outside the scope of this License.
+
+  However, linking a "work that uses the Library" with the Library
+creates an executable that is a derivative of the Library (because it
+contains portions of the Library), rather than a "work that uses the
+library".  The executable is therefore covered by this License.
+Section 6 states terms for distribution of such executables.
+
+  When a "work that uses the Library" uses material from a header file
+that is part of the Library, the object code for the work may be a
+derivative work of the Library even though the source code is not.
+Whether this is true is especially significant if the work can be
+linked without the Library, or if the work is itself a library.  The
+threshold for this to be true is not precisely defined by law.
+
+  If such an object file uses only numerical parameters, data
+structure layouts and accessors, and small macros and small inline
+functions (ten lines or less in length), then the use of the object
+file is unrestricted, regardless of whether it is legally a derivative
+work.  (Executables containing this object code plus portions of the
+Library will still fall under Section 6.)
+
+  Otherwise, if the work is a derivative of the Library, you may
+distribute the object code for the work under the terms of Section 6.
+Any executables containing that work also fall under Section 6,
+whether or not they are linked directly with the Library itself.
+
+  6. As an exception to the Sections above, you may also combine or
+link a "work that uses the Library" with the Library to produce a
+work containing portions of the Library, and distribute that work
+under terms of your choice, provided that the terms permit
+modification of the work for the customer's own use and reverse
+engineering for debugging such modifications.
+
+  You must give prominent notice with each copy of the work that the
+Library is used in it and that the Library and its use are covered by
+this License.  You must supply a copy of this License.  If the work
+during execution displays copyright notices, you must include the
+copyright notice for the Library among them, as well as a reference
+directing the user to the copy of this License.  Also, you must do one
+of these things:
+
+    a) Accompany the work with the complete corresponding
+    machine-readable source code for the Library including whatever
+    changes were used in the work (which must be distributed under
+    Sections 1 and 2 above); and, if the work is an executable linked
+    with the Library, with the complete machine-readable "work that
+    uses the Library", as object code and/or source code, so that the
+    user can modify the Library and then relink to produce a modified
+    executable containing the modified Library.  (It is understood
+    that the user who changes the contents of definitions files in the
+    Library will not necessarily be able to recompile the application
+    to use the modified definitions.)
+
+    b) Use a suitable shared library mechanism for linking with the
+    Library.  A suitable mechanism is one that (1) uses at run time a
+    copy of the library already present on the user's computer system,
+    rather than copying library functions into the executable, and (2)
+    will operate properly with a modified version of the library, if
+    the user installs one, as long as the modified version is
+    interface-compatible with the version that the work was made with.
+
+    c) Accompany the work with a written offer, valid for at
+    least three years, to give the same user the materials
+    specified in Subsection 6a, above, for a charge no more
+    than the cost of performing this distribution.
+
+    d) If distribution of the work is made by offering access to copy
+    from a designated place, offer equivalent access to copy the above
+    specified materials from the same place.
+
+    e) Verify that the user has already received a copy of these
+    materials or that you have already sent this user a copy.
+
+  For an executable, the required form of the "work that uses the
+Library" must include any data and utility programs needed for
+reproducing the executable from it.  However, as a special exception,
+the materials to be distributed need not include anything that is
+normally distributed (in either source or binary form) with the major
+components (compiler, kernel, and so on) of the operating system on
+which the executable runs, unless that component itself accompanies
+the executable.
+
+  It may happen that this requirement contradicts the license
+restrictions of other proprietary libraries that do not normally
+accompany the operating system.  Such a contradiction means you cannot
+use both them and the Library together in an executable that you
+distribute.
+
+  7. You may place library facilities that are a work based on the
+Library side-by-side in a single library together with other library
+facilities not covered by this License, and distribute such a combined
+library, provided that the separate distribution of the work based on
+the Library and of the other library facilities is otherwise
+permitted, and provided that you do these two things:
+
+    a) Accompany the combined library with a copy of the same work
+    based on the Library, uncombined with any other library
+    facilities.  This must be distributed under the terms of the
+    Sections above.
+
+    b) Give prominent notice with the combined library of the fact
+    that part of it is a work based on the Library, and explaining
+    where to find the accompanying uncombined form of the same work.
+
+  8. You may not copy, modify, sublicense, link with, or distribute
+the Library except as expressly provided under this License.  Any
+attempt otherwise to copy, modify, sublicense, link with, or
+distribute the Library is void, and will automatically terminate your
+rights under this License.  However, parties who have received copies,
+or rights, from you under this License will not have their licenses
+terminated so long as such parties remain in full compliance.
+
+  9. You are not required to accept this License, since you have not
+signed it.  However, nothing else grants you permission to modify or
+distribute the Library or its derivative works.  These actions are
+prohibited by law if you do not accept this License.  Therefore, by
+modifying or distributing the Library (or any work based on the
+Library), you indicate your acceptance of this License to do so, and
+all its terms and conditions for copying, distributing or modifying
+the Library or works based on it.
+
+  10. Each time you redistribute the Library (or any work based on the
+Library), the recipient automatically receives a license from the
+original licensor to copy, distribute, link with or modify the Library
+subject to these terms and conditions.  You may not impose any further
+restrictions on the recipients' exercise of the rights granted herein.
+You are not responsible for enforcing compliance by third parties with
+this License.
+
+  11. If, as a consequence of a court judgment or allegation of patent
+infringement or for any other reason (not limited to patent issues),
+conditions are imposed on you (whether by court order, agreement or
+otherwise) that contradict the conditions of this License, they do not
+excuse you from the conditions of this License.  If you cannot
+distribute so as to satisfy simultaneously your obligations under this
+License and any other pertinent obligations, then as a consequence you
+may not distribute the Library at all.  For example, if a patent
+license would not permit royalty-free redistribution of the Library by
+all those who receive copies directly or indirectly through you, then
+the only way you could satisfy both it and this License would be to
+refrain entirely from distribution of the Library.
+
+If any portion of this section is held invalid or unenforceable under any
+particular circumstance, the balance of the section is intended to apply,
+and the section as a whole is intended to apply in other circumstances.
+
+It is not the purpose of this section to induce you to infringe any
+patents or other property right claims or to contest validity of any
+such claims; this section has the sole purpose of protecting the
+integrity of the free software distribution system which is
+implemented by public license practices.  Many people have made
+generous contributions to the wide range of software distributed
+through that system in reliance on consistent application of that
+system; it is up to the author/donor to decide if he or she is willing
+to distribute software through any other system and a licensee cannot
+impose that choice.
+
+This section is intended to make thoroughly clear what is believed to
+be a consequence of the rest of this License.
+
+  12. If the distribution and/or use of the Library is restricted in
+certain countries either by patents or by copyrighted interfaces, the
+original copyright holder who places the Library under this License may add
+an explicit geographical distribution limitation excluding those countries,
+so that distribution is permitted only in or among countries not thus
+excluded.  In such case, this License incorporates the limitation as if
+written in the body of this License.
+
+  13. The Free Software Foundation may publish revised and/or new
+versions of the Lesser General Public License from time to time.
+Such new versions will be similar in spirit to the present version,
+but may differ in detail to address new problems or concerns.
+
+Each version is given a distinguishing version number.  If the Library
+specifies a version number of this License which applies to it and
+"any later version", you have the option of following the terms and
+conditions either of that version or of any later version published by
+the Free Software Foundation.  If the Library does not specify a
+license version number, you may choose any version ever published by
+the Free Software Foundation.
+
+  14. If you wish to incorporate parts of the Library into other free
+programs whose distribution conditions are incompatible with these,
+write to the author to ask for permission.  For software which is
+copyrighted by the Free Software Foundation, write to the Free
+Software Foundation; we sometimes make exceptions for this.  Our
+decision will be guided by the two goals of preserving the free status
+of all derivatives of our free software and of promoting the sharing
+and reuse of software generally.
+
+			    NO WARRANTY
+
+  15. BECAUSE THE LIBRARY IS LICENSED FREE OF CHARGE, THERE IS NO
+WARRANTY FOR THE LIBRARY, TO THE EXTENT PERMITTED BY APPLICABLE LAW.
+EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR
+OTHER PARTIES PROVIDE THE LIBRARY "AS IS" WITHOUT WARRANTY OF ANY
+KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE
+IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
+PURPOSE.  THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE
+LIBRARY IS WITH YOU.  SHOULD THE LIBRARY PROVE DEFECTIVE, YOU ASSUME
+THE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION.
+
+  16. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN
+WRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY
+AND/OR REDISTRIBUTE THE LIBRARY AS PERMITTED ABOVE, BE LIABLE TO YOU
+FOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR
+CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE
+LIBRARY (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING
+RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A
+FAILURE OF THE LIBRARY TO OPERATE WITH ANY OTHER SOFTWARE), EVEN IF
+SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH
+DAMAGES.
+
+		     END OF TERMS AND CONDITIONS
+
+           How to Apply These Terms to Your New Libraries
+
+  If you develop a new library, and you want it to be of the greatest
+possible use to the public, we recommend making it free software that
+everyone can redistribute and change.  You can do so by permitting
+redistribution under these terms (or, alternatively, under the terms of the
+ordinary General Public License).
+
+  To apply these terms, attach the following notices to the library.  It is
+safest to attach them to the start of each source file to most effectively
+convey the exclusion of warranty; and each file should have at least the
+"copyright" line and a pointer to where the full notice is found.
+
+    <one line to give the library's name and a brief idea of what it does.>
+    Copyright (C) <year>  <name of author>
+
+    This library is free software; you can redistribute it and/or
+    modify it under the terms of the GNU Lesser General Public
+    License as published by the Free Software Foundation; either
+    version 2.1 of the License, or (at your option) any later version.
+
+    This library is distributed in the hope that it will be useful,
+    but WITHOUT ANY WARRANTY; without even the implied warranty of
+    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+    Lesser General Public License for more details.
+
+    You should have received a copy of the GNU Lesser General Public
+    License along with this library; if not, write to the Free Software
+    Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+
+Also add information on how to contact you by electronic and paper mail.
+
+You should also get your employer (if you work as a programmer) or your
+school, if any, to sign a "copyright disclaimer" for the library, if
+necessary.  Here is a sample; alter the names:
+
+  Yoyodyne, Inc., hereby disclaims all copyright interest in the
+  library `Frob' (a library for tweaking knobs) written by James Random Hacker.
+
+  <signature of Ty Coon>, 1 April 1990
+  Ty Coon, President of Vice
+
+That's all there is to it!
+
+
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/README.txt b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/README.txt
new file mode 100644
index 0000000000000000000000000000000000000000..53fc2ab4f86279d99ce969744a5a762f17c6dd7f
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/README.txt
@@ -0,0 +1,92 @@
+##
+##	qpOASES -- An Implementation of the Online Active Set Strategy.
+##	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+##
+##	qpOASES is free software; you can redistribute it and/or
+##	modify it under the terms of the GNU Lesser General Public
+##	License as published by the Free Software Foundation; either
+##	version 2.1 of the License, or (at your option) any later version.
+##
+##	qpOASES is distributed in the hope that it will be useful,
+##	but WITHOUT ANY WARRANTY; without even the implied warranty of
+##	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+##	Lesser General Public License for more details.
+##
+##	You should have received a copy of the GNU Lesser General Public
+##	License along with qpOASES; if not, write to the Free Software
+##	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+##
+
+
+
+INTRODUCTION
+=============
+
+qpOASES is an open-source C++ implementation of the recently proposed 
+online active set strategy (see [1], [2]), which was inspired by important 
+observations from the field of parametric quadratic programming. It has 
+several theoretical features that make it particularly suited for model 
+predictive control (MPC) applications.
+
+The software package qpOASES implements these ideas and has already been 
+successfully used for closed-loop control of a real-world Diesel engine [3].
+
+
+References:
+
+[1] H.J. Ferreau. An Online Active Set Strategy for Fast Solution of 
+Parametric Quadratic Programs with Applications to Predictive Engine Control. 
+Diplom thesis, University of Heidelberg, 2006.
+
+[2] H.J. Ferreau, H.G. Bock, M. Diehl. An online active set strategy to 
+overcome the limitations of explicit MPC. International Journal of Robust 
+and Nonlinear Control, 18 (8), pp. 816-830, 2008.
+
+[3] H.J. Ferreau, P. Ortner, P. Langthaler, L. del Re, M. Diehl. Predictive 
+Control of a Real-World Diesel Engine using an Extended Online Active Set 
+Strategy. Annual Reviews in Control, 31 (2), pp. 293-301, 2007.
+
+
+
+GETTING STARTED
+================
+
+1. For installation, usage and additional information on this software package 
+   see the qpOASES User's Manual located at ./DOC/manual.pdf!
+
+
+2. The file ./LICENSE.txt contains a copy of the GNU Lesser General Public 
+   License. Please read it carefully before using qpOASES!
+
+
+3. The whole software package can be downloaded from 
+
+        http://homes.esat.kuleuven.be/~optec/software/qpOASES/ 
+
+   On this webpage you will also find a list of frequently asked questions.
+
+
+
+CONTACT THE AUTHORS
+====================
+
+If you have got questions, remarks or comments on qpOASES 
+please contact the main author:
+
+        Hans Joachim Ferreau
+        Katholieke Universiteit Leuven
+        Department of Electrical Engineering (ESAT)
+        Kasteelpark Arenberg 10, bus 2446
+        B-3001 Leuven-Heverlee, Belgium
+
+        Phone: +32 16 32 03 63
+        E-mail: joachim.ferreau@esat.kuleuven.be
+                qpOASES@esat.kuleuven.be
+
+Also bug reports and source code extensions are most welcome!
+
+
+
+##
+##	end of file
+##
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Bounds.cpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Bounds.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..cf8ed69890623f1be8a2798bc097298ce09c1442
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Bounds.cpp
@@ -0,0 +1,252 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/Bounds.cpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of the Bounds class designed to manage working sets of
+ *	bounds within a QProblem.
+ */
+
+
+#include <Bounds.hpp>
+
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+
+/*
+ *	B o u n d s
+ */
+Bounds::Bounds( ) :	SubjectTo( ),
+					nV( 0 ),
+					nFV( 0 ),
+					nBV( 0 ),
+					nUV( 0 )
+{
+}
+
+
+/*
+ *	B o u n d s
+ */
+Bounds::Bounds( const Bounds& rhs ) :	SubjectTo( rhs ),
+										nV( rhs.nV ),
+										nFV( rhs.nFV ),
+										nBV( rhs.nBV ),
+										nUV( rhs.nUV )
+{
+	free  = rhs.free;
+	fixed = rhs.fixed;
+}
+
+
+/*
+ *	~ B o u n d s
+ */
+Bounds::~Bounds( )
+{
+}
+
+
+/*
+ *	o p e r a t o r =
+ */
+Bounds& Bounds::operator=( const Bounds& rhs )
+{
+	if ( this != &rhs )
+	{
+		SubjectTo::operator=( rhs );
+
+		nV  = rhs.nV;
+		nFV = rhs.nFV;
+		nBV = rhs.nBV;
+		nUV = rhs.nUV;
+
+		free  = rhs.free;
+		fixed = rhs.fixed;
+	}
+
+	return *this;
+}
+
+
+/*
+ *	i n i t
+ */
+returnValue Bounds::init( int n )
+{
+	nV = n;
+	nFV = 0;
+	nBV = 0;
+	nUV = 0;
+
+	free.init( );
+	fixed.init( );
+
+	return SubjectTo::init( n );
+}
+
+
+/*
+ *	s e t u p B o u n d
+ */
+returnValue Bounds::setupBound(	int _number, SubjectToStatus _status
+								)
+{
+	/* consistency check */
+	if ( ( _number < 0 ) || ( _number >= getNV( ) ) )
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+	
+	/* Add bound index to respective index list. */
+	switch ( _status )
+	{
+		case ST_INACTIVE:
+			if ( this->addIndex( this->getFree( ),_number,_status ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_BOUND_FAILED );
+			break;
+
+		case ST_LOWER:
+			if ( this->addIndex( this->getFixed( ),_number,_status ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_BOUND_FAILED );
+			break;
+
+		case ST_UPPER:
+			if ( this->addIndex( this->getFixed( ),_number,_status ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_BOUND_FAILED );
+			break;
+
+		default:
+			return THROWERROR( RET_INVALID_ARGUMENTS );
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p A l l F r e e
+ */
+returnValue Bounds::setupAllFree( )
+{
+	int i;
+
+	/* 1) Place unbounded variables at the beginning of the index list of free variables. */
+	for( i=0; i<nV; ++i )
+	{
+		if ( getType( i ) == ST_UNBOUNDED )
+		{
+			if ( setupBound( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_SETUP_BOUND_FAILED );
+		}
+	}
+
+	/* 2) Add remaining (i.e. bounded but possibly free) variables to the index list of free variables. */
+	for( i=0; i<nV; ++i )
+	{
+		if ( getType( i ) == ST_BOUNDED )
+		{
+			if ( setupBound( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_BOUND_FAILED );
+		}
+	}
+
+	/* 3) Place implicitly fixed variables at the end of the index list of free variables. */
+	for( i=0; i<nV; ++i )
+	{
+		if ( getType( i ) == ST_EQUALITY )
+		{
+			if ( setupBound( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_BOUND_FAILED );
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	m o v e F i x e d T o F r e e
+ */
+returnValue Bounds::moveFixedToFree( int _number )
+{
+	/* consistency check */
+	if ( ( _number < 0 ) || ( _number >= getNV( ) ) )
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+
+	/* Move index from indexlist of fixed variables to that of free ones. */
+	if ( this->removeIndex( this->getFixed( ),_number ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_MOVING_BOUND_FAILED );
+
+	if ( this->addIndex( this->getFree( ),_number,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_MOVING_BOUND_FAILED );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	m o v e F r e e T o F i x e d
+ */
+returnValue Bounds::moveFreeToFixed(	int _number, SubjectToStatus _status
+										)
+{
+	/* consistency check */
+	if ( ( _number < 0 ) || ( _number >= getNV( ) ) )
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+
+	/* Move index from indexlist of free variables to that of fixed ones. */
+	if ( this->removeIndex( this->getFree( ),_number ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_MOVING_BOUND_FAILED );
+
+	if ( this->addIndex( this->getFixed( ),_number,_status ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_MOVING_BOUND_FAILED );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s w a p F r e e
+ */
+returnValue Bounds::swapFree(	int number1, int number2
+								)
+{
+	/* consistency check */
+	if ( ( number1 < 0 ) || ( number1 >= getNV( ) ) || ( number2 < 0 ) || ( number2 >= getNV( ) ) )
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+
+	/* Swap index within indexlist of free variables. */
+	return this->swapIndex( this->getFree( ),number1,number2 );
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Bounds.ipp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Bounds.ipp
new file mode 100644
index 0000000000000000000000000000000000000000..d2ab1ba2d89835a1f1de05a5e7f50836123f5905
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Bounds.ipp
@@ -0,0 +1,144 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/Bounds.ipp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of inlined member functions of the Bounds class designed 
+ *	to manage working sets of bounds within a QProblem.
+ */
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+/*
+ *	g e t N V
+ */
+inline int Bounds::getNV( ) const
+{
+ 	return nV;
+}
+
+
+/*
+ *	g e t N F X
+ */
+inline int Bounds::getNFV( ) const
+{
+ 	return nFV;
+}
+
+
+/*
+ *	g e t N B V
+ */
+inline int Bounds::getNBV( ) const
+{
+ 	return nBV;
+}
+ 
+
+/*
+ *	g e t N U V
+ */
+inline int Bounds::getNUV( ) const
+{
+	return nUV;
+}
+
+
+
+/*
+ *	s e t N F X
+ */
+inline returnValue Bounds::setNFV( int n )
+{
+ 	nFV = n;
+	return SUCCESSFUL_RETURN;	
+}
+ 
+ 
+/*
+ *	s e t N B V
+ */
+inline returnValue Bounds::setNBV( int n )
+{
+ 	nBV = n;
+	return SUCCESSFUL_RETURN;
+}
+ 
+
+/*
+ *	s e t N U V
+ */
+inline returnValue Bounds::setNUV( int n )
+{
+	nUV = n;
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t N F R
+ */
+inline int Bounds::getNFR( )
+{
+ 	return free.getLength( );
+}
+
+
+/*
+ *	g e t N F X
+ */
+inline int Bounds::getNFX( )
+{
+ 	return fixed.getLength( );
+}
+
+
+/*
+ *	g e t F r e e
+ */
+inline Indexlist* Bounds::getFree( )
+{
+	return &free;
+}
+
+
+/*
+ *	g e t F i x e d
+ */
+inline Indexlist* Bounds::getFixed( )
+{
+	return &fixed;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Constraints.cpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Constraints.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..b2ad5bd111547e064fc44eabc520fdbe748bef5d
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Constraints.cpp
@@ -0,0 +1,248 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/Constraints.cpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of the Constraints class designed to manage working sets of
+ *	constraints within a QProblem.
+ */
+
+
+#include <Constraints.hpp>
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+
+/*
+ *	C o n s t r a i n t s
+ */
+Constraints::Constraints( ) :	SubjectTo( ),
+								nC( 0 ),
+								nEC( 0 ),
+								nIC( 0 ),
+								nUC( 0 )
+{
+}
+
+
+/*
+ *	C o n s t r a i n t s
+ */
+Constraints::Constraints( const Constraints& rhs ) :	SubjectTo( rhs ),
+														nC( rhs.nC ),
+														nEC( rhs.nEC ),
+														nIC( rhs.nIC ),
+														nUC( rhs.nUC )
+{
+	active =   rhs.active;
+	inactive = rhs.inactive;
+}
+
+
+/*
+ *	~ C o n s t r a i n t s
+ */
+Constraints::~Constraints( )
+{
+}
+
+
+/*
+ *	o p e r a t o r =
+ */
+Constraints& Constraints::operator=( const Constraints& rhs )
+{
+	if ( this != &rhs )
+	{
+		SubjectTo::operator=( rhs );
+
+		nC  = rhs.nC;
+		nEC = rhs.nEC;
+		nIC = rhs.nIC;
+		nUC = rhs.nUC;
+
+		active =   rhs.active;
+		inactive = rhs.inactive;
+	}
+
+	return *this;
+}
+
+
+/*
+ *	i n i t
+ */
+returnValue Constraints::init( int n )
+{
+	nC = n;
+	nEC = 0;
+	nIC = 0;
+	nUC = 0;
+
+	active.init( );
+	inactive.init( );
+
+	return SubjectTo::init( n );
+}
+
+
+/*
+ *	s e t u p C o n s t r a i n t
+ */
+returnValue Constraints::setupConstraint(	int _number, SubjectToStatus _status
+											)
+{
+	/* consistency check */
+	if ( ( _number < 0 ) || ( _number >= getNC( ) ) )
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+	
+	/* Add constraint index to respective index list. */
+	switch ( _status )
+	{
+		case ST_INACTIVE:
+			if ( this->addIndex( this->getInactive( ),_number,_status ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_CONSTRAINT_FAILED );
+			break;
+
+		case ST_LOWER:
+			if ( this->addIndex( this->getActive( ),_number,_status ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_CONSTRAINT_FAILED );
+			break;
+
+		case ST_UPPER:
+			if ( this->addIndex( this->getActive( ),_number,_status ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_CONSTRAINT_FAILED );
+			break;
+
+		default:
+			return THROWERROR( RET_INVALID_ARGUMENTS );
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p A l l I n a c t i v e
+ */
+returnValue Constraints::setupAllInactive( )
+{
+	int i;
+
+
+	/* 1) Place unbounded constraints at the beginning of the index list of inactive constraints. */
+	for( i=0; i<nC; ++i )
+	{
+		if ( getType( i ) == ST_UNBOUNDED )
+		{
+			if ( setupConstraint( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_CONSTRAINT_FAILED );
+		}
+	}
+
+	/* 2) Add remaining (i.e. "real" inequality) constraints to the index list of inactive constraints. */
+	for( i=0; i<nC; ++i )
+	{
+		if ( getType( i ) == ST_BOUNDED )
+		{
+			if ( setupConstraint( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_CONSTRAINT_FAILED );
+		}
+	}
+
+	/* 3) Place implicit equality constraints at the end of the index list of inactive constraints. */
+	for( i=0; i<nC; ++i )
+	{
+		if ( getType( i ) == ST_EQUALITY )
+		{
+			if ( setupConstraint( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_CONSTRAINT_FAILED );
+		}
+	}
+
+	/* 4) Moreover, add all constraints of unknown type. */
+	for( i=0; i<nC; ++i )
+	{
+		if ( getType( i ) == ST_UNKNOWN )
+		{
+			if ( setupConstraint( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_CONSTRAINT_FAILED );
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	m o v e A c t i v e T o I n a c t i v e
+ */
+returnValue Constraints::moveActiveToInactive( int _number )
+{
+	/* consistency check */
+	if ( ( _number < 0 ) || ( _number >= getNC( ) ) )
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+
+	/* Move index from indexlist of active constraints to that of inactive ones. */
+	if ( this->removeIndex( this->getActive( ),_number ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_MOVING_BOUND_FAILED );
+
+	if ( this->addIndex( this->getInactive( ),_number,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_MOVING_BOUND_FAILED );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	m o v e I n a c t i v e T o A c t i v e
+ */
+returnValue Constraints::moveInactiveToActive(	int _number, SubjectToStatus _status
+												)
+{
+	/* consistency check */
+	if ( ( _number < 0 ) || ( _number >= getNC( ) ) )
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+
+	/* Move index from indexlist of inactive constraints to that of active ones. */
+	if ( this->removeIndex( this->getInactive( ),_number ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_MOVING_BOUND_FAILED );
+
+	if ( this->addIndex( this->getActive( ),_number,_status ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_MOVING_BOUND_FAILED );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Constraints.ipp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Constraints.ipp
new file mode 100644
index 0000000000000000000000000000000000000000..1b874ef3c6596bf52bda2ae93147e2bb7e942be9
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Constraints.ipp
@@ -0,0 +1,144 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/Constraints.ipp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Declaration of inlined member functions of the Constraints class designed 
+ *	to manage working sets of constraints within a QProblem.
+ */
+
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+/*
+ *	g e t N C
+ */
+inline int Constraints::getNC( ) const
+{
+ 	return nC;
+}
+ 
+
+/*
+ *	g e t N E C
+ */
+inline int Constraints::getNEC( ) const
+{
+ 	return nEC;
+}
+ 
+
+/*
+ *	g e t N I C
+ */
+inline int Constraints::getNIC( ) const
+{
+ 	return nIC;
+}
+ 
+
+/*
+ *	g e t N U C
+ */
+inline int Constraints::getNUC( ) const
+{
+ 	return nUC;
+}
+
+
+/*
+ *	s e t N E C
+ */
+inline returnValue Constraints::setNEC( int n )
+{
+ 	nEC = n;
+	return SUCCESSFUL_RETURN;
+}
+ 
+
+/*
+ *	s e t N I C
+ */
+inline returnValue Constraints::setNIC( int n )
+{
+ 	nIC = n;
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t N U C
+ */
+inline returnValue Constraints::setNUC( int n )
+{
+ 	nUC = n;
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t N A C
+ */
+inline int Constraints::getNAC( )
+{
+ 	return active.getLength( );
+}
+
+
+/*
+ *	g e t N I A C
+ */
+inline int Constraints::getNIAC( )
+{
+ 	return inactive.getLength( );
+}
+
+
+/*
+ *	g e t A c t i v e
+ */
+inline Indexlist* Constraints::getActive( )
+{
+	return &active;
+}
+
+
+/*
+ *	g e t I n a c t i v e
+ */
+inline Indexlist* Constraints::getInactive( )
+{
+	return &inactive;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/CyclingManager.cpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/CyclingManager.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..27c2996ef3fff2e3ac8234f4e59cb4511571d3b0
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/CyclingManager.cpp
@@ -0,0 +1,188 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/CyclingManager.cpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of the CyclingManager class designed to detect
+ *	and handle possible cycling during QP iterations.
+ *
+ */
+
+
+#include <CyclingManager.hpp>
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+
+/*
+ *	C y c l i n g M a n a g e r
+ */
+CyclingManager::CyclingManager( ) :	nV( 0 ),
+									nC( 0 )
+{
+	cyclingDetected = BT_FALSE;
+}
+
+
+/*
+ *	C y c l i n g M a n a g e r
+ */
+CyclingManager::CyclingManager( const CyclingManager& rhs ) :	nV( rhs.nV ),
+																nC( rhs.nC ),
+																cyclingDetected( rhs.cyclingDetected )
+{
+	int i;
+
+	for( i=0; i<nV+nC; ++i )
+		status[i] = rhs.status[i];
+}
+
+
+/*
+ *	~ C y c l i n g M a n a g e r
+ */
+CyclingManager::~CyclingManager( )
+{
+}
+
+
+/*
+ *	o p e r a t o r =
+ */
+CyclingManager& CyclingManager::operator=( const CyclingManager& rhs )
+{
+	int i;
+
+	if ( this != &rhs )
+	{
+		nV = rhs.nV;
+		nC = rhs.nC;
+
+		for( i=0; i<nV+nC; ++i )
+			status[i] = rhs.status[i];
+
+		cyclingDetected = rhs.cyclingDetected;
+	}
+
+	return *this;
+}
+
+
+
+/*
+ *	i n i t
+ */
+returnValue CyclingManager::init( int _nV, int _nC )
+{
+	nV = _nV;
+	nC = _nC;
+
+	cyclingDetected = BT_FALSE;
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*
+ *	s e t C y c l i n g S t a t u s
+ */
+returnValue CyclingManager::setCyclingStatus(	int number,
+												BooleanType isBound, CyclingStatus _status
+												)
+{
+	if ( isBound == BT_TRUE )
+	{
+		/* Set cycling status of a bound. */
+		if ( ( number >= 0 ) && ( number < nV ) )
+		{
+			status[number] = _status;
+			return SUCCESSFUL_RETURN;
+		}
+		else
+			return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+	}
+	else
+	{
+		/* Set cycling status of a constraint. */
+		if ( ( number >= 0 ) && ( number < nC ) )
+		{
+			status[nV+number] = _status;
+			return SUCCESSFUL_RETURN;
+		}
+		else
+			return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+	}
+}
+
+
+/*
+ *	g e t C y c l i n g S t a t u s
+ */
+CyclingStatus CyclingManager::getCyclingStatus( int number, BooleanType isBound ) const
+{
+	if ( isBound == BT_TRUE )
+	{
+		/* Return cycling status of a bound. */
+		if ( ( number >= 0 ) && ( number < nV ) )
+			return status[number];
+	}
+	else
+	{
+		/* Return cycling status of a constraint. */
+		if ( ( number >= 0 ) && ( number < nC ) )
+			return status[nV+number];
+	}
+
+	return CYC_NOT_INVOLVED;
+}
+
+
+/*
+ *	c l e a r C y c l i n g D a t a
+ */
+returnValue CyclingManager::clearCyclingData( )
+{
+	int i;
+
+	/* Reset all status values ... */
+	for( i=0; i<nV+nC; ++i )
+		status[i] = CYC_NOT_INVOLVED;
+
+	/* ... and the main cycling flag. */
+	cyclingDetected = BT_FALSE;
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/CyclingManager.ipp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/CyclingManager.ipp
new file mode 100644
index 0000000000000000000000000000000000000000..386409a532bee46494649700215b5fd731c81716
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/CyclingManager.ipp
@@ -0,0 +1,51 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/CyclingManager.ipp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of inlined member functions of the CyclingManager class 
+ *	designed to detect and handle possible cycling during QP iterations.
+ *	
+ */
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+/*
+ *	i s C y c l i n g D e t e c t e d
+ */
+inline BooleanType CyclingManager::isCyclingDetected( ) const
+{
+	return cyclingDetected;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..c744adc0d60fb6066c6c5347b1adbe3c941565ab
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp
@@ -0,0 +1,434 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/EXTRAS/SolutionAnalysis.cpp
+ *	\author Milan Vukov, Boris Houska, Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2012
+ *
+ *	Solution analysis class, based on a class in the standard version of the qpOASES
+ */
+
+#include <EXTRAS/SolutionAnalysis.hpp>
+
+/*
+ *	S o l u t i o n A n a l y s i s
+ */
+SolutionAnalysis::SolutionAnalysis( )
+{
+	
+}
+
+/*
+ *	S o l u t i o n A n a l y s i s
+ */
+SolutionAnalysis::SolutionAnalysis( const SolutionAnalysis& rhs )
+{
+	
+}
+
+/*
+ *	~ S o l u t i o n A n a l y s i s
+ */
+SolutionAnalysis::~SolutionAnalysis( )
+{
+	
+}
+
+/*
+ *	o p e r a t o r =
+ */
+SolutionAnalysis& SolutionAnalysis::operator=( const SolutionAnalysis& rhs )
+{
+	if ( this != &rhs )
+	{
+		
+	}
+	
+	return *this;
+}
+
+/*
+ * g e t H e s s i a n I n v e r s e
+ */
+returnValue SolutionAnalysis::getHessianInverse( QProblem* qp, real_t* hessianInverse )
+{
+	returnValue returnvalue; /* the return value */
+	BooleanType Delta_bC_isZero = BT_FALSE; /* (just use FALSE here) */
+	BooleanType Delta_bB_isZero = BT_FALSE; /* (just use FALSE here) */
+	
+	register int run1, run2, run3;
+	
+	register int nFR, nFX;
+	
+	/* Ask for the number of free and fixed variables, assumes that active set
+	 * is constant for the covariance evaluation */
+	nFR = qp->getNFR( );
+	nFX = qp->getNFX( );
+	
+	/* Ask for the corresponding index arrays: */
+	if ( qp->bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_HOTSTART_FAILED );
+	
+	if ( qp->bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_HOTSTART_FAILED );
+	
+	if ( qp->constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_HOTSTART_FAILED );
+	
+	/* Initialization: */
+	for( run1 = 0; run1 < NVMAX; run1++ )
+		delta_g_cov[ run1 ] = 0.0;
+	
+	for( run1 = 0; run1 < NVMAX; run1++ )
+		delta_lb_cov[ run1 ] = 0.0;
+	
+	for( run1 = 0; run1 < NVMAX; run1++ )
+		delta_ub_cov[ run1 ] = 0.0;
+	
+	for( run1 = 0; run1 < NCMAX; run1++ )
+		delta_lbA_cov[ run1 ] = 0.0;
+	
+	for( run1 = 0; run1 < NCMAX; run1++ )
+		delta_ubA_cov[ run1 ] = 0.0;
+	
+	/* The following loop solves the following:
+	 *
+	 * KKT * x =
+	 *   [delta_g_cov', delta_lbA_cov', delta_ubA_cov', delta_lb_cov', delta_ub_cov]'
+	 *
+	 * for the first NVMAX (negative) elementary vectors in order to get
+	 * transposed inverse of the Hessian. Assuming that the Hessian is
+	 * symmetric, the function will return transposed inverse, instead of the
+	 * true inverse.
+	 *
+	 * Note, that we use negative elementary vectors due because internal
+	 * implementation of the function hotstart_determineStepDirection requires
+	 * so.
+	 *
+	 * */
+	
+	for( run3 = 0; run3 < NVMAX; run3++ )
+	{
+		/* Line wise loading of the corresponding (negative) elementary vector: */
+		delta_g_cov[ run3 ] = -1.0;
+		
+		/* Evaluation of the step: */
+		returnvalue = qp->hotstart_determineStepDirection(
+			FR_idx, FX_idx, AC_idx,
+			delta_g_cov, delta_lbA_cov, delta_ubA_cov, delta_lb_cov, delta_ub_cov,
+			Delta_bC_isZero, Delta_bB_isZero,
+			delta_xFX, delta_xFR, delta_yAC, delta_yFX
+			);
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			return returnvalue;
+		}
+		
+		/* Line wise storage of the QP reaction: */
+		for( run1 = 0; run1 < nFR; run1++ )
+		{
+			run2 = FR_idx[ run1 ];
+			
+			hessianInverse[run3 * NVMAX + run2] = delta_xFR[ run1 ];
+		} 
+		
+		for( run1 = 0; run1 < nFX; run1++ )
+		{ 
+			run2 = FX_idx[ run1 ];
+			
+			hessianInverse[run3 * NVMAX + run2] = delta_xFX[ run1 ];
+		}
+		
+		/* Prepare for the next iteration */
+		delta_g_cov[ run3 ] = 0.0;
+	}
+	
+	// TODO: Perform the transpose of the inverse of the Hessian matrix
+	
+	return SUCCESSFUL_RETURN; 
+}
+
+/*
+ * g e t H e s s i a n I n v e r s e
+ */
+returnValue SolutionAnalysis::getHessianInverse( QProblemB* qp, real_t* hessianInverse )
+{
+	returnValue returnvalue; /* the return value */
+	BooleanType Delta_bB_isZero = BT_FALSE; /* (just use FALSE here) */
+	
+	register int run1, run2, run3;
+	
+	register int nFR, nFX;
+	
+	/* Ask for the number of free and fixed variables, assumes that active set
+	 * is constant for the covariance evaluation */
+	nFR = qp->getNFR( );
+	nFX = qp->getNFX( );
+	
+	/* Ask for the corresponding index arrays: */
+	if ( qp->bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_HOTSTART_FAILED );
+	
+	if ( qp->bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_HOTSTART_FAILED );
+	
+	/* Initialization: */
+	for( run1 = 0; run1 < NVMAX; run1++ )
+		delta_g_cov[ run1 ] = 0.0;
+	
+	for( run1 = 0; run1 < NVMAX; run1++ )
+		delta_lb_cov[ run1 ] = 0.0;
+	
+	for( run1 = 0; run1 < NVMAX; run1++ )
+		delta_ub_cov[ run1 ] = 0.0;
+	
+	/* The following loop solves the following:
+	 *
+	 * KKT * x =
+	 *   [delta_g_cov', delta_lb_cov', delta_ub_cov']'
+	 *
+	 * for the first NVMAX (negative) elementary vectors in order to get
+	 * transposed inverse of the Hessian. Assuming that the Hessian is
+	 * symmetric, the function will return transposed inverse, instead of the
+	 * true inverse.
+	 *
+	 * Note, that we use negative elementary vectors due because internal
+	 * implementation of the function hotstart_determineStepDirection requires
+	 * so.
+	 *
+	 * */
+	
+	for( run3 = 0; run3 < NVMAX; run3++ )
+	{
+		/* Line wise loading of the corresponding (negative) elementary vector: */
+		delta_g_cov[ run3 ] = -1.0;
+		
+		/* Evaluation of the step: */
+		returnvalue = qp->hotstart_determineStepDirection(
+			FR_idx, FX_idx,
+			delta_g_cov, delta_lb_cov, delta_ub_cov,
+			Delta_bB_isZero,
+			delta_xFX, delta_xFR, delta_yFX
+			);
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			return returnvalue;
+		}
+				
+		/* Line wise storage of the QP reaction: */
+		for( run1 = 0; run1 < nFR; run1++ )
+		{
+			run2 = FR_idx[ run1 ];
+			
+			hessianInverse[run3 * NVMAX + run2] = delta_xFR[ run1 ];
+		} 
+		
+		for( run1 = 0; run1 < nFX; run1++ )
+		{ 
+			run2 = FX_idx[ run1 ];
+			
+			hessianInverse[run3 * NVMAX + run2] = delta_xFX[ run1 ];
+		}
+		
+		/* Prepare for the next iteration */
+		delta_g_cov[ run3 ] = 0.0;
+	}
+	
+	// TODO: Perform the transpose of the inverse of the Hessian matrix
+	
+	return SUCCESSFUL_RETURN; 
+}
+
+/*
+ * g e t V a r i a n c e C o v a r i a n c e
+ */
+
+#if QPOASES_USE_OLD_VERSION
+
+returnValue SolutionAnalysis::getVarianceCovariance( QProblem* qp, real_t* g_b_bA_VAR, real_t* Primal_Dual_VAR )
+{
+	int run1, run2, run3; /* simple run variables (for loops). */
+	
+	returnValue returnvalue; /* the return value */
+	BooleanType Delta_bC_isZero = BT_FALSE; /* (just use FALSE here) */
+	BooleanType Delta_bB_isZero = BT_FALSE; /* (just use FALSE here) */
+	
+	/* ASK FOR THE NUMBER OF FREE AND FIXED VARIABLES:
+	 * (ASSUMES THAT ACTIVE SET IS CONSTANT FOR THE
+	 *  VARIANCE-COVARIANCE EVALUATION)
+	 * ----------------------------------------------- */
+	int nFR, nFX, nAC;
+	
+	nFR = qp->getNFR( );
+	nFX = qp->getNFX( );
+	nAC = qp->getNAC( );
+	
+	if ( qp->bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_HOTSTART_FAILED );
+	
+	if ( qp->bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_HOTSTART_FAILED );
+	
+	if ( qp->constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_HOTSTART_FAILED );
+	
+	/* SOME INITIALIZATIONS:
+	 * --------------------- */
+	for( run1 = 0; run1 < KKT_DIM * KKT_DIM; run1++ )
+	{
+		K [run1] = 0.0;
+		Primal_Dual_VAR[run1] = 0.0;
+	}
+	
+	/* ================================================================= */
+	
+	/* FIRST MATRIX MULTIPLICATION (OBTAINS THE INTERMEDIATE RESULT
+	 *  K := [ ("ACTIVE" KKT-MATRIX OF THE QP)^(-1) * g_b_bA_VAR ]^T )
+	 * THE EVALUATION OF THE INVERSE OF THE KKT-MATRIX OF THE QP
+	 * WITH RESPECT TO THE CURRENT ACTIVE SET
+	 * USES THE EXISTING CHOLESKY AND TQ-DECOMPOSITIONS. FOR DETAILS
+	 * cf. THE (protected) FUNCTION determineStepDirection. */
+	
+	for( run3 = 0; run3 < KKT_DIM; run3++ )
+	{
+		
+		for( run1 = 0; run1 < NVMAX; run1++ )
+		{
+			delta_g_cov [run1] = g_b_bA_VAR[run3*KKT_DIM+run1];
+			delta_lb_cov [run1] = g_b_bA_VAR[run3*KKT_DIM+NVMAX+run1]; /*  LINE-WISE LOADING OF THE INPUT */
+			delta_ub_cov [run1] = g_b_bA_VAR[run3*KKT_DIM+NVMAX+run1]; /*  VARIANCE-COVARIANCE            */
+		}
+		for( run1 = 0; run1 < NCMAX; run1++ )
+		{
+			delta_lbA_cov [run1] = g_b_bA_VAR[run3*KKT_DIM+2*NVMAX+run1];
+			delta_ubA_cov [run1] = g_b_bA_VAR[run3*KKT_DIM+2*NVMAX+run1];
+		}
+		
+		/* EVALUATION OF THE STEP:
+		 * ------------------------------------------------------------------------------ */
+		
+		returnvalue = qp->hotstart_determineStepDirection(
+			FR_idx, FX_idx, AC_idx,
+			delta_g_cov, delta_lbA_cov, delta_ubA_cov, delta_lb_cov, delta_ub_cov,
+			Delta_bC_isZero, Delta_bB_isZero, delta_xFX,delta_xFR,
+			delta_yAC,delta_yFX );
+		
+		/* ------------------------------------------------------------------------------ */
+		
+		/* STOP THE ALGORITHM IN THE CASE OF NO SUCCESFUL RETURN:
+		 * ------------------------------------------------------ */
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			return returnvalue;
+		}
+		
+		/*  LINE WISE                  */
+		/*  STORAGE OF THE QP-REACTION */
+		/*  (uses the index list)      */
+		
+		for( run1=0; run1<nFR; run1++ )
+		{
+			run2 = FR_idx[run1];
+			K[run3*KKT_DIM+run2] = delta_xFR[run1];
+		} 
+		for( run1=0; run1<nFX; run1++ )
+		{ 
+			run2 = FX_idx[run1]; 
+			K[run3*KKT_DIM+run2] = delta_xFX[run1];
+			K[run3*KKT_DIM+NVMAX+run2] = delta_yFX[run1];
+		}
+		for( run1=0; run1<nAC; run1++ )
+		{
+			run2 = AC_idx[run1];
+			K[run3*KKT_DIM+2*NVMAX+run2] = delta_yAC[run1];
+		}
+	}
+	
+	/* ================================================================= */
+	
+	/* SECOND MATRIX MULTIPLICATION (OBTAINS THE FINAL RESULT
+	 * Primal_Dual_VAR := ("ACTIVE" KKT-MATRIX OF THE QP)^(-1) * K )
+	 * THE APPLICATION OF THE KKT-INVERSE IS AGAIN REALIZED
+	 * BY USING THE PROTECTED FUNCTION
+	 * determineStepDirection */
+	
+	for( run3 = 0; run3 < KKT_DIM; run3++ )
+	{
+		
+		for( run1 = 0; run1 < NVMAX; run1++ )
+		{
+			delta_g_cov [run1] = K[run3+ run1*KKT_DIM];
+			delta_lb_cov [run1] = K[run3+(NVMAX+run1)*KKT_DIM]; /*  ROW WISE LOADING OF THE */
+			delta_ub_cov [run1] = K[run3+(NVMAX+run1)*KKT_DIM]; /*  INTERMEDIATE RESULT K   */
+		}
+		for( run1 = 0; run1 < NCMAX; run1++ )
+		{
+			delta_lbA_cov [run1] = K[run3+(2*NVMAX+run1)*KKT_DIM];
+			delta_ubA_cov [run1] = K[run3+(2*NVMAX+run1)*KKT_DIM];
+		}
+		
+		/* EVALUATION OF THE STEP:
+		 * ------------------------------------------------------------------------------ */
+		
+		returnvalue = qp->hotstart_determineStepDirection(
+			FR_idx, FX_idx, AC_idx,
+			delta_g_cov, delta_lbA_cov, delta_ubA_cov, delta_lb_cov, delta_ub_cov,
+			Delta_bC_isZero, Delta_bB_isZero, delta_xFX,delta_xFR,
+			delta_yAC,delta_yFX );
+		
+		/* ------------------------------------------------------------------------------ */
+		
+		/* STOP THE ALGORITHM IN THE CASE OF NO SUCCESFUL RETURN:
+		 * ------------------------------------------------------ */
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			return returnvalue;
+		}
+		
+		/*  ROW-WISE STORAGE */
+		/*  OF THE RESULT.   */
+		
+		for( run1=0; run1<nFR; run1++ )
+		{
+			run2 = FR_idx[run1];
+			Primal_Dual_VAR[run3+run2*KKT_DIM] = delta_xFR[run1];
+		}
+		for( run1=0; run1<nFX; run1++ )
+		{ 
+			run2 = FX_idx[run1]; 
+			Primal_Dual_VAR[run3+run2*KKT_DIM ] = delta_xFX[run1];
+			Primal_Dual_VAR[run3+(NVMAX+run2)*KKT_DIM] = delta_yFX[run1];
+		}
+		for( run1=0; run1<nAC; run1++ )
+		{
+			run2 = AC_idx[run1];
+			Primal_Dual_VAR[run3+(2*NVMAX+run2)*KKT_DIM] = delta_yAC[run1];
+		}
+	}
+	
+	return SUCCESSFUL_RETURN;
+}
+
+#endif
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Indexlist.cpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Indexlist.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..b512569a800be25deee4f9090b07511eaa608153
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Indexlist.cpp
@@ -0,0 +1,342 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/Indexlist.cpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of the Indexlist class designed to manage index lists of
+ *	constraints and bounds within a QProblem_SubjectTo.
+ */
+
+
+#include <Indexlist.hpp>
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+
+/*
+ *	I n d e x l i s t
+ */
+Indexlist::Indexlist( ) :	length( 0 ),
+							first( -1 ),
+							last( -1 ),
+							lastusedindex( -1 ),
+							physicallength( INDEXLISTFACTOR*(NVMAX+NCMAX) )
+{
+	int i;
+
+	for( i=0; i<physicallength; ++i )
+	{
+		number[i] = -1;
+		next[i] = -1;
+		previous[i] = -1;
+	}
+}
+
+
+/*
+ *	I n d e x l i s t
+ */
+Indexlist::Indexlist( const Indexlist& rhs ) :	length( rhs.length ),
+												first( rhs.first ),
+												last( rhs.last ),
+												lastusedindex( rhs.lastusedindex ),
+												physicallength( rhs.physicallength )
+{
+	int i;
+
+	for( i=0; i<physicallength; ++i )
+	{
+		number[i] = rhs.number[i];
+		next[i] = rhs.next[i];
+		previous[i] = rhs.previous[i];
+	}
+}
+
+
+/*
+ *	~ I n d e x l i s t
+ */
+Indexlist::~Indexlist( )
+{
+}
+
+
+/*
+ *	o p e r a t o r =
+ */
+Indexlist& Indexlist::operator=( const Indexlist& rhs )
+{
+	int i;
+
+	if ( this != &rhs )
+	{
+		length = rhs.length;
+		first = rhs.first;
+		last = rhs.last;
+		lastusedindex = rhs.lastusedindex;
+		physicallength = rhs.physicallength;
+
+		for( i=0; i<physicallength; ++i )
+		{
+			number[i] = rhs.number[i];
+			next[i] = rhs.next[i];
+			previous[i] = rhs.previous[i];
+		}
+	}
+
+	return *this;
+}
+
+
+/*
+ *	i n i t
+ */
+returnValue Indexlist::init( )
+{
+	int i;
+
+	length = 0;
+	first = -1;
+	last = -1;
+	lastusedindex = -1;
+	physicallength = INDEXLISTFACTOR*(NVMAX+NCMAX);
+
+	for( i=0; i<physicallength; ++i )
+	{
+		number[i] = -1;
+		next[i] = -1;
+		previous[i] = -1;
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t N u m b e r A r r a y
+ */
+returnValue Indexlist::getNumberArray( int* const numberarray ) const
+{
+	int i;
+	int n = first;
+
+	/* Run trough indexlist and store numbers in numberarray. */
+	for( i=0; i<length; ++i )
+	{
+		if ( ( n >= 0 ) && ( number[n] >= 0 ) )
+			numberarray[i] = number[n];
+		else
+			return THROWERROR( RET_INDEXLIST_CORRUPTED );
+
+		n = next[n];
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t I n d e x
+ */
+int Indexlist::getIndex( int givennumber ) const
+{
+	int i;
+	int n = first;
+	int index = -1;	/* return -1 by default */
+
+	/* Run trough indexlist until number is found, if so return it index. */
+	for ( i=0; i<length; ++i )
+	{
+		if ( number[n] == givennumber )
+		{
+			index = i;
+			break;
+		}
+
+		n = next[n];
+	}
+
+	return index;
+}
+
+
+/*
+ *	g e t P h y s i c a l I n d e x
+ */
+int Indexlist::getPhysicalIndex( int givennumber ) const
+{
+	int i;
+	int n = first;
+	int index = -1;	/* return -1 by default */
+
+	/* Run trough indexlist until number is found, if so return it physicalindex. */
+	for ( i=0; i<length; ++i )
+	{
+		if ( number[n] == givennumber )
+		{
+			index = n;
+			break;
+		}
+
+		n = next[n];
+	}
+
+	return index;
+}
+
+
+/*
+ *	a d d N u m b e r
+ */
+returnValue Indexlist::addNumber( int addnumber )
+{
+	int i;
+
+	if ( lastusedindex+1 < physicallength )
+	{
+		/* If there is enough storage, add number to indexlist. */
+		++lastusedindex;
+		number[lastusedindex] = addnumber;
+		next[lastusedindex] = 0;
+
+		if ( length == 0 )
+		{
+			first = lastusedindex;
+			previous[lastusedindex] = 0;
+		}
+		else
+		{
+			next[last] = lastusedindex;
+			previous[lastusedindex] = last;
+		}
+
+		last = lastusedindex;
+		++length;
+
+		return SUCCESSFUL_RETURN;
+	}
+	else
+	{
+		/* Rearrangement of index list necessary! */
+		if ( length == physicallength )
+			return THROWERROR( RET_INDEXLIST_EXCEEDS_MAX_LENGTH );
+		else
+		{
+			int numberArray[NVMAX+NCMAX];
+			getNumberArray( numberArray );
+
+			/* copy existing elements */
+			for ( i=0; i<length; ++i )
+			{
+				number[i] = numberArray[i];
+				next[i] = i+1;
+				previous[i] = i-1;
+			}
+
+			/* add new number at end of list */
+			number[length] = addnumber;
+			next[length] = -1;
+			previous[length] = length-1;
+
+			/* and set remaining entries to empty */
+			for ( i=length+1; i<physicallength; ++i )
+			{
+				number[i] = -1;
+				next[i] = -1;
+				previous[i] = -1;
+			}
+
+			first = 0;
+			last = length;
+			lastusedindex = length;
+			++length;
+
+			return THROWWARNING( RET_INDEXLIST_MUST_BE_REORDERD );
+		}
+	}
+}
+
+
+/*
+ *	r e m o v e N u m b e r
+ */
+returnValue Indexlist::removeNumber( int removenumber )
+{
+	int i = getPhysicalIndex( removenumber );
+
+	/* nothing to be done if number is not contained in index set */
+	if ( i < 0 )
+		return SUCCESSFUL_RETURN;
+
+	int p = previous[i];
+	int n = next[i];
+
+	if ( i == last )
+		last = p;
+	else
+		previous[n] = p;
+
+	if ( i == first )
+		first = n;
+	else
+		next[p] = n;
+
+	number[i] = -1;
+	next[i] = -1;
+	previous[i] = -1;
+	--length;
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s w a p N u m b e r s
+ */
+returnValue Indexlist::swapNumbers( int number1, int number2 )
+{
+	int index1 = getPhysicalIndex( number1 );
+	int index2 = getPhysicalIndex( number2 );
+
+	/* consistency check */
+	if ( ( index1 < 0 ) || ( index2 < 0 ) )
+		return THROWERROR( RET_INDEXLIST_CORRUPTED );
+
+	int tmp = number[index1];
+	number[index1] = number[index2];
+	number[index2] = tmp;
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Indexlist.ipp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Indexlist.ipp
new file mode 100644
index 0000000000000000000000000000000000000000..b75db81ae974901fb4ed77fa7c18e92dfeaedf99
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Indexlist.ipp
@@ -0,0 +1,85 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/Indexlist.ipp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of inlined member functions of the Indexlist class designed 
+ *	to manage index lists of constraints and bounds within a QProblem_SubjectTo.
+ */
+
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+/*
+ *	g e t N u m b e r
+ */
+inline int Indexlist::getNumber( int physicalindex ) const
+{
+	/* consistency check */
+	if ( ( physicalindex < 0 ) || ( physicalindex > length ) )
+		return -RET_INDEXLIST_OUTOFBOUNDS;
+
+	return number[physicalindex];
+}
+
+
+/*
+ *	g e t L e n g t h
+ */
+inline int Indexlist::getLength( )
+{
+	return length;
+}
+
+
+/*
+ *	g e t L a s t N u m b e r
+ */
+inline int Indexlist::getLastNumber( ) const
+{
+	return number[last];
+}
+
+
+/*
+ *	g e t L a s t N u m b e r
+ */
+inline BooleanType Indexlist::isMember( int _number ) const
+{
+	if ( getIndex( _number ) >= 0 )
+		return BT_TRUE;
+	else
+		return BT_FALSE;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/MessageHandling.cpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/MessageHandling.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..18a7654a104afaa86f46c3d198939c40fb04747e
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/MessageHandling.cpp
@@ -0,0 +1,529 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/MessageHandling.cpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of the MessageHandling class including global return values.
+ *
+ */
+
+
+
+#include <MessageHandling.hpp>
+#include <Utils.hpp>
+
+
+
+
+/** Defines pairs of global return values and messages. */
+MessageHandling::ReturnValueList returnValueList[] =
+{
+/* miscellaneous */
+{ SUCCESSFUL_RETURN, "Successful return", VS_VISIBLE },
+{ RET_DIV_BY_ZERO, "Division by zero", VS_VISIBLE },
+{ RET_INDEX_OUT_OF_BOUNDS, "Index out of bounds", VS_VISIBLE },
+{ RET_INVALID_ARGUMENTS, "At least one of the arguments is invalid", VS_VISIBLE },
+{ RET_ERROR_UNDEFINED, "Error number undefined", VS_VISIBLE },
+{ RET_WARNING_UNDEFINED, "Warning number undefined", VS_VISIBLE },
+{ RET_INFO_UNDEFINED, "Info number undefined", VS_VISIBLE },
+{ RET_EWI_UNDEFINED, "Error/warning/info number undefined", VS_VISIBLE },
+{ RET_AVAILABLE_WITH_LINUX_ONLY, "This function is available under Linux only", VS_HIDDEN },
+{ RET_UNKNOWN_BUG, "The error occured is not yet known", VS_VISIBLE },
+{ RET_PRINTLEVEL_CHANGED, "Print level changed", VS_VISIBLE },
+{ RET_NOT_YET_IMPLEMENTED, "Requested function is not yet implemented.", VS_VISIBLE },
+/* Indexlist */
+{ RET_INDEXLIST_MUST_BE_REORDERD, "Index list has to be reordered", VS_VISIBLE },
+{ RET_INDEXLIST_EXCEEDS_MAX_LENGTH, "Index list exceeds its maximal physical length", VS_VISIBLE },
+{ RET_INDEXLIST_CORRUPTED, "Index list corrupted", VS_VISIBLE },
+{ RET_INDEXLIST_OUTOFBOUNDS, "Physical index is out of bounds", VS_VISIBLE },
+{ RET_INDEXLIST_ADD_FAILED, "Adding indices from another index set failed", VS_VISIBLE },
+{ RET_INDEXLIST_INTERSECT_FAILED, "Intersection with another index set failed", VS_VISIBLE },
+/* SubjectTo / Bounds / Constraints */
+{ RET_INDEX_ALREADY_OF_DESIRED_STATUS, "Index is already of desired status", VS_VISIBLE },
+{ RET_SWAPINDEX_FAILED, "Cannot swap between different indexsets", VS_VISIBLE },
+{ RET_ADDINDEX_FAILED, "Adding index to index set failed", VS_VISIBLE },
+{ RET_NOTHING_TO_DO, "Nothing to do", VS_VISIBLE },
+{ RET_SETUP_BOUND_FAILED, "Setting up bound index failed", VS_VISIBLE },
+{ RET_SETUP_CONSTRAINT_FAILED, "Setting up constraint index failed", VS_VISIBLE },
+{ RET_MOVING_BOUND_FAILED, "Moving bound between index sets failed", VS_VISIBLE },
+{ RET_MOVING_CONSTRAINT_FAILED, "Moving constraint between index sets failed", VS_VISIBLE },
+/* QProblem */
+{ RET_QP_ALREADY_INITIALISED, "QProblem has already been initialised", VS_VISIBLE },
+{ RET_NO_INIT_WITH_STANDARD_SOLVER, "Initialisation via extern QP solver is not yet implemented", VS_VISIBLE },
+{ RET_RESET_FAILED, "Reset failed", VS_VISIBLE },
+{ RET_INIT_FAILED, "Initialisation failed", VS_VISIBLE },
+{ RET_INIT_FAILED_TQ, "Initialisation failed due to TQ factorisation", VS_VISIBLE },
+{ RET_INIT_FAILED_CHOLESKY, "Initialisation failed due to Cholesky decomposition", VS_VISIBLE },
+{ RET_INIT_FAILED_HOTSTART, "Initialisation failed! QP could not be solved!", VS_VISIBLE },
+{ RET_INIT_FAILED_INFEASIBILITY, "Initial QP could not be solved due to infeasibility!", VS_VISIBLE },
+{ RET_INIT_FAILED_UNBOUNDEDNESS, "Initial QP could not be solved due to unboundedness!", VS_VISIBLE },
+{ RET_INIT_SUCCESSFUL, "Initialisation done", VS_VISIBLE },
+{ RET_OBTAINING_WORKINGSET_FAILED, "Failed to obtain working set for auxiliary QP", VS_VISIBLE },
+{ RET_SETUP_WORKINGSET_FAILED, "Failed to setup working set for auxiliary QP", VS_VISIBLE },
+{ RET_SETUP_AUXILIARYQP_FAILED, "Failed to setup auxiliary QP for initialised homotopy", VS_VISIBLE },
+{ RET_NO_EXTERN_SOLVER, "No extern QP solver available", VS_VISIBLE },
+{ RET_QP_UNBOUNDED, "QP is unbounded", VS_VISIBLE },
+{ RET_QP_INFEASIBLE, "QP is infeasible", VS_VISIBLE },
+{ RET_QP_NOT_SOLVED, "Problems occured while solving QP with standard solver", VS_VISIBLE },
+{ RET_QP_SOLVED, "QP successfully solved", VS_VISIBLE },
+{ RET_UNABLE_TO_SOLVE_QP, "Problems occured while solving QP", VS_VISIBLE },
+{ RET_INITIALISATION_STARTED, "Starting problem initialisation...", VS_VISIBLE },
+{ RET_HOTSTART_FAILED, "Unable to perform homotopy due to internal error", VS_VISIBLE },
+{ RET_HOTSTART_FAILED_TO_INIT, "Unable to initialise problem", VS_VISIBLE },
+{ RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED, "Unable to perform homotopy as previous QP is not solved", VS_VISIBLE },
+{ RET_ITERATION_STARTED, "Iteration", VS_VISIBLE },
+{ RET_SHIFT_DETERMINATION_FAILED, "Determination of shift of the QP data failed", VS_VISIBLE },
+{ RET_STEPDIRECTION_DETERMINATION_FAILED, "Determination of step direction failed", VS_VISIBLE },
+{ RET_STEPLENGTH_DETERMINATION_FAILED, "Determination of step direction failed", VS_VISIBLE },
+{ RET_OPTIMAL_SOLUTION_FOUND, "Optimal solution of neighbouring QP found", VS_VISIBLE },
+{ RET_HOMOTOPY_STEP_FAILED, "Unable to perform homotopy step", VS_VISIBLE },
+{ RET_HOTSTART_STOPPED_INFEASIBILITY, "Premature homotopy termination because QP is infeasible", VS_VISIBLE },
+{ RET_HOTSTART_STOPPED_UNBOUNDEDNESS, "Premature homotopy termination because QP is unbounded", VS_VISIBLE },
+{ RET_WORKINGSET_UPDATE_FAILED, "Unable to update working sets according to initial guesses", VS_VISIBLE },
+{ RET_MAX_NWSR_REACHED, "Maximum number of working set recalculations performed", VS_VISIBLE },
+{ RET_CONSTRAINTS_NOT_SPECIFIED, "Problem does comprise constraints! You have to specify new constraints' bounds", VS_VISIBLE },
+{ RET_INVALID_FACTORISATION_FLAG, "Invalid factorisation flag", VS_VISIBLE },
+{ RET_UNABLE_TO_SAVE_QPDATA, "Unable to save QP data", VS_VISIBLE },
+{ RET_STEPDIRECTION_FAILED_TQ, "Abnormal termination due to TQ factorisation", VS_VISIBLE },
+{ RET_STEPDIRECTION_FAILED_CHOLESKY, "Abnormal termination due to Cholesky factorisation", VS_VISIBLE },
+{ RET_CYCLING_DETECTED, "Cycling detected", VS_VISIBLE },
+{ RET_CYCLING_NOT_RESOLVED, "Cycling cannot be resolved, QP is probably infeasible", VS_VISIBLE },
+{ RET_CYCLING_RESOLVED, "Cycling probably resolved", VS_VISIBLE },
+{ RET_STEPSIZE, "", VS_VISIBLE },
+{ RET_STEPSIZE_NONPOSITIVE, "", VS_VISIBLE },
+{ RET_SETUPSUBJECTTOTYPE_FAILED, "Setup of SubjectToTypes failed", VS_VISIBLE },
+{ RET_ADDCONSTRAINT_FAILED, "Addition of constraint to working set failed", VS_VISIBLE },
+{ RET_ADDCONSTRAINT_FAILED_INFEASIBILITY, "Addition of constraint to working set failed", VS_VISIBLE },
+{ RET_ADDBOUND_FAILED, "Addition of bound to working set failed", VS_VISIBLE },
+{ RET_ADDBOUND_FAILED_INFEASIBILITY, "Addition of bound to working set failed", VS_VISIBLE },
+{ RET_REMOVECONSTRAINT_FAILED, "Removal of constraint from working set failed", VS_VISIBLE },
+{ RET_REMOVEBOUND_FAILED, "Removal of bound from working set failed", VS_VISIBLE },
+{ RET_REMOVE_FROM_ACTIVESET, "Removing from active set:", VS_VISIBLE },
+{ RET_ADD_TO_ACTIVESET, "Adding to active set:", VS_VISIBLE },
+{ RET_REMOVE_FROM_ACTIVESET_FAILED, "Removing from active set failed", VS_VISIBLE },
+{ RET_ADD_TO_ACTIVESET_FAILED, "Adding to active set failed", VS_VISIBLE },
+{ RET_CONSTRAINT_ALREADY_ACTIVE, "Constraint is already active", VS_VISIBLE },
+{ RET_ALL_CONSTRAINTS_ACTIVE, "All constraints are active, no further constraint can be added", VS_VISIBLE },
+{ RET_LINEARLY_DEPENDENT, "New bound/constraint is linearly dependent", VS_VISIBLE },
+{ RET_LINEARLY_INDEPENDENT, "New bound/constraint is linearly independent", VS_VISIBLE },
+{ RET_LI_RESOLVED, "Linear independence of active contraint matrix successfully resolved", VS_VISIBLE },
+{ RET_ENSURELI_FAILED, "Failed to ensure linear indepence of active contraint matrix", VS_VISIBLE },
+{ RET_ENSURELI_FAILED_TQ, "Abnormal termination due to TQ factorisation", VS_VISIBLE },
+{ RET_ENSURELI_FAILED_NOINDEX, "No index found, QP is probably infeasible", VS_VISIBLE },
+{ RET_ENSURELI_FAILED_CYCLING, "Cycling detected, QP is probably infeasible", VS_VISIBLE },
+{ RET_BOUND_ALREADY_ACTIVE, "Bound is already active", VS_VISIBLE },
+{ RET_ALL_BOUNDS_ACTIVE, "All bounds are active, no further bound can be added", VS_VISIBLE },
+{ RET_CONSTRAINT_NOT_ACTIVE, "Constraint is not active", VS_VISIBLE },
+{ RET_BOUND_NOT_ACTIVE, "Bound is not active", VS_VISIBLE },
+{ RET_HESSIAN_NOT_SPD, "Projected Hessian matrix not positive definite", VS_VISIBLE },
+{ RET_MATRIX_SHIFT_FAILED, "Unable to update matrices or to transform vectors", VS_VISIBLE },
+{ RET_MATRIX_FACTORISATION_FAILED, "Unable to calculate new matrix factorisations", VS_VISIBLE },
+{ RET_PRINT_ITERATION_FAILED, "Unable to print information on current iteration", VS_VISIBLE },
+{ RET_NO_GLOBAL_MESSAGE_OUTPUTFILE, "No global message output file initialised", VS_VISIBLE },
+/* Utils */
+{ RET_UNABLE_TO_OPEN_FILE, "Unable to open file", VS_VISIBLE },
+{ RET_UNABLE_TO_WRITE_FILE, "Unable to write into file", VS_VISIBLE },
+{ RET_UNABLE_TO_READ_FILE, "Unable to read from file", VS_VISIBLE },
+{ RET_FILEDATA_INCONSISTENT, "File contains inconsistent data", VS_VISIBLE },
+/* SolutionAnalysis */
+{ RET_NO_SOLUTION, "QP solution does not satisfy KKT optimality conditions", VS_VISIBLE },
+{ RET_INACCURATE_SOLUTION, "KKT optimality conditions not satisfied to sufficient accuracy", VS_VISIBLE },
+{ TERMINAL_LIST_ELEMENT, "", VS_HIDDEN } /* IMPORTANT: Terminal list element! */
+};
+
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+
+/*
+ *	M e s s a g e H a n d l i n g
+ */
+MessageHandling::MessageHandling( ) :	errorVisibility( VS_VISIBLE ),
+										warningVisibility( VS_VISIBLE ),
+										infoVisibility( VS_VISIBLE ),
+										outputFile( myStdout ),
+										errorCount( 0 )
+{
+}
+
+/*
+ *	M e s s a g e H a n d l i n g
+ */
+MessageHandling::MessageHandling( myFILE* _outputFile ) :
+										errorVisibility( VS_VISIBLE ),
+										warningVisibility( VS_VISIBLE ),
+										infoVisibility( VS_VISIBLE ),
+										outputFile( _outputFile ),
+										errorCount( 0 )
+{
+}
+
+/*
+ *	M e s s a g e H a n d l i n g
+ */
+MessageHandling::MessageHandling(	VisibilityStatus _errorVisibility,
+									VisibilityStatus _warningVisibility,
+		 							VisibilityStatus _infoVisibility
+									) :
+										errorVisibility( _errorVisibility ),
+										warningVisibility( _warningVisibility ),
+										infoVisibility( _infoVisibility ),
+										outputFile( myStderr ),
+										errorCount( 0 )
+{
+}
+
+/*
+ *	M e s s a g e H a n d l i n g
+ */
+MessageHandling::MessageHandling( 	myFILE* _outputFile,
+									VisibilityStatus _errorVisibility,
+									VisibilityStatus _warningVisibility,
+		 							VisibilityStatus _infoVisibility
+									) :
+										errorVisibility( _errorVisibility ),
+										warningVisibility( _warningVisibility ),
+										infoVisibility( _infoVisibility ),
+										outputFile( _outputFile ),
+										errorCount( 0 )
+{
+}
+
+
+
+/*
+ *	M e s s a g e H a n d l i n g
+ */
+MessageHandling::MessageHandling( const MessageHandling& rhs ) :
+										errorVisibility( rhs.errorVisibility ),
+										warningVisibility( rhs.warningVisibility ),
+										infoVisibility( rhs.infoVisibility ),
+										outputFile( rhs.outputFile ),
+										errorCount( rhs.errorCount )
+{
+}
+
+
+/*
+ *	~ M e s s a g e H a n d l i n g
+ */
+MessageHandling::~MessageHandling( )
+{
+	#ifdef PC_DEBUG
+	if ( outputFile != 0 )
+		fclose( outputFile );
+	#endif
+}
+
+
+/*
+ *	o p e r a t o r =
+ */
+MessageHandling& MessageHandling::operator=( const MessageHandling& rhs )
+{
+	if ( this != &rhs )
+	{
+		errorVisibility = rhs.errorVisibility;
+		warningVisibility = rhs.warningVisibility;
+		infoVisibility = rhs.infoVisibility;
+		outputFile = rhs.outputFile;
+		errorCount = rhs.errorCount;
+	}
+
+	return *this;
+}
+
+
+/*
+ *	t h r o w E r r o r
+ */
+returnValue MessageHandling::throwError(
+	returnValue Enumber,
+	const char* additionaltext,
+	const char* functionname,
+	const char* filename,
+	const unsigned long linenumber,
+	VisibilityStatus localVisibilityStatus
+	)
+{
+	/* consistency check */
+	if ( Enumber <= SUCCESSFUL_RETURN )
+		return throwError( RET_ERROR_UNDEFINED,0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+
+	/* Call to common throwMessage function if error shall be displayed. */
+	if ( errorVisibility == VS_VISIBLE )
+		return throwMessage( Enumber,additionaltext,functionname,filename,linenumber,localVisibilityStatus,"ERROR" );
+	else
+		return Enumber;
+}
+
+
+/*
+ *	t h r o w W a r n i n g
+ */
+returnValue MessageHandling::throwWarning(
+	returnValue Wnumber,
+	const char* additionaltext,
+	const char* functionname,
+	const char* filename,
+	const unsigned long linenumber,
+	VisibilityStatus localVisibilityStatus
+  	)
+{
+	/* consistency check */
+  	if ( Wnumber <= SUCCESSFUL_RETURN )
+		return throwError( RET_WARNING_UNDEFINED,0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+
+	/* Call to common throwMessage function if warning shall be displayed. */
+	if ( warningVisibility == VS_VISIBLE )
+		return throwMessage( Wnumber,additionaltext,functionname,filename,linenumber,localVisibilityStatus,"WARNING" );
+  	else
+  		return Wnumber;
+}
+
+
+/*
+ *	t h r o w I n f o
+ */
+returnValue MessageHandling::throwInfo(
+  	returnValue Inumber,
+	const char* additionaltext,
+  	const char* functionname,
+	const char* filename,
+	const unsigned long linenumber,
+	VisibilityStatus localVisibilityStatus
+ 	)
+{
+	/* consistency check */
+	if ( Inumber < SUCCESSFUL_RETURN )
+		return throwError( RET_INFO_UNDEFINED,0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+
+	/* Call to common throwMessage function if info shall be displayed. */
+	if ( infoVisibility == VS_VISIBLE )
+		return throwMessage( Inumber,additionaltext,functionname,filename,linenumber,localVisibilityStatus,"INFO" );
+	else
+		return Inumber;
+}
+
+
+/*
+ *	r e s e t
+ */
+returnValue MessageHandling::reset( )
+{
+	setErrorVisibilityStatus(   VS_VISIBLE );
+	setWarningVisibilityStatus( VS_VISIBLE );
+	setInfoVisibilityStatus(    VS_VISIBLE );
+
+	setOutputFile( myStderr );
+	setErrorCount( 0 );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	l i s t A l l M e s s a g e s
+ */
+returnValue MessageHandling::listAllMessages( )
+{
+	#ifdef PC_DEBUG
+	int keypos = 0;
+	char myPrintfString[160];
+
+	/* Run through whole returnValueList and print each item. */
+	while ( returnValueList[keypos].key != TERMINAL_LIST_ELEMENT )
+	{
+		sprintf( myPrintfString," %d - %s \n",keypos,returnValueList[keypos].data );
+		myPrintf( myPrintfString );
+
+		++keypos;
+	}
+	#endif
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*****************************************************************************
+ *  P R O T E C T E D                                                        *
+ *****************************************************************************/
+
+
+#ifdef PC_DEBUG  /* Re-define throwMessage function for embedded code! */
+
+/*
+ *	t h r o w M e s s a g e
+ */
+returnValue MessageHandling::throwMessage(
+	returnValue RETnumber,
+	const char* additionaltext,
+	const char* functionname,
+	const char* filename,
+	const unsigned long linenumber,
+	VisibilityStatus localVisibilityStatus,
+	const char* RETstring
+ 	)
+{
+	int i;
+
+	int keypos = 0;
+	char myPrintfString[160];
+
+	/* 1) Determine number of whitespace for output. */
+	char whitespaces[41];
+	int numberOfWhitespaces = (errorCount-1)*2;
+
+	if ( numberOfWhitespaces < 0 )
+		numberOfWhitespaces = 0;
+
+	if ( numberOfWhitespaces > 40 )
+		numberOfWhitespaces = 40;
+
+	for( i=0; i<numberOfWhitespaces; ++i )
+		whitespaces[i] = ' ';
+	whitespaces[numberOfWhitespaces] = '\0';
+
+	/* 2) Find error/warning/info in list. */
+	while ( returnValueList[keypos].key != TERMINAL_LIST_ELEMENT )
+	{
+		if ( returnValueList[keypos].key == RETnumber )
+			break;
+		else
+			++keypos;
+	}
+
+	if ( returnValueList[keypos].key == TERMINAL_LIST_ELEMENT )
+	{
+		throwError( RET_EWI_UNDEFINED,0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		return RETnumber;
+	}
+
+	/* 3) Print error/warning/info. */
+	if ( ( returnValueList[keypos].globalVisibilityStatus == VS_VISIBLE ) && ( localVisibilityStatus == VS_VISIBLE ) )
+	{
+		if ( errorCount > 0 )
+		{
+			sprintf( myPrintfString,"%s->", whitespaces );
+			myPrintf( myPrintfString );
+		}
+
+		if ( additionaltext == 0 )
+		{
+			sprintf(	myPrintfString,"%s (%s, %s:%d): \t%s\n",
+						RETstring,functionname,filename,(int)linenumber,returnValueList[keypos].data
+						);
+			myPrintf( myPrintfString );
+		}
+		else
+		{
+			sprintf(	myPrintfString,"%s (%s, %s:%d): \t%s %s\n",
+						RETstring,functionname,filename,(int)linenumber,returnValueList[keypos].data,additionaltext
+						);
+			myPrintf( myPrintfString );
+		}
+
+		/* take care of proper indention for subsequent error messages */
+		if ( RETstring[0] == 'E' )
+		{
+			++errorCount;
+		}
+		else
+		{
+			if ( errorCount > 0 )
+				myPrintf( "\n" );
+			errorCount = 0;
+		}
+	}
+
+	return RETnumber;
+}
+
+#else  /* = PC_DEBUG not defined */
+
+/*
+ *	t h r o w M e s s a g e
+ */
+returnValue MessageHandling::throwMessage(
+	returnValue RETnumber,
+	const char* additionaltext,
+	const char* functionname,
+	const char* filename,
+	const unsigned long linenumber,
+	VisibilityStatus localVisibilityStatus,
+	const char* RETstring
+ 	)
+{
+	/* DUMMY CODE FOR PRETENDING USE OF ARGUMENTS
+	 * FOR SUPPRESSING COMPILER WARNINGS! */
+	int i = 0;
+	if ( additionaltext == 0 ) i++;
+	if ( functionname == 0 ) i++;
+	if ( filename == 0 ) i++;
+	if ( linenumber == 0 ) i++;
+	if ( localVisibilityStatus == VS_VISIBLE ) i++;
+	if ( RETstring == 0 ) i++;
+	/* END OF DUMMY CODE */
+
+	return RETnumber;
+}
+
+#endif  /* PC_DEBUG */
+
+
+
+/*****************************************************************************
+ *  G L O B A L  M E S S A G E  H A N D L E R                                *
+ *****************************************************************************/
+
+
+/** Global message handler for all qpOASES modules.*/
+MessageHandling globalMessageHandler( myStderr,VS_VISIBLE,VS_VISIBLE,VS_VISIBLE );
+
+
+/*
+ *	g e t G l o b a l M e s s a g e H a n d l e r
+ */
+MessageHandling* getGlobalMessageHandler( )
+{
+	return &globalMessageHandler;
+}
+
+const char* MessageHandling::getErrorString(int error)
+{
+	return returnValueList[ error ].data;
+}
+
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/MessageHandling.ipp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/MessageHandling.ipp
new file mode 100644
index 0000000000000000000000000000000000000000..033957b2842610c3cb1f80364eff9f3db8f7031b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/MessageHandling.ipp
@@ -0,0 +1,137 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/MessageHandling.ipp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of inlined member functions of the MessageHandling class. 
+ */
+
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+ 
+/*
+ *	g e t E r r o r V i s i b i l i t y S t a t u s
+ */
+inline VisibilityStatus MessageHandling::getErrorVisibilityStatus( ) const
+{
+ 	return errorVisibility;
+}
+
+
+/*
+ *	g e t W a r n i n g V i s i b i l i t y S t a t u s
+ */
+inline VisibilityStatus MessageHandling::getWarningVisibilityStatus( ) const
+{
+ 	return warningVisibility;
+}
+
+
+/*
+ *	g e t I n f o V i s i b i l i t y S t a t u s
+ */
+inline VisibilityStatus MessageHandling::getInfoVisibilityStatus( ) const
+{
+ 	return infoVisibility;
+}
+
+
+/*
+ *	g e t O u t p u t F i l e
+ */
+inline myFILE* MessageHandling::getOutputFile( ) const
+{
+ 	return outputFile;
+}
+
+
+/*
+ *	g e t E r r o r C o u n t
+ */
+inline int MessageHandling::getErrorCount( ) const
+{
+ 	return errorCount;
+}
+
+
+/*
+ *	s e t E r r o r V i s i b i l i t y S t a t u s
+ */
+inline void MessageHandling::setErrorVisibilityStatus( VisibilityStatus _errorVisibility ) 
+{
+ 	errorVisibility = _errorVisibility;
+}
+
+
+/*
+ *	s e t W a r n i n g V i s i b i l i t y S t a t u s
+ */
+inline void MessageHandling::setWarningVisibilityStatus( VisibilityStatus _warningVisibility ) 
+{
+ 	warningVisibility = _warningVisibility;
+}
+
+
+/*
+ *	s e t I n f o V i s i b i l i t y S t a t u s
+ */
+inline void MessageHandling::setInfoVisibilityStatus( VisibilityStatus _infoVisibility ) 
+{
+ 	infoVisibility = _infoVisibility;
+}
+
+
+/*
+ *	s e t O u t p u t F i l e
+ */
+inline void MessageHandling::setOutputFile( myFILE* _outputFile ) 
+{
+ 	outputFile = _outputFile;
+}
+
+
+/*
+ *	s e t E r r o r C o u n t
+ */
+inline returnValue MessageHandling::setErrorCount( int _errorCount )
+{
+	if ( _errorCount >= 0 ) 	
+	{
+		errorCount = _errorCount;
+		return SUCCESSFUL_RETURN;
+	}
+	else
+		return RET_INVALID_ARGUMENTS;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/QProblem.cpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/QProblem.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..75e2f324d567c5e466639cf4017cfaf0cd0dfe62
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/QProblem.cpp
@@ -0,0 +1,3867 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/QProblem.cpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of the QProblem class which is able to use the newly
+ *	developed online active set strategy for parametric quadratic programming.
+ */
+
+
+#include <QProblem.hpp>
+
+#include <stdio.h>
+
+void printmatrix2(char *name, double *A, int m, int n) {
+  int i, j;
+
+  printf("%s = [...\n", name);
+  for (i = 0; i < m; i++) {
+    for (j = 0; j < n; j++)
+        printf("  % 9.4f", A[i*n+j]);
+    printf(",\n");
+  }
+  printf("];\n");
+}
+
+//#define __PERFORM_KKT_TEST__
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+
+/*
+ *	Q P r o b l e m
+ */
+QProblem::QProblem( ) : QProblemB( )
+{
+	constraints.init( 0 );
+
+	sizeT = 0;
+
+	cyclingManager.init( 0,0 );
+}
+
+
+/*
+ *	Q P r o b l e m
+ */
+QProblem::QProblem( int _nV, int _nC ) : QProblemB( _nV )
+{
+	/* consistency checks */
+	if ( _nV <= 0 )
+		_nV = 1;
+
+	if ( _nC < 0 )
+	{
+		_nC = 0;
+		THROWERROR( RET_INVALID_ARGUMENTS );
+	}
+
+	constraints.init( _nC );
+
+
+	sizeT = _nC;
+	if ( _nC > _nV )
+		sizeT = _nV;
+
+	cyclingManager.init( _nV,_nC );
+}
+
+
+/*
+ *	Q P r o b l e m
+ */
+QProblem::QProblem( const QProblem& rhs ) :	QProblemB( rhs )
+{
+	int i, j;
+
+	int _nV = rhs.bounds.getNV( );
+	int _nC = rhs.constraints.getNC( );
+
+	for( i=0; i<_nC; ++i )
+		for( j=0; j<_nV; ++j )
+			A[i*NVMAX + j] = rhs.A[i*NVMAX + j];
+
+	for( i=0; i<_nC; ++i )
+		lbA[i] = rhs.lbA[i];
+
+	for( i=0; i<_nC; ++i )
+			ubA[i] = rhs.ubA[i];
+
+	constraints = rhs.constraints;
+
+	for( i=0; i<(_nV+_nC); ++i )
+		y[i] = rhs.y[i];
+
+
+	sizeT = rhs.sizeT;
+
+	for( i=0; i<sizeT; ++i )
+		for( j=0; j<sizeT; ++j )
+			T[i*NVMAX + j] = rhs.T[i*NVMAX + j];
+
+	for( i=0; i<_nV; ++i )
+		for( j=0; j<_nV; ++j )
+			Q[i*NVMAX + j] = rhs.Q[i*NVMAX + j];
+
+	for( i=0; i<_nC; ++i )
+		Ax[i] = rhs.Ax[i];
+
+	cyclingManager = rhs.cyclingManager;
+}
+
+
+/*
+ *	~ Q P r o b l e m
+ */
+QProblem::~QProblem( )
+{
+}
+
+
+/*
+ *	o p e r a t o r =
+ */
+QProblem& QProblem::operator=( const QProblem& rhs )
+{
+	int i, j;
+
+	if ( this != &rhs )
+	{
+		QProblemB::operator=( rhs );
+
+
+		int _nV = rhs.bounds.getNV( );
+		int _nC = rhs.constraints.getNC( );
+
+		for( i=0; i<_nC; ++i )
+			for( j=0; j<_nV; ++j )
+				A[i*NVMAX + j] = rhs.A[i*NVMAX + j];
+
+		for( i=0; i<_nC; ++i )
+			lbA[i] = rhs.lbA[i];
+
+		for( i=0; i<_nC; ++i )
+			ubA[i] = rhs.ubA[i];
+
+		constraints = rhs.constraints;
+
+		for( i=0; i<(_nV+_nC); ++i )
+			y[i] = rhs.y[i];
+
+
+		sizeT = rhs.sizeT;
+
+		for( i=0; i<sizeT; ++i )
+			for( j=0; j<sizeT; ++j )
+				T[i*NVMAX + j] = rhs.T[i*NVMAX + j];
+
+		for( i=0; i<_nV; ++i )
+			for( j=0; j<_nV; ++j )
+				Q[i*NVMAX + j] = rhs.Q[i*NVMAX + j];
+
+		for( i=0; i<_nC; ++i )
+			Ax[i] = rhs.Ax[i];
+
+		cyclingManager = rhs.cyclingManager;
+	}
+
+	return *this;
+}
+
+
+/*
+ *	r e s e t
+ */
+returnValue QProblem::reset( )
+{
+	int i, j;
+	int nV = getNV( );
+	int nC = getNC( );
+
+
+	/* 1) Reset bounds, Cholesky decomposition and status flags. */
+	if ( QProblemB::reset( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_RESET_FAILED );
+
+	/* 2) Reset constraints. */
+	constraints.init( nC );
+
+	/* 3) Reset TQ factorisation. */
+	for( i=0; i<sizeT; ++i )
+		for( j=0; j<sizeT; ++j )
+			T[i*NVMAX + j] = 0.0;
+
+	for( i=0; i<nV; ++i )
+		for( j=0; j<nV; ++j )
+			Q[i*NVMAX + j] = 0.0;
+
+	/* 4) Reset cycling manager. */
+	if ( cyclingManager.clearCyclingData( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_RESET_FAILED );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	i n i t
+ */
+returnValue QProblem::init(	const real_t* const _H, const real_t* const _g, const real_t* const _A,
+							const real_t* const _lb, const real_t* const _ub,
+							const real_t* const _lbA, const real_t* const _ubA,
+							int& nWSR, const real_t* const yOpt, real_t* const cputime
+							)
+{
+	/* 1) Setup QP data. */
+	if (setupQPdata(_H, 0, _g, _A, _lb, _ub, _lbA, _ubA) != SUCCESSFUL_RETURN)
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	/* 2) Call to main initialisation routine (without any additional information). */
+	return solveInitialQP( 0,yOpt,0,0, nWSR,cputime );
+}
+
+returnValue QProblem::init(	const real_t* const _H, const real_t* const _R, const real_t* const _g, const real_t* const _A,
+							const real_t* const _lb, const real_t* const _ub,
+							const real_t* const _lbA, const real_t* const _ubA,
+							int& nWSR, const real_t* const yOpt, real_t* const cputime
+							)
+{
+	/* 1) Setup QP data. */
+	if (setupQPdata(_H, _R, _g, _A, _lb, _ub, _lbA, _ubA) != SUCCESSFUL_RETURN)
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	/* 2) Call to main initialisation routine (without any additional information). */
+	return solveInitialQP( 0,yOpt,0,0, nWSR,cputime );
+}
+
+
+/*
+ *	h o t s t a r t
+ */
+returnValue QProblem::hotstart(	const real_t* const g_new, const real_t* const lb_new, const real_t* const ub_new,
+								const real_t* const lbA_new, const real_t* const ubA_new,
+								int& nWSR, real_t* const cputime
+								)
+{
+	int l;
+
+	/* consistency check */
+	if ( ( getStatus( ) == QPS_NOTINITIALISED )       ||
+		 ( getStatus( ) == QPS_PREPARINGAUXILIARYQP ) ||
+		 ( getStatus( ) == QPS_PERFORMINGHOMOTOPY )   )
+	{
+		return THROWERROR( RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED );
+	}
+
+	/* start runtime measurement */
+	real_t starttime = 0.0;
+	if ( cputime != 0 )
+		starttime = getCPUtime( );
+
+
+	/* I) PREPARATIONS */
+	/* 1) Reset cycling and status flags and increase QP counter. */
+	cyclingManager.clearCyclingData( );
+
+	infeasible = BT_FALSE;
+	unbounded = BT_FALSE;
+
+	++count;
+
+	/* 2) Allocate delta vectors of gradient and (constraints') bounds. */
+	returnValue returnvalue;
+	BooleanType Delta_bC_isZero, Delta_bB_isZero;
+
+	int FR_idx[NVMAX];
+	int FX_idx[NVMAX];
+	int AC_idx[NCMAX_ALLOC];
+	int IAC_idx[NCMAX_ALLOC];
+
+	real_t delta_g[NVMAX];
+	real_t delta_lb[NVMAX];
+	real_t delta_ub[NVMAX];
+	real_t delta_lbA[NCMAX_ALLOC];
+	real_t delta_ubA[NCMAX_ALLOC];
+
+	real_t delta_xFR[NVMAX];
+	real_t delta_xFX[NVMAX];
+	real_t delta_yAC[NCMAX_ALLOC];
+	real_t delta_yFX[NVMAX];
+	real_t delta_Ax[NCMAX_ALLOC];
+
+	int BC_idx;
+	SubjectToStatus BC_status;
+	BooleanType BC_isBound;
+
+	#ifdef PC_DEBUG
+	char messageString[80];
+	#endif
+
+
+	/* II) MAIN HOMOTOPY LOOP */
+	for( l=0; l<nWSR; ++l )
+	{
+		status = QPS_PERFORMINGHOMOTOPY;
+
+		if ( printlevel == PL_HIGH )
+		{
+			#ifdef PC_DEBUG
+			sprintf( messageString,"%d ...",l );
+		  	getGlobalMessageHandler( )->throwInfo( RET_ITERATION_STARTED,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+			#endif
+		}
+
+		/* 1) Setup index arrays. */
+		if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_HOTSTART_FAILED );
+
+		if ( bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_HOTSTART_FAILED );
+
+		if ( constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_HOTSTART_FAILED );
+
+		if ( constraints.getInactive( )->getNumberArray( IAC_idx ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_HOTSTART_FAILED );
+
+		/* 2) Detemination of shift direction of the gradient and the (constraints') bounds. */
+		returnvalue = hotstart_determineDataShift(  FX_idx, AC_idx,
+													g_new,lbA_new,ubA_new,lb_new,ub_new,
+													delta_g,delta_lbA,delta_ubA,delta_lb,delta_ub,
+													Delta_bC_isZero, Delta_bB_isZero );
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			nWSR = l;
+			THROWERROR( RET_SHIFT_DETERMINATION_FAILED );
+			return returnvalue;
+		}
+
+		/* 3) Determination of step direction of X and Y. */
+		returnvalue = hotstart_determineStepDirection(	FR_idx,FX_idx,AC_idx,
+														delta_g,delta_lbA,delta_ubA,delta_lb,delta_ub,
+														Delta_bC_isZero, Delta_bB_isZero,
+														delta_xFX,delta_xFR,delta_yAC,delta_yFX
+														);
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			nWSR = l;
+			THROWERROR( RET_STEPDIRECTION_DETERMINATION_FAILED );
+			return returnvalue;
+		}
+
+		/* 4) Determination of step length TAU. */
+		returnvalue = hotstart_determineStepLength(	FR_idx,FX_idx,AC_idx,IAC_idx,
+													delta_lbA,delta_ubA,delta_lb,delta_ub,
+													delta_xFX,delta_xFR,delta_yAC,delta_yFX,delta_Ax,
+													BC_idx,BC_status,BC_isBound
+													);
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			nWSR = l;
+			THROWERROR( RET_STEPLENGTH_DETERMINATION_FAILED );
+			return returnvalue;
+		}
+
+		/* 5) Realisation of the homotopy step. */
+		returnvalue = hotstart_performStep(	FR_idx,FX_idx,AC_idx,IAC_idx,
+											delta_g,delta_lbA,delta_ubA,delta_lb,delta_ub,
+											delta_xFX,delta_xFR,delta_yAC,delta_yFX,delta_Ax,
+											BC_idx,BC_status,BC_isBound
+											);
+
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			nWSR = l;
+
+			/* stop runtime measurement */
+			if ( cputime != 0 )
+					*cputime = getCPUtime( ) - starttime;
+
+			/* optimal solution found? */
+			if ( returnvalue == RET_OPTIMAL_SOLUTION_FOUND )
+			{
+				status = QPS_SOLVED;
+
+				if ( printlevel == PL_HIGH )
+					THROWINFO( RET_OPTIMAL_SOLUTION_FOUND );
+
+				#ifdef PC_DEBUG
+	 			if ( printIteration( l,BC_idx,BC_status,BC_isBound ) != SUCCESSFUL_RETURN )
+					THROWERROR( RET_PRINT_ITERATION_FAILED ); /* do not pass this as return value! */
+				#endif
+
+				/* check KKT optimality conditions */
+				return checkKKTconditions( );
+			}
+			else
+			{
+				/* checks for infeasibility... */
+				if ( isInfeasible( ) == BT_TRUE )
+				{
+					status = QPS_HOMOTOPYQPSOLVED;
+					return THROWERROR( RET_HOTSTART_STOPPED_INFEASIBILITY );
+				}
+
+				/* ...unboundedness... */
+				if ( unbounded == BT_TRUE ) /* not necessary since objective function convex! */
+					return THROWERROR( RET_HOTSTART_STOPPED_UNBOUNDEDNESS );
+
+				/* ... and throw unspecific error otherwise */
+				THROWERROR( RET_HOMOTOPY_STEP_FAILED );
+				return returnvalue;
+			}
+		}
+
+		/* 6) Output information of successful QP iteration. */
+		status = QPS_HOMOTOPYQPSOLVED;
+
+		#ifdef PC_DEBUG
+		if ( printIteration( l,BC_idx,BC_status,BC_isBound ) != SUCCESSFUL_RETURN )
+			THROWERROR( RET_PRINT_ITERATION_FAILED ); /* do not pass this as return value! */
+		#endif
+	}
+
+
+	/* stop runtime measurement */
+	if ( cputime != 0 )
+		*cputime = getCPUtime( ) - starttime;
+
+
+	/* if programm gets to here, output information that QP could not be solved
+	 * within the given maximum numbers of working set changes */
+	if ( printlevel == PL_HIGH )
+	{
+		#ifdef PC_DEBUG
+		sprintf( messageString,"(nWSR = %d)",nWSR );
+		return getGlobalMessageHandler( )->throwWarning( RET_MAX_NWSR_REACHED,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		#endif
+	}
+
+	/* Finally check KKT optimality conditions. */
+	returnValue returnvalueKKTcheck = checkKKTconditions( );
+
+	if ( returnvalueKKTcheck != SUCCESSFUL_RETURN )
+		return returnvalueKKTcheck;
+	else
+		return RET_MAX_NWSR_REACHED;
+}
+
+
+/*
+ *	g e t N Z
+ */
+int QProblem::getNZ( )
+{
+	/* nZ = nFR - nAC */
+	return bounds.getFree( )->getLength( ) - constraints.getActive( )->getLength( );
+}
+
+
+/*
+ *	g e t D u a l S o l u t i o n
+ */
+returnValue QProblem::getDualSolution( real_t* const yOpt ) const
+{
+	int i;
+
+	/* return optimal dual solution vector
+	 * only if current QP has been solved */
+	if ( ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) ||
+		 ( getStatus( ) == QPS_HOMOTOPYQPSOLVED )  ||
+		 ( getStatus( ) == QPS_SOLVED ) )
+	{
+		for( i=0; i<getNV( )+getNC( ); ++i )
+			yOpt[i] = y[i];
+
+		return SUCCESSFUL_RETURN;
+	}
+	else
+	{
+		return RET_QP_NOT_SOLVED;
+	}
+}
+
+
+
+/*****************************************************************************
+ *  P R O T E C T E D                                                        *
+ *****************************************************************************/
+
+/*
+ *	s e t u p S u b j e c t T o T y p e
+ */
+returnValue QProblem::setupSubjectToType( )
+{
+	int i;
+	int nC = getNC( );
+
+
+	/* I) SETUP SUBJECTTOTYPE FOR BOUNDS */
+	if ( QProblemB::setupSubjectToType( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_SETUPSUBJECTTOTYPE_FAILED );
+
+
+	/* II) SETUP SUBJECTTOTYPE FOR CONSTRAINTS */
+	/* 1) Check if lower constraints' bounds are present. */
+	constraints.setNoLower( BT_TRUE );
+	for( i=0; i<nC; ++i )
+	{
+		if ( lbA[i] > -INFTY )
+		{
+			constraints.setNoLower( BT_FALSE );
+			break;
+		}
+	}
+
+	/* 2) Check if upper constraints' bounds are present. */
+	constraints.setNoUpper( BT_TRUE );
+	for( i=0; i<nC; ++i )
+	{
+		if ( ubA[i] < INFTY )
+		{
+			constraints.setNoUpper( BT_FALSE );
+			break;
+		}
+	}
+
+	/* 3) Determine implicit equality constraints and unbounded constraints. */
+	int nEC = 0;
+	int nUC = 0;
+
+	for( i=0; i<nC; ++i )
+	{
+		if ( ( lbA[i] < -INFTY + BOUNDTOL ) && ( ubA[i] > INFTY - BOUNDTOL ) )
+		{
+			constraints.setType( i,ST_UNBOUNDED );
+			++nUC;
+		}
+		else
+		{
+			if ( lbA[i] > ubA[i] - BOUNDTOL )
+			{
+				constraints.setType( i,ST_EQUALITY );
+				++nEC;
+			}
+			else
+			{
+				constraints.setType( i,ST_BOUNDED );
+			}
+		}
+	}
+
+	/* 4) Set dimensions of constraints structure. */
+	constraints.setNEC( nEC );
+	constraints.setNUC( nUC );
+	constraints.setNIC( nC - nEC - nUC );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	c h o l e s k y D e c o m p o s i t i o n P r o j e c t e d
+ */
+returnValue QProblem::setupCholeskyDecompositionProjected( )
+{
+	int i, j, k, ii, kk;
+	int nV  = getNV( );
+	int nFR = getNFR( );
+	int nZ  = getNZ( );
+
+	/* 1) Initialises R with all zeros. */
+	for( i=0; i<nV; ++i )
+		for( j=0; j<nV; ++j )
+			R[i*NVMAX + j] = 0.0;
+
+	/* 2) Calculate Cholesky decomposition of projected Hessian Z'*H*Z. */
+	if ( hessianType == HST_IDENTITY )
+	{
+		/* if Hessian is identity, so is its Cholesky factor. */
+		for( i=0; i<nV; ++i )
+			R[i*NVMAX + i] = 1.0;
+	}
+	else
+	{
+		if ( nZ > 0 )
+		{
+			int FR_idx[NVMAX];
+			if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_INDEXLIST_CORRUPTED );
+
+#if 0
+			real_t HZ[NVMAX*NVMAX];
+			real_t ZHZ[NVMAX*NVMAX];
+
+			/* calculate H*Z */
+			for ( i=0; i<nFR; ++i )
+			{
+				ii = FR_idx[i];
+
+				for ( j=0; j<nZ; ++j )
+				{
+					real_t sum = 0.0;
+					for ( k=0; k<nFR; ++k )
+					{
+						kk = FR_idx[k];
+						sum += H[ii*NVMAX + kk] * Q[kk*NVMAX + j];
+					}
+					HZ[i * NVMAX + j] = sum;
+				}
+			}
+
+			/* calculate Z'*H*Z */
+			for ( i=0; i<nZ; ++i )
+				for ( j=0; j<nZ; ++j )
+				{
+					real_t sum = 0.0;
+					for ( k=0; k<nFR; ++k )
+					{
+						kk = FR_idx[k];
+						sum += Q[kk*NVMAX + i] * HZ[k*NVMAX + j];
+					}
+					ZHZ[i * NVMAX + j] = sum;
+				}
+
+			/* R'*R = Z'*H*Z */
+			real_t sum, inv;
+
+			for( i=0; i<nZ; ++i )
+			{
+				/* j == i */
+				sum = ZHZ[i*NVMAX + i];
+
+				for( k=(i-1); k>=0; --k )
+					sum -= R[k*NVMAX + i] * R[k*NVMAX + i];
+
+				if ( sum > 0.0 )
+				{
+					R[i*NVMAX + i] = sqrt( sum );
+					inv = 1.0 / R[i * NVMAX + i];
+				}
+				else
+				{
+					hessianType = HST_SEMIDEF;
+					return THROWERROR( RET_HESSIAN_NOT_SPD );
+				}
+
+				for( j=(i+1); j<nZ; ++j )
+				{
+					sum = ZHZ[j*NVMAX + i];
+
+					for( k=(i-1); k>=0; --k )
+						sum -= R[k*NVMAX + i] * R[k*NVMAX + j];
+
+					R[i*NVMAX + j] = sum * inv;
+				}
+			}
+#else
+			real_t HZ[NVMAX];
+			real_t ZHZ[NVMAX];
+
+			real_t sum, inv;
+			for (j = 0; j < nZ; ++j)
+			{
+				/* Cache one column of Z. */
+				for (i = 0; i < NVMAX; ++i)
+					ZHZ[i] = Q[i * NVMAX + j];
+
+				/* Create one column of the product H * Z. */
+				for (i = 0; i < nFR; ++i)
+				{
+					ii = FR_idx[i];
+
+					sum = 0.0;
+					for (k = 0; k < nFR; ++k)
+					{
+						kk = FR_idx[k];
+						sum += H[ii * NVMAX + kk] * ZHZ[kk];
+					}
+					HZ[ii] = sum;
+				}
+
+				/* Create one column of the product Z^T * H * Z. */
+				for (i = j; i < nZ; ++i)
+					ZHZ[ i ] = 0.0;
+
+				for (k = 0; k < nFR; ++k)
+				{
+					kk = FR_idx[k];
+					real_t q = HZ[kk];
+					for (i = j; i < nZ; ++i)
+					{
+						ZHZ[i] += Q[kk * NVMAX + i] * q;
+					}
+				}
+
+				/* Use the computed column to update the factorization. */
+				/* j == i */
+				sum = ZHZ[j];
+
+				for (k = (j - 1); k >= 0; --k)
+					sum -= R[k * NVMAX + j] * R[k * NVMAX + j];
+
+				if (sum > 0.0)
+				{
+					R[j * NVMAX + j] = sqrt(sum);
+					inv = 1.0 / R[j * NVMAX + j];
+				}
+				else
+				{
+					hessianType = HST_SEMIDEF;
+					return THROWERROR( RET_HESSIAN_NOT_SPD );
+				}
+
+				for (i = (j + 1); i < nZ; ++i)
+				{
+					sum = ZHZ[i];
+
+					for (k = (j - 1); k >= 0; --k)
+						sum -= R[k * NVMAX + j] * R[k * NVMAX + i];
+
+					R[j * NVMAX + i] = sum * inv;
+				}
+			}
+#endif
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p T Q f a c t o r i s a t i o n
+ */
+returnValue QProblem::setupTQfactorisation( )
+{
+	int i, j, ii;
+	int nV  = getNV( );
+	int nFR = getNFR( );
+
+	int FR_idx[NVMAX];
+	if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INDEXLIST_CORRUPTED );
+
+	/* 1) Set Q to unity matrix. */
+	for( i=0; i<nV; ++i )
+		for( j=0; j<nV; ++j )
+			Q[i*NVMAX + j] = 0.0;
+
+	for( i=0; i<nFR; ++i )
+	{
+		ii = FR_idx[i];
+		Q[ii*NVMAX + i] = 1.0;
+	}
+
+ 	/* 2) Set T to zero matrix. */
+	for( i=0; i<sizeT; ++i )
+		for( j=0; j<sizeT; ++j )
+			T[i*NVMAX + j] = 0.0;
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s o l v e I n i t i a l Q P
+ */
+returnValue QProblem::solveInitialQP(	const real_t* const xOpt, const real_t* const yOpt,
+										const Bounds* const guessedBounds, const Constraints* const guessedConstraints,
+										int& nWSR, real_t* const cputime
+										)
+{
+	int i;
+
+	/* some definitions */
+	int nV = getNV( );
+	int nC = getNC( );
+
+
+	/* start runtime measurement */
+	real_t starttime = 0.0;
+	if ( cputime != 0 )
+		starttime = getCPUtime( );
+
+
+	status = QPS_NOTINITIALISED;
+
+	/* I) ANALYSE QP DATA: */
+	/* 1) Check if Hessian happens to be the identity matrix. */
+	if ( checkForIdentityHessian( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	/* 2) Setup type of bounds and constraints (i.e. unbounded, implicitly fixed etc.). */
+	if ( setupSubjectToType( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	/* 3) Initialise cycling manager. */
+	cyclingManager.clearCyclingData( );
+
+	status = QPS_PREPARINGAUXILIARYQP;
+
+
+	/* II) SETUP AUXILIARY QP WITH GIVEN OPTIMAL SOLUTION: */
+	/* 1) Setup bounds and constraints data structure. */
+	if ( bounds.setupAllFree( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	if ( constraints.setupAllInactive( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	/* 2) Setup optimal primal/dual solution for auxiliary QP. */
+	if ( setupAuxiliaryQPsolution( xOpt,yOpt ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	/* 3) Obtain linear independent working set for auxiliary QP. */
+
+	static Bounds auxiliaryBounds;
+
+	auxiliaryBounds.init( nV );
+
+	static Constraints auxiliaryConstraints;
+
+	auxiliaryConstraints.init( nC );
+
+	if ( obtainAuxiliaryWorkingSet(	xOpt,yOpt,guessedBounds,guessedConstraints,
+									&auxiliaryBounds,&auxiliaryConstraints ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	/* 4) Setup working set of auxiliary QP and setup matrix factorisations. */
+	if ( setupTQfactorisation( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED_TQ );
+
+	if ( setupAuxiliaryWorkingSet( &auxiliaryBounds,&auxiliaryConstraints,BT_TRUE ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	if ( ( getNAC( ) + getNFX( ) ) == 0 )
+	{
+		/* Factorise full Hessian if no bounds/constraints are active. */
+		if (hasCholesky == BT_FALSE)
+			if ( setupCholeskyDecomposition( ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_INIT_FAILED_CHOLESKY );
+		/* ... else we use user provided Cholesky factorization. At the moment
+		 * we can do that only for cold-started solver. */
+	}
+	else
+	{
+		/* Factorise projected Hessian if there active bounds/constraints. */
+		if ( setupCholeskyDecompositionProjected( ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_INIT_FAILED_CHOLESKY );
+		/* TODO: use user-supplied Hessian decomposition. R_Z = R * Z. */
+	}
+
+	/* 5) Store original QP formulation... */
+	real_t g_original[NVMAX];
+	real_t lb_original[NVMAX];
+	real_t ub_original[NVMAX];
+	real_t lbA_original[NCMAX_ALLOC];
+	real_t ubA_original[NCMAX_ALLOC];
+
+	for( i=0; i<nV; ++i )
+	{
+		g_original[i] = g[i];
+		lb_original[i] = lb[i];
+		ub_original[i] = ub[i];
+	}
+
+	for( i=0; i<nC; ++i )
+	{
+		lbA_original[i] = lbA[i];
+		ubA_original[i] = ubA[i];
+	}
+
+	/* ... and setup QP data of an auxiliary QP having an optimal solution
+	 * as specified by the user (or xOpt = yOpt = 0, by default). */
+	if ( setupAuxiliaryQPgradient( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	if ( setupAuxiliaryQPbounds( &auxiliaryBounds,&auxiliaryConstraints,BT_TRUE ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	status = QPS_AUXILIARYQPSOLVED;
+
+
+	/* III) SOLVE ACTUAL INITIAL QP: */
+	/* Use hotstart method to find the solution of the original initial QP,... */
+	returnValue returnvalue = hotstart( g_original,lb_original,ub_original,lbA_original,ubA_original, nWSR,0 );
+
+
+	/* ... check for infeasibility and unboundedness... */
+	if ( isInfeasible( ) == BT_TRUE )
+		return THROWERROR( RET_INIT_FAILED_INFEASIBILITY );
+
+	if ( isUnbounded( ) == BT_TRUE )
+		return THROWERROR( RET_INIT_FAILED_UNBOUNDEDNESS );
+
+	/* ... and internal errors. */
+	if ( ( returnvalue != SUCCESSFUL_RETURN ) && ( returnvalue != RET_MAX_NWSR_REACHED )  &&
+	     ( returnvalue != RET_INACCURATE_SOLUTION ) && ( returnvalue != RET_NO_SOLUTION ) )
+		return THROWERROR( RET_INIT_FAILED_HOTSTART );
+
+
+	/* stop runtime measurement */
+	if ( cputime != 0 )
+		*cputime = getCPUtime( ) - starttime;
+
+	if ( printlevel == PL_HIGH )
+		THROWINFO( RET_INIT_SUCCESSFUL );
+
+	return returnvalue;
+}
+
+
+/*
+ *	o b t a i n A u x i l i a r y W o r k i n g S e t
+ */
+returnValue QProblem::obtainAuxiliaryWorkingSet(	const real_t* const xOpt, const real_t* const yOpt,
+													const Bounds* const guessedBounds, const Constraints* const guessedConstraints,
+													Bounds* auxiliaryBounds, Constraints* auxiliaryConstraints
+													) const
+{
+	int i = 0;
+	int nV = getNV( );
+	int nC = getNC( );
+
+
+	/* 1) Ensure that desiredBounds is allocated (and different from guessedBounds). */
+	if ( ( auxiliaryBounds == 0 ) || ( auxiliaryBounds == guessedBounds ) )
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	if ( ( auxiliaryConstraints == 0 ) || ( auxiliaryConstraints == guessedConstraints ) )
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+
+	SubjectToStatus guessedStatus;
+
+	/* 2) Setup working set of bounds for auxiliary initial QP. */
+	if ( QProblemB::obtainAuxiliaryWorkingSet( xOpt,yOpt,guessedBounds, auxiliaryBounds ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+
+	/* 3) Setup working set of constraints for auxiliary initial QP. */
+	if ( guessedConstraints != 0 )
+	{
+		/* If an initial working set is specific, use it!
+		 * Moreover, add all equality constraints if specified. */
+		for( i=0; i<nC; ++i )
+		{
+			guessedStatus = guessedConstraints->getStatus( i );
+
+			if ( constraints.getType( i ) == ST_EQUALITY )
+			{
+				if ( auxiliaryConstraints->setupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+			}
+			else
+			{
+				if ( auxiliaryConstraints->setupConstraint( i,guessedStatus ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+			}
+		}
+	}
+	else	/* No initial working set specified. */
+	{
+		/* Obtain initial working set by "clipping". */
+		if ( ( xOpt != 0 ) && ( yOpt == 0 ) )
+		{
+			for( i=0; i<nC; ++i )
+			{
+				if ( Ax[i] <= lbA[i] + BOUNDTOL )
+				{
+					if ( auxiliaryConstraints->setupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+					continue;
+				}
+
+				if ( Ax[i] >= ubA[i] - BOUNDTOL )
+				{
+					if ( auxiliaryConstraints->setupConstraint( i,ST_UPPER ) != SUCCESSFUL_RETURN )
+							return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+					continue;
+				}
+
+				/* Moreover, add all equality constraints if specified. */
+				if ( constraints.getType( i ) == ST_EQUALITY )
+				{
+					if ( auxiliaryConstraints->setupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+				else
+				{
+					if ( auxiliaryConstraints->setupConstraint( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+			}
+		}
+
+		/* Obtain initial working set in accordance to sign of dual solution vector. */
+		if ( ( xOpt == 0 ) && ( yOpt != 0 ) )
+		{
+			for( i=0; i<nC; ++i )
+			{
+				if ( yOpt[nV+i] > ZERO )
+				{
+					if ( auxiliaryConstraints->setupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+					continue;
+				}
+
+				if ( yOpt[nV+i] < -ZERO )
+				{
+					if ( auxiliaryConstraints->setupConstraint( i,ST_UPPER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+					continue;
+				}
+
+				/* Moreover, add all equality constraints if specified. */
+				if ( constraints.getType( i ) == ST_EQUALITY )
+				{
+					if ( auxiliaryConstraints->setupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+				else
+				{
+					if ( auxiliaryConstraints->setupConstraint( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+			}
+		}
+
+		/* If xOpt and yOpt are null pointer and no initial working is specified,
+		 * start with empty working set (or implicitly fixed bounds and equality constraints only)
+		 * for auxiliary QP. */
+		if ( ( xOpt == 0 ) && ( yOpt == 0 ) )
+		{
+			for( i=0; i<nC; ++i )
+			{
+				/* Only add all equality constraints if specified. */
+				if ( constraints.getType( i ) == ST_EQUALITY )
+				{
+					if ( auxiliaryConstraints->setupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+				else
+				{
+					if ( auxiliaryConstraints->setupConstraint( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+			}
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*
+ *	s e t u p A u x i l i a r y W o r k i n g S e t
+ */
+returnValue QProblem::setupAuxiliaryWorkingSet(	const Bounds* const auxiliaryBounds,
+												const Constraints* const auxiliaryConstraints,
+												BooleanType setupAfresh
+												)
+{
+	int i;
+	int nV = getNV( );
+	int nC = getNC( );
+
+	/* consistency checks */
+	if ( auxiliaryBounds != 0 )
+	{
+		for( i=0; i<nV; ++i )
+			if ( ( bounds.getStatus( i ) == ST_UNDEFINED ) || ( auxiliaryBounds->getStatus( i ) == ST_UNDEFINED ) )
+				return THROWERROR( RET_UNKNOWN_BUG );
+	}
+	else
+	{
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+	}
+
+	if ( auxiliaryConstraints != 0 )
+	{
+		for( i=0; i<nC; ++i )
+			if ( ( constraints.getStatus( i ) == ST_UNDEFINED ) || ( auxiliaryConstraints->getStatus( i ) == ST_UNDEFINED ) )
+				return THROWERROR( RET_UNKNOWN_BUG );
+	}
+	else
+	{
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+	}
+
+
+	/* I) SETUP CHOLESKY FLAG:
+	 *    Cholesky decomposition shall only be updated if working set
+	 *    shall be updated (i.e. NOT setup afresh!) */
+	BooleanType updateCholesky;
+	if ( setupAfresh == BT_TRUE )
+		updateCholesky = BT_FALSE;
+	else
+		updateCholesky = BT_TRUE;
+
+
+	/* II) REMOVE FORMERLY ACTIVE (CONSTRAINTS') BOUNDS (IF NECESSARY): */
+	if ( setupAfresh == BT_FALSE )
+	{
+		/* 1) Remove all active constraints that shall be inactive AND
+		*    all active constraints that are active at the wrong bound. */
+		for( i=0; i<nC; ++i )
+		{
+			if ( ( constraints.getStatus( i ) == ST_LOWER ) && ( auxiliaryConstraints->getStatus( i ) != ST_LOWER ) )
+				if ( removeConstraint( i,updateCholesky ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_SETUP_WORKINGSET_FAILED );
+
+			if ( ( constraints.getStatus( i ) == ST_UPPER ) && ( auxiliaryConstraints->getStatus( i ) != ST_UPPER ) )
+				if ( removeConstraint( i,updateCholesky ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_SETUP_WORKINGSET_FAILED );
+		}
+
+		/* 2) Remove all active bounds that shall be inactive AND
+		*    all active bounds that are active at the wrong bound. */
+		for( i=0; i<nV; ++i )
+		{
+			if ( ( bounds.getStatus( i ) == ST_LOWER ) && ( auxiliaryBounds->getStatus( i ) != ST_LOWER ) )
+				if ( removeBound( i,updateCholesky ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_SETUP_WORKINGSET_FAILED );
+
+			if ( ( bounds.getStatus( i ) == ST_UPPER ) && ( auxiliaryBounds->getStatus( i ) != ST_UPPER ) )
+				if ( removeBound( i,updateCholesky ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_SETUP_WORKINGSET_FAILED );
+		}
+	}
+
+
+	/* III) ADD NEWLY ACTIVE (CONSTRAINTS') BOUNDS: */
+	/* 1) Add all inactive bounds that shall be active AND
+	 *    all formerly active bounds that have been active at the wrong bound. */
+	for( i=0; i<nV; ++i )
+	{
+		if ( ( bounds.getStatus( i ) == ST_INACTIVE ) && ( auxiliaryBounds->getStatus( i ) != ST_INACTIVE ) )
+		{
+			/* Add bound only if it is linearly independent from the current working set. */
+			if ( addBound_checkLI( i ) == RET_LINEARLY_INDEPENDENT )
+			{
+				if ( addBound( i,auxiliaryBounds->getStatus( i ),updateCholesky ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_SETUP_WORKINGSET_FAILED );
+			}
+		}
+	}
+
+	/* 2) Add all inactive constraints that shall be active AND
+	 *    all formerly active constraints that have been active at the wrong bound. */
+	for( i=0; i<nC; ++i )
+	{
+		if ( ( auxiliaryConstraints->getStatus( i ) == ST_LOWER ) || ( auxiliaryConstraints->getStatus( i ) == ST_UPPER ) )
+		{
+			/* formerly inactive */
+			if ( constraints.getStatus( i ) == ST_INACTIVE )
+			{
+				/* Add constraint only if it is linearly independent from the current working set. */
+				if ( addConstraint_checkLI( i ) == RET_LINEARLY_INDEPENDENT )
+				{
+					if ( addConstraint( i,auxiliaryConstraints->getStatus( i ),updateCholesky ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_SETUP_WORKINGSET_FAILED );
+				}
+			}
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p A u x i l i a r y Q P s o l u t i o n
+ */
+returnValue QProblem::setupAuxiliaryQPsolution(	const real_t* const xOpt, const real_t* const yOpt
+												)
+{
+	int i, j;
+	int nV = getNV( );
+	int nC = getNC( );
+
+
+	/* Setup primal/dual solution vector for auxiliary initial QP:
+	 * if a null pointer is passed, a zero vector is assigned;
+	 *  old solution vector is kept if pointer to internal solution vevtor is passed. */
+	if ( xOpt != 0 )
+	{
+		if ( xOpt != x )
+			for( i=0; i<nV; ++i )
+				x[i] = xOpt[i];
+
+		for ( j=0; j<nC; ++j )
+		{
+			Ax[j] = 0.0;
+
+			for( i=0; i<nV; ++i )
+				Ax[j] += A[j*NVMAX + i] * x[i];
+		}
+	}
+	else
+	{
+		for( i=0; i<nV; ++i )
+			x[i] = 0.0;
+
+		for ( j=0; j<nC; ++j )
+			Ax[j] = 0.0;
+	}
+
+	if ( yOpt != 0 )
+	{
+		if ( yOpt != y )
+			for( i=0; i<nV+nC; ++i )
+				y[i] = yOpt[i];
+	}
+	else
+	{
+		for( i=0; i<nV+nC; ++i )
+			y[i] = 0.0;
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p A u x i l i a r y Q P g r a d i e n t
+ */
+returnValue QProblem::setupAuxiliaryQPgradient( )
+{
+	int i, j;
+	int nV = getNV( );
+	int nC = getNC( );
+
+
+	/* Setup gradient vector: g = -H*x + [Id A]'*[yB yC]. */
+	for ( i=0; i<nV; ++i )
+	{
+		/* Id'*yB */
+		g[i] = y[i];
+
+		/* A'*yC */
+		for ( j=0; j<nC; ++j )
+			g[i] += A[j*NVMAX + i] * y[nV+j];
+
+		/* -H*x */
+		for ( j=0; j<nV; ++j )
+			g[i] -= H[i*NVMAX + j] * x[j];
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p A u x i l i a r y Q P b o u n d s
+ */
+returnValue QProblem::setupAuxiliaryQPbounds(	const Bounds* const auxiliaryBounds,
+												const Constraints* const auxiliaryConstraints,
+												BooleanType useRelaxation
+												)
+{
+	int i;
+	int nV = getNV( );
+	int nC = getNC( );
+
+
+	/* 1) Setup bound vectors. */
+	for ( i=0; i<nV; ++i )
+	{
+		switch ( bounds.getStatus( i ) )
+		{
+			case ST_INACTIVE:
+				if ( useRelaxation == BT_TRUE )
+				{
+					if ( bounds.getType( i ) == ST_EQUALITY )
+					{
+						lb[i] = x[i];
+						ub[i] = x[i];
+					}
+					else
+					{
+						/* If a bound is inactive although it was supposed to be
+						* active by the auxiliaryBounds, it could not be added
+						* due to linear dependence. Thus set it "strongly inactive". */
+						if ( auxiliaryBounds->getStatus( i ) == ST_LOWER )
+							lb[i] = x[i];
+						else
+							lb[i] = x[i] - BOUNDRELAXATION;
+
+						if ( auxiliaryBounds->getStatus( i ) == ST_UPPER )
+							ub[i] = x[i];
+						else
+							ub[i] = x[i] + BOUNDRELAXATION;
+					}
+				}
+				break;
+
+			case ST_LOWER:
+				lb[i] = x[i];
+				if ( bounds.getType( i ) == ST_EQUALITY )
+				{
+					ub[i] = x[i];
+				}
+				else
+				{
+					if ( useRelaxation == BT_TRUE )
+						ub[i] = x[i] + BOUNDRELAXATION;
+				}
+				break;
+
+			case ST_UPPER:
+				ub[i] = x[i];
+				if ( bounds.getType( i ) == ST_EQUALITY )
+				{
+					lb[i] = x[i];
+				}
+				else
+				{
+					if ( useRelaxation == BT_TRUE )
+						lb[i] = x[i] - BOUNDRELAXATION;
+				}
+				break;
+
+			default:
+				return THROWERROR( RET_UNKNOWN_BUG );
+		}
+	}
+
+	/* 2) Setup constraints vectors. */
+	for ( i=0; i<nC; ++i )
+	{
+		switch ( constraints.getStatus( i ) )
+		{
+			case ST_INACTIVE:
+				if ( useRelaxation == BT_TRUE )
+				{
+					if ( constraints.getType( i ) == ST_EQUALITY )
+					{
+						lbA[i] = Ax[i];
+						ubA[i] = Ax[i];
+					}
+					else
+					{
+						/* If a constraint is inactive although it was supposed to be
+						* active by the auxiliaryConstraints, it could not be added
+						* due to linear dependence. Thus set it "strongly inactive". */
+						if ( auxiliaryConstraints->getStatus( i ) == ST_LOWER )
+							lbA[i] = Ax[i];
+						else
+							lbA[i] = Ax[i] - BOUNDRELAXATION;
+
+						if ( auxiliaryConstraints->getStatus( i ) == ST_UPPER )
+							ubA[i] = Ax[i];
+						else
+							ubA[i] = Ax[i] + BOUNDRELAXATION;
+					}
+				}
+				break;
+
+			case ST_LOWER:
+				lbA[i] = Ax[i];
+				if ( constraints.getType( i ) == ST_EQUALITY )
+				{
+					ubA[i] = Ax[i];
+				}
+				else
+				{
+					if ( useRelaxation == BT_TRUE )
+						ubA[i] = Ax[i] + BOUNDRELAXATION;
+				}
+				break;
+
+			case ST_UPPER:
+				ubA[i] = Ax[i];
+				if ( constraints.getType( i ) == ST_EQUALITY )
+				{
+					lbA[i] = Ax[i];
+				}
+				else
+				{
+					if ( useRelaxation == BT_TRUE )
+						lbA[i] = Ax[i] - BOUNDRELAXATION;
+				}
+				break;
+
+			default:
+				return THROWERROR( RET_UNKNOWN_BUG );
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	a d d C o n s t r a i n t
+ */
+returnValue QProblem::addConstraint(	int number, SubjectToStatus C_status,
+										BooleanType updateCholesky
+										)
+{
+	int i, j, ii;
+
+	/* consistency checks */
+	if ( constraints.getStatus( number ) != ST_INACTIVE )
+		return THROWERROR( RET_CONSTRAINT_ALREADY_ACTIVE );
+
+	if ( ( constraints.getNC( ) - getNAC( ) ) == constraints.getNUC( ) )
+		return THROWERROR( RET_ALL_CONSTRAINTS_ACTIVE );
+
+	if ( ( getStatus( ) == QPS_NOTINITIALISED )    ||
+		 ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) ||
+		 ( getStatus( ) == QPS_HOMOTOPYQPSOLVED )  ||
+		 ( getStatus( ) == QPS_SOLVED )            )
+	{
+		return THROWERROR( RET_UNKNOWN_BUG );
+	}
+
+
+	/* I) ENSURE LINEAR INDEPENDENCE OF THE WORKING SET,
+	 *    i.e. remove a constraint or bound if linear dependence occurs. */
+	/* check for LI only if Cholesky decomposition shall be updated! */
+	if ( updateCholesky == BT_TRUE )
+	{
+		returnValue ensureLIreturnvalue = addConstraint_ensureLI( number,C_status );
+
+		switch ( ensureLIreturnvalue )
+		{
+			case SUCCESSFUL_RETURN:
+				break;
+
+			case RET_LI_RESOLVED:
+				break;
+
+			case RET_ENSURELI_FAILED_NOINDEX:
+				return THROWERROR( RET_ADDCONSTRAINT_FAILED_INFEASIBILITY );
+
+			case RET_ENSURELI_FAILED_CYCLING:
+				return THROWERROR( RET_ADDCONSTRAINT_FAILED_INFEASIBILITY );
+
+			default:
+				return THROWERROR( RET_ENSURELI_FAILED );
+		}
+	}
+
+	/* some definitions */
+	int nFR = getNFR( );
+	int nAC = getNAC( );
+	int nZ  = getNZ( );
+
+	int tcol = sizeT - nAC;
+
+
+	int FR_idx[NVMAX];
+	if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ADDCONSTRAINT_FAILED );
+
+	real_t aFR[NVMAX];
+	real_t wZ[NVMAX];
+	for( i=0; i<nZ; ++i )
+		wZ[i] = 0.0;
+
+
+	/* II) ADD NEW ACTIVE CONSTRAINT TO MATRIX T: */
+	/* 1) Add row [wZ wY] = aFR'*[Z Y] to the end of T: assign aFR. */
+	for( i=0; i<nFR; ++i )
+	{
+		ii = FR_idx[i];
+		aFR[i] = A[number*NVMAX + ii];
+	}
+
+	/* calculate wZ */
+	for( i=0; i<nFR; ++i )
+	{
+		ii = FR_idx[i];
+		for( j=0; j<nZ; ++j )
+			wZ[j] += aFR[i] * Q[ii*NVMAX + j];
+	}
+
+	/* 2) Calculate wY and store it directly into T. */
+	if ( nAC > 0 )
+	{
+		for( j=0; j<nAC; ++j )
+			T[nAC*NVMAX + tcol+j] = 0.0;
+		for( i=0; i<nFR; ++i )
+		{
+			ii = FR_idx[i];
+			for( j=0; j<nAC; ++j )
+				T[nAC*NVMAX + tcol+j] += aFR[i] * Q[ii*NVMAX + nZ+j];
+		}
+	}
+
+
+	real_t c, s;
+
+	if ( nZ > 0 )
+	{
+		/* II) RESTORE TRIANGULAR FORM OF T: */
+		/*     Use column-wise Givens rotations to restore reverse triangular form
+		*      of T, simultanenous change of Q (i.e. Z) and R. */
+		for( j=0; j<nZ-1; ++j )
+		{
+			computeGivens( wZ[j+1],wZ[j], wZ[j+1],wZ[j],c,s );
+
+			for( i=0; i<nFR; ++i )
+			{
+				ii = FR_idx[i];
+				applyGivens( c,s,Q[ii*NVMAX + 1+j],Q[ii*NVMAX + j], Q[ii*NVMAX + 1+j],Q[ii*NVMAX + j] );
+			}
+
+			if ( ( updateCholesky == BT_TRUE ) && ( hessianType != HST_IDENTITY ) )
+			{
+				for( i=0; i<=j+1; ++i )
+					applyGivens( c,s,R[i*NVMAX + 1+j],R[i*NVMAX + j], R[i*NVMAX + 1+j],R[i*NVMAX + j] );
+			}
+		}
+
+		T[nAC*NVMAX + tcol-1] = wZ[nZ-1];
+
+
+		if ( ( updateCholesky == BT_TRUE ) && ( hessianType != HST_IDENTITY ) )
+		{
+			/* III) RESTORE TRIANGULAR FORM OF R:
+			 *      Use row-wise Givens rotations to restore upper triangular form of R. */
+			for( i=0; i<nZ-1; ++i )
+			{
+				computeGivens( R[i*NVMAX + i],R[(1+i)*NVMAX + i], R[i*NVMAX + i],R[(1+i)*NVMAX + i],c,s );
+
+				for( j=(1+i); j<(nZ-1); ++j ) /* last column of R is thrown away */
+					applyGivens( c,s,R[i*NVMAX + j],R[(1+i)*NVMAX + j], R[i*NVMAX + j],R[(1+i)*NVMAX + j] );
+			}
+			/* last column of R is thrown away */
+			for( i=0; i<nZ; ++i )
+				R[i*NVMAX + nZ-1] = 0.0;
+		}
+	}
+
+
+	/* IV) UPDATE INDICES */
+	if ( constraints.moveInactiveToActive( number,C_status ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ADDCONSTRAINT_FAILED );
+
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*
+ *	a d d C o n s t r a i n t _ c h e c k L I
+ */
+returnValue QProblem::addConstraint_checkLI( int number )
+{
+	int i, j, jj;
+	int nFR = getNFR( );
+	int nZ  = getNZ( );
+
+	int FR_idx[NVMAX];
+	if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INDEXLIST_CORRUPTED );
+
+	/* Check if constraint <number> is linearly independent from the
+	   the active ones (<=> is element of null space of Afr). */
+	real_t sum;
+
+	for( i=0; i<nZ; ++i )
+	{
+		sum = 0.0;
+		for( j=0; j<nFR; ++j )
+		{
+			jj = FR_idx[j];
+			sum += Q[jj*NVMAX + i] * A[number*NVMAX + jj];
+		}
+
+		if ( getAbs( sum ) > 10.0*EPS )
+			return RET_LINEARLY_INDEPENDENT;
+	}
+
+	return RET_LINEARLY_DEPENDENT;
+}
+
+
+/*
+ *	a d d C o n s t r a i n t _ e n s u r e L I
+ */
+returnValue QProblem::addConstraint_ensureLI( int number, SubjectToStatus C_status )
+{
+	int i, j, ii, jj;
+	int nV  = getNV( );
+	int nFR = getNFR( );
+	int nFX = getNFX( );
+	int nAC = getNAC( );
+	int nZ  = getNZ( );
+
+
+	/* I) Check if new constraint is linearly independent from the active ones. */
+	returnValue returnvalueCheckLI = addConstraint_checkLI( number );
+
+	if ( returnvalueCheckLI == RET_INDEXLIST_CORRUPTED )
+		return THROWERROR( RET_ENSURELI_FAILED );
+
+	if ( returnvalueCheckLI == RET_LINEARLY_INDEPENDENT )
+		return SUCCESSFUL_RETURN;
+
+
+ 	/* II) NEW CONSTRAINT IS LINEARLY DEPENDENT: */
+	/* 1) Determine coefficients of linear combination,
+	 *    cf. M.J. Best. Applied Mathematics and Parallel Computing, chapter:
+	 *    An Algorithm for the Solution of the Parametric Quadratic Programming
+	 *    Problem, pages 57-76. Physica-Verlag, Heidelberg, 1996. */
+	int FR_idx[NVMAX];
+	if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ENSURELI_FAILED );
+
+	int FX_idx[NVMAX];
+	if ( bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ENSURELI_FAILED );
+
+	real_t xiC[NCMAX_ALLOC];
+	real_t xiC_TMP[NCMAX_ALLOC];
+	real_t xiB[NVMAX];
+
+	/* 2) Calculate xiC */
+	if ( nAC > 0 )
+	{
+		if ( C_status == ST_LOWER )
+		{
+			for( i=0; i<nAC; ++i )
+			{
+				xiC_TMP[i] = 0.0;
+				for( j=0; j<nFR; ++j )
+				{
+					jj = FR_idx[j];
+					xiC_TMP[i] += Q[jj*NVMAX + nZ+i] * A[number*NVMAX + jj];
+				}
+			}
+		}
+		else
+		{
+			for( i=0; i<nAC; ++i )
+			{
+				xiC_TMP[i] = 0.0;
+				for( j=0; j<nFR; ++j )
+				{
+					jj = FR_idx[j];
+					xiC_TMP[i] -= Q[jj*NVMAX + nZ+i] * A[number*NVMAX + jj];
+				}
+			}
+		}
+
+		if ( backsolveT( xiC_TMP, BT_TRUE, xiC ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_ENSURELI_FAILED_TQ );
+	}
+
+	/* 3) Calculate xiB. */
+	int AC_idx[NCMAX_ALLOC];
+	if ( constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ENSURELI_FAILED );
+
+	if ( C_status == ST_LOWER )
+	{
+		for( i=0; i<nFX; ++i )
+		{
+			ii = FX_idx[i];
+			xiB[i] = A[number*NVMAX + ii];
+
+			for( j=0; j<nAC; ++j )
+			{
+				jj = AC_idx[j];
+				xiB[i] -= A[jj*NVMAX + ii] * xiC[j];
+			}
+		}
+	}
+	else
+	{
+		for( i=0; i<nFX; ++i )
+		{
+			ii = FX_idx[i];
+			xiB[i] = -A[number*NVMAX + ii];
+
+			for( j=0; j<nAC; ++j )
+			{
+				jj = AC_idx[j];
+				xiB[i] -= A[jj*NVMAX + ii] * xiC[j];
+			}
+		}
+	}
+
+
+	/* III) DETERMINE CONSTRAINT/BOUND TO BE REMOVED. */
+	real_t y_min = INFTY * INFTY;
+	int y_min_number = -1;
+	BooleanType y_min_isBound = BT_FALSE;
+
+	/* 1) Constraints. */
+	for( i=0; i<nAC; ++i )
+	{
+		ii = AC_idx[i];
+
+		if ( constraints.getStatus( ii ) == ST_LOWER )
+		{
+			if ( ( xiC[i] > ZERO ) && ( y[nV+ii] >= 0.0 ) )
+			{
+				if ( y[nV+ii]/xiC[i] < y_min )
+				{
+					y_min = y[nV+ii]/xiC[i];
+					y_min_number = ii;
+				}
+			}
+		}
+		else
+		{
+			if ( ( xiC[i] < -ZERO ) && ( y[nV+ii] <= 0.0 ) )
+			{
+				if ( y[nV+ii]/xiC[i] < y_min )
+				{
+					y_min = y[nV+ii]/xiC[i];
+					y_min_number = ii;
+				}
+			}
+		}
+	}
+
+	/* 2) Bounds. */
+	for( i=0; i<nFX; ++i )
+	{
+		ii = FX_idx[i];
+
+		if ( bounds.getStatus( ii ) == ST_LOWER )
+		{
+			if ( ( xiB[i] > ZERO ) && ( y[ii] >= 0.0 ) )
+			{
+				if ( y[ii]/xiB[i] < y_min )
+				{
+					y_min = y[ii]/xiB[i];
+					y_min_number = ii;
+					y_min_isBound = BT_TRUE;
+				}
+			}
+		}
+		else
+		{
+			if ( ( xiB[i] < -ZERO ) && ( y[ii] <= 0.0 ) )
+			{
+				if ( y[ii]/xiB[i] < y_min )
+				{
+					y_min = y[ii]/xiB[i];
+					y_min_number = ii;
+					y_min_isBound = BT_TRUE;
+				}
+			}
+		}
+	}
+
+	/* setup output preferences */
+	#ifdef PC_DEBUG
+	char messageString[80];
+	VisibilityStatus visibilityStatus;
+
+	if ( printlevel == PL_HIGH )
+		visibilityStatus = VS_VISIBLE;
+	else
+		visibilityStatus = VS_HIDDEN;
+	#endif
+
+
+	/* IV) REMOVE CONSTRAINT/BOUND FOR RESOLVING LINEAR DEPENDENCE: */
+	if ( y_min_number >= 0 )
+	{
+		/* 1) Check for cycling due to infeasibility. */
+		if ( ( cyclingManager.getCyclingStatus( number,BT_FALSE ) == CYC_PREV_REMOVED ) &&
+			 ( cyclingManager.getCyclingStatus( y_min_number,y_min_isBound ) == CYC_PREV_ADDED ) )
+		{
+			infeasible = BT_TRUE;
+
+			return THROWERROR( RET_ENSURELI_FAILED_CYCLING );
+		}
+		else
+		{
+			/* set cycling data */
+			cyclingManager.clearCyclingData( );
+			cyclingManager.setCyclingStatus( number,BT_FALSE, CYC_PREV_ADDED );
+			cyclingManager.setCyclingStatus( y_min_number,y_min_isBound, CYC_PREV_REMOVED );
+		}
+
+		/* 2) Update Lagrange multiplier... */
+		for( i=0; i<nAC; ++i )
+		{
+			ii = AC_idx[i];
+			y[nV+ii] -= y_min * xiC[i];
+		}
+		for( i=0; i<nFX; ++i )
+		{
+			ii = FX_idx[i];
+			y[ii] -= y_min * xiB[i];
+		}
+
+		/* ... also for newly active constraint... */
+		if ( C_status == ST_LOWER )
+			y[nV+number] = y_min;
+		else
+			y[nV+number] = -y_min;
+
+		/* ... and for constraint to be removed. */
+		if ( y_min_isBound == BT_TRUE )
+		{
+			#ifdef PC_DEBUG
+			sprintf( messageString,"bound no. %d.",y_min_number );
+			getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus );
+			#endif
+
+			if ( removeBound( y_min_number,BT_TRUE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED );
+
+			y[y_min_number] = 0.0;
+		}
+		else
+		{
+			#ifdef PC_DEBUG
+			sprintf( messageString,"constraint no. %d.",y_min_number );
+			getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus );
+			#endif
+
+			if ( removeConstraint( y_min_number,BT_TRUE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED );
+
+			y[nV+y_min_number] = 0.0;
+		}
+	}
+	else
+	{
+		/* no constraint/bound can be removed => QP is infeasible! */
+		infeasible = BT_TRUE;
+
+		return THROWERROR( RET_ENSURELI_FAILED_NOINDEX );
+	}
+
+	return getGlobalMessageHandler( )->throwInfo( RET_LI_RESOLVED,0,__FUNCTION__,__FILE__,__LINE__,VS_HIDDEN );
+}
+
+
+
+/*
+ *	a d d B o u n d
+ */
+returnValue QProblem::addBound(	int number, SubjectToStatus B_status,
+								BooleanType updateCholesky
+								)
+{
+	int i, j, ii;
+
+	/* consistency checks */
+	if ( bounds.getStatus( number ) != ST_INACTIVE )
+		return THROWERROR( RET_BOUND_ALREADY_ACTIVE );
+
+	if ( getNFR( ) == bounds.getNUV( ) )
+		return THROWERROR( RET_ALL_BOUNDS_ACTIVE );
+
+	if ( ( getStatus( ) == QPS_NOTINITIALISED )    ||
+		 ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) ||
+		 ( getStatus( ) == QPS_HOMOTOPYQPSOLVED )  ||
+ 		 ( getStatus( ) == QPS_SOLVED )            )
+	{
+		return THROWERROR( RET_UNKNOWN_BUG );
+	}
+
+
+	/* I) ENSURE LINEAR INDEPENDENCE OF THE WORKING SET,
+	 *    i.e. remove a constraint or bound if linear dependence occurs. */
+	/* check for LI only if Cholesky decomposition shall be updated! */
+	if ( updateCholesky == BT_TRUE )
+	{
+		returnValue ensureLIreturnvalue = addBound_ensureLI( number,B_status );
+
+		switch ( ensureLIreturnvalue )
+		{
+			case SUCCESSFUL_RETURN:
+				break;
+
+			case RET_LI_RESOLVED:
+				break;
+
+			case RET_ENSURELI_FAILED_NOINDEX:
+				return THROWERROR( RET_ADDBOUND_FAILED_INFEASIBILITY );
+
+			case RET_ENSURELI_FAILED_CYCLING:
+				return THROWERROR( RET_ADDBOUND_FAILED_INFEASIBILITY );
+
+			default:
+				return THROWERROR( RET_ENSURELI_FAILED );
+		}
+	}
+
+
+	/* some definitions */
+	int nFR = getNFR( );
+	int nAC = getNAC( );
+	int nZ  = getNZ( );
+
+	int tcol = sizeT - nAC;
+
+
+	/* I) SWAP INDEXLIST OF FREE VARIABLES:
+	 *    move the variable to be fixed to the end of the list of free variables. */
+	int lastfreenumber = bounds.getFree( )->getLastNumber( );
+	if ( lastfreenumber != number )
+		if ( bounds.swapFree( number,lastfreenumber ) != SUCCESSFUL_RETURN )
+			THROWERROR( RET_ADDBOUND_FAILED );
+
+
+	int FR_idx[NVMAX];
+	if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ADDBOUND_FAILED );
+
+	real_t w[NVMAX];
+
+
+	/* II) ADD NEW ACTIVE BOUND TO TOP OF MATRIX T: */
+	/* 1) add row [wZ wY] = [Z Y](number) at the top of T: assign w */
+	for( i=0; i<nFR; ++i )
+		w[i] = Q[FR_idx[nFR-1]*NVMAX + i];
+
+
+	/* 2) Use column-wise Givens rotations to restore reverse triangular form
+	 *    of the first row of T, simultanenous change of Q (i.e. Z) and R. */
+	real_t c, s;
+
+	for( j=0; j<nZ-1; ++j )
+	{
+		computeGivens( w[j+1],w[j], w[j+1],w[j],c,s );
+
+		for( i=0; i<nFR; ++i )
+		{
+			ii = FR_idx[i];
+			applyGivens( c,s,Q[ii*NVMAX + 1+j],Q[ii*NVMAX + j], Q[ii*NVMAX + 1+j],Q[ii*NVMAX + j] );
+		}
+
+		if ( ( updateCholesky == BT_TRUE ) && ( hessianType != HST_IDENTITY ) )
+		{
+			for( i=0; i<=j+1; ++i )
+				applyGivens( c,s,R[i*NVMAX + 1+j],R[i*NVMAX + j], R[i*NVMAX + 1+j],R[i*NVMAX + j] );
+		}
+	}
+
+
+	if ( nAC > 0 )	  /* ( nAC == 0 ) <=> ( nZ == nFR ) <=> Y and T are empty => nothing to do */
+	{
+		/* store new column a in a temporary vector instead of shifting T one column to the left */
+		real_t tmp[NCMAX_ALLOC];
+		for( i=0; i<nAC; ++i )
+			tmp[i] = 0.0;
+
+		{
+			j = nZ-1;
+
+			computeGivens( w[j+1],w[j], w[j+1],w[j],c,s );
+
+			for( i=0; i<nFR; ++i )
+			{
+				ii = FR_idx[i];
+				applyGivens( c,s,Q[ii*NVMAX + 1+j],Q[ii*NVMAX + j], Q[ii*NVMAX + 1+j],Q[ii*NVMAX + j] );
+			}
+
+			applyGivens( c,s,T[(nAC-1)*NVMAX + tcol],tmp[nAC-1], tmp[nAC-1],T[(nAC-1)*NVMAX + tcol] );
+		}
+
+		for( j=nZ; j<nFR-1; ++j )
+		{
+			computeGivens( w[j+1],w[j], w[j+1],w[j],c,s );
+
+			for( i=0; i<nFR; ++i )
+			{
+				ii = FR_idx[i];
+				applyGivens( c,s,Q[ii*NVMAX + 1+j],Q[ii*NVMAX + j], Q[ii*NVMAX + 1+j],Q[ii*NVMAX + j] );
+			}
+
+			for( i=(nFR-2-j); i<nAC; ++i )
+				applyGivens( c,s,T[i*NVMAX + 1+tcol-nZ+j],tmp[i], tmp[i],T[i*NVMAX + 1+tcol-nZ+j] );
+		}
+
+	}
+
+
+	if ( ( updateCholesky == BT_TRUE ) && ( hessianType != HST_IDENTITY ) )
+	{
+		/* III) RESTORE TRIANGULAR FORM OF R:
+		 *      use row-wise Givens rotations to restore upper triangular form of R */
+		for( i=0; i<nZ-1; ++i )
+		{
+			computeGivens( R[i*NVMAX + i],R[(1+i)*NVMAX + i], R[i*NVMAX + i],R[(1+i)*NVMAX + i],c,s );
+
+			for( j=(1+i); j<nZ-1; ++j ) /* last column of R is thrown away */
+				applyGivens( c,s,R[i*NVMAX + j],R[(1+i)*NVMAX + j], R[i*NVMAX + j],R[(1+i)*NVMAX + j] );
+		}
+		/* last column of R is thrown away */
+		for( i=0; i<nZ; ++i )
+			R[i*NVMAX + nZ-1] = 0.0;
+	}
+
+
+	/* IV) UPDATE INDICES */
+	if ( bounds.moveFreeToFixed( number,B_status ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ADDBOUND_FAILED );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	a d d B o u n d _ c h e c k L I
+ */
+returnValue QProblem::addBound_checkLI( int number )
+{
+	int i;
+
+	/* some definitions */
+	int nZ  = getNZ( );
+
+	/* Check if constraint <number> is linearly independent from the
+	   the active ones (<=> is element of null space of Afr). */
+	for( i=0; i<nZ; ++i )
+	{
+		if ( getAbs( Q[number*NVMAX + i] ) > EPS )
+			return RET_LINEARLY_INDEPENDENT;
+	}
+
+	return RET_LINEARLY_DEPENDENT;
+}
+
+
+/*
+ *	a d d B o u n d _ e n s u r e L I
+ */
+returnValue QProblem::addBound_ensureLI( int number, SubjectToStatus B_status )
+{
+	int i, j, ii, jj;
+	int nV  = getNV( );
+	int nFX = getNFX( );
+	int nAC = getNAC( );
+	int nZ  = getNZ( );
+
+
+	/* I) Check if new constraint is linearly independent from the active ones. */
+	returnValue returnvalueCheckLI = addBound_checkLI( number );
+
+	if ( returnvalueCheckLI == RET_LINEARLY_INDEPENDENT )
+		return SUCCESSFUL_RETURN;
+
+
+ 	/* II) NEW BOUND IS LINEARLY DEPENDENT: */
+	/* 1) Determine coefficients of linear combination,
+	 *    cf. M.J. Best. Applied Mathematics and Parallel Computing, chapter:
+	 *    An Algorithm for the Solution of the Parametric Quadratic Programming
+	 *    Problem, pages 57-76. Physica-Verlag, Heidelberg, 1996. */
+	int FR_idx[NVMAX];
+	if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ENSURELI_FAILED );
+
+	int FX_idx[NVMAX];
+	if ( bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ENSURELI_FAILED );
+
+	int AC_idx[NCMAX_ALLOC];
+	if ( constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ENSURELI_FAILED );
+
+	real_t xiC[NCMAX_ALLOC];
+	real_t xiC_TMP[NCMAX_ALLOC];
+	real_t xiB[NVMAX];
+
+	/* 2) Calculate xiC. */
+	if ( nAC > 0 )
+	{
+		if ( B_status == ST_LOWER )
+		{
+			for( i=0; i<nAC; ++i )
+				xiC_TMP[i] = Q[number*NVMAX + nZ+i];
+		}
+		else
+		{
+			for( i=0; i<nAC; ++i )
+				xiC_TMP[i] = -Q[number*NVMAX + nZ+i];
+		}
+
+		if ( backsolveT( xiC_TMP, BT_TRUE, xiC ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_ENSURELI_FAILED_TQ );
+	}
+
+	/* 3) Calculate xiB. */
+	for( i=0; i<nFX; ++i )
+	{
+		ii = FX_idx[i];
+
+		xiB[i] = 0.0;
+		for( j=0; j<nAC; ++j )
+		{
+			jj = AC_idx[j];
+			xiB[i] -= A[jj*NVMAX + ii] * xiC[j];
+		}
+	}
+
+
+	/* III) DETERMINE CONSTRAINT/BOUND TO BE REMOVED. */
+	real_t y_min = INFTY * INFTY;
+	int y_min_number = -1;
+	BooleanType y_min_isBound = BT_FALSE;
+
+	/* 1) Constraints. */
+	for( i=0; i<nAC; ++i )
+	{
+		ii = AC_idx[i];
+
+		if ( constraints.getStatus( ii ) == ST_LOWER )
+		{
+			if ( ( xiC[i] > ZERO ) && ( y[nV+ii] >= 0.0 ) )
+			{
+				if ( y[nV+ii]/xiC[i] < y_min )
+				{
+					y_min = y[nV+ii]/xiC[i];
+					y_min_number = ii;
+				}
+			}
+		}
+		else
+		{
+			if ( ( xiC[i] < -ZERO ) && ( y[nV+ii] <= 0.0 ) )
+			{
+				if ( y[nV+ii]/xiC[i] < y_min )
+				{
+					y_min = y[nV+ii]/xiC[i];
+					y_min_number = ii;
+				}
+			}
+		}
+	}
+
+	/* 2) Bounds. */
+	for( i=0; i<nFX; ++i )
+	{
+		ii = FX_idx[i];
+
+		if ( bounds.getStatus( ii ) == ST_LOWER )
+		{
+			if ( ( xiB[i] > ZERO ) && ( y[ii] >= 0.0 ) )
+			{
+				if ( y[ii]/xiB[i] < y_min )
+				{
+					y_min = y[ii]/xiB[i];
+					y_min_number = ii;
+					y_min_isBound = BT_TRUE;
+				}
+			}
+		}
+		else
+		{
+			if ( ( xiB[i] < -ZERO ) && ( y[ii] <= 0.0 ) )
+			{
+				if ( y[ii]/xiB[i] < y_min )
+				{
+					y_min = y[ii]/xiB[i];
+					y_min_number = ii;
+					y_min_isBound = BT_TRUE;
+				}
+			}
+		}
+	}
+
+	/* setup output preferences */
+	#ifdef PC_DEBUG
+	char messageString[80];
+	VisibilityStatus visibilityStatus;
+
+	if ( printlevel == PL_HIGH )
+		visibilityStatus = VS_VISIBLE;
+	else
+		visibilityStatus = VS_HIDDEN;
+	#endif
+
+
+	/* IV) REMOVE CONSTRAINT/BOUND FOR RESOLVING LINEAR DEPENDENCE: */
+	if ( y_min_number >= 0 )
+	{
+		/* 1) Check for cycling due to infeasibility. */
+		if ( ( cyclingManager.getCyclingStatus( number,BT_TRUE ) == CYC_PREV_REMOVED ) &&
+			 ( cyclingManager.getCyclingStatus( y_min_number,y_min_isBound ) == CYC_PREV_ADDED ) )
+		{
+			infeasible = BT_TRUE;
+
+			return THROWERROR( RET_ENSURELI_FAILED_CYCLING );
+		}
+		else
+		{
+			/* set cycling data */
+			cyclingManager.clearCyclingData( );
+			cyclingManager.setCyclingStatus( number,BT_TRUE, CYC_PREV_ADDED );
+			cyclingManager.setCyclingStatus( y_min_number,y_min_isBound, CYC_PREV_REMOVED );
+		}
+
+
+		/* 2) Update Lagrange multiplier... */
+		for( i=0; i<nAC; ++i )
+		{
+			ii = AC_idx[i];
+			y[nV+ii] -= y_min * xiC[i];
+		}
+		for( i=0; i<nFX; ++i )
+		{
+			ii = FX_idx[i];
+			y[ii] -= y_min * xiB[i];
+		}
+
+		/* ... also for newly active bound ... */
+		if ( B_status == ST_LOWER )
+			y[number] = y_min;
+		else
+			y[number] = -y_min;
+
+		/* ... and for bound to be removed. */
+		if ( y_min_isBound == BT_TRUE )
+		{
+			#ifdef PC_DEBUG
+			sprintf( messageString,"bound no. %d.",y_min_number );
+			getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus );
+			#endif
+
+			if ( removeBound( y_min_number,BT_TRUE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED );
+
+			y[y_min_number] = 0.0;
+		}
+		else
+		{
+			#ifdef PC_DEBUG
+			sprintf( messageString,"constraint no. %d.",y_min_number );
+			getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus );
+			#endif
+
+			if ( removeConstraint( y_min_number,BT_TRUE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED );
+
+			y[nV+y_min_number] = 0.0;
+		}
+	}
+	else
+	{
+		/* no constraint/bound can be removed => QP is infeasible! */
+		infeasible = BT_TRUE;
+
+		return THROWERROR( RET_ENSURELI_FAILED_NOINDEX );
+	}
+
+	return getGlobalMessageHandler( )->throwInfo( RET_LI_RESOLVED,0,__FUNCTION__,__FILE__,__LINE__,VS_HIDDEN );
+}
+
+
+
+/*
+ *	r e m o v e C o n s t r a i n t
+ */
+returnValue QProblem::removeConstraint(	int number,
+										BooleanType updateCholesky
+										)
+{
+	int i, j, ii, jj;
+
+	/* consistency check */
+	if ( ( getStatus( ) == QPS_NOTINITIALISED )    ||
+		 ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) ||
+		 ( getStatus( ) == QPS_HOMOTOPYQPSOLVED )  ||
+ 		 ( getStatus( ) == QPS_SOLVED )            )
+	{
+		return THROWERROR( RET_UNKNOWN_BUG );
+	}
+
+	/* some definitions */
+	int nFR = getNFR( );
+	int nAC = getNAC( );
+	int nZ  = getNZ( );
+
+	int tcol = sizeT - nAC;
+	int number_idx = constraints.getActive( )->getIndex( number );
+
+
+	/* consistency checks */
+	if ( constraints.getStatus( number ) == ST_INACTIVE )
+		return THROWERROR( RET_CONSTRAINT_NOT_ACTIVE );
+
+	if ( ( number_idx < 0 ) || ( number_idx >= nAC ) )
+		return THROWERROR( RET_CONSTRAINT_NOT_ACTIVE );
+
+
+	int FR_idx[NVMAX];
+	if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_REMOVECONSTRAINT_FAILED );
+
+
+	/* I) REMOVE <number>th ROW FROM T,
+	 *    i.e. shift rows number+1 through nAC  upwards (instead of the actual
+	 *    constraint number its corresponding index within matrix A is used). */
+	if ( number_idx < nAC-1 )
+	{
+		for( i=(number_idx+1); i<nAC; ++i )
+			for( j=(nAC-i-1); j<nAC; ++j )
+				T[(i-1)*NVMAX + tcol+j] = T[i*NVMAX + tcol+j];
+		/* gimmick: write zeros into the last row of T */
+		for( j=0; j<nAC; ++j )
+			T[(nAC-1)*NVMAX + tcol+j] = 0.0;
+
+
+		/* II) RESTORE TRIANGULAR FORM OF T,
+		 *     use column-wise Givens rotations to restore reverse triangular form
+		 *     of T simultanenous change of Q (i.e. Y). */
+		real_t c, s;
+
+		for( j=(nAC-2-number_idx); j>=0; --j )
+		{
+			computeGivens( T[(nAC-2-j)*NVMAX + tcol+1+j],T[(nAC-2-j)*NVMAX + tcol+j], T[(nAC-2-j)*NVMAX + tcol+1+j],T[(nAC-2-j)*NVMAX + tcol+j],c,s );
+
+			for( i=(nAC-j-1); i<(nAC-1); ++i )
+				applyGivens( c,s,T[i*NVMAX + tcol+1+j],T[i*NVMAX + tcol+j], T[i*NVMAX + tcol+1+j],T[i*NVMAX + tcol+j] );
+
+			for( i=0; i<nFR; ++i )
+			{
+				ii = FR_idx[i];
+				applyGivens( c,s,Q[ii*NVMAX + nZ+1+j],Q[ii*NVMAX + nZ+j], Q[ii*NVMAX + nZ+1+j],Q[ii*NVMAX + nZ+j] );
+			}
+		}
+	}
+	else
+	{
+		/* gimmick: write zeros into the last row of T */
+		for( j=0; j<nAC; ++j )
+			T[(nAC-1)*NVMAX + tcol+j] = 0.0;
+	}
+
+
+	if ( ( updateCholesky == BT_TRUE ) && ( hessianType != HST_IDENTITY ) )
+	{
+		/* III) UPDATE CHOLESKY DECOMPOSITION,
+		 *      calculate new additional column (i.e. [r sqrt(rho2)]')
+		 *      of the Cholesky factor R. */
+		real_t Hz[NVMAX];
+		for ( i=0; i<nFR; ++i )
+			Hz[i] = 0.0;
+		real_t rho2 = 0.0;
+
+		/* 1) Calculate Hz = H*z, where z is the new rightmost column of Z
+		 *    (i.e. the old leftmost column of Y).  */
+		for( j=0; j<nFR; ++j )
+		{
+			jj = FR_idx[j];
+			for( i=0; i<nFR; ++i )
+				Hz[i] += H[jj*NVMAX + FR_idx[i]] * Q[jj*NVMAX + nZ];
+		}
+
+		if ( nZ > 0 )
+		{
+			real_t ZHz[NVMAX];
+			for ( i=0; i<nZ; ++i )
+				ZHz[i] = 0.0;
+			real_t r[NVMAX];
+
+			/* 2) Calculate ZHz = Z'*Hz (old Z). */
+			for( j=0; j<nFR; ++j )
+			{
+				jj = FR_idx[j];
+
+				for( i=0; i<nZ; ++i )
+					ZHz[i] += Q[jj*NVMAX + i] * Hz[j];
+			}
+
+			/* 3) Calculate r = R^-T * ZHz. */
+			if ( backsolveR( ZHz,BT_TRUE,r ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_REMOVECONSTRAINT_FAILED );
+
+			/* 4) Calculate rho2 = rho^2 = z'*Hz - r'*r
+			 *    and store r into R. */
+			for( i=0; i<nZ; ++i )
+			{
+				rho2 -= r[i]*r[i];
+				R[i*NVMAX + nZ] = r[i];
+			}
+		}
+
+		for( j=0; j<nFR; ++j )
+			rho2 += Q[FR_idx[j]*NVMAX + nZ] * Hz[j];
+
+		/* 5) Store rho into R. */
+		if ( rho2 > 0.0 )
+			R[nZ*NVMAX + nZ] = sqrt( rho2 );
+		else
+		{
+			hessianType = HST_SEMIDEF;
+			return THROWERROR( RET_HESSIAN_NOT_SPD );
+		}
+	}
+
+	/* IV) UPDATE INDICES */
+	if ( constraints.moveActiveToInactive( number ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_REMOVECONSTRAINT_FAILED );
+
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	r e m o v e B o u n d
+ */
+returnValue QProblem::removeBound(	int number,
+									BooleanType updateCholesky
+									)
+{
+	int i, j, ii, jj;
+
+	/* consistency checks */
+	if ( bounds.getStatus( number ) == ST_INACTIVE )
+		return THROWERROR( RET_BOUND_NOT_ACTIVE );
+
+	if ( ( getStatus( ) == QPS_NOTINITIALISED )    ||
+		 ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) ||
+		 ( getStatus( ) == QPS_HOMOTOPYQPSOLVED )  ||
+ 		 ( getStatus( ) == QPS_SOLVED )            )
+	{
+		return THROWERROR( RET_UNKNOWN_BUG );
+	}
+
+	/* some definitions */
+	int nFR = getNFR( );
+	int nAC = getNAC( );
+	int nZ  = getNZ( );
+
+	int tcol = sizeT - nAC;
+
+
+	/* I) UPDATE INDICES */
+	if ( bounds.moveFixedToFree( number ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_REMOVEBOUND_FAILED );
+
+
+	int FR_idx[NVMAX];
+	if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_REMOVEBOUND_FAILED );
+
+	/* I) APPEND <nFR+1>th UNITY VECOTR TO Q. */
+	int nnFRp1 = FR_idx[nFR];
+	for( i=0; i<nFR; ++i )
+	{
+		ii = FR_idx[i];
+		Q[ii*NVMAX + nFR] = 0.0;
+		Q[nnFRp1*NVMAX + i] = 0.0;
+	}
+	Q[nnFRp1*NVMAX + nFR] = 1.0;
+
+	if ( nAC > 0 )
+	{
+		/* store new column a in a temporary vector instead of shifting T one column to the left and appending a */
+		int AC_idx[NCMAX_ALLOC];
+		if ( constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_REMOVEBOUND_FAILED );
+
+		real_t tmp[NCMAX_ALLOC];
+		for( i=0; i<nAC; ++i )
+		{
+			ii = AC_idx[i];
+			tmp[i] =  A[ii*NVMAX + number];
+		}
+
+
+		/* II) RESTORE TRIANGULAR FORM OF T,
+		 *     use column-wise Givens rotations to restore reverse triangular form
+		 *     of T = [T A(:,number)], simultanenous change of Q (i.e. Y and Z). */
+		real_t c, s;
+
+		for( j=(nAC-1); j>=0; --j )
+		{
+			computeGivens( tmp[nAC-1-j],T[(nAC-1-j)*NVMAX + tcol+j],T[(nAC-1-j)*NVMAX + tcol+j],tmp[nAC-1-j],c,s );
+
+			for( i=(nAC-j); i<nAC; ++i )
+				applyGivens( c,s,tmp[i],T[i*NVMAX + tcol+j],T[i*NVMAX + tcol+j],tmp[i] );
+
+			for( i=0; i<=nFR; ++i )
+			{
+				ii = FR_idx[i];
+				/* nZ+1+nAC = nFR+1  /  nZ+(1) = nZ+1 */
+				applyGivens( c,s,Q[ii*NVMAX + nZ+1+j],Q[ii*NVMAX + nZ+j],Q[ii*NVMAX + nZ+1+j],Q[ii*NVMAX + nZ+j] );
+			}
+		}
+	}
+
+
+	if ( ( updateCholesky == BT_TRUE ) && ( hessianType != HST_IDENTITY ) )
+	{
+		/* III) UPDATE CHOLESKY DECOMPOSITION,
+		 *      calculate new additional column (i.e. [r sqrt(rho2)]')
+		 *      of the Cholesky factor R: */
+		real_t z2 = Q[nnFRp1*NVMAX + nZ];
+		real_t rho2 = H[nnFRp1*NVMAX + nnFRp1]*z2*z2; /* rho2 = h2*z2*z2 */
+
+		if ( nFR > 0 )
+		{
+			real_t Hz[NVMAX];
+			for( i=0; i<nFR; ++i )
+				Hz[i] = 0.0;
+			/* 1) Calculate R'*r = Zfr'*Hfr*z1 + z2*Zfr'*h1 =: Zfr'*Hz + z2*Zfr'*h1 =: rhs and
+			 *    rho2 = z1'*Hfr*z1 + 2*z2*h1'*z1 + h2*z2^2 - r'*r =: z1'*Hz + 2*z2*h1'*z1 + h2*z2^2 - r'r */
+			for( j=0; j<nFR; ++j )
+			{
+				jj = FR_idx[j];
+				for( i=0; i<nFR; ++i )
+				{
+					ii = FR_idx[i];
+					/*			   H * z1 */
+					Hz[i] += H[jj*NVMAX + ii] * Q[jj*NVMAX + nZ];
+				}
+			}
+
+			if ( nZ > 0 )
+			{
+				real_t r[NVMAX];
+				real_t rhs[NVMAX];
+				for( i=0; i<nZ; ++i )
+					rhs[i] = 0.0;
+
+				/* 2) Calculate rhs. */
+				for( j=0; j<nFR; ++j )
+				{
+					jj = FR_idx[j];
+					for( i=0; i<nZ; ++i )
+										/* Zfr' * ( Hz + z2*h1 ) */
+						rhs[i] += Q[jj*NVMAX + i] * ( Hz[j] + z2 * H[nnFRp1*NVMAX + jj] );
+				}
+
+				/* 3) Calculate r = R^-T * rhs. */
+				if ( backsolveR( rhs,BT_TRUE,BT_TRUE,r ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_REMOVEBOUND_FAILED );
+
+				/* 4) Calculate rho2 = rho^2 = z'*Hz - r'*r
+				 *    and store r into R. */
+				for( i=0; i<nZ; ++i )
+				{
+					rho2 -= r[i]*r[i];
+					R[i*NVMAX + nZ] = r[i];
+				}
+			}
+
+			for( j=0; j<nFR; ++j )
+			{
+				jj = FR_idx[j];
+							/* z1' * ( Hz + 2*z2*h1 ) */
+				rho2 += Q[jj*NVMAX + nZ] * ( Hz[j] + 2.0*z2*H[nnFRp1*NVMAX + jj] );
+			}
+		}
+
+
+		/* 5) Store rho into R. */
+		if ( rho2 > 0.0 )
+			R[nZ*NVMAX + nZ] = sqrt( rho2 );
+		else
+		{
+			hessianType = HST_SEMIDEF;
+			return THROWERROR( RET_HESSIAN_NOT_SPD );
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	b a c k s o l v e R  (CODE DUPLICATE OF QProblemB CLASS!!!)
+ */
+returnValue QProblem::backsolveR(	const real_t* const b, BooleanType transposed,
+									real_t* const a
+									)
+{
+	/* Call standard backsolve procedure (i.e. removingBound == BT_FALSE). */
+	return backsolveR( b,transposed,BT_FALSE,a );
+}
+
+
+/*
+ *	b a c k s o l v e R  (CODE DUPLICATE OF QProblemB CLASS!!!)
+ */
+returnValue QProblem::backsolveR(	const real_t* const b, BooleanType transposed,
+									BooleanType removingBound,
+									real_t* const a
+									)
+{
+	int i, j;
+	int nR = getNZ( );
+
+	real_t sum;
+
+	/* if backsolve is called while removing a bound, reduce nZ by one. */
+	if ( removingBound == BT_TRUE )
+		--nR;
+
+	/* nothing to do */
+	if ( nR <= 0 )
+		return SUCCESSFUL_RETURN;
+
+
+	/* Solve Ra = b, where R might be transposed. */
+	if ( transposed == BT_FALSE )
+	{
+		/* solve Ra = b */
+		for( i=(nR-1); i>=0; --i )
+		{
+			sum = b[i];
+			for( j=(i+1); j<nR; ++j )
+				sum -= R[i*NVMAX + j] * a[j];
+
+			if ( getAbs( R[i*NVMAX + i] ) > ZERO )
+				a[i] = sum / R[i*NVMAX + i];
+			else
+				return THROWERROR( RET_DIV_BY_ZERO );
+		}
+	}
+	else
+	{
+		/* solve R^T*a = b */
+		for( i=0; i<nR; ++i )
+		{
+			sum = b[i];
+
+			for( j=0; j<i; ++j )
+				sum -= R[j*NVMAX + i] * a[j];
+
+			if ( getAbs( R[i*NVMAX + i] ) > ZERO )
+				a[i] = sum / R[i*NVMAX + i];
+			else
+				return THROWERROR( RET_DIV_BY_ZERO );
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*
+ *	b a c k s o l v e T
+ */
+returnValue QProblem::backsolveT( const real_t* const b, BooleanType transposed, real_t* const a )
+{
+	int i, j;
+	int nT = getNAC( );
+	int tcol = sizeT - nT;
+
+	real_t sum;
+
+	/* nothing to do */
+	if ( nT <= 0 )
+		return SUCCESSFUL_RETURN;
+
+
+	/* Solve Ta = b, where T might be transposed. */
+	if ( transposed == BT_FALSE )
+	{
+		/* solve Ta = b */
+		for( i=0; i<nT; ++i )
+		{
+			sum = b[i];
+			for( j=0; j<i; ++j )
+				sum -= T[i*NVMAX + sizeT-1-j] * a[nT-1-j];
+
+			if ( getAbs( T[i*NVMAX + sizeT-1-i] ) > ZERO )
+				a[nT-1-i] = sum / T[i*NVMAX + sizeT-1-i];
+			else
+				return THROWERROR( RET_DIV_BY_ZERO );
+		}
+	}
+	else
+	{
+		/* solve T^T*a = b */
+		for( i=0; i<nT; ++i )
+		{
+			sum = b[i];
+			for( j=0; j<i; ++j )
+				sum -= T[(nT-1-j)*NVMAX + tcol+i] * a[nT-1-j];
+
+			if ( getAbs( T[(nT-1-i)*NVMAX + tcol+i] ) > ZERO )
+				a[nT-1-i] = sum / T[(nT-1-i)*NVMAX + tcol+i];
+			else
+				return THROWERROR( RET_DIV_BY_ZERO );
+		}
+	}
+
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	h o t s t a r t _ d e t e r m i n e D a t a S h i f t
+ */
+returnValue QProblem::hotstart_determineDataShift(  const int* const FX_idx, const int* const AC_idx,
+													const real_t* const g_new, const real_t* const lbA_new, const real_t* const ubA_new,
+													const real_t* const lb_new, const real_t* const ub_new,
+													real_t* const delta_g, real_t* const delta_lbA, real_t* const delta_ubA,
+													real_t* const delta_lb, real_t* const delta_ub,
+													BooleanType& Delta_bC_isZero, BooleanType& Delta_bB_isZero
+													)
+{
+	int i, ii;
+	int nC  = getNC( );
+	int nAC = getNAC( );
+
+
+	/* I) DETERMINE DATA SHIFT FOR BOUNDS */
+	QProblemB::hotstart_determineDataShift( FX_idx,g_new,lb_new,ub_new, delta_g,delta_lb,delta_ub, Delta_bB_isZero );
+
+
+	/* II) DETERMINE DATA SHIFT FOR CONSTRAINTS */
+	/* 1) Calculate shift directions. */
+	for( i=0; i<nC; ++i )
+	{
+		/* if lower constraints' bounds do not exist, shift them to -infinity */
+		if ( lbA_new != 0 )
+			delta_lbA[i] = lbA_new[i] - lbA[i];
+		else
+			delta_lbA[i] = -INFTY - lbA[i];
+	}
+
+	for( i=0; i<nC; ++i )
+	{
+		/* if upper constraints' bounds do not exist, shift them to infinity */
+		if ( ubA_new != 0 )
+			delta_ubA[i] = ubA_new[i] - ubA[i];
+		else
+			delta_ubA[i] = INFTY - ubA[i];
+	}
+
+	/* 2) Determine if active constraints' bounds are to be shifted. */
+	Delta_bC_isZero = BT_TRUE;
+
+	for ( i=0; i<nAC; ++i )
+	{
+		ii = AC_idx[i];
+
+		if ( ( getAbs( delta_lbA[ii] ) > EPS ) || ( getAbs( delta_ubA[ii] ) > EPS ) )
+		{
+			Delta_bC_isZero = BT_FALSE;
+			break;
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	h o t s t a r t _ d e t e r m i n e S t e p D i r e c t i o n
+ */
+returnValue QProblem::hotstart_determineStepDirection(	const int* const FR_idx, const int* const FX_idx, const int* const AC_idx,
+														const real_t* const delta_g, const real_t* const delta_lbA, const real_t* const delta_ubA,
+														const real_t* const delta_lb, const real_t* const delta_ub,
+														BooleanType Delta_bC_isZero, BooleanType Delta_bB_isZero,
+														real_t* const delta_xFX, real_t* const delta_xFR,
+														real_t* const delta_yAC, real_t* const delta_yFX
+														)
+{
+	int i, j, ii, jj;
+	int nFR = getNFR( );
+	int nFX = getNFX( );
+	int nAC = getNAC( );
+	int nZ  = getNZ( );
+
+	/* initialise auxiliary vectors */
+	real_t HMX_delta_xFX[NVMAX];
+	real_t YFR_delta_xFRy[NVMAX];
+	real_t ZFR_delta_xFRz[NVMAX];
+	real_t HFR_YFR_delta_xFRy[NVMAX];
+	for( i=0; i<nFR; ++i )
+	{
+		delta_xFR[i] = 0.0;
+		HMX_delta_xFX[i] = 0.0;
+		YFR_delta_xFRy[i] = 0.0;
+		ZFR_delta_xFRz[i] = 0.0;
+		HFR_YFR_delta_xFRy[i] = 0.0;
+	}
+
+	real_t delta_xFRy[NCMAX_ALLOC];
+	real_t delta_xFRz[NVMAX];
+	for( i=0; i<nZ; ++i )
+		delta_xFRz[i] = 0.0;
+
+
+	/* I) DETERMINE delta_xFX */
+	if ( nFX > 0 )
+	{
+		for( i=0; i<nFX; ++i )
+		{
+			ii = FX_idx[i];
+
+			if ( bounds.getStatus( ii ) == ST_LOWER )
+				delta_xFX[i] = delta_lb[ii];
+			else
+				delta_xFX[i] = delta_ub[ii];
+		}
+	}
+
+	/* II) DETERMINE delta_xFR */
+	if ( nFR > 0 )
+	{
+		/* 1) Determine delta_xFRy. */
+		if ( nAC > 0 )
+		{
+			if ( ( Delta_bC_isZero == BT_TRUE ) && ( Delta_bB_isZero == BT_TRUE ) )
+			{
+				for( i=0; i<nAC; ++i )
+					delta_xFRy[i] = 0.0;
+
+				for( i=0; i<nFR; ++i )
+					delta_xFR[i] = 0.0;
+			}
+			else
+			{
+				/* auxillary variable */
+				real_t delta_xFRy_TMP[NCMAX_ALLOC];
+
+				for( i=0; i<nAC; ++i )
+				{
+					ii = AC_idx[i];
+
+					if ( constraints.getStatus( ii ) == ST_LOWER )
+						delta_xFRy_TMP[i] = delta_lbA[ii];
+					else
+						delta_xFRy_TMP[i] = delta_ubA[ii];
+
+					if ( Delta_bB_isZero == BT_FALSE )
+					{
+						for( j=0; j<nFX; ++j )
+						{
+							jj = FX_idx[j];
+							delta_xFRy_TMP[i] -= A[ii*NVMAX + jj] * delta_xFX[j];
+						}
+					}
+				}
+
+				if ( backsolveT( delta_xFRy_TMP, BT_FALSE, delta_xFRy ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_STEPDIRECTION_FAILED_TQ );
+
+				for( i=0; i<nFR; ++i )
+				{
+					ii = FR_idx[i];
+					for( j=0; j<nAC; ++j )
+						YFR_delta_xFRy[i] += Q[ii*NVMAX + nZ+j] * delta_xFRy[j];
+
+					/* delta_xFR = YFR*delta_xFRy (+ ZFR*delta_xFRz) */
+					delta_xFR[i] = YFR_delta_xFRy[i];
+				}
+			}
+		}
+
+		/* 2) Determine delta_xFRz. */
+		if ( hessianType == HST_IDENTITY )
+		{
+			for( j=0; j<nFR; ++j )
+			{
+				jj = FR_idx[j];
+				for( i=0; i<nZ; ++i )
+					delta_xFRz[i] -= Q[jj*NVMAX + i] * delta_g[jj];
+			}
+
+			if ( nZ > 0 )
+			{
+				for( i=0; i<nFR; ++i )
+				{
+					ii = FR_idx[i];
+					for( j=0; j<nZ; ++j )
+						ZFR_delta_xFRz[i] += Q[ii*NVMAX + j] * delta_xFRz[j];
+
+					delta_xFR[i] += ZFR_delta_xFRz[i];
+				}
+			}
+		}
+		else
+		{
+			if ( Delta_bB_isZero == BT_FALSE )
+			{
+				for( i=0; i<nFR; ++i )
+				{
+					ii = FR_idx[i];
+					for( j=0; j<nFX; ++j )
+					{
+						jj = FX_idx[j];
+						HMX_delta_xFX[i] += H[ii*NVMAX + jj] * delta_xFX[j];
+					}
+				}
+			}
+
+			if ( nAC > 0 )
+			{
+				if ( ( Delta_bC_isZero == BT_FALSE ) || ( Delta_bB_isZero == BT_FALSE ) )
+				{
+					for( i=0; i<nFR; ++i )
+					{
+						ii = FR_idx[i];
+						for( j=0; j<nFR; ++j )
+						{
+							jj = FR_idx[j];
+							HFR_YFR_delta_xFRy[i] += H[ii*NVMAX + jj] * YFR_delta_xFRy[j];
+						}
+					}
+				}
+			}
+
+
+			if ( nZ > 0 )
+			{
+				/* auxiliary variable */
+				real_t delta_xFRz_TMP[NVMAX];
+				real_t delta_xFRz_RHS[NVMAX];
+
+
+				if ( ( nAC > 0 ) && ( nFX > 0 ) && ( Delta_bB_isZero == BT_FALSE ) )
+				{
+					for( j=0; j<nFR; ++j )
+					{
+						jj = FR_idx[j];
+						delta_xFRz_RHS[j] = delta_g[jj] + HFR_YFR_delta_xFRy[j] + HMX_delta_xFX[j];
+					}
+				}
+				else
+				{
+					if ( ( nAC == 0 ) && ( Delta_bB_isZero == BT_TRUE ) )
+					{
+						for( j=0; j<nFR; ++j )
+						{
+							jj = FR_idx[j];
+							delta_xFRz_RHS[j] = delta_g[jj];
+						}
+					}
+					else
+					{
+						if ( nAC > 0 ) /* => Delta_bB_isZero == BT_TRUE, as BT_FALSE would imply nFX>0 */
+						{
+							for( j=0; j<nFR; ++j )
+							{
+								jj = FR_idx[j];
+								delta_xFRz_RHS[j] = delta_g[jj] + HFR_YFR_delta_xFRy[j];
+							}
+						}
+						else /* Delta_bB_isZero == BT_FALSE, as nAC==0 */
+						{
+							for( j=0; j<nFR; ++j )
+							{
+								jj = FR_idx[j];
+								delta_xFRz_RHS[j] = delta_g[jj] + HMX_delta_xFX[j];
+							}
+						}
+					}
+				}
+
+				for( j=0; j<nFR; ++j )
+				{
+					jj = FR_idx[j];
+					for( i=0; i<nZ; ++i )
+						delta_xFRz[i] -= Q[jj*NVMAX + i] * delta_xFRz_RHS[j];
+				}
+
+
+				if ( backsolveR( delta_xFRz,BT_TRUE,delta_xFRz_TMP ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_STEPDIRECTION_FAILED_CHOLESKY );
+
+				if ( backsolveR( delta_xFRz_TMP,BT_FALSE,delta_xFRz ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_STEPDIRECTION_FAILED_CHOLESKY );
+
+
+				for( i=0; i<nFR; ++i )
+				{
+					ii = FR_idx[i];
+					for( j=0; j<nZ; ++j )
+						ZFR_delta_xFRz[i] += Q[ii*NVMAX + j] * delta_xFRz[j];
+
+					delta_xFR[i] += ZFR_delta_xFRz[i];
+				}
+			}
+		}
+	}
+
+	/* III) DETERMINE delta_yAC */
+	if ( nAC > 0 ) /* => ( nFR = nZ + nAC > 0 ) */
+	{
+		/* auxiliary variables */
+		real_t delta_yAC_TMP[NCMAX_ALLOC];
+		for( i=0; i<nAC; ++i )
+			delta_yAC_TMP[i] = 0.0;
+		real_t delta_yAC_RHS[NVMAX];
+		for( i=0; i<nFR; ++i )
+			delta_yAC_RHS[i] = 0.0;
+
+		if ( hessianType == HST_IDENTITY )
+		{
+			/* delta_yAC = (T')^-1 * ( Yfr*delta_gFR + delta_xFRy ) */
+			for( j=0; j<nAC; ++j )
+			{
+				for( i=0; i<nFR; ++i )
+				{
+					ii = FR_idx[i];
+					delta_yAC_TMP[j] += Q[ii*NVMAX + nZ+j] * delta_g[ii];
+				}
+
+				delta_yAC_TMP[j] += delta_xFRy[j];
+			}
+		}
+		else
+		{
+			if ( ( Delta_bC_isZero == BT_TRUE ) && ( Delta_bB_isZero == BT_TRUE ) )
+			{
+				for( i=0; i<nFR; ++i )
+				{
+					ii = FR_idx[i];
+					delta_yAC_RHS[i] = delta_g[ii];
+				}
+			}
+			else
+			{
+				for( i=0; i<nFR; ++i )
+				{
+					ii = FR_idx[i];
+					delta_yAC_RHS[i] = HFR_YFR_delta_xFRy[i] + delta_g[ii];
+				}
+			}
+
+			if ( nZ > 0 )
+			{
+				for( i=0; i<nFR; ++i )
+				{
+					ii = FR_idx[i];
+					for( j=0; j<nFR; ++j )
+					{
+						jj = FR_idx[j];
+						delta_yAC_RHS[i] += H[ii*NVMAX + jj] * ZFR_delta_xFRz[j];
+					}
+				}
+			}
+
+			if ( nFX > 0 )
+			{
+				if ( Delta_bB_isZero == BT_FALSE )
+				{
+					for( i=0; i<nFR; ++i )
+						delta_yAC_RHS[i] += HMX_delta_xFX[i];
+				}
+			}
+
+			for( i=0; i<nAC; ++i)
+			{
+				for( j=0; j<nFR; ++j )
+				{
+					jj = FR_idx[j];
+					delta_yAC_TMP[i] += Q[jj*NVMAX + nZ+i] * delta_yAC_RHS[j];
+				}
+			}
+		}
+
+		if ( backsolveT( delta_yAC_TMP,BT_TRUE,delta_yAC ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_STEPDIRECTION_FAILED_TQ );
+	}
+
+
+	/* IV) DETERMINE delta_yFX */
+	if ( nFX > 0 )
+	{
+		for( i=0; i<nFX; ++i )
+		{
+			ii = FX_idx[i];
+
+			delta_yFX[i] = delta_g[ii];
+
+			for( j=0; j<nAC; ++j )
+			{
+				jj = AC_idx[j];
+				delta_yFX[i] -= A[jj*NVMAX + ii] * delta_yAC[j];
+			}
+
+			if ( hessianType == HST_IDENTITY )
+			{
+				delta_yFX[i] += delta_xFX[i];
+			}
+			else
+			{
+				for( j=0; j<nFR; ++j )
+				{
+					jj = FR_idx[j];
+					delta_yFX[i] += H[ii*NVMAX + jj] * delta_xFR[j];
+				}
+
+				if ( Delta_bB_isZero == BT_FALSE )
+				{
+					for( j=0; j<nFX; ++j )
+					{
+						jj = FX_idx[j];
+						delta_yFX[i] += H[ii*NVMAX + jj] * delta_xFX[j];
+					}
+				}
+			}
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	h o t s t a r t _ d e t e r m i n e S t e p L e n g t h
+ */
+returnValue QProblem::hotstart_determineStepLength(	const int* const FR_idx, const int* const FX_idx, const int* const AC_idx, const int* const IAC_idx,
+													const real_t* const delta_lbA, const real_t* const delta_ubA,
+													const real_t* const delta_lb, const real_t* const delta_ub,
+													const real_t* const delta_xFX, const real_t* const delta_xFR,
+													const real_t* const delta_yAC, const real_t* const delta_yFX,
+													real_t* const delta_Ax, int& BC_idx, SubjectToStatus& BC_status, BooleanType& BC_isBound
+													)
+{
+	int i, j, ii, jj;
+	int nV  = getNV( );
+	int nC  = getNC( );
+	int nFR = getNFR( );
+	int nFX = getNFX( );
+	int nAC = getNAC( );
+	int nIAC = getNIAC( );
+
+	/* initialise maximum steplength array */
+	real_t maxStepLength[2*(NVMAX+NCMAX_ALLOC)];
+	for ( i=0; i<2*(nV+nC); ++i )
+		maxStepLength[i] = 1.0;
+
+
+	/* I) DETERMINE MAXIMUM DUAL STEPLENGTH: */
+	/* 1) Ensure that active dual constraints' bounds remain valid
+	 *    (ignoring inequality constraints).  */
+	for( i=0; i<nAC; ++i )
+	{
+		ii = AC_idx[i];
+
+		if ( constraints.getType( ii ) != ST_EQUALITY )
+		{
+			if ( constraints.getStatus( ii ) == ST_LOWER )
+			{
+				/* active lower constraints' bounds */
+				if ( delta_yAC[i] < -ZERO )
+				{
+					if ( y[nV+ii] > 0.0 )
+						maxStepLength[nV+ii] = y[nV+ii] / ( -delta_yAC[i] );
+					else
+						maxStepLength[nV+ii] = 0.0;
+				}
+			}
+			else
+			{
+				/* active upper constraints' bounds */
+				if ( delta_yAC[i] > ZERO )
+				{
+					if ( y[nV+ii] < 0.0 )
+						maxStepLength[nV+ii] = y[nV+ii] / ( -delta_yAC[i] );
+					else
+						maxStepLength[nV+ii] = 0.0;
+				}
+			}
+		}
+	}
+
+	/* 2) Ensure that active dual bounds remain valid
+	 *    (ignoring implicitly fixed variables). */
+	for( i=0; i<nFX; ++i )
+	{
+		ii = FX_idx[i];
+
+		if ( bounds.getType( ii ) != ST_EQUALITY )
+		{
+			if ( bounds.getStatus( ii ) == ST_LOWER )
+			{
+				/* active lower bounds */
+				if ( delta_yFX[i] < -ZERO )
+				{
+					if ( y[ii] > 0.0 )
+						maxStepLength[ii] = y[ii] / ( -delta_yFX[i] );
+					else
+						maxStepLength[ii] = 0.0;
+				}
+			}
+			else
+			{
+				/* active upper bounds */
+				if ( delta_yFX[i] > ZERO )
+				{
+					if ( y[ii] < 0.0 )
+						maxStepLength[ii] = y[ii] / ( -delta_yFX[i] );
+					else
+						maxStepLength[ii] = 0.0;
+				}
+			}
+		}
+	}
+
+
+	/* II) DETERMINE MAXIMUM PRIMAL STEPLENGTH */
+	/* 1) Ensure that inactive constraints' bounds remain valid
+	 *    (ignoring unbounded constraints). */
+	real_t delta_x[NVMAX];
+	for( j=0; j<nFR; ++j )
+	{
+		jj = FR_idx[j];
+		delta_x[jj] = delta_xFR[j];
+	}
+	for( j=0; j<nFX; ++j )
+	{
+		jj = FX_idx[j];
+		delta_x[jj] = delta_xFX[j];
+	}
+
+	for( i=0; i<nIAC; ++i )
+	{
+		ii = IAC_idx[i];
+
+		if ( constraints.getType( ii ) != ST_UNBOUNDED )
+		{
+			delta_Ax[ii] = 0.0;
+			for( j=0; j<nV; ++j )
+				delta_Ax[ii] += A[ii*NVMAX + j] * delta_x[j]; // POSSIBLE SPEEDUP!
+
+			/* inactive lower constraints' bounds */
+			if ( constraints.isNoLower( ) == BT_FALSE )
+			{
+				if ( delta_lbA[ii] > delta_Ax[ii] )
+				{
+					if ( Ax[ii] > lbA[ii] )
+						maxStepLength[nV+ii] = ( Ax[ii] - lbA[ii] ) / ( delta_lbA[ii] - delta_Ax[ii] );
+					else
+						maxStepLength[nV+ii] = 0.0;
+				}
+			}
+
+			/* inactive upper constraints' bounds */
+			if ( constraints.isNoUpper( ) == BT_FALSE )
+			{
+				if ( delta_ubA[ii] < delta_Ax[ii] )
+				{
+					if ( Ax[ii] < ubA[ii] )
+						maxStepLength[nV+nC+nV+ii] = ( Ax[ii] - ubA[ii] ) / ( delta_ubA[ii] - delta_Ax[ii] );
+					else
+						maxStepLength[nV+nC+nV+ii] = 0.0;
+				}
+			}
+		}
+	}
+
+
+	/* 2) Ensure that inactive bounds remain valid
+	 *    (ignoring unbounded variables). */
+	/* inactive lower bounds */
+	if ( bounds.isNoLower( ) == BT_FALSE )
+	{
+		for( i=0; i<nFR; ++i )
+		{
+			ii = FR_idx[i];
+			if ( bounds.getType( ii ) != ST_UNBOUNDED )
+				if ( delta_lb[ii] > delta_xFR[i] )
+				{
+					if ( x[ii] > lb[ii] )
+						maxStepLength[ii] = ( x[ii] - lb[ii] ) / ( delta_lb[ii] - delta_xFR[i] );
+					else
+						maxStepLength[ii] = 0.0;
+				}
+		}
+	}
+
+	/* inactive upper bounds */
+	if ( bounds.isNoUpper( ) == BT_FALSE )
+	{
+		for( i=0; i<nFR; ++i )
+		{
+			ii = FR_idx[i];
+			if ( bounds.getType( ii ) != ST_UNBOUNDED )
+				if ( delta_ub[ii] < delta_xFR[i] )
+				{
+					if ( x[ii] < ub[ii] )
+						maxStepLength[nV+nC+ii] = ( x[ii] - ub[ii] ) / ( delta_ub[ii] - delta_xFR[i] );
+					else
+						maxStepLength[nV+nC+ii] = 0.0;
+				}
+		}
+	}
+
+
+	/* III) DETERMINE MAXIMUM HOMOTOPY STEPLENGTH */
+	real_t tau_new = 1.0;
+
+	BC_idx = 0;
+	BC_status = ST_UNDEFINED;
+	BC_isBound = BT_FALSE;
+
+	for ( i=0; i<nV; ++i )
+	{
+		/* 1) Consider lower/dual blocking bounds. */
+		if ( maxStepLength[i] < tau_new )
+		{
+			tau_new = maxStepLength[i];
+			BC_idx = i;
+			BC_isBound = BT_TRUE;
+			if ( bounds.getStatus( i ) == ST_INACTIVE ) /* inactive? */
+				BC_status = ST_LOWER;
+			else
+				BC_status = ST_INACTIVE;
+		}
+
+		/* 2) Consider upper blocking bounds. */
+		if ( maxStepLength[nV+nC+i] < tau_new )
+		{
+			tau_new = maxStepLength[nV+nC+i];
+			BC_idx = i;
+			BC_isBound = BT_TRUE;
+			BC_status = ST_UPPER;
+		}
+	}
+
+	for ( i=nV; i<nV+nC; ++i )
+	{
+		/* 3) Consider lower/dual blocking constraints. */
+		if ( maxStepLength[i] < tau_new )
+		{
+			tau_new = maxStepLength[i];
+			BC_idx = i-nV;
+			BC_isBound = BT_FALSE;
+			if ( constraints.getStatus( i-nV ) == ST_INACTIVE ) /* inactive? */
+				BC_status = ST_LOWER;
+			else
+				BC_status = ST_INACTIVE;
+		}
+
+		/* 4) Consider upper blocking constraints. */
+		if ( maxStepLength[nV+nC+i] < tau_new )
+		{
+			tau_new = maxStepLength[nV+nC+i];
+			BC_idx = i-nV;
+			BC_isBound = BT_FALSE;
+			BC_status = ST_UPPER;
+		}
+	}
+
+
+	/* IV) CLEAR CYCLING DATA
+	 *     if a positive step can be taken */
+	if ( tau_new > EPS )
+		cyclingManager.clearCyclingData( );
+
+
+	/* V) SET MAXIMUM HOMOTOPY STEPLENGTH */
+	tau = tau_new;
+
+	#ifdef PC_DEBUG
+	if ( printlevel == PL_HIGH )
+	{
+
+	 	char messageString[80];
+
+		if ( BC_status == ST_UNDEFINED )
+			sprintf( messageString,"Stepsize is %.6e!",tau );
+		else
+			sprintf( messageString,"Stepsize is %.6e! (BC_idx = %d, BC_isBound = %d, BC_status = %d)",tau,BC_idx,BC_isBound,BC_status );
+
+		getGlobalMessageHandler( )->throwInfo( RET_STEPSIZE_NONPOSITIVE,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+	}
+	#endif
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	h o t s t a r t _ p e r f o r m S t e p
+ */
+returnValue QProblem::hotstart_performStep(	const int* const FR_idx, const int* const FX_idx, const int* const AC_idx, const int* const IAC_idx,
+											const real_t* const delta_g, const real_t* const delta_lbA, const real_t* const delta_ubA,
+											const real_t* const delta_lb, const real_t* const delta_ub,
+											const real_t* const delta_xFX, const real_t* const delta_xFR,
+											const real_t* const delta_yAC, const real_t* const delta_yFX,
+											const real_t* const delta_Ax, int BC_idx, SubjectToStatus BC_status, BooleanType BC_isBound
+											)
+{
+	int i, j, ii;
+	int nV  = getNV( );
+	int nC  = getNC( );
+	int nFR = getNFR( );
+	int nFX = getNFX( );
+	int nAC = getNAC( );
+	int nIAC = getNIAC( );
+
+
+	/* I) CHECK (CONSTRAINTS') BOUNDS' CONSISTENCY */
+	if ( areBoundsConsistent( delta_lb,delta_ub,delta_lbA,delta_ubA ) == BT_FALSE )
+	{
+		infeasible = BT_TRUE;
+		tau = 0.0;
+
+		return THROWERROR( RET_QP_INFEASIBLE );
+	}
+
+
+	/* II) GO TO ACTIVE SET CHANGE */
+	if ( tau > ZERO )
+	{
+		/* 1) Perform step in primal und dual space... */
+		for( i=0; i<nFR; ++i )
+		{
+			ii = FR_idx[i];
+			x[ii] += tau*delta_xFR[i];
+		}
+
+		for( i=0; i<nFX; ++i )
+		{
+			ii = FX_idx[i];
+			x[ii] += tau*delta_xFX[i];
+			y[ii] += tau*delta_yFX[i];
+		}
+
+		for( i=0; i<nAC; ++i )
+		{
+			ii = AC_idx[i];
+			y[nV+ii] += tau*delta_yAC[i];
+		}
+
+		/* ... also for Ax. */
+		for( i=0; i<nIAC; ++i )
+		{
+			ii = IAC_idx[i];
+			if ( constraints.getType( ii ) != ST_UNBOUNDED )
+				Ax[ii] += tau*delta_Ax[ii];
+		}
+		for( i=0; i<nAC; ++i )
+		{
+			ii = AC_idx[i];
+
+			Ax[ii] = 0.0;
+			for( j=0; j<nV; ++j )
+				Ax[ii] += A[ii*NVMAX + j] * x[j];
+		}
+
+		/* 2) Shift QP data. */
+		for( i=0; i<nV; ++i )
+		{
+			g[i]  += tau*delta_g[i];
+			lb[i] += tau*delta_lb[i];
+			ub[i] += tau*delta_ub[i];
+		}
+
+		for( i=0; i<nC; ++i )
+		{
+			lbA[i] += tau*delta_lbA[i];
+			ubA[i] += tau*delta_ubA[i];
+		}
+	}
+	else
+	{
+		/* print a stepsize warning if stepsize is zero */
+		#ifdef PC_DEBUG
+		char messageString[80];
+		sprintf( messageString,"Stepsize is %.6e",tau );
+		getGlobalMessageHandler( )->throwWarning( RET_STEPSIZE,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		#endif
+	}
+
+
+	/* setup output preferences */
+	#ifdef PC_DEBUG
+	char messageString[80];
+	VisibilityStatus visibilityStatus;
+
+	if ( printlevel == PL_HIGH )
+		visibilityStatus = VS_VISIBLE;
+	else
+		visibilityStatus = VS_HIDDEN;
+	#endif
+
+	
+	/* III) UPDATE ACTIVE SET */
+	switch ( BC_status )
+	{
+		/* Optimal solution found as no working set change detected. */
+		case ST_UNDEFINED:
+			return RET_OPTIMAL_SOLUTION_FOUND;
+
+
+		/* Remove one variable from active set. */
+		case ST_INACTIVE:
+			if ( BC_isBound == BT_TRUE )
+			{
+				#ifdef PC_DEBUG
+				sprintf( messageString,"bound no. %d.", BC_idx );
+				getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus );
+				#endif
+
+				if ( removeBound( BC_idx,BT_TRUE ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED );
+
+				y[BC_idx] = 0.0;
+			}
+			else
+			{
+				#ifdef PC_DEBUG
+				sprintf( messageString,"constraint no. %d.", BC_idx );
+				getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus );
+				#endif
+
+				if ( removeConstraint( BC_idx,BT_TRUE ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED );
+
+				y[nV+BC_idx] = 0.0;
+			}
+			break;
+
+
+		/* Add one variable to active set. */
+		default:
+			if ( BC_isBound == BT_TRUE )
+			{
+				#ifdef PC_DEBUG
+				if ( BC_status == ST_LOWER )
+					sprintf( messageString,"lower bound no. %d.", BC_idx );
+				else
+					sprintf( messageString,"upper bound no. %d.", BC_idx );
+				getGlobalMessageHandler( )->throwInfo( RET_ADD_TO_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus );
+				#endif
+
+				if ( addBound( BC_idx,BC_status,BT_TRUE ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_ADD_TO_ACTIVESET_FAILED );
+			}
+			else
+			{
+				#ifdef PC_DEBUG
+				if ( BC_status == ST_LOWER )
+					sprintf( messageString,"lower constraint's bound no. %d.", BC_idx );
+				else
+					sprintf( messageString,"upper constraint's bound no. %d.", BC_idx );
+				getGlobalMessageHandler( )->throwInfo( RET_ADD_TO_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus );
+				#endif
+
+				if ( addConstraint( BC_idx,BC_status,BT_TRUE ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_ADD_TO_ACTIVESET_FAILED );
+			}
+			break;
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	a r e B o u n d s C o n s i s t e n t
+ */
+BooleanType QProblem::areBoundsConsistent(	const real_t* const delta_lb, const real_t* const delta_ub,
+											const real_t* const delta_lbA, const real_t* const delta_ubA
+											) const
+{
+	int i;
+
+	/* 1) Check bounds' consistency. */
+	if ( QProblemB::areBoundsConsistent( delta_lb,delta_ub ) == BT_FALSE )
+		return BT_FALSE;
+
+	/* 2) Check constraints' consistency, i.e.
+	 *    check if delta_lb[i] is greater than delta_ub[i]
+	 *    for a component i whose bounds are already (numerically) equal. */
+	for( i=0; i<getNC( ); ++i )
+		if ( ( lbA[i] > ubA[i] - BOUNDTOL ) && ( delta_lbA[i] > delta_ubA[i] + EPS ) )
+			return BT_FALSE;
+
+	return BT_TRUE;
+}
+
+
+/*
+ *	s e t u p Q P d a t a
+ */
+returnValue QProblem::setupQPdata(	const real_t* const _H, const real_t* const _R, const real_t* const _g, const real_t* const _A,
+									const real_t* const _lb, const real_t* const _ub,
+									const real_t* const _lbA, const real_t* const _ubA
+									)
+{
+	int i, j;
+	int nV = getNV( );
+	int nC = getNC( );
+
+
+	/* 1) Load Hessian matrix as well as lower and upper bounds vectors. */
+	if (QProblemB::setupQPdata(_H, _R, _g, _lb, _ub) != SUCCESSFUL_RETURN)
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	/* 2) Load constraint matrix. */
+	if ( ( nC > 0 ) && ( _A == 0 ) )
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	if ( nC > 0 )
+	{
+		for( i=0; i<nC; ++i )
+			for( j=0; j<nV; ++j )
+				A[i*NVMAX + j] = _A[i*nV + j];
+
+		/* 3) Setup lower constraints' bounds vector. */
+		if ( _lbA != 0 )
+		{
+			for( i=0; i<nC; ++i )
+				lbA[i] = _lbA[i];
+		}
+		else
+		{
+			/* if no lower constraints' bounds are specified, set them to -infinity */
+			for( i=0; i<nC; ++i )
+				lbA[i] = -INFTY;
+		}
+
+		/* 4) Setup upper constraints' bounds vector. */
+		if ( _ubA != 0 )
+		{
+			for( i=0; i<nC; ++i )
+				ubA[i] = _ubA[i];
+		}
+		else
+		{
+			/* if no upper constraints' bounds are specified, set them to infinity */
+			for( i=0; i<nC; ++i )
+				ubA[i] = INFTY;
+		}
+	}
+
+// 	printmatrix2( "A",A,10,20 );
+	
+// 	printmatrix2( "lbA",lbA,1,nC );
+// 	printmatrix2( "ubA",ubA,1,nC );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+#ifdef PC_DEBUG  /* Define print functions only for debugging! */
+
+/*
+ *	p r i n t I t e r a t i o n
+ */
+returnValue QProblem::printIteration( 	int iteration,
+										int BC_idx,	SubjectToStatus BC_status, BooleanType BC_isBound
+		  								)
+{
+	char myPrintfString[160];
+
+	/* consistency check */
+	if ( iteration < 0 )
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	/* nothing to do */
+	if ( printlevel != PL_MEDIUM )
+		return SUCCESSFUL_RETURN;
+
+
+	/* 1) Print header at first iteration. */
+ 	if ( iteration == 0 )
+	{
+		sprintf( myPrintfString,"\n##############  qpOASES  --  QP NO.%4.1d  ###############\n", count );
+		myPrintf( myPrintfString );
+
+		sprintf( myPrintfString,"  Iter  |  StepLength   |     Info      |  nFX  |  nAC  \n" );
+		myPrintf( myPrintfString );
+	}
+
+	/* 2) Print iteration line. */
+	if ( BC_status == ST_UNDEFINED )
+	{
+		sprintf( myPrintfString,"  %4.1d  |  %1.5e  |   QP SOLVED   | %4.1d  | %4.1d  \n", iteration,tau,getNFX( ),getNAC( ) );
+		myPrintf( myPrintfString );
+	}
+	else
+	{
+		char info[8];
+
+		if ( BC_status == ST_INACTIVE )
+			sprintf( info,"REM " );
+		else
+			sprintf( info,"ADD " );
+
+		if ( BC_isBound == BT_TRUE )
+			sprintf( &(info[4]),"BND" );
+		else
+			sprintf( &(info[4]),"CON" );
+
+		sprintf( myPrintfString,"  %4.1d  |  %1.5e  |  %s%4.1d  | %4.1d  | %4.1d  \n", iteration,tau,info,BC_idx,getNFX( ),getNAC( ) );
+		myPrintf( myPrintfString );
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	p r i n t I t e r a t i o n
+ */
+returnValue QProblem::printIteration( 	int iteration,
+										int BC_idx,	SubjectToStatus BC_status
+		  								)
+{
+	return printIteration( iteration,BC_idx,BC_status,BT_TRUE );
+}
+
+#endif  /* PC_DEBUG */
+
+
+
+/*
+ *	c h e c k K K T c o n d i t i o n s
+ */
+returnValue QProblem::checkKKTconditions( )
+{
+	#ifdef __PERFORM_KKT_TEST__
+
+	int i, j, jj;
+	int nV  = getNV( );
+	int nC  = getNC( );
+	int nAC = getNAC( );
+
+	real_t tmp;
+	real_t maxKKTviolation = 0.0;
+
+	int AC_idx[NCMAX_ALLOC];
+	constraints.getActive( )->getNumberArray( AC_idx );
+
+	/* 1) check for Hx + g - [yFX yAC]*[Id A]' = 0. */
+	for( i=0; i<nV; ++i )
+	{
+		tmp = g[i];
+
+		for( j=0; j<nV; ++j )
+			tmp += H[i*NVMAX + j] * x[j];
+
+		tmp -= y[i];
+
+		/* Only sum over active constraints as y is zero for all inactive ones. */
+		for( j=0; j<nAC; ++j )
+		{
+			jj = AC_idx[j];
+			tmp -= A[jj*NVMAX + i] * y[nV+jj];
+		}
+
+		if ( getAbs( tmp ) > maxKKTviolation )
+			maxKKTviolation = getAbs( tmp );
+	}
+
+	/* 2) Check for [lb lbA] <= [Id A]*x <= [ub ubA]. */
+	/* lbA <= Ax <= ubA */
+	for( i=0; i<nC; ++i )
+	{
+		if ( lbA[i] - Ax[i] > maxKKTviolation )
+			maxKKTviolation = lbA[i] - Ax[i];
+
+		if ( Ax[i] - ubA[i] > maxKKTviolation )
+			maxKKTviolation = Ax[i] - ubA[i];
+	}
+
+	/* lb <= x <= ub */
+	for( i=0; i<nV; ++i )
+	{
+		if ( lb[i] - x[i] > maxKKTviolation )
+			maxKKTviolation = lb[i] - x[i];
+
+		if ( x[i] - ub[i] > maxKKTviolation )
+			maxKKTviolation = x[i] - ub[i];
+	}
+
+	/* 3) Check for correct sign of y and for complementary slackness. */
+	/* bounds */
+	for( i=0; i<nV; ++i )
+	{
+		switch ( bounds.getStatus( i ) )
+		{
+			case ST_LOWER:
+				if ( -y[i] > maxKKTviolation )
+					maxKKTviolation = -y[i];
+				if ( getAbs( x[i] - lb[i] ) > maxKKTviolation )
+					maxKKTviolation = getAbs( x[i] - lb[i] );
+				break;
+
+			case ST_UPPER:
+				if ( y[i] > maxKKTviolation )
+					maxKKTviolation = y[i];
+				if ( getAbs( ub[i] - x[i] ) > maxKKTviolation )
+					maxKKTviolation = getAbs( ub[i] - x[i] );
+				break;
+
+			default: /* inactive */
+			if ( getAbs( y[i] ) > maxKKTviolation )
+					maxKKTviolation = getAbs( y[i] );
+				break;
+		}
+	}
+
+	/* constraints */
+	for( i=0; i<nC; ++i )
+	{
+		switch ( constraints.getStatus( i ) )
+		{
+			case ST_LOWER:
+				if ( -y[nV+i] > maxKKTviolation )
+					maxKKTviolation = -y[nV+i];
+				if ( getAbs( Ax[i] - lbA[i] ) > maxKKTviolation )
+					maxKKTviolation = getAbs( Ax[i] - lbA[i] );
+				break;
+
+			case ST_UPPER:
+				if ( y[nV+i] > maxKKTviolation )
+					maxKKTviolation = y[nV+i];
+				if ( getAbs( ubA[i] - Ax[i] ) > maxKKTviolation )
+					maxKKTviolation = getAbs( ubA[i] - Ax[i] );
+				break;
+
+			default: /* inactive */
+			if ( getAbs( y[nV+i] ) > maxKKTviolation )
+					maxKKTviolation = getAbs( y[nV+i] );
+				break;
+		}
+	}
+
+	if ( maxKKTviolation > CRITICALACCURACY )
+		return RET_NO_SOLUTION;
+
+	if ( maxKKTviolation > DESIREDACCURACY )
+		return RET_INACCURATE_SOLUTION;
+
+	#endif /* __PERFORM_KKT_TEST__ */
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/QProblem.ipp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/QProblem.ipp
new file mode 100644
index 0000000000000000000000000000000000000000..e98ada6330fb22ecdd37799e4b52d5e31b645dd0
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/QProblem.ipp
@@ -0,0 +1,299 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/QProblem.ipp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of inlined member functions of the QProblem class which 
+ *	is able to use the newly developed online active set strategy for 
+ *	parametric quadratic programming.
+ */
+
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+/*
+ *	g e t A
+ */
+inline returnValue QProblem::getA( real_t* const _A ) const
+{
+	int i;
+
+	for ( i=0; i<getNV( )*getNC( ); ++i )
+		_A[i] = A[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t A
+ */
+inline returnValue QProblem::getA( int number, real_t* const row ) const
+{
+	int nV = getNV( );
+		
+	if ( ( number >= 0 ) && ( number < getNC( ) ) )
+	{
+		for ( int i=0; i<nV; ++i )
+			row[i] = A[number*NVMAX + i];
+
+		return SUCCESSFUL_RETURN;
+	}
+	else
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+}
+
+
+/*
+ *	g e t L B A
+ */
+inline returnValue QProblem::getLBA( real_t* const _lbA ) const
+{
+	int i;
+
+	for ( i=0; i<getNC( ); ++i )
+		_lbA[i] = lbA[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t L B A
+ */
+inline returnValue QProblem::getLBA( int number, real_t& value ) const
+{
+	if ( ( number >= 0 ) && ( number < getNC( ) ) )
+	{
+		value = lbA[number];
+		return SUCCESSFUL_RETURN;
+	}
+	else
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+}
+
+
+/*
+ *	g e t U B A
+ */
+inline returnValue QProblem::getUBA( real_t* const _ubA ) const
+{
+	int i;
+
+	for ( i=0; i<getNC( ); ++i )
+		_ubA[i] = ubA[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t U B A
+ */
+inline returnValue QProblem::getUBA( int number, real_t& value ) const
+{
+	if ( ( number >= 0 ) && ( number < getNC( ) ) )
+	{
+		value = ubA[number];
+		return SUCCESSFUL_RETURN;
+	}
+	else
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+}
+
+
+/*
+ *	g e t C o n s t r a i n t s
+ */
+inline returnValue QProblem::getConstraints( Constraints* const _constraints ) const
+{
+	*_constraints = constraints;
+	
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*
+ *	g e t N C
+ */
+inline int QProblem::getNC( ) const
+{
+	return constraints.getNC( );
+}
+
+
+/*
+ *	g e t N E C
+ */
+inline int QProblem::getNEC( ) const
+{
+	return constraints.getNEC( );
+}
+
+
+/*
+ *	g e t N A C
+ */
+inline int QProblem::getNAC( )
+{
+	return constraints.getNAC( );
+}
+
+
+/*
+ *	g e t N I A C
+ */
+inline int QProblem::getNIAC( )
+{
+	return constraints.getNIAC( );
+}
+
+
+
+/*****************************************************************************
+ *  P R O T E C T E D                                                        *
+ *****************************************************************************/
+ 
+
+/*
+ *	s e t A
+ */
+inline returnValue QProblem::setA( const real_t* const A_new )
+{
+	int i, j;
+	int nV = getNV( );
+	int nC = getNC( );
+
+	/* Set constraint matrix AND update member AX. */
+	for( j=0; j<nC; ++j )
+	{
+		Ax[j] = 0.0;
+
+		for( i=0; i<nV; ++i )
+		{	
+			A[j*NVMAX + i] = A_new[j*nV + i];
+			Ax[j] += A[j*NVMAX + i] * x[i];
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t A
+ */
+inline returnValue QProblem::setA( int number, const real_t* const row )
+{
+	int i;
+	int nV = getNV( );
+
+	/* Set constraint matrix AND update member AX. */
+	if ( ( number >= 0 ) && ( number < getNC( ) ) )
+	{
+		Ax[number] = 0.0;
+
+		for( i=0; i<nV; ++i )
+		{
+			A[number*NVMAX + i] = row[i];
+			Ax[number] += A[number*NVMAX + i] * x[i];
+		}
+
+		return SUCCESSFUL_RETURN;
+	}
+	else
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+}
+
+
+/*
+ *	s e t L B A
+ */
+inline returnValue QProblem::setLBA( const real_t* const lbA_new )
+{
+	int i;
+	int nC = getNC();
+
+	for( i=0; i<nC; ++i )
+		lbA[i] = lbA_new[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t L B A
+ */
+inline returnValue QProblem::setLBA( int number, real_t value )
+{
+	if ( ( number >= 0 ) && ( number < getNC( ) ) )
+	{
+		lbA[number] = value;
+		return SUCCESSFUL_RETURN;
+	}
+	else
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+}
+
+
+/*
+ *	s e t U B A
+ */
+inline returnValue QProblem::setUBA( const real_t* const ubA_new )
+{
+	int i;
+	int nC = getNC();
+
+	for( i=0; i<nC; ++i )
+		ubA[i] = ubA_new[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t U B A
+ */
+inline returnValue QProblem::setUBA( int number, real_t value )
+{
+	if ( ( number >= 0 ) && ( number < getNC( ) ) )
+	{
+		ubA[number] = value;
+		return SUCCESSFUL_RETURN;
+	}
+	else
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/QProblemB.cpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/QProblemB.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..47ac3536f35cf50b28803550fc6409a4a7f96a12
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/QProblemB.cpp
@@ -0,0 +1,2151 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/QProblemB.cpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of the QProblemB class which is able to use the newly
+ *	developed online active set strategy for parametric quadratic programming.
+ */
+
+
+#include <QProblemB.hpp>
+
+#include <stdio.h>
+
+void printmatrix(char *name, double *A, int m, int n) {
+  int i, j;
+
+  printf("%s = [...\n", name);
+  for (i = 0; i < m; i++) {
+    for (j = 0; j < n; j++)
+        printf("  % 9.4f", A[i*n+j]);
+    printf(",\n");
+  }
+  printf("];\n");
+}
+
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+
+/*
+ *	Q P r o b l e m B
+ */
+QProblemB::QProblemB( )
+{
+	/* reset global message handler */
+	getGlobalMessageHandler( )->reset( );
+
+	hasHessian = BT_FALSE;
+
+	bounds.init( 0 );
+
+	hasCholesky = BT_FALSE;
+
+	tau = 0.0;
+
+	hessianType = HST_POSDEF_NULLSPACE; /* Hessian is assumed to be positive definite by default */
+	infeasible = BT_FALSE;
+	unbounded = BT_FALSE;
+
+	status = QPS_NOTINITIALISED;
+
+	#ifdef PC_DEBUG
+	printlevel = PL_MEDIUM;
+	setPrintLevel( PL_MEDIUM );
+	#else
+	printlevel = QPOASES_PRINTLEVEL;
+	#endif
+
+	count = 0;
+}
+
+
+/*
+ *	Q P r o b l e m B
+ */
+QProblemB::QProblemB( int _nV )
+{
+	/* consistency check */
+	if ( _nV <= 0 )
+	{
+		_nV = 1;
+		THROWERROR( RET_INVALID_ARGUMENTS );
+	}
+
+	hasHessian = BT_FALSE;
+
+	/* reset global message handler */
+	getGlobalMessageHandler( )->reset( );
+
+	bounds.init( _nV );
+
+	hasCholesky = BT_FALSE;
+
+	tau = 0.0;
+
+	hessianType = HST_POSDEF_NULLSPACE; /* Hessian is assumed to be positive definite by default */
+	infeasible = BT_FALSE;
+	unbounded = BT_FALSE;
+
+	status = QPS_NOTINITIALISED;
+
+	#ifdef PC_DEBUG
+	printlevel = PL_MEDIUM;
+	setPrintLevel( PL_MEDIUM );
+	#else
+	printlevel = QPOASES_PRINTLEVEL;
+	#endif
+
+	count = 0;
+}
+
+
+/*
+ *	Q P r o b l e m B
+ */
+QProblemB::QProblemB( const QProblemB& rhs )
+{
+	int i, j;
+
+	int _nV = rhs.bounds.getNV( );
+
+	for( i=0; i<_nV; ++i )
+		for( j=0; j<_nV; ++j )
+			H[i*NVMAX + j] = rhs.H[i*NVMAX + j];
+
+	hasHessian = rhs.hasHessian;
+
+	for( i=0; i<_nV; ++i )
+		g[i] = rhs.g[i];
+
+	for( i=0; i<_nV; ++i )
+		lb[i] = rhs.lb[i];
+
+	for( i=0; i<_nV; ++i )
+		ub[i] = rhs.ub[i];
+
+
+	bounds = rhs.bounds;
+
+	for( i=0; i<_nV; ++i )
+		for( j=0; j<_nV; ++j )
+			R[i*NVMAX + j] = rhs.R[i*NVMAX + j];
+	hasCholesky = rhs.hasCholesky;
+
+	for( i=0; i<_nV; ++i )
+		x[i] = rhs.x[i];
+
+	for( i=0; i<_nV; ++i )
+		y[i] = rhs.y[i];
+
+	tau = rhs.tau;
+
+	hessianType = rhs.hessianType;
+	infeasible = rhs.infeasible;
+	unbounded = rhs.unbounded;
+
+	status = rhs.status;
+
+	printlevel = rhs.printlevel;
+
+	count = rhs.count;
+}
+
+
+/*
+ *	~ Q P r o b l e m B
+ */
+QProblemB::~QProblemB( )
+{
+}
+
+
+/*
+ *	o p e r a t o r =
+ */
+QProblemB& QProblemB::operator=( const QProblemB& rhs )
+{
+	int i, j;
+
+	if ( this != &rhs )
+	{
+		int _nV = rhs.bounds.getNV( );
+
+		for( i=0; i<_nV; ++i )
+			for( j=0; j<_nV; ++j )
+				H[i*NVMAX + j] = rhs.H[i*NVMAX + j];
+
+		hasHessian = rhs.hasHessian;
+
+		for( i=0; i<_nV; ++i )
+			g[i] = rhs.g[i];
+
+		for( i=0; i<_nV; ++i )
+			lb[i] = rhs.lb[i];
+
+		for( i=0; i<_nV; ++i )
+			ub[i] = rhs.ub[i];
+
+		bounds = rhs.bounds;
+
+		for( i=0; i<_nV; ++i )
+			for( j=0; j<_nV; ++j )
+				R[i*NVMAX + j] = rhs.R[i*NVMAX + j];
+		hasCholesky = rhs.hasCholesky;
+
+
+		for( i=0; i<_nV; ++i )
+			x[i] = rhs.x[i];
+
+		for( i=0; i<_nV; ++i )
+			y[i] = rhs.y[i];
+
+		tau = rhs.tau;
+
+		hessianType = rhs.hessianType;
+		infeasible = rhs.infeasible;
+		unbounded = rhs.unbounded;
+
+		status = rhs.status;
+
+		printlevel = rhs.printlevel;
+		setPrintLevel( rhs.printlevel );
+
+		count = rhs.count;
+	}
+
+	return *this;
+}
+
+
+/*
+ *	r e s e t
+ */
+returnValue QProblemB::reset( )
+{
+	int i, j;
+	int nV = getNV( );
+
+	/** 0) Reset has Hessian flag. */
+	hasHessian = BT_FALSE;
+
+	/* 1) Reset bounds. */
+	bounds.init( nV );
+
+	/* 2) Reset Cholesky decomposition. */
+	for( i=0; i<nV; ++i )
+		for( j=0; j<nV; ++j )
+			R[i*NVMAX + j] = 0.0;
+	hasCholesky = BT_FALSE;
+
+	/* 3) Reset steplength and status flags. */
+	tau = 0.0;
+
+	hessianType = HST_POSDEF_NULLSPACE; /* Hessian is assumed to be positive definite by default */
+	infeasible = BT_FALSE;
+	unbounded = BT_FALSE;
+
+	status = QPS_NOTINITIALISED;
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	i n i t
+ */
+returnValue QProblemB::init(	const real_t* const _H, const real_t* const _g,
+								const real_t* const _lb, const real_t* const _ub,
+								int& nWSR, const real_t* const yOpt, real_t* const cputime
+								)
+{
+	/* 1) Setup QP data. */
+	if (setupQPdata(_H, 0, _g, _lb, _ub) != SUCCESSFUL_RETURN)
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	/* 2) Call to main initialisation routine (without any additional information). */
+	return solveInitialQP(0, yOpt, 0, nWSR, cputime);
+}
+
+returnValue QProblemB::init(	const real_t* const _H, const real_t* const _R, const real_t* const _g,
+								const real_t* const _lb, const real_t* const _ub,
+								int& nWSR, const real_t* const yOpt, real_t* const cputime
+								)
+{
+	/* 1) Setup QP data. */
+	if (setupQPdata(_H, _R, _g, _lb, _ub) != SUCCESSFUL_RETURN)
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	/* 2) Call to main initialisation routine (without any additional information). */
+	return solveInitialQP(0, yOpt, 0, nWSR, cputime);
+}
+
+
+/*
+ *	h o t s t a r t
+ */
+returnValue QProblemB::hotstart(	const real_t* const g_new, const real_t* const lb_new, const real_t* const ub_new,
+									int& nWSR, real_t* const cputime
+									)
+{
+	int l;
+
+	/* consistency check */
+	if ( ( getStatus( ) == QPS_NOTINITIALISED )       ||
+		 ( getStatus( ) == QPS_PREPARINGAUXILIARYQP ) ||
+		 ( getStatus( ) == QPS_PERFORMINGHOMOTOPY )   )
+	{
+		return THROWERROR( RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED );
+	}
+
+	/* start runtime measurement */
+	real_t starttime = 0.0;
+	if ( cputime != 0 )
+		starttime = getCPUtime( );
+
+
+	/* I) PREPARATIONS */
+	/* 1) Reset status flags and increase QP counter. */
+	infeasible = BT_FALSE;
+	unbounded = BT_FALSE;
+
+	++count;
+
+	/* 2) Allocate delta vectors of gradient and bounds. */
+	returnValue returnvalue;
+	BooleanType Delta_bB_isZero;
+
+	int FR_idx[NVMAX];
+	int FX_idx[NVMAX];
+
+	real_t delta_g[NVMAX];
+	real_t delta_lb[NVMAX];
+	real_t delta_ub[NVMAX];
+
+	real_t delta_xFR[NVMAX];
+	real_t delta_xFX[NVMAX];
+	real_t delta_yFX[NVMAX];
+
+	int BC_idx;
+	SubjectToStatus BC_status;
+
+	#ifdef PC_DEBUG
+	char messageString[80];
+	#endif
+
+	/* II) MAIN HOMOTOPY LOOP */
+	for( l=0; l<nWSR; ++l )
+	{
+		status = QPS_PERFORMINGHOMOTOPY;
+
+		if ( printlevel == PL_HIGH )
+		{
+			#ifdef PC_DEBUG
+			sprintf( messageString,"%d ...",l );
+			getGlobalMessageHandler( )->throwInfo( RET_ITERATION_STARTED,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+			#endif
+		}
+
+		/* 1) Setup index arrays. */
+		if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_HOTSTART_FAILED );
+
+		if ( bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_HOTSTART_FAILED );
+
+		/* 2) Initialize shift direction of the gradient and the bounds. */
+		returnvalue = hotstart_determineDataShift(  FX_idx,
+													g_new,lb_new,ub_new,
+													delta_g,delta_lb,delta_ub,
+													Delta_bB_isZero
+													);
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			nWSR = l;
+			THROWERROR( RET_SHIFT_DETERMINATION_FAILED );
+			return returnvalue;
+		}
+
+		/* 3) Determination of step direction of X and Y. */
+		returnvalue = hotstart_determineStepDirection(	FR_idx,FX_idx,
+														delta_g,delta_lb,delta_ub,
+														Delta_bB_isZero,
+														delta_xFX,delta_xFR,delta_yFX
+														);
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			nWSR = l;
+			THROWERROR( RET_STEPDIRECTION_DETERMINATION_FAILED );
+			return returnvalue;
+		}
+
+
+		/* 4) Determination of step length TAU. */
+		returnvalue = hotstart_determineStepLength(	FR_idx,FX_idx,
+													delta_lb,delta_ub,
+													delta_xFR,delta_yFX,
+													BC_idx,BC_status );
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			nWSR = l;
+			THROWERROR( RET_STEPLENGTH_DETERMINATION_FAILED );
+			return returnvalue;
+		}
+
+		/* 5) Realization of the homotopy step. */
+		returnvalue = hotstart_performStep(	FR_idx,FX_idx,
+											delta_g,delta_lb,delta_ub,
+											delta_xFX,delta_xFR,delta_yFX,
+											BC_idx,BC_status
+											);
+
+
+		if ( returnvalue != SUCCESSFUL_RETURN )
+		{
+			nWSR = l;
+
+			/* stop runtime measurement */
+			if ( cputime != 0 )
+				*cputime = getCPUtime( ) - starttime;
+
+			/* optimal solution found? */
+			if ( returnvalue == RET_OPTIMAL_SOLUTION_FOUND )
+			{
+				status = QPS_SOLVED;
+
+				if ( printlevel == PL_HIGH )
+					THROWINFO( RET_OPTIMAL_SOLUTION_FOUND );
+
+				#ifdef PC_DEBUG
+	 			if ( printIteration( l,BC_idx,BC_status ) != SUCCESSFUL_RETURN )
+					THROWERROR( RET_PRINT_ITERATION_FAILED ); /* do not pass this as return value! */
+				#endif
+
+				/* check KKT optimality conditions */
+				return checkKKTconditions( );
+			}
+			else
+			{
+				/* checks for infeasibility... */
+				if ( infeasible == BT_TRUE )
+				{
+					status = QPS_HOMOTOPYQPSOLVED;
+					return THROWERROR( RET_HOTSTART_STOPPED_INFEASIBILITY );
+				}
+
+				/* ...unboundedness... */
+				if ( unbounded == BT_TRUE ) /* not necessary since objective function convex! */
+					return THROWERROR( RET_HOTSTART_STOPPED_UNBOUNDEDNESS );
+
+				/* ... and throw unspecific error otherwise */
+				THROWERROR( RET_HOMOTOPY_STEP_FAILED );
+				return returnvalue;
+			}
+		}
+
+		/* 6) Output information of successful QP iteration. */
+		status = QPS_HOMOTOPYQPSOLVED;
+
+		#ifdef PC_DEBUG
+		if ( printIteration( l,BC_idx,BC_status ) != SUCCESSFUL_RETURN )
+			THROWERROR( RET_PRINT_ITERATION_FAILED ); /* do not pass this as return value! */
+		#endif
+	}
+
+
+	/* stop runtime measurement */
+	if ( cputime != 0 )
+		*cputime = getCPUtime( ) - starttime;
+
+
+	/* if programm gets to here, output information that QP could not be solved
+	 * within the given maximum numbers of working set changes */
+	if ( printlevel == PL_HIGH )
+	{
+		#ifdef PC_DEBUG
+		sprintf( messageString,"(nWSR = %d)",nWSR );
+		return getGlobalMessageHandler( )->throwWarning( RET_MAX_NWSR_REACHED,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		#endif
+	}
+
+	/* Finally check KKT optimality conditions. */
+	returnValue returnvalueKKTcheck = checkKKTconditions( );
+
+	if ( returnvalueKKTcheck != SUCCESSFUL_RETURN )
+		return returnvalueKKTcheck;
+	else
+		return RET_MAX_NWSR_REACHED;
+}
+
+
+/*
+ *	g e t N Z
+ */
+int QProblemB::getNZ( )
+{
+	/* if no constraints are present: nZ=nFR */
+	return bounds.getFree( )->getLength( );
+}
+
+
+/*
+ *	g e t O b j V a l
+ */
+real_t QProblemB::getObjVal( ) const
+{
+	real_t objVal;
+
+	/* calculated optimal objective function value
+	 * only if current QP has been solved */
+	if ( ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) ||
+		 ( getStatus( ) == QPS_HOMOTOPYQPSOLVED )  ||
+		 ( getStatus( ) == QPS_SOLVED ) )
+	{
+		objVal = getObjVal( x );
+	}
+	else
+	{
+		objVal = INFTY;
+	}
+
+	return objVal;
+}
+
+
+/*
+ *	g e t O b j V a l
+ */
+real_t QProblemB::getObjVal( const real_t* const _x ) const
+{
+	int i, j;
+	int nV = getNV( );
+
+	real_t obj_tmp = 0.0;
+
+	for( i=0; i<nV; ++i )
+	{
+		obj_tmp += _x[i]*g[i];
+
+		for( j=0; j<nV; ++j )
+			obj_tmp += 0.5*_x[i]*H[i*NVMAX + j]*_x[j];
+	}
+
+	return obj_tmp;
+}
+
+
+/*
+ *	g e t P r i m a l S o l u t i o n
+ */
+returnValue QProblemB::getPrimalSolution( real_t* const xOpt ) const
+{
+	int i;
+
+	/* return optimal primal solution vector
+	 * only if current QP has been solved */
+	if ( ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) ||
+		 ( getStatus( ) == QPS_HOMOTOPYQPSOLVED )  ||
+		 ( getStatus( ) == QPS_SOLVED ) )
+	{
+		for( i=0; i<getNV( ); ++i )
+			xOpt[i] = x[i];
+
+		return SUCCESSFUL_RETURN;
+	}
+	else
+	{
+		return RET_QP_NOT_SOLVED;
+	}
+}
+
+
+/*
+ *	g e t D u a l S o l u t i o n
+ */
+returnValue QProblemB::getDualSolution( real_t* const yOpt ) const
+{
+	int i;
+
+	/* return optimal dual solution vector
+	 * only if current QP has been solved */
+	if ( ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) ||
+		 ( getStatus( ) == QPS_HOMOTOPYQPSOLVED )  ||
+		 ( getStatus( ) == QPS_SOLVED ) )
+	{
+		for( i=0; i<getNV( ); ++i )
+			yOpt[i] = y[i];
+
+		return SUCCESSFUL_RETURN;
+	}
+	else
+	{
+		return RET_QP_NOT_SOLVED;
+	}
+}
+
+
+/*
+ *	s e t P r i n t L e v e l
+ */
+returnValue QProblemB::setPrintLevel( PrintLevel _printlevel )
+{
+	#ifndef __MATLAB__
+	if ( ( printlevel >= PL_MEDIUM ) && ( printlevel != _printlevel ) )
+		THROWINFO( RET_PRINTLEVEL_CHANGED );
+	#endif
+
+	printlevel = _printlevel;
+
+	/* update message handler preferences */
+ 	switch ( printlevel )
+ 	{
+ 		case PL_NONE:
+ 			getGlobalMessageHandler( )->setErrorVisibilityStatus( VS_HIDDEN );
+			getGlobalMessageHandler( )->setWarningVisibilityStatus( VS_HIDDEN );
+			getGlobalMessageHandler( )->setInfoVisibilityStatus( VS_HIDDEN );
+			break;
+
+		case PL_LOW:
+ 			getGlobalMessageHandler( )->setErrorVisibilityStatus( VS_VISIBLE );
+			getGlobalMessageHandler( )->setWarningVisibilityStatus( VS_HIDDEN );
+			getGlobalMessageHandler( )->setInfoVisibilityStatus( VS_HIDDEN );
+			break;
+
+ 		default: /* PL_MEDIUM, PL_HIGH */
+ 			getGlobalMessageHandler( )->setErrorVisibilityStatus( VS_VISIBLE );
+			getGlobalMessageHandler( )->setWarningVisibilityStatus( VS_VISIBLE );
+			getGlobalMessageHandler( )->setInfoVisibilityStatus( VS_VISIBLE );
+			break;
+ 	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*****************************************************************************
+ *  P R O T E C T E D                                                        *
+ *****************************************************************************/
+
+/*
+ *	c h e c k F o r I d e n t i t y H e s s i a n
+ */
+returnValue QProblemB::checkForIdentityHessian( )
+{
+	int i, j;
+	int nV = getNV( );
+
+	/* nothing to do as status flag remains unaltered
+	 * if Hessian differs from identity matrix */
+	if ( hessianType == HST_IDENTITY )
+		return SUCCESSFUL_RETURN;
+
+	/* 1) If Hessian differs from identity matrix,
+	 *    return without changing the internal HessianType. */
+	for ( i=0; i<nV; ++i )
+		if ( getAbs( H[i*NVMAX + i] - 1.0 ) > EPS )
+			return SUCCESSFUL_RETURN;
+
+	for ( i=0; i<nV; ++i )
+	{
+		for ( j=0; j<i; ++j )
+			if ( ( getAbs( H[i*NVMAX + j] ) > EPS ) || ( getAbs( H[j*NVMAX + i] ) > EPS ) )
+				return SUCCESSFUL_RETURN;
+	}
+
+	/* 2) If this point is reached, Hessian equals the idetity matrix. */
+	hessianType = HST_IDENTITY;
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p S u b j e c t T o T y p e
+ */
+returnValue QProblemB::setupSubjectToType( )
+{
+	int i;
+	int nV = getNV( );
+
+
+	/* 1) Check if lower bounds are present. */
+	bounds.setNoLower( BT_TRUE );
+	for( i=0; i<nV; ++i )
+		if ( lb[i] > -INFTY )
+		{
+			bounds.setNoLower( BT_FALSE );
+			break;
+		}
+
+	/* 2) Check if upper bounds are present. */
+	bounds.setNoUpper( BT_TRUE );
+	for( i=0; i<nV; ++i )
+		if ( ub[i] < INFTY )
+		{
+			bounds.setNoUpper( BT_FALSE );
+			break;
+		}
+
+	/* 3) Determine implicitly fixed and unbounded variables. */
+	int nFV = 0;
+	int nUV = 0;
+
+	for( i=0; i<nV; ++i )
+		if ( ( lb[i] < -INFTY + BOUNDTOL ) && ( ub[i] > INFTY - BOUNDTOL ) )
+		{
+			bounds.setType( i,ST_UNBOUNDED );
+			++nUV;
+		}
+		else
+		{
+			if ( lb[i] > ub[i] - BOUNDTOL )
+			{
+				bounds.setType( i,ST_EQUALITY );
+				++nFV;
+			}
+			else
+			{
+				bounds.setType( i,ST_BOUNDED );
+			}
+		}
+
+	/* 4) Set dimensions of bounds structure. */
+	bounds.setNFV( nFV );
+	bounds.setNUV( nUV );
+	bounds.setNBV( nV - nFV - nUV );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	c h o l e s k y D e c o m p o s i t i o n
+ */
+returnValue QProblemB::setupCholeskyDecomposition( )
+{
+	int i, j, k, ii, jj;
+	int nV  = getNV( );
+	int nFR = getNFR( );
+
+	/* If Hessian flag is false, it means that H & R already contain Cholesky
+	 * factorization -- provided from outside. */
+	if (hasHessian == BT_FALSE)
+		return SUCCESSFUL_RETURN;
+
+	/* 1) Initialises R with all zeros. */
+	for( i=0; i<nV; ++i )
+		for( j=0; j<nV; ++j )
+			R[i*NVMAX + j] = 0.0;
+
+	/* 2) Calculate Cholesky decomposition of H (projected to free variables). */
+	if ( hessianType == HST_IDENTITY )
+	{
+		/* if Hessian is identity, so is its Cholesky factor. */
+		for( i=0; i<nFR; ++i )
+			R[i*NVMAX + i] = 1.0;
+	}
+	else
+	{
+		if ( nFR > 0 )
+		{
+			int FR_idx[NVMAX];
+			if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_INDEXLIST_CORRUPTED );
+
+			/* R'*R = H */
+			real_t sum;
+			real_t inv;
+
+			for( i=0; i<nFR; ++i )
+			{
+				/* j == i */
+				ii = FR_idx[i];
+				sum = H[ii*NVMAX + ii];
+
+				for( k=(i-1); k>=0; --k )
+					sum -= R[k*NVMAX + i] * R[k*NVMAX + i];
+
+				if ( sum > 0.0 )
+				{
+					R[i*NVMAX + i] = sqrt( sum );
+					inv = 1.0 / R[i*NVMAX + i];
+				}
+				else
+				{
+					hessianType = HST_SEMIDEF;
+					return THROWERROR( RET_HESSIAN_NOT_SPD );
+				}
+
+				/* j > i */
+				for( j=(i+1); j<nFR; ++j )
+				{
+					jj = FR_idx[j];
+					sum = H[jj*NVMAX + ii];
+
+					for( k=(i-1); k>=0; --k )
+						sum -= R[k*NVMAX + i] * R[k*NVMAX + j];
+
+					R[i*NVMAX + j] = sum * inv;
+				}
+			}
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s o l v e I n i t i a l Q P
+ */
+returnValue QProblemB::solveInitialQP(	const real_t* const xOpt, const real_t* const yOpt,
+										const Bounds* const guessedBounds,
+										int& nWSR, real_t* const cputime
+										)
+{
+	int i, nFR;
+	int nV = getNV( );
+
+
+	/* start runtime measurement */
+	real_t starttime = 0.0;
+	if ( cputime != 0 )
+		starttime = getCPUtime( );
+
+
+	status = QPS_NOTINITIALISED;
+
+	/* I) ANALYSE QP DATA: */
+	/* 1) Check if Hessian happens to be the identity matrix. */
+	if ( checkForIdentityHessian( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	/* 2) Setup type of bounds (i.e. unbounded, implicitly fixed etc.). */
+	if ( setupSubjectToType( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	status = QPS_PREPARINGAUXILIARYQP;
+
+
+	/* II) SETUP AUXILIARY QP WITH GIVEN OPTIMAL SOLUTION: */
+	/* 1) Setup bounds data structure. */
+	if ( bounds.setupAllFree( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	/* 2) Setup optimal primal/dual solution for auxiliary QP. */
+	if ( setupAuxiliaryQPsolution( xOpt,yOpt ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	/* 3) Obtain linear independent working set for auxiliary QP. */
+
+	static Bounds auxiliaryBounds;
+
+	auxiliaryBounds.init( nV );
+
+	if ( obtainAuxiliaryWorkingSet( xOpt,yOpt,guessedBounds, &auxiliaryBounds ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	/* 4) Setup working set of auxiliary QP and setup cholesky decomposition. */
+	if ( setupAuxiliaryWorkingSet( &auxiliaryBounds,BT_TRUE ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	nFR = getNFR();
+	/* At the moment we can only provide a Cholesky of the Hessian if
+	 * the solver is cold-started. */
+	if (hasCholesky == BT_FALSE || nFR != nV)
+		if (setupCholeskyDecomposition() != SUCCESSFUL_RETURN)
+			return THROWERROR( RET_INIT_FAILED_CHOLESKY );
+
+	/* 5) Store original QP formulation... */
+	real_t g_original[NVMAX];
+	real_t lb_original[NVMAX];
+	real_t ub_original[NVMAX];
+
+	for( i=0; i<nV; ++i )
+		g_original[i] = g[i];
+	for( i=0; i<nV; ++i )
+		lb_original[i] = lb[i];
+	for( i=0; i<nV; ++i )
+		ub_original[i] = ub[i];
+
+	/* ... and setup QP data of an auxiliary QP having an optimal solution
+	 * as specified by the user (or xOpt = yOpt = 0, by default). */
+	if ( setupAuxiliaryQPgradient( ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	if ( setupAuxiliaryQPbounds( BT_TRUE ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_INIT_FAILED );
+
+	status = QPS_AUXILIARYQPSOLVED;
+
+
+	/* III) SOLVE ACTUAL INITIAL QP: */
+	/* Use hotstart method to find the solution of the original initial QP,... */
+	returnValue returnvalue = hotstart( g_original,lb_original,ub_original, nWSR,0 );
+
+
+	/* ... check for infeasibility and unboundedness... */
+	if ( isInfeasible( ) == BT_TRUE )
+		return THROWERROR( RET_INIT_FAILED_INFEASIBILITY );
+
+	if ( isUnbounded( ) == BT_TRUE )
+		return THROWERROR( RET_INIT_FAILED_UNBOUNDEDNESS );
+
+	/* ... and internal errors. */
+	if ( ( returnvalue != SUCCESSFUL_RETURN ) && ( returnvalue != RET_MAX_NWSR_REACHED )  &&
+	     ( returnvalue != RET_INACCURATE_SOLUTION ) && ( returnvalue != RET_NO_SOLUTION ) )
+		return THROWERROR( RET_INIT_FAILED_HOTSTART );
+
+
+	/* stop runtime measurement */
+	if ( cputime != 0 )
+		*cputime = getCPUtime( ) - starttime;
+
+	if ( printlevel == PL_HIGH )
+		THROWINFO( RET_INIT_SUCCESSFUL );
+
+	return returnvalue;
+}
+
+
+/*
+ *	o b t a i n A u x i l i a r y W o r k i n g S e t
+ */
+returnValue QProblemB::obtainAuxiliaryWorkingSet(	const real_t* const xOpt, const real_t* const yOpt,
+													const Bounds* const guessedBounds, Bounds* auxiliaryBounds
+													) const
+{
+	int i = 0;
+	int nV = getNV( );
+
+
+	/* 1) Ensure that desiredBounds is allocated (and different from guessedBounds). */
+	if ( ( auxiliaryBounds == 0 ) || ( auxiliaryBounds == guessedBounds ) )
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+
+	/* 2) Setup working set for auxiliary initial QP. */
+	if ( guessedBounds != 0 )
+	{
+		/* If an initial working set is specific, use it!
+		 * Moreover, add all implictly fixed variables if specified. */
+		for( i=0; i<nV; ++i )
+		{
+			if ( bounds.getType( i ) == ST_EQUALITY )
+			{
+				if ( auxiliaryBounds->setupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+			}
+			else
+			{
+				if ( auxiliaryBounds->setupBound( i,guessedBounds->getStatus( i ) ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+			}
+		}
+	}
+	else	/* No initial working set specified. */
+	{
+		if ( ( xOpt != 0 ) && ( yOpt == 0 ) )
+		{
+			/* Obtain initial working set by "clipping". */
+			for( i=0; i<nV; ++i )
+			{
+				if ( xOpt[i] <= lb[i] + BOUNDTOL )
+				{
+					if ( auxiliaryBounds->setupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+					continue;
+				}
+
+				if ( xOpt[i] >= ub[i] - BOUNDTOL )
+				{
+					if ( auxiliaryBounds->setupBound( i,ST_UPPER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+					continue;
+				}
+
+				/* Moreover, add all implictly fixed variables if specified. */
+				if ( bounds.getType( i ) == ST_EQUALITY )
+				{
+					if ( auxiliaryBounds->setupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+				else
+				{
+					if ( auxiliaryBounds->setupBound( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+			}
+		}
+
+		if ( ( xOpt == 0 ) && ( yOpt != 0 ) )
+		{
+			/* Obtain initial working set in accordance to sign of dual solution vector. */
+			for( i=0; i<nV; ++i )
+			{
+				if ( yOpt[i] > ZERO )
+				{
+					if ( auxiliaryBounds->setupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+					continue;
+				}
+
+				if ( yOpt[i] < -ZERO )
+				{
+					if ( auxiliaryBounds->setupBound( i,ST_UPPER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+					continue;
+				}
+
+				/* Moreover, add all implictly fixed variables if specified. */
+				if ( bounds.getType( i ) == ST_EQUALITY )
+				{
+					if ( auxiliaryBounds->setupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+				else
+				{
+					if ( auxiliaryBounds->setupBound( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+			}
+		}
+
+		/* If xOpt and yOpt are null pointer and no initial working is specified,
+		 * start with empty working set (or implicitly fixed bounds only)
+		 * for auxiliary QP. */
+		if ( ( xOpt == 0 ) && ( yOpt == 0 ) )
+		{
+			for( i=0; i<nV; ++i )
+			{
+				/* Only add all implictly fixed variables if specified. */
+				if ( bounds.getType( i ) == ST_EQUALITY )
+				{
+					if ( auxiliaryBounds->setupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+				else
+				{
+					if ( auxiliaryBounds->setupBound( i,ST_INACTIVE ) != SUCCESSFUL_RETURN )
+						return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED );
+				}
+			}
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p A u x i l i a r y W o r k i n g S e t
+ */
+returnValue QProblemB::setupAuxiliaryWorkingSet( 	const Bounds* const auxiliaryBounds,
+													BooleanType setupAfresh
+													)
+{
+	int i;
+	int nV = getNV( );
+
+	/* consistency checks */
+	if ( auxiliaryBounds != 0 )
+	{
+		for( i=0; i<nV; ++i )
+			if ( ( bounds.getStatus( i ) == ST_UNDEFINED ) || ( auxiliaryBounds->getStatus( i ) == ST_UNDEFINED ) )
+				return THROWERROR( RET_UNKNOWN_BUG );
+	}
+	else
+	{
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+	}
+
+
+	/* I) SETUP CHOLESKY FLAG:
+	 *    Cholesky decomposition shall only be updated if working set
+	 *    shall be updated (i.e. NOT setup afresh!) */
+	BooleanType updateCholesky;
+	if ( setupAfresh == BT_TRUE )
+		updateCholesky = BT_FALSE;
+	else
+		updateCholesky = BT_TRUE;
+
+
+	/* II) REMOVE FORMERLY ACTIVE BOUNDS (IF NECESSARY): */
+	if ( setupAfresh == BT_FALSE )
+	{
+		/* Remove all active bounds that shall be inactive AND
+		*  all active bounds that are active at the wrong bound. */
+		for( i=0; i<nV; ++i )
+		{
+			if ( ( bounds.getStatus( i ) == ST_LOWER ) && ( auxiliaryBounds->getStatus( i ) != ST_LOWER ) )
+				if ( removeBound( i,updateCholesky ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_SETUP_WORKINGSET_FAILED );
+
+			if ( ( bounds.getStatus( i ) == ST_UPPER ) && ( auxiliaryBounds->getStatus( i ) != ST_UPPER ) )
+				if ( removeBound( i,updateCholesky ) != SUCCESSFUL_RETURN )
+					return THROWERROR( RET_SETUP_WORKINGSET_FAILED );
+		}
+	}
+
+
+	/* III) ADD NEWLY ACTIVE BOUNDS: */
+	/*      Add all inactive bounds that shall be active AND
+	 *      all formerly active bounds that have been active at the wrong bound. */
+	for( i=0; i<nV; ++i )
+	{
+		if ( ( bounds.getStatus( i ) == ST_INACTIVE ) && ( auxiliaryBounds->getStatus( i ) != ST_INACTIVE ) )
+		{
+			if ( addBound( i,auxiliaryBounds->getStatus( i ),updateCholesky ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_SETUP_WORKINGSET_FAILED );
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p A u x i l i a r y Q P s o l u t i o n
+ */
+returnValue QProblemB::setupAuxiliaryQPsolution(	const real_t* const xOpt, const real_t* const yOpt
+													)
+{
+	int i;
+	int nV = getNV( );
+
+
+	/* Setup primal/dual solution vectors for auxiliary initial QP:
+	 * if a null pointer is passed, a zero vector is assigned;
+	 * old solution vector is kept if pointer to internal solution vector is passed. */
+	if ( xOpt != 0 )
+	{
+		if ( xOpt != x )
+			for( i=0; i<nV; ++i )
+				x[i] = xOpt[i];
+	}
+	else
+	{
+		for( i=0; i<nV; ++i )
+			x[i] = 0.0;
+	}
+
+	if ( yOpt != 0 )
+	{
+		if ( yOpt != y )
+			for( i=0; i<nV; ++i )
+				y[i] = yOpt[i];
+	}
+	else
+	{
+		for( i=0; i<nV; ++i )
+			y[i] = 0.0;
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p A u x i l i a r y Q P g r a d i e n t
+ */
+returnValue QProblemB::setupAuxiliaryQPgradient( )
+{
+	int i, j;
+	int nV = getNV( );
+
+
+	/* Setup gradient vector: g = -H*x + y'*Id. */
+	for ( i=0; i<nV; ++i )
+	{
+		/* y'*Id */
+		g[i] = y[i];
+
+		/* -H*x */
+		for ( j=0; j<nV; ++j )
+			g[i] -= H[i*NVMAX + j] * x[j];
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t u p A u x i l i a r y Q P b o u n d s
+ */
+returnValue QProblemB::setupAuxiliaryQPbounds( BooleanType useRelaxation )
+{
+	int i;
+	int nV = getNV( );
+
+
+	/* Setup bound vectors. */
+	for ( i=0; i<nV; ++i )
+	{
+		switch ( bounds.getStatus( i ) )
+		{
+			case ST_INACTIVE:
+				if ( useRelaxation == BT_TRUE )
+				{
+					if ( bounds.getType( i ) == ST_EQUALITY )
+					{
+						lb[i] = x[i];
+						ub[i] = x[i];
+					}
+					else
+					{
+						lb[i] = x[i] - BOUNDRELAXATION;
+						ub[i] = x[i] + BOUNDRELAXATION;
+					}
+				}
+				break;
+
+			case ST_LOWER:
+				lb[i] = x[i];
+				if ( bounds.getType( i ) == ST_EQUALITY )
+				{
+					ub[i] = x[i];
+				}
+				else
+				{
+					if ( useRelaxation == BT_TRUE )
+						ub[i] = x[i] + BOUNDRELAXATION;
+				}
+				break;
+
+			case ST_UPPER:
+				ub[i] = x[i];
+				if ( bounds.getType( i ) == ST_EQUALITY )
+				{
+					lb[i] = x[i];
+				}
+				else
+				{
+					if ( useRelaxation == BT_TRUE )
+						lb[i] = x[i] - BOUNDRELAXATION;
+				}
+				break;
+
+			default:
+				return THROWERROR( RET_UNKNOWN_BUG );
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	a d d B o u n d
+ */
+returnValue QProblemB::addBound(	int number, SubjectToStatus B_status,
+									BooleanType updateCholesky
+									)
+{
+	int i, j;
+	int nFR = getNFR( );
+
+
+	/* consistency check */
+	if ( ( getStatus( ) == QPS_NOTINITIALISED )    ||
+		 ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) ||
+		 ( getStatus( ) == QPS_HOMOTOPYQPSOLVED )  ||
+		 ( getStatus( ) == QPS_SOLVED )            )
+	{
+		return THROWERROR( RET_UNKNOWN_BUG );
+	}
+
+	/* Perform cholesky updates only if QProblemB has been initialised! */
+	if ( ( getStatus( ) == QPS_PREPARINGAUXILIARYQP ) || ( updateCholesky == BT_FALSE ) )
+	{
+		/* UPDATE INDICES */
+		if ( bounds.moveFreeToFixed( number,B_status ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_ADDBOUND_FAILED );
+
+		return SUCCESSFUL_RETURN;
+	}
+
+
+	/* I) PERFORM CHOLESKY UPDATE: */
+	/* 1) Index of variable to be added within the list of free variables. */
+	int number_idx = bounds.getFree( )->getIndex( number );
+
+	real_t c, s;
+
+	/* 2) Use row-wise Givens rotations to restore upper triangular form of R. */
+	for( i=number_idx+1; i<nFR; ++i )
+	{
+		computeGivens( R[(i-1)*NVMAX + i],R[i*NVMAX + i], R[(i-1)*NVMAX + i],R[i*NVMAX + i],c,s );
+
+		for( j=(1+i); j<nFR; ++j ) /* last column of R is thrown away */
+			applyGivens( c,s,R[(i-1)*NVMAX + j],R[i*NVMAX + j], R[(i-1)*NVMAX + j],R[i*NVMAX + j] );
+	}
+
+	/* 3) Delete <number_idx>th column and ... */
+	for( i=0; i<nFR-1; ++i )
+		for( j=number_idx+1; j<nFR; ++j )
+			R[i*NVMAX + j-1] = R[i*NVMAX + j];
+	/* ... last column of R. */
+	for( i=0; i<nFR; ++i )
+		R[i*NVMAX + nFR-1] = 0.0;
+
+
+	/* II) UPDATE INDICES */
+	if ( bounds.moveFreeToFixed( number,B_status ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_ADDBOUND_FAILED );
+
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+returnValue QProblemB::removeBound(	int number,
+									BooleanType updateCholesky
+									)
+{
+	int i, ii;
+	int nFR = getNFR( );
+
+
+	/* consistency check */
+	if ( ( getStatus( ) == QPS_NOTINITIALISED )    ||
+		 ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) ||
+		 ( getStatus( ) == QPS_HOMOTOPYQPSOLVED )  ||
+		 ( getStatus( ) == QPS_SOLVED )            )
+	{
+		return THROWERROR( RET_UNKNOWN_BUG );
+	}
+
+
+	/* I) UPDATE INDICES */
+	if ( bounds.moveFixedToFree( number ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_REMOVEBOUND_FAILED );
+
+	/* Perform cholesky updates only if QProblemB has been initialised! */
+	if ( ( getStatus( ) == QPS_PREPARINGAUXILIARYQP ) || ( updateCholesky == BT_FALSE ) )
+		return SUCCESSFUL_RETURN;
+
+
+	/* II) PERFORM CHOLESKY UPDATE */
+	int FR_idx[NVMAX];
+	if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_REMOVEBOUND_FAILED );
+
+	/* 1) Calculate new column of cholesky decomposition. */
+	real_t rhs[NVMAX];
+	real_t r[NVMAX];
+	real_t r0 = H[number*NVMAX + number];
+
+	for( i=0; i<nFR; ++i )
+	{
+		ii = FR_idx[i];
+		rhs[i] = H[number*NVMAX + ii];
+	}
+
+	if ( backsolveR( rhs,BT_TRUE,BT_TRUE,r ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_REMOVEBOUND_FAILED );
+
+	for( i=0; i<nFR; ++i )
+		r0 -= r[i]*r[i];
+
+	/* 2) Store new column into R. */
+	for( i=0; i<nFR; ++i )
+		R[i*NVMAX + nFR] = r[i];
+
+	if ( r0 > 0.0 )
+		R[nFR*NVMAX + nFR] = sqrt( r0 );
+	else
+	{
+		hessianType = HST_SEMIDEF;
+		return THROWERROR( RET_HESSIAN_NOT_SPD );
+	}
+
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	b a c k s o l v e R  (CODE DUPLICATED IN QProblem CLASS!!!)
+ */
+returnValue QProblemB::backsolveR(	const real_t* const b, BooleanType transposed,
+									real_t* const a
+									)
+{
+	/* Call standard backsolve procedure (i.e. removingBound == BT_FALSE). */
+	return backsolveR( b,transposed,BT_FALSE,a );
+}
+
+
+/*
+ *	b a c k s o l v e R  (CODE DUPLICATED IN QProblem CLASS!!!)
+ */
+returnValue QProblemB::backsolveR(	const real_t* const b, BooleanType transposed,
+									BooleanType removingBound,
+									real_t* const a
+									)
+{
+	int i, j;
+	int nR = getNZ( );
+
+	real_t sum;
+
+	/* if backsolve is called while removing a bound, reduce nZ by one. */
+	if ( removingBound == BT_TRUE )
+		--nR;
+
+	/* nothing to do */
+	if ( nR <= 0 )
+		return SUCCESSFUL_RETURN;
+
+
+	/* Solve Ra = b, where R might be transposed. */
+	if ( transposed == BT_FALSE )
+	{
+		/* solve Ra = b */
+		for( i=(nR-1); i>=0; --i )
+		{
+			sum = b[i];
+			for( j=(i+1); j<nR; ++j )
+				sum -= R[i*NVMAX + j] * a[j];
+
+			if ( getAbs( R[i*NVMAX + i] ) > ZERO )
+				a[i] = sum / R[i*NVMAX + i];
+			else
+				return THROWERROR( RET_DIV_BY_ZERO );
+		}
+	}
+	else
+	{
+		/* solve R^T*a = b */
+		for( i=0; i<nR; ++i )
+		{
+			sum = b[i];
+
+			for( j=0; j<i; ++j )
+				sum -= R[j*NVMAX + i] * a[j];
+
+			if ( getAbs( R[i*NVMAX + i] ) > ZERO )
+				a[i] = sum / R[i*NVMAX + i];
+			else
+				return THROWERROR( RET_DIV_BY_ZERO );
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	h o t s t a r t _ d e t e r m i n e D a t a S h i f t
+ */
+returnValue QProblemB::hotstart_determineDataShift(	const int* const FX_idx,
+													const real_t* const g_new, const real_t* const lb_new, const real_t* const ub_new,
+													real_t* const delta_g, real_t* const delta_lb, real_t* const delta_ub,
+													BooleanType& Delta_bB_isZero
+													)
+{
+	int i, ii;
+	int nV  = getNV( );
+	int nFX = getNFX( );
+
+
+	/* 1) Calculate shift directions. */
+	for( i=0; i<nV; ++i )
+		delta_g[i]  = g_new[i]  - g[i];
+
+	if ( lb_new != 0 )
+	{
+		for( i=0; i<nV; ++i )
+			delta_lb[i] = lb_new[i] - lb[i];
+	}
+	else
+	{
+		/* if no lower bounds exist, assume the new lower bounds to be -infinity */
+		for( i=0; i<nV; ++i )
+			delta_lb[i] = -INFTY - lb[i];
+	}
+
+	if ( ub_new != 0 )
+	{
+		for( i=0; i<nV; ++i )
+			delta_ub[i] = ub_new[i] - ub[i];
+	}
+	else
+	{
+		/* if no upper bounds exist, assume the new upper bounds to be infinity */
+		for( i=0; i<nV; ++i )
+			delta_ub[i] = INFTY - ub[i];
+	}
+
+	/* 2) Determine if active bounds are to be shifted. */
+	Delta_bB_isZero = BT_TRUE;
+
+	for ( i=0; i<nFX; ++i )
+	{
+		ii = FX_idx[i];
+
+		if ( ( getAbs( delta_lb[ii] ) > EPS ) || ( getAbs( delta_ub[ii] ) > EPS ) )
+		{
+			Delta_bB_isZero = BT_FALSE;
+			break;
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	a r e B o u n d s C o n s i s t e n t
+ */
+BooleanType QProblemB::areBoundsConsistent(	const real_t* const delta_lb, const real_t* const delta_ub
+											) const
+{
+	int i;
+
+	/* Check if delta_lb[i] is greater than delta_ub[i]
+	 * for a component i whose bounds are already (numerically) equal. */
+	for( i=0; i<getNV( ); ++i )
+		if ( ( lb[i] > ub[i] - BOUNDTOL ) && ( delta_lb[i] > delta_ub[i] + EPS ) )
+			return BT_FALSE;
+
+	return BT_TRUE;
+}
+
+
+/*
+ *	s e t u p Q P d a t a
+ */
+returnValue QProblemB::setupQPdata(	const real_t* const _H, const real_t* const _R, const real_t* const _g,
+									const real_t* const _lb, const real_t* const _ub
+									)
+{
+	int i, j;
+	int nV = getNV( );
+
+	/* 1) Setup Hessian matrix and it's Cholesky factorization. */
+	if (_H != 0)
+	{
+		for( i=0; i<nV; ++i )
+			for( j=0; j<nV; ++j )
+				H[i*NVMAX + j] = _H[i*nV + j];
+		hasHessian = BT_TRUE;
+	}
+	else
+		hasHessian = BT_FALSE;
+
+	if (_R != 0)
+	{
+		for( i=0; i<nV; ++i )
+			for( j=0; j<nV; ++j )
+				R[i*NVMAX + j] = _R[i*nV + j];
+		hasCholesky = BT_TRUE;
+
+		/* If Hessian is not provided, store it's factorization in H, and that guy
+		 * is going to be used for H * x products (R^T * R * x in this case). */
+		if (hasHessian == BT_FALSE)
+			for( i=0; i<nV; ++i )
+				for( j=0; j<nV; ++j )
+					H[i*NVMAX + j] = _R[i*nV + j];
+	}
+	else
+		hasCholesky = BT_FALSE;
+
+	if (hasHessian == BT_FALSE && hasCholesky == BT_FALSE)
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	/* 2) Setup gradient vector. */
+	if ( _g == 0 )
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	for( i=0; i<nV; ++i )
+		g[i] = _g[i];
+
+	/* 3) Setup lower bounds vector. */
+	if ( _lb != 0 )
+	{
+		for( i=0; i<nV; ++i )
+			lb[i] = _lb[i];
+	}
+	else
+	{
+		/* if no lower bounds are specified, set them to -infinity */
+		for( i=0; i<nV; ++i )
+			lb[i] = -INFTY;
+	}
+
+	/* 4) Setup upper bounds vector. */
+	if ( _ub != 0 )
+	{
+		for( i=0; i<nV; ++i )
+			ub[i] = _ub[i];
+	}
+	else
+	{
+		/* if no upper bounds are specified, set them to infinity */
+		for( i=0; i<nV; ++i )
+			ub[i] = INFTY;
+	}
+
+	//printmatrix( "H",H,nV,nV );
+	//printmatrix( "R",R,nV,nV );
+	//printmatrix( "g",g,1,nV );
+	//printmatrix( "lb",lb,1,nV );
+	//printmatrix( "ub",ub,1,nV );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*****************************************************************************
+ *  P R I V A T E                                                            *
+ *****************************************************************************/
+
+/*
+ *	h o t s t a r t _ d e t e r m i n e S t e p D i r e c t i o n
+ */
+returnValue QProblemB::hotstart_determineStepDirection(	const int* const FR_idx, const int* const FX_idx,
+														const real_t* const delta_g, const real_t* const delta_lb, const real_t* const delta_ub,
+														BooleanType Delta_bB_isZero,
+														real_t* const delta_xFX, real_t* const delta_xFR,
+														real_t* const delta_yFX
+														)
+{
+	int i, j, ii, jj;
+	int nFR = getNFR( );
+	int nFX = getNFX( );
+
+
+	/* initialise auxiliary vectors */
+	real_t HMX_delta_xFX[NVMAX];
+	for( i=0; i<nFR; ++i )
+		HMX_delta_xFX[i] = 0.0;
+
+
+	/* I) DETERMINE delta_xFX */
+	if ( nFX > 0 )
+	{
+		for( i=0; i<nFX; ++i )
+		{
+			ii = FX_idx[i];
+
+			if ( bounds.getStatus( ii ) == ST_LOWER )
+				delta_xFX[i] = delta_lb[ii];
+			else
+				delta_xFX[i] = delta_ub[ii];
+		}
+	}
+
+
+	/* II) DETERMINE delta_xFR */
+	if ( nFR > 0 )
+	{
+		/* auxiliary variables */
+		real_t delta_xFRz_TMP[NVMAX];
+		real_t delta_xFRz_RHS[NVMAX];
+
+		/* Determine delta_xFRz. */
+		if ( Delta_bB_isZero == BT_FALSE )
+		{
+			for( i=0; i<nFR; ++i )
+			{
+				ii = FR_idx[i];
+				for( j=0; j<nFX; ++j )
+				{
+					jj = FX_idx[j];
+					HMX_delta_xFX[i] += H[ii*NVMAX + jj] * delta_xFX[j];
+				}
+			}
+		}
+
+		if ( Delta_bB_isZero == BT_TRUE )
+		{
+			for( j=0; j<nFR; ++j )
+			{
+				jj = FR_idx[j];
+				delta_xFRz_RHS[j] = delta_g[jj];
+			}
+		}
+		else
+		{
+			for( j=0; j<nFR; ++j )
+			{
+				jj = FR_idx[j];
+				delta_xFRz_RHS[j] = delta_g[jj] + HMX_delta_xFX[j]; /* *ZFR */
+			}
+		}
+
+		for( i=0; i<nFR; ++i )
+			delta_xFR[i] = -delta_xFRz_RHS[i];
+
+		if ( backsolveR( delta_xFR,BT_TRUE,delta_xFRz_TMP ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_STEPDIRECTION_FAILED_CHOLESKY );
+
+		if ( backsolveR( delta_xFRz_TMP,BT_FALSE,delta_xFR ) != SUCCESSFUL_RETURN )
+			return THROWERROR( RET_STEPDIRECTION_FAILED_CHOLESKY );
+	}
+
+
+	/* III) DETERMINE delta_yFX */
+	if ( nFX > 0 )
+	{
+		for( i=0; i<nFX; ++i )
+		{
+			ii = FX_idx[i];
+
+			delta_yFX[i] = 0.0;
+			for( j=0; j<nFR; ++j )
+			{
+				jj = FR_idx[j];
+				delta_yFX[i] += H[ii*NVMAX + jj] * delta_xFR[j];
+			}
+
+			if ( Delta_bB_isZero == BT_FALSE )
+			{
+				for( j=0; j<nFX; ++j )
+				{
+					jj = FX_idx[j];
+					delta_yFX[i] += H[ii*NVMAX + jj] * delta_xFX[j];
+				}
+			}
+
+			delta_yFX[i] += delta_g[ii];
+		}
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	h o t s t a r t _ d e t e r m i n e S t e p L e n g t h
+ */
+returnValue QProblemB::hotstart_determineStepLength(	const int* const FR_idx, const int* const FX_idx,
+														const real_t* const delta_lb, const real_t* const delta_ub,
+														const real_t* const delta_xFR,
+														const real_t* const delta_yFX,
+														int& BC_idx, SubjectToStatus& BC_status
+														)
+{
+	int i, ii;
+	int nFR = getNFR( );
+	int nFX = getNFX( );
+
+	real_t tau_tmp;
+	real_t tau_new = 1.0;
+
+	BC_idx = 0;
+	BC_status = ST_UNDEFINED;
+
+
+	/* I) DETERMINE MAXIMUM DUAL STEPLENGTH, i.e. ensure that
+	 *    active dual bounds remain valid (ignoring implicitly fixed variables): */
+	for( i=0; i<nFX; ++i )
+	{
+		ii = FX_idx[i];
+
+		if ( bounds.getType( ii ) != ST_EQUALITY )
+		{
+			if ( bounds.getStatus( ii ) == ST_LOWER )
+			{
+				/* 1) Active lower bounds. */
+				if ( ( delta_yFX[i] < -ZERO ) && ( y[ii] >= 0.0 ) )
+				{
+					tau_tmp = y[ii] / ( -delta_yFX[i] );
+					if ( tau_tmp < tau_new )
+					{
+						if ( tau_tmp >= 0.0 )
+						{
+							tau_new = tau_tmp;
+							BC_idx = ii;
+							BC_status = ST_INACTIVE;
+						}
+					}
+				}
+			}
+			else
+			{
+				/* 2) Active upper bounds. */
+				if ( ( delta_yFX[i] > ZERO ) && ( y[ii] <= 0.0 ) )
+				{
+					tau_tmp = y[ii] / ( -delta_yFX[i] );
+					if ( tau_tmp < tau_new )
+					{
+						if ( tau_tmp >= 0.0 )
+						{
+							tau_new = tau_tmp;
+							BC_idx = ii;
+							BC_status = ST_INACTIVE;
+						}
+					}
+				}
+			}
+		}
+	}
+
+
+	/* II) DETERMINE MAXIMUM PRIMAL STEPLENGTH, i.e. ensure that
+	 *     inactive bounds remain valid (ignoring unbounded variables). */
+	/* 1) Inactive lower bounds. */
+	if ( bounds.isNoLower( ) == BT_FALSE )
+	{
+		for( i=0; i<nFR; ++i )
+		{
+			ii = FR_idx[i];
+
+			if ( bounds.getType( ii ) != ST_UNBOUNDED )
+			{
+				if ( delta_lb[ii] > delta_xFR[i] )
+				{
+					if ( x[ii] > lb[ii] )
+						tau_tmp = ( x[ii] - lb[ii] ) / ( delta_lb[ii] - delta_xFR[i] );
+					else
+						tau_tmp = 0.0;
+
+					if ( tau_tmp < tau_new )
+					{
+						if ( tau_tmp >= 0.0 )
+						{
+							tau_new = tau_tmp;
+							BC_idx = ii;
+							BC_status = ST_LOWER;
+						}
+					}
+				}
+			}
+		}
+	}
+
+	/* 2) Inactive upper bounds. */
+	if ( bounds.isNoUpper( ) == BT_FALSE )
+	{
+		for( i=0; i<nFR; ++i )
+		{
+			ii = FR_idx[i];
+
+			if ( bounds.getType( ii ) != ST_UNBOUNDED )
+			{
+				if ( delta_ub[ii] < delta_xFR[i] )
+				{
+					if ( x[ii] < ub[ii] )
+						tau_tmp = ( x[ii] - ub[ii] ) / ( delta_ub[ii] - delta_xFR[i] );
+					else
+						tau_tmp = 0.0;
+
+					if ( tau_tmp < tau_new )
+					{
+						if ( tau_tmp >= 0.0 )
+						{
+							tau_new = tau_tmp;
+							BC_idx = ii;
+							BC_status = ST_UPPER;
+						}
+					}
+				}
+			}
+		}
+	}
+
+
+	/* III) SET MAXIMUM HOMOTOPY STEPLENGTH */
+	tau = tau_new;
+
+	if ( printlevel ==  PL_HIGH )
+	{
+		#ifdef PC_DEBUG
+		char messageString[80];
+
+		if ( BC_status == ST_UNDEFINED )
+			sprintf( messageString,"Stepsize is %.6e!",tau );
+		else
+			sprintf( messageString,"Stepsize is %.6e! (BC_idx = %d, BC_status = %d)",tau,BC_idx,BC_status );
+
+		getGlobalMessageHandler( )->throwInfo( RET_STEPSIZE_NONPOSITIVE,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		#endif
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	h o t s t a r t _ p e r f o r m S t e p
+ */
+returnValue QProblemB::hotstart_performStep(	const int* const FR_idx, const int* const FX_idx,
+												const real_t* const delta_g, const real_t* const  delta_lb, const real_t* const delta_ub,
+												const real_t* const delta_xFX, const real_t* const delta_xFR,
+												const real_t* const delta_yFX,
+												int BC_idx, SubjectToStatus BC_status
+												)
+{
+	int i, ii;
+	int nV  = getNV( );
+	int nFR = getNFR( );
+	int nFX = getNFX( );
+
+
+	/* I) CHECK BOUNDS' CONSISTENCY */
+	if ( areBoundsConsistent( delta_lb,delta_ub ) == BT_FALSE )
+	{
+		infeasible = BT_TRUE;
+		tau = 0.0;
+
+		return THROWERROR( RET_QP_INFEASIBLE );
+	}
+
+
+	/* II) GO TO ACTIVE SET CHANGE */
+	if ( tau > ZERO )
+	{
+		/* 1) Perform step in primal und dual space. */
+		for( i=0; i<nFR; ++i )
+		{
+			ii = FR_idx[i];
+			x[ii] += tau*delta_xFR[i];
+		}
+
+		for( i=0; i<nFX; ++i )
+		{
+			ii = FX_idx[i];
+			x[ii] += tau*delta_xFX[i];
+			y[ii] += tau*delta_yFX[i];
+		}
+
+		/* 2) Shift QP data. */
+		for( i=0; i<nV; ++i )
+		{
+			g[i]  += tau*delta_g[i];
+			lb[i] += tau*delta_lb[i];
+			ub[i] += tau*delta_ub[i];
+		}
+	}
+	else
+	{
+		/* print a stepsize warning if stepsize is zero */
+		#ifdef PC_DEBUG
+		char messageString[80];
+		sprintf( messageString,"Stepsize is %.6e",tau );
+		getGlobalMessageHandler( )->throwWarning( RET_STEPSIZE,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		#endif
+	}
+
+
+	/* setup output preferences */
+	#ifdef PC_DEBUG
+	char messageString[80];
+  	VisibilityStatus visibilityStatus;
+
+  	if ( printlevel == PL_HIGH )
+		visibilityStatus = VS_VISIBLE;
+	else
+		visibilityStatus = VS_HIDDEN;
+	#endif
+
+
+	/* III) UPDATE ACTIVE SET */
+	switch ( BC_status )
+	{
+		/* Optimal solution found as no working set change detected. */
+		case ST_UNDEFINED:
+			return RET_OPTIMAL_SOLUTION_FOUND;
+
+
+		/* Remove one variable from active set. */
+		case ST_INACTIVE:
+			#ifdef PC_DEBUG
+			sprintf( messageString,"bound no. %d.", BC_idx );
+			getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus );
+			#endif
+
+			if ( removeBound( BC_idx,BT_TRUE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED );
+
+			y[BC_idx] = 0.0;
+			break;
+
+
+		/* Add one variable to active set. */
+		default:
+			#ifdef PC_DEBUG
+			if ( BC_status == ST_LOWER )
+				sprintf( messageString,"lower bound no. %d.", BC_idx );
+			else
+				sprintf( messageString,"upper bound no. %d.", BC_idx );
+				getGlobalMessageHandler( )->throwInfo( RET_ADD_TO_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus );
+			#endif
+
+			if ( addBound( BC_idx,BC_status,BT_TRUE ) != SUCCESSFUL_RETURN )
+				return THROWERROR( RET_ADD_TO_ACTIVESET_FAILED );
+			break;
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+#ifdef PC_DEBUG  /* Define print functions only for debugging! */
+
+/*
+ *	p r i n t I t e r a t i o n
+ */
+returnValue QProblemB::printIteration( 	int iteration,
+										int BC_idx,	SubjectToStatus BC_status
+		  								)
+{
+	char myPrintfString[160];
+
+	/* consistency check */
+	if ( iteration < 0 )
+		return THROWERROR( RET_INVALID_ARGUMENTS );
+
+	/* nothing to do */
+	if ( printlevel != PL_MEDIUM )
+		return SUCCESSFUL_RETURN;
+
+
+	/* 1) Print header at first iteration. */
+ 	if ( iteration == 0 )
+	{
+		sprintf( myPrintfString,"\n##############  qpOASES  --  QP NO.%4.1d  ###############\n", count );
+		myPrintf( myPrintfString );
+
+		sprintf( myPrintfString,"   Iter   |   StepLength    |       Info      |   nFX   \n" );
+		myPrintf( myPrintfString );
+	}
+
+	/* 2) Print iteration line. */
+	if ( BC_status == ST_UNDEFINED )
+	{
+		sprintf( myPrintfString,"   %4.1d   |   %1.5e   |    QP SOLVED    |  %4.1d   \n", iteration,tau,getNFX( ) );
+		myPrintf( myPrintfString );
+	}
+	else
+	{
+		char info[8];
+
+		if ( BC_status == ST_INACTIVE )
+			sprintf( info,"REM BND" );
+		else
+			sprintf( info,"ADD BND" );
+
+		sprintf( myPrintfString,"   %4.1d   |   %1.5e   |   %s%4.1d   |  %4.1d   \n", iteration,tau,info,BC_idx,getNFX( ) );
+		myPrintf( myPrintfString );
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+#endif  /* PC_DEBUG */
+
+
+
+/*
+ *	c h e c k K K T c o n d i t i o n s
+ */
+returnValue QProblemB::checkKKTconditions( )
+{
+	#ifdef __PERFORM_KKT_TEST__
+
+	int i, j;
+	int nV = getNV( );
+
+	real_t tmp;
+	real_t maxKKTviolation = 0.0;
+
+
+	/* 1) Check for Hx + g - y*A' = 0  (here: A = Id). */
+	for( i=0; i<nV; ++i )
+	{
+		tmp = g[i];
+
+		for( j=0; j<nV; ++j )
+			tmp += H[i*nV + j] * x[j];
+
+		tmp -= y[i];
+
+		if ( getAbs( tmp ) > maxKKTviolation )
+			maxKKTviolation = getAbs( tmp );
+	}
+
+	/* 2) Check for lb <= x <= ub. */
+	for( i=0; i<nV; ++i )
+	{
+		if ( lb[i] - x[i] > maxKKTviolation )
+			maxKKTviolation = lb[i] - x[i];
+
+		if ( x[i] - ub[i] > maxKKTviolation )
+			maxKKTviolation = x[i] - ub[i];
+	}
+
+	/* 3) Check for correct sign of y and for complementary slackness. */
+	for( i=0; i<nV; ++i )
+	{
+		switch ( bounds.getStatus( i ) )
+		{
+			case ST_LOWER:
+				if ( -y[i] > maxKKTviolation )
+					maxKKTviolation = -y[i];
+				if ( getAbs( ( x[i] - lb[i] ) * y[i] ) > maxKKTviolation )
+					maxKKTviolation = getAbs( ( x[i] - lb[i] ) * y[i] );
+				break;
+
+			case ST_UPPER:
+				if ( y[i] > maxKKTviolation )
+					maxKKTviolation = y[i];
+				if ( getAbs( ( ub[i] - x[i] ) * y[i] ) > maxKKTviolation )
+					maxKKTviolation = getAbs( ( ub[i] - x[i] ) * y[i] );
+				break;
+
+			default: /* inactive */
+			if ( getAbs( y[i] ) > maxKKTviolation )
+					maxKKTviolation = getAbs( y[i] );
+				break;
+		}
+	}
+
+	if ( maxKKTviolation > CRITICALACCURACY )
+		return RET_NO_SOLUTION;
+
+	if ( maxKKTviolation > DESIREDACCURACY )
+		return RET_INACCURATE_SOLUTION;
+
+	#endif /* __PERFORM_KKT_TEST__ */
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/QProblemB.ipp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/QProblemB.ipp
new file mode 100644
index 0000000000000000000000000000000000000000..0b031301e6c41531e9a7f25bf888c1d20e62c371
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/QProblemB.ipp
@@ -0,0 +1,425 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/QProblemB.ipp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of inlined member functions of the QProblemB class which 
+ *	is able to use the newly developed online active set strategy for 
+ *	parametric quadratic programming.
+ */
+
+
+
+#include <math.h>
+
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+/*
+ *	g e t H
+ */
+inline returnValue QProblemB::getH( real_t* const _H ) const
+{
+	int i;
+
+	for ( i=0; i<getNV( )*getNV( ); ++i )
+		_H[i] = H[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t G
+ */
+inline returnValue QProblemB::getG( real_t* const _g ) const
+{
+	int i;
+
+	for ( i=0; i<getNV( ); ++i )
+		_g[i] = g[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t L B
+ */
+inline returnValue QProblemB::getLB( real_t* const _lb ) const
+{
+	int i;
+
+	for ( i=0; i<getNV( ); ++i )
+		_lb[i] = lb[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t L B
+ */
+inline returnValue QProblemB::getLB( int number, real_t& value ) const
+{
+	if ( ( number >= 0 ) && ( number < getNV( ) ) )
+	{
+		value = lb[number];
+		return SUCCESSFUL_RETURN;
+	}
+	else
+	{
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+	}
+}
+
+
+/*
+ *	g e t U B
+ */
+inline returnValue QProblemB::getUB( real_t* const _ub ) const
+{
+	int i;
+
+	for ( i=0; i<getNV( ); ++i )
+		_ub[i] = ub[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t U B
+ */
+inline returnValue QProblemB::getUB( int number, real_t& value ) const
+{
+	if ( ( number >= 0 ) && ( number < getNV( ) ) )
+	{
+		value = ub[number];
+		return SUCCESSFUL_RETURN;
+	}
+	else
+	{
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+	}
+}
+
+
+/*
+ *	g e t B o u n d s
+ */
+inline returnValue QProblemB::getBounds( Bounds* const _bounds ) const
+{
+	*_bounds = bounds;
+	
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	g e t N V
+ */
+inline int QProblemB::getNV( ) const
+{
+	return bounds.getNV( );
+}
+
+
+/*
+ *	g e t N F R
+ */
+inline int QProblemB::getNFR( )
+{
+	return bounds.getNFR( );
+}
+
+
+/*
+ *	g e t N F X
+ */
+inline int QProblemB::getNFX( )
+{
+	return bounds.getNFX( );
+}
+
+
+/*
+ *	g e t N F V
+ */
+inline int QProblemB::getNFV( ) const
+{
+	return bounds.getNFV( );
+}
+
+
+/*
+ *	g e t S t a t u s
+ */
+inline QProblemStatus QProblemB::getStatus( ) const
+{
+	return status;
+}
+
+
+/*
+ *	i s I n i t i a l i s e d
+ */
+inline BooleanType QProblemB::isInitialised( ) const
+{
+	if ( status == QPS_NOTINITIALISED )
+		return BT_FALSE;
+	else
+		return BT_TRUE;
+}
+
+
+/*
+ *	i s S o l v e d
+ */
+inline BooleanType QProblemB::isSolved( ) const
+{
+	if ( status == QPS_SOLVED )
+		return BT_TRUE;
+	else
+		return BT_FALSE;
+}
+
+
+/*
+ *	i s I n f e a s i b l e
+ */
+inline BooleanType QProblemB::isInfeasible( ) const
+{
+	return infeasible;
+}
+
+
+/*
+ *	i s U n b o u n d e d
+ */
+inline BooleanType QProblemB::isUnbounded( ) const
+{
+	return unbounded;
+}
+
+
+/*
+ *	g e t P r i n t L e v e l
+ */
+inline PrintLevel QProblemB::getPrintLevel( ) const
+{
+	return printlevel;
+}
+
+
+/*
+ *	g e t H e s s i a n T y p e
+ */
+inline HessianType QProblemB::getHessianType( ) const
+{
+	return hessianType;
+}
+
+
+/*
+ *	s e t H e s s i a n T y p e
+ */
+inline returnValue QProblemB::setHessianType( HessianType _hessianType )
+{
+	hessianType = _hessianType;
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*****************************************************************************
+ *  P R O T E C T E D                                                        *
+ *****************************************************************************/
+
+/*
+ *	s e t H
+ */
+inline returnValue QProblemB::setH( const real_t* const H_new )
+{
+	int i, j;
+
+	int nV = getNV();
+
+	for( i=0; i<nV; ++i )
+		for( j=0; j<nV; ++j )
+			H[i*NVMAX + j] = H_new[i*nV + j];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t G
+ */
+inline returnValue QProblemB::setG( const real_t* const g_new )
+{
+	int i;
+
+	int nV = getNV();
+
+	for( i=0; i<nV; ++i )
+		g[i] = g_new[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t L B
+ */
+inline returnValue QProblemB::setLB( const real_t* const lb_new )
+{
+	int i;
+
+	int nV = getNV();
+
+	for( i=0; i<nV; ++i )
+		lb[i] = lb_new[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t L B
+ */
+inline returnValue QProblemB::setLB( int number, real_t value )
+{
+	if ( ( number >= 0 ) && ( number < getNV( ) ) )
+	{
+		lb[number] = value;
+		return SUCCESSFUL_RETURN;
+	}
+	else
+	{
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+	}
+}
+
+
+/*
+ *	s e t U B
+ */
+inline returnValue QProblemB::setUB( const real_t* const ub_new )
+{
+	int i;
+
+	int nV = getNV();
+
+	for( i=0; i<nV; ++i )
+		ub[i] = ub_new[i];
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s e t U B
+ */
+inline returnValue QProblemB::setUB( int number, real_t value )
+{
+	if ( ( number >= 0 ) && ( number < getNV( ) ) )
+	{
+		ub[number] = value;
+
+		return SUCCESSFUL_RETURN;
+	}
+	else
+	{
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+	}
+}
+
+
+/*
+ *	c o m p u t e G i v e n s
+ */
+inline void QProblemB::computeGivens(	real_t xold, real_t yold, real_t& xnew, real_t& ynew,
+										real_t& c, real_t& s 
+										) const
+{
+    if ( getAbs( yold ) <= ZERO )
+	{
+        c = 1.0;
+        s = 0.0;
+		
+		xnew = xold;
+		ynew = yold;
+	}
+    else
+	{
+		real_t t, mu;
+
+        mu = getAbs( xold );
+		if ( getAbs( yold ) > mu )
+			mu = getAbs( yold );
+		
+        t = mu * sqrt( (xold/mu)*(xold/mu) + (yold/mu)*(yold/mu) );
+		
+		if ( xold < 0.0 )
+            t = -t;
+		
+        c = xold/t;
+        s = yold/t;
+        xnew = t;
+        ynew = 0.0;
+	}
+	
+	return;
+}
+
+		
+/*
+ *	a p p l y G i v e n s
+ */
+inline void QProblemB::applyGivens(	real_t c, real_t s, real_t xold, real_t yold,
+									real_t& xnew, real_t& ynew 
+									) const
+{
+	/* Usual Givens plane rotation requiring four multiplications. */
+	xnew =  c*xold + s*yold;
+	ynew = -s*xold + c*yold;
+// 	double nu = s/(1.0+c);
+// 
+// 	xnew = xold*c + yold*s;
+// 	ynew = (xnew+xold)*nu - yold;
+	
+	return;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/SubjectTo.cpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/SubjectTo.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..371f0d76d3278143bcdcd786bfb7b755d49de50d
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/SubjectTo.cpp
@@ -0,0 +1,200 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/SubjectTo.cpp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of the SubjectTo class designed to manage working sets of
+ *	constraints and bounds within a QProblem.
+ */
+
+
+#include <SubjectTo.hpp>
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+
+
+/*
+ *	S u b j e c t T o
+ */
+SubjectTo::SubjectTo( ) :	noLower( BT_TRUE ),
+							noUpper( BT_TRUE ),
+							size( 0 )
+{
+	int i;
+
+	for( i=0; i<size; ++i )
+	{
+		type[i] = ST_UNKNOWN;
+		status[i] = ST_UNDEFINED;
+	}
+}
+
+
+/*
+ *	S u b j e c t T o
+ */
+SubjectTo::SubjectTo( const SubjectTo& rhs ) :	noLower( rhs.noLower ),
+												noUpper( rhs.noUpper ),
+												size( rhs.size )
+{
+	int i;
+
+	for( i=0; i<size; ++i )
+	{
+		type[i] = rhs.type[i];
+		status[i] = rhs.status[i];
+	}
+}
+
+
+/*
+ *	~ S u b j e c t T o
+ */
+SubjectTo::~SubjectTo( )
+{
+}
+
+
+/*
+ *	o p e r a t o r =
+ */
+SubjectTo& SubjectTo::operator=( const SubjectTo& rhs )
+{
+	int i;
+
+	if ( this != &rhs )
+	{
+		size = rhs.size;
+
+		for( i=0; i<size; ++i )
+		{
+			type[i] = rhs.type[i];
+			status[i] = rhs.status[i];
+		}
+
+		noLower = rhs.noLower;
+		noUpper = rhs.noUpper;
+	}
+
+	return *this;
+}
+
+
+
+/*
+ *	i n i t
+ */
+returnValue SubjectTo::init( int n )
+{
+	int i;
+
+	size = n;
+
+	noLower = BT_TRUE;
+	noUpper = BT_TRUE;
+
+	for( i=0; i<size; ++i )
+	{
+		type[i] = ST_UNKNOWN;
+		status[i] = ST_UNDEFINED;
+	}
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+
+/*****************************************************************************
+ *  P R O T E C T E D                                                        *
+ *****************************************************************************/
+
+/*
+ *	a d d I n d e x
+ */
+returnValue SubjectTo::addIndex(	Indexlist* const indexlist,
+									int newnumber, SubjectToStatus newstatus
+									)
+{
+	/* consistency check */
+	if ( status[newnumber] == newstatus )
+		return THROWERROR( RET_INDEX_ALREADY_OF_DESIRED_STATUS );
+
+	status[newnumber] = newstatus;
+
+	if ( indexlist->addNumber( newnumber ) == RET_INDEXLIST_EXCEEDS_MAX_LENGTH )
+		return THROWERROR( RET_ADDINDEX_FAILED );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	r e m o v e I n d e x
+ */
+returnValue SubjectTo::removeIndex(	Indexlist* const indexlist, 
+									int removenumber
+									)
+{
+	status[removenumber] = ST_UNDEFINED;
+
+	if ( indexlist->removeNumber( removenumber ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_UNKNOWN_BUG );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	s w a p I n d e x
+ */
+returnValue SubjectTo::swapIndex(	Indexlist* const indexlist,
+									int number1, int number2
+									)
+{
+	/* consistency checks */
+	if ( status[number1] != status[number2] )
+		return THROWERROR( RET_SWAPINDEX_FAILED );
+
+	if ( number1 == number2 )
+	{
+		THROWWARNING( RET_NOTHING_TO_DO );
+		return SUCCESSFUL_RETURN;
+	}
+
+	if ( indexlist->swapNumbers( number1,number2 ) != SUCCESSFUL_RETURN )
+		return THROWERROR( RET_SWAPINDEX_FAILED );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/SubjectTo.ipp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/SubjectTo.ipp
new file mode 100644
index 0000000000000000000000000000000000000000..32215ba7e458552ffa734b57b59d220ee11bc02d
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/SubjectTo.ipp
@@ -0,0 +1,132 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/SubjectTo.ipp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of the inlined member functions of the SubjectTo class 
+ *	designed to manage working sets of constraints and bounds within a QProblem.
+ */
+
+
+/*****************************************************************************
+ *  P U B L I C                                                              *
+ *****************************************************************************/
+ 
+
+/*
+ *	g e t T y p e
+ */
+inline SubjectToType SubjectTo::getType( int i ) const
+{
+	if ( ( i >= 0 ) && ( i < size ) )
+		return type[i];
+	else
+		return ST_UNKNOWN;
+}
+
+
+/*
+ *	g e t S t a t u s
+ */
+inline SubjectToStatus SubjectTo::getStatus( int i ) const
+{
+	if ( ( i >= 0 ) && ( i < size ) )
+		return status[i];
+	else
+		return ST_UNDEFINED;
+}
+
+
+/*
+ *	s e t T y p e
+ */
+inline returnValue SubjectTo::setType( int i, SubjectToType value )
+{
+	if ( ( i >= 0 ) && ( i < size ) )
+	{
+		type[i] = value;
+		return SUCCESSFUL_RETURN;
+	}
+	else
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+}
+
+
+/*
+ *	s e t S t a t u s
+ */
+inline returnValue SubjectTo::setStatus( int i, SubjectToStatus value )
+{
+	if ( ( i >= 0 ) && ( i < size ) )
+	{
+		status[i] = value;
+		return SUCCESSFUL_RETURN;
+	}
+	else
+		return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
+}
+
+
+/*
+ *	s e t N o L o w e r
+ */
+inline void SubjectTo::setNoLower( BooleanType _status )
+{
+	noLower = _status;
+}
+ 
+
+/*
+ *	s e t N o U p p e r
+ */
+inline void SubjectTo::setNoUpper( BooleanType _status )
+{
+	noUpper = _status;
+}
+
+
+/*
+ *	i s N o L o w e r
+ */
+inline BooleanType SubjectTo::isNoLower( ) const
+{
+	return noLower;
+}
+
+ 
+/*
+ *	i s N o L o w e r
+ */
+inline BooleanType SubjectTo::isNoUpper( ) const
+{
+	return noUpper;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Utils.cpp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Utils.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..c11722c4797d99c4dd90f794eb3d880a54eb14d2
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Utils.cpp
@@ -0,0 +1,471 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+/**
+ *	\file SRC/Utils.cpp
+ *	\author Hans Joachim Ferreau, Eckhard Arnold
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of some inlined utilities for working with the different QProblem
+ *  classes.
+ */
+
+
+#include <math.h>
+
+#if defined(__WIN32__) || defined(WIN32)
+  #include <windows.h>
+#elif defined(LINUX)
+  #include <sys/stat.h>
+  #include <sys/time.h>
+#endif
+
+#ifdef __MATLAB__
+  #include <mex.h>
+#endif
+
+
+#include <Utils.hpp>
+
+
+
+#ifdef PC_DEBUG  /* Define print functions only for debugging! */
+/*
+ *	p r i n t
+ */
+returnValue print( const real_t* const v, int n )
+{
+	int i;
+	char myPrintfString[160];
+
+	/* Print a vector. */
+	myPrintf( "[\t" );
+	for( i=0; i<n; ++i )
+	{
+		sprintf( myPrintfString," %.16e\t", v[i] );
+		myPrintf( myPrintfString );
+	}
+	myPrintf( "]\n" );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	p r i n t
+ */
+returnValue print(	const real_t* const v, int n,
+					const int* const V_idx
+					)
+{
+	int i;
+	char myPrintfString[160];
+
+	/* Print a permuted vector. */
+	myPrintf( "[\t" );
+	for( i=0; i<n; ++i )
+	{
+		sprintf( myPrintfString," %.16e\t", v[ V_idx[i] ] );
+		myPrintf( myPrintfString );
+	}
+	myPrintf( "]\n" );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	p r i n t
+ */
+returnValue print(	const real_t* const v, int n,
+					const char* name
+					)
+{
+	char myPrintfString[160];
+
+	/* Print vector name ... */
+	sprintf( myPrintfString,"%s = ", name );
+	myPrintf( myPrintfString );
+
+	/* ... and the vector itself. */
+	return print( v, n );
+}
+
+
+/*
+ *	p r i n t
+ */
+returnValue print( const real_t* const M, int nrow, int ncol )
+{
+	int i;
+
+	/* Print a matrix as a collection of row vectors. */
+	for( i=0; i<nrow; ++i )
+		print( &(M[i*ncol]), ncol );
+	myPrintf( "\n" );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	p r i n t
+ */
+returnValue print(	const real_t* const M, int nrow, int ncol,
+					const int* const ROW_idx, const int* const COL_idx
+					)
+{
+	int i;
+
+	/* Print a permuted matrix as a collection of permuted row vectors. */
+	for( i=0; i<nrow; ++i )
+		print( &( M[ ROW_idx[i]*ncol ] ), ncol, COL_idx );
+	myPrintf( "\n" );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	p r i n t
+ */
+returnValue print(	const real_t* const M, int nrow, int ncol,
+					const char* name
+					)
+{
+	char myPrintfString[160];
+
+	/* Print matrix name ... */
+	sprintf( myPrintfString,"%s = ", name );
+	myPrintf( myPrintfString );
+
+	/* ... and the matrix itself. */
+	return print( M, nrow, ncol );
+}
+
+
+/*
+ *	p r i n t
+ */
+returnValue print( const int* const index, int n )
+{
+	int i;
+	char myPrintfString[160];
+
+	/* Print a indexlist. */
+	myPrintf( "[\t" );
+	for( i=0; i<n; ++i )
+	{
+		sprintf( myPrintfString," %d\t", index[i] );
+		myPrintf( myPrintfString );
+	}
+	myPrintf( "]\n" );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	p r i n t
+ */
+returnValue print(	const int* const index, int n,
+					const char* name
+					)
+{
+	char myPrintfString[160];
+
+	/* Print indexlist name ... */
+	sprintf( myPrintfString,"%s = ", name );
+	myPrintf( myPrintfString );
+
+	/* ... and the indexlist itself. */
+	return print( index, n );
+}
+
+
+/*
+ *	m y P r i n t f
+ */
+returnValue myPrintf( const char* s )
+{
+	#ifdef __MATLAB__
+	mexPrintf( s );
+	#else
+	myFILE* outputfile = getGlobalMessageHandler( )->getOutputFile( );
+	if ( outputfile == 0 )
+		return THROWERROR( RET_NO_GLOBAL_MESSAGE_OUTPUTFILE );
+
+	fprintf( outputfile, "%s", s );
+	#endif
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	p r i n t C o p y r i g h t N o t i c e
+ */
+returnValue printCopyrightNotice( )
+{
+	return myPrintf( "\nqpOASES -- An Implementation of the Online Active Set Strategy.\nCopyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.\n\nqpOASES is distributed under the terms of the \nGNU Lesser General Public License 2.1 in the hope that it will be \nuseful, but WITHOUT ANY WARRANTY; without even the implied warranty \nof MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. \nSee the GNU Lesser General Public License for more details.\n\n" );
+}
+
+
+/*
+ *	r e a d F r o m F i l e
+ */
+returnValue readFromFile(	real_t* data, int nrow, int ncol,
+							const char* datafilename
+							)
+{
+	int i, j;
+	float float_data;
+	myFILE* datafile;
+
+	/* 1) Open file. */
+	if ( ( datafile = fopen( datafilename, "r" ) ) == 0 )
+	{
+		char errstr[80];
+		sprintf( errstr,"(%s)",datafilename );
+		return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+	}
+
+	/* 2) Read data from file. */
+	for( i=0; i<nrow; ++i )
+	{
+		for( j=0; j<ncol; ++j )
+		{
+			if ( fscanf( datafile, "%f ", &float_data ) == 0 )
+			{
+				fclose( datafile );
+				char errstr[80];
+				sprintf( errstr,"(%s)",datafilename );
+				return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_READ_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+			}
+			data[i*ncol + j] = ( (real_t) float_data );
+		}
+	}
+
+	/* 3) Close file. */
+	fclose( datafile );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	r e a d F r o m F i l e
+ */
+returnValue readFromFile(	real_t* data, int n,
+							const char* datafilename
+							)
+{
+	return readFromFile( data, n, 1, datafilename );
+}
+
+
+
+/*
+ *	r e a d F r o m F i l e
+ */
+returnValue readFromFile(	int* data, int n,
+							const char* datafilename
+							)
+{
+	int i;
+	myFILE* datafile;
+
+	/* 1) Open file. */
+	if ( ( datafile = fopen( datafilename, "r" ) ) == 0 )
+	{
+		char errstr[80];
+		sprintf( errstr,"(%s)",datafilename );
+		return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+	}
+
+	/* 2) Read data from file. */
+	for( i=0; i<n; ++i )
+	{
+		if ( fscanf( datafile, "%d\n", &(data[i]) ) == 0 )
+		{
+			fclose( datafile );
+			char errstr[80];
+			sprintf( errstr,"(%s)",datafilename );
+			return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_READ_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		}
+	}
+
+	/* 3) Close file. */
+	fclose( datafile );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	w r i t e I n t o F i l e
+ */
+returnValue writeIntoFile(	const real_t* const data, int nrow, int ncol,
+							const char* datafilename, BooleanType append
+							)
+{
+	int i, j;
+	myFILE* datafile;
+
+	/* 1) Open file. */
+	if ( append == BT_TRUE )
+	{
+		/* append data */
+		if ( ( datafile = fopen( datafilename, "a" ) ) == 0 )
+		{
+			char errstr[80];
+			sprintf( errstr,"(%s)",datafilename );
+			return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		}
+	}
+	else
+	{
+		/* do not append data */
+		if ( ( datafile = fopen( datafilename, "w" ) ) == 0 )
+		{
+			char errstr[80];
+			sprintf( errstr,"(%s)",datafilename );
+			return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		}
+	}
+
+	/* 2) Write data into file. */
+	for( i=0; i<nrow; ++i )
+	{
+		for( j=0; j<ncol; ++j )
+		 	fprintf( datafile, "%.16e ", data[i*ncol+j] );
+
+		fprintf( datafile, "\n" );
+	}
+
+	/* 3) Close file. */
+	fclose( datafile );
+
+	return SUCCESSFUL_RETURN;
+}
+
+
+/*
+ *	w r i t e I n t o F i l e
+ */
+returnValue writeIntoFile(	const real_t* const data, int n,
+							const char* datafilename, BooleanType append
+							)
+{
+	return writeIntoFile( data,1,n,datafilename,append );
+}
+
+
+/*
+ *	w r i t e I n t o F i l e
+ */
+returnValue writeIntoFile(	const int* const data, int n,
+							const char* datafilename, BooleanType append
+							)
+{
+	int i;
+
+	myFILE* datafile;
+
+	/* 1) Open file. */
+	if ( append == BT_TRUE )
+	{
+		/* append data */
+		if ( ( datafile = fopen( datafilename, "a" ) ) == 0 )
+		{
+			char errstr[80];
+			sprintf( errstr,"(%s)",datafilename );
+			return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		}
+	}
+	else
+	{
+		/* do not append data */
+		if ( ( datafile = fopen( datafilename, "w" ) ) == 0 )
+		{
+			char errstr[80];
+			sprintf( errstr,"(%s)",datafilename );
+			return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE );
+		}
+	}
+
+	/* 2) Write data into file. */
+	for( i=0; i<n; ++i )
+		fprintf( datafile, "%d\n", data[i] );
+
+	/* 3) Close file. */
+	fclose( datafile );
+
+	return SUCCESSFUL_RETURN;
+}
+#endif  /* PC_DEBUG */
+
+
+/*
+ *	g e t C P U t i m e
+ */
+real_t getCPUtime( )
+{
+	real_t current_time = -1.0;
+
+	#if defined(__WIN32__) || defined(WIN32)
+	LARGE_INTEGER counter, frequency;
+	QueryPerformanceFrequency(&frequency);
+	QueryPerformanceCounter(&counter);
+	current_time = ((real_t) counter.QuadPart) / ((real_t) frequency.QuadPart);
+	#elif defined(LINUX)
+	struct timeval theclock;
+	gettimeofday( &theclock,0 );
+	current_time = 1.0*theclock.tv_sec + 1.0e-6*theclock.tv_usec;
+	#endif
+
+	return current_time;
+}
+
+
+/*
+ *	g e t N o r m
+ */
+real_t getNorm( const real_t* const v, int n )
+{
+	int i;
+
+	real_t norm = 0.0;
+
+	for( i=0; i<n; ++i )
+		norm += v[i]*v[i];
+
+	return sqrt( norm );
+}
+
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Utils.ipp b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Utils.ipp
new file mode 100644
index 0000000000000000000000000000000000000000..861bdb3726717da533849c02f0e16f516d182ce7
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/SRC/Utils.ipp
@@ -0,0 +1,51 @@
+/*
+ *	This file is part of qpOASES.
+ *
+ *	qpOASES -- An Implementation of the Online Active Set Strategy.
+ *	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+ *
+ *	qpOASES is free software; you can redistribute it and/or
+ *	modify it under the terms of the GNU Lesser General Public
+ *	License as published by the Free Software Foundation; either
+ *	version 2.1 of the License, or (at your option) any later version.
+ *
+ *	qpOASES is distributed in the hope that it will be useful,
+ *	but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ *	Lesser General Public License for more details.
+ *
+ *	You should have received a copy of the GNU Lesser General Public
+ *	License along with qpOASES; if not, write to the Free Software
+ *	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ */
+
+
+
+/**
+ *	\file SRC/Utils.ipp
+ *	\author Hans Joachim Ferreau
+ *	\version 1.3embedded
+ *	\date 2007-2008
+ *
+ *	Implementation of some inlined utilities for working with the different QProblem 
+ *  classes.
+ */
+
+
+
+/*
+ *	g e t A b s
+ */
+inline real_t getAbs( real_t x )
+{
+	if ( x < 0.0 )
+		return -x;
+	else
+		return x;
+}
+
+
+/*
+ *	end of file
+ */
diff --git a/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/VERSIONS.txt b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/VERSIONS.txt
new file mode 100644
index 0000000000000000000000000000000000000000..35a6740b142fb59d8bef519dfbd5457301189a0b
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/solver_made_from_cpp/qpoases/VERSIONS.txt
@@ -0,0 +1,87 @@
+##
+##	qpOASES -- An Implementation of the Online Active Set Strategy.
+##	Copyright (C) 2007-2008 by Hans Joachim Ferreau et al. All rights reserved.
+##
+##	qpOASES is free software; you can redistribute it and/or
+##	modify it under the terms of the GNU Lesser General Public
+##	License as published by the Free Software Foundation; either
+##	version 2.1 of the License, or (at your option) any later version.
+##
+##	qpOASES is distributed in the hope that it will be useful,
+##	but WITHOUT ANY WARRANTY; without even the implied warranty of
+##	MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+##	Lesser General Public License for more details.
+##
+##	You should have received a copy of the GNU Lesser General Public
+##	License along with qpOASES; if not, write to the Free Software
+##	Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
+##
+
+
+
+VERSION HISTORY
+===============
+
+1.3embedded (last updated on 30th April 2009):
+-----------------------------------------------------------------------
+
++ Re-programming of internal memory management to avoid dynamic memory allocations 
++ Most #ifdef directives removed
++ Almost all type definitions gathered within INCLUDE/Types.hpp
++ Irrelevant functionality removed (like the SQProblem class, functionality 
+  for loading data from files or the SCILAB interface)
++ Replacement of all doubles by real_t
++ Introduction of define "PC_DEBUG" for switching off all print functions
++ stdio.h was made optional, string.h is no longer needed
++ relative paths removed from #include directives
++ made auxiliary objects locally static within solveInitialQP()
++ Matlab interface fixed for single precision
++ New return value -2 from Legacy wrapper added to Matlab/Simulink interfaces
++ KKT optimality check moved into QProblem(B) class, SolutionAnalysis class removed
+
+
+1.3 (released on 2nd June 2008, last updated on 19th June 2008):
+-----------------------------------------------------------------------
+
++ Implementation of "initialised homotopy" concept
++ Addition of the SolutionAnalysis class
++ Utility functions for solving test problems in OQP format added
++ Flexibility of Matlab(R) interface enhanced
++ Major source code cleanup
+  (Attention: a few class names and calling interfaces have changed!)
+
+
+
+1.2 (released on 9th October 2007):
+-----------------------------------------------------------------------
+
++ Special treatment of diagonal Hessians
++ Improved infeasibility detection
++ Further improved Matlab(R) interface
++ Extended Simulink(R) interface
++ scilab interface added
++ Code cleanup and several bugfixes
+
+
+
+1.1 (released on 8th July 2007):
+--------------------------------
+
++ Implementation of the QProblemB class
++ Basic implementation of the SQProblem class
++ Improved Matlab(R) interface
++ Enabling/Disabling of constraints introduced
++ Several bugfixes
+
+
+
+1.0 (released on 17th April 2007):
+----------------------------------
+
+Initial release.
+
+
+
+##
+##	end of file
+##
diff --git a/mav_control_rw/mav_nonlinear_mpc/src/nonlinear_mpc.cc b/mav_control_rw/mav_nonlinear_mpc/src/nonlinear_mpc.cc
new file mode 100644
index 0000000000000000000000000000000000000000..9cfab0bb29343e55e45a691dda07fad7ce4051da
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/src/nonlinear_mpc.cc
@@ -0,0 +1,287 @@
+#include <tf/transform_datatypes.h>
+#include <mav_nonlinear_mpc/nonlinear_mpc.h>
+
+/* Some convenient definitions. */
+#define NX          ACADO_NX  /* Number of differential state variables.  */
+#define NXA         ACADO_NXA /* Number of algebraic variables. */
+#define NU          ACADO_NU  /* Number of control inputs. */
+#define NOD         ACADO_NOD  /* Number of online data values. */
+
+#define NY          ACADO_NY  /* Number of measurements/references on nodes 0..N - 1. */
+#define NYN         ACADO_NYN /* Number of measurements/references on node N. */
+
+#define N           ACADO_N   /* Number of intervals in the horizon. */
+
+#define VERBOSE     1         /* Show iterations: 1, silent: 0.  */
+
+namespace mav_control {
+
+NonlinearModelPredictiveControl::NonlinearModelPredictiveControl(ros::NodeHandle& nh,
+                                                                 const ros::NodeHandle& private_nh)
+    : nh_(nh),
+      private_nh_(private_nh)
+{
+	/* Some variables. */
+	double forward_acc_ref, angular_acc_ref, new_forward_vel, new_angular_vel;
+	acado_timer t;
+
+	/* Create publisher for moving husky */
+	ros::Publisher pub=nh.advertise<geometry_msgs::Twist>("/husky_velocity_controller/cmd_vel", 1);
+	srand(time(0));
+	ros::Rate rate(2.5);
+
+	/* Create subscriber for goal position */
+	ros::Subscriber sub_goal = nh.subscribe("/move_base_simple/goal", 1,
+											&NonlinearModelPredictiveControl::goalCallback, this);
+
+	/* Create subscriber for scan data */
+	ros::Subscriber sub_scan = nh.subscribe("/scan", 1,
+											&NonlinearModelPredictiveControl::scanCallback, this);
+
+
+	/* Create service for husky position */
+	ros::ServiceClient husky_position = nh.serviceClient<gazebo_msgs::GetModelState>("/gazebo/get_model_state");
+	gazebo_msgs::GetModelState husky_state;
+	husky_state.request.model_name = (std::string)("husky");
+
+	/* Initialize solver and initial values for state variables */
+	this->initializeSolver();
+
+	/* Real-time loop */
+	while (ros::ok())
+	{
+		/* Get the time at the start of the loop. */
+		acado_tic( &t );
+		/* Perform the feedback step. */
+		std::cout << "Feedback status: "
+				  << acado_feedbackStep() << std::endl;
+
+		/* Read reference variables */
+		forward_acc_ref = acadoVariables.u[0];
+		angular_acc_ref = acadoVariables.u[1];
+		/* Calculate new forward and angular velocities */
+		new_forward_vel = acadoVariables.x0[3] + 0.2*forward_acc_ref;
+		new_angular_vel = acadoVariables.x0[4] + 0.2*angular_acc_ref;
+		/* Move the Husky */
+		geometry_msgs::Twist msg;
+		msg.linear.x = new_forward_vel;
+		msg.angular.z = new_angular_vel;
+		pub.publish(msg);
+
+		/* Get Husky position */
+		if (husky_position.call(husky_state))
+		{
+			husky_x = husky_state.response.pose.position.x;
+			husky_y = husky_state.response.pose.position.y;
+
+			/* Get Husky yaw angle */
+			tf::Pose pose;
+			tf::poseMsgToTF(husky_state.response.pose, pose);
+			yaw_angle = tf::getYaw(pose.getRotation());
+
+			/* Set next initial state */
+			acadoVariables.x0[0] = husky_x;
+			acadoVariables.x0[1] = husky_y;
+			acadoVariables.x0[2] = yaw_angle;
+			acadoVariables.x0[3] = husky_state.response.twist.linear.x;
+			acadoVariables.x0[4] = husky_state.response.twist.angular.z;
+
+			// Update the reference angle, so it values turning before moving forward
+			angleToGoal = atan2(target_y - husky_y, target_x - husky_x);
+			for (int i = 0; i < N; ++i)
+			{
+				acadoVariables.y[i*NY + 2] = angleToGoal;
+			}
+			acadoVariables.yN[2] = angleToGoal;
+
+			/* Prints */
+			if ( VERBOSE )
+			printInformation();
+
+			/* Update LSQ matrices, value correct heading less the closer to the target it is */
+			this->updateWeightingMatrices();
+
+			acado_preparationStep();
+
+			// Spin once, needed for communication
+			ros::spinOnce();
+			//Delays until it is time to send another message
+			rate.sleep();
+		}
+
+		/* Read the elapsed time. */
+		real_t te = acado_toc( &t );
+		/* Eye-candy. */
+		if( VERBOSE )
+		printf("\n\nAverage time of one real-time iteration:   %.2f seconds\n\n", te);
+	}
+
+	if( VERBOSE ) printf("\n\nEnd of the RTI loop. \n\n\n");
+}
+
+NonlinearModelPredictiveControl::~NonlinearModelPredictiveControl() { }
+
+void NonlinearModelPredictiveControl::initializeSolver()
+{
+	int i;
+
+	/* Clear solver memory */
+	memset(&acadoWorkspace, 0, sizeof( acadoWorkspace ));
+    memset(&acadoVariables, 0, sizeof( acadoVariables ));
+
+	/* Initialize the solver. */
+	acado_initializeSolver();
+
+	/* Initialize the states and controls. */
+	for (i = 0; i < NX * (N + 1); ++i)  acadoVariables.x[ i ] = 0.0;
+	for (i = 0; i < NU * N; ++i)  acadoVariables.u[ i ] = 0.0;
+
+	/* Initialize the measurements/reference. */
+	for (i = 0; i < NY * N; ++i)  acadoVariables.y[ i ] = 0.0;
+	for (i = 0; i < NYN; ++i)  acadoVariables.yN[ i ] = 0.0;
+
+	/* MPC: initialize the current state feedback. */
+	for (i = 0; i < NX; ++i) acadoVariables.x0[ i ] = 0.0;
+
+	/* Set the initial goal states */
+	acadoVariables.yN[0] = target_x;
+	acadoVariables.yN[1] = target_y;
+	for (i = 0; i < N; ++i)
+	{
+		acadoVariables.y[i*NY] = target_x;
+		acadoVariables.y[i*NY + 1] = target_y;
+	}
+
+	// Set the reference angle, so it values turning before moving forward
+	angleToGoal = atan2(target_y - husky_y, target_x - husky_x);
+	originalGoalDist = sqrt(powf(husky_y - target_y, 2) + powf(husky_x - target_x, 2));
+	acadoVariables.yN[2] = angleToGoal;
+	for (i = 0; i < N; ++i)
+	{
+		acadoVariables.y[i*NY + 2] = angleToGoal;
+	}
+
+	for (i = 0; i < (N + 1); ++i)
+	{
+		for (int j = 0; j < NOD; ++j)
+		{
+			acadoVariables.od[i*NOD + j] = 0.0;
+		}
+	}
+
+	if( VERBOSE ) acado_printHeader();
+
+	/* Prepare first step */
+	acado_preparationStep();
+}
+
+void NonlinearModelPredictiveControl::updateWeightingMatrices()
+{
+	/* Calculate distance */
+	distToGoal = sqrt(powf(husky_y - target_y, 2) + powf(husky_x - target_x, 2));
+
+	/*
+	Weight for heading is dynamic depending on distance to goal.
+	If we are very close to the goal, we don't care about the heading.
+	If we are far away, we want to value turning before going forward.
+	*/
+	for (int i = 0; i < N; ++i)
+	{
+		acadoVariables.W[i*NY*NY] = 10.0;
+		acadoVariables.W[i*NY*NY + 1*NY + 1] = 10.0;
+		acadoVariables.W[i*NY*NY + 2*NY + 2] = 1.0;
+		acadoVariables.W[i*NY*NY + 3*NY + 3] = 1.0;
+		acadoVariables.W[i*NY*NY + 4*NY + 4] = 1.0;
+		acadoVariables.W[i*NY*NY + 5*NY + 5] = 1.0;
+		acadoVariables.W[i*NY*NY + 6*NY + 6] = 1.0;
+		acadoVariables.W[i*NY*NY + 7*NY + 7] = 0.1;
+	}
+	acadoVariables.WN[0] = 1.0;
+	acadoVariables.WN[1*NYN + 1] = 1.0;
+	acadoVariables.WN[2*NYN + 2] = 1.0;
+	acadoVariables.WN[3*NYN + 3] = 0.1;
+	acadoVariables.WN[4*NYN + 4] = 0.1;
+}
+
+void NonlinearModelPredictiveControl::goalCallback(const geometry_msgs::PoseStamped::ConstPtr& msg)
+{
+	/* Read new target position */
+  	target_x = msg->pose.position.x;
+  	target_y = msg->pose.position.y;
+
+	/* Print new goal position */
+  	std::cout << "New Goal Position: "
+			  << target_x << " " << target_y << std::endl;
+
+	/* Update the objective variables */
+	for (int i = 0; i < N; ++i)
+	{
+		acadoVariables.y[i*NY] = target_x;
+		acadoVariables.y[i*NY + 1] = target_y;
+	}
+  	acadoVariables.yN[0] = target_x;
+  	acadoVariables.yN[1] = target_y;
+	originalGoalDist = sqrt(powf(husky_y - target_y, 2) + powf(husky_x - target_x, 2));
+}
+
+void NonlinearModelPredictiveControl::printInformation()
+{
+	/* Show acceleration variables */
+	acado_printDifferentialVariables();
+	acado_printControlVariables();
+
+	/* Print objective value */
+	std::cout << "Objective Value:"
+			  << std::to_string(acado_getObjective()) << std::endl;
+
+	/* Print information relating to the Husky and the goal */
+	std::cout << "Husky Forward Velocity: "
+			  << acadoVariables.x0[3] << std::endl;
+	std::cout << "Husky Position: "
+			  << husky_x << " " << husky_y << std::endl;
+	std::cout << "Goal Position: "
+			  << target_x << " " << target_y << std::endl;
+	std::cout << "Husky Yaw: "
+			  << yaw_angle << std::endl;
+	std::cout << "Angle To Goal: "
+			  << angleToGoal << std::endl;
+	std::cout << "Distance To Goal: "
+			  << distToGoal << std::endl;
+}
+
+void NonlinearModelPredictiveControl::scanCallback(const sensor_msgs::LaserScan::ConstPtr& msg)
+{
+    std::cout << "\nLaser Scan: " << std::endl;
+
+    int sector_size = msg->ranges.size() / (NOD/2);
+	int i, j, ts, index;
+	float min_value, range, angle_of_min, x, y;
+    for (i = 0; i < NOD/2; ++i)
+	{
+		// Find angle to and position of nearest point in sector
+        index = sector_size*i;
+        min_value = SCAN_MAX_VALUE;
+		angle_of_min = 0;
+        for (j = index; j < index + sector_size && j < msg->ranges.size(); ++j)
+		{
+			range = std::min(msg->ranges[j], min_value);
+            if (range <= min_value)
+			{
+				min_value = range;
+				angle_of_min = msg->angle_min + msg->angle_increment*j;
+			}
+        }
+		// Calculate position of nearest point and save to OnlineData array
+		x = husky_x + cos(yaw_angle + angle_of_min)*min_value;
+		y = husky_y + sin(yaw_angle + angle_of_min)*min_value;
+		for (ts = 0; ts < N; ++ts)
+		{
+			acadoVariables.od[ts*NOD + i] = x;
+			acadoVariables.od[ts*NOD + NOD/2 + i] = y;
+		}
+		std::cout << "Dist: " << min_value << " x: " << x << " y: " << y << std::endl;
+    }
+}
+
+
+};
diff --git a/mav_control_rw/mav_nonlinear_mpc/src/nonlinear_mpc_node.cc b/mav_control_rw/mav_nonlinear_mpc/src/nonlinear_mpc_node.cc
new file mode 100644
index 0000000000000000000000000000000000000000..3374dd042f6967e9daadc6d2828f21bee6436d4c
--- /dev/null
+++ b/mav_control_rw/mav_nonlinear_mpc/src/nonlinear_mpc_node.cc
@@ -0,0 +1,33 @@
+#include <ros/ros.h>
+#include <mav_nonlinear_mpc/nonlinear_mpc_node.h>
+
+namespace mav_control {
+
+NonLinearModelPredictiveControllerNode::NonLinearModelPredictiveControllerNode(
+    ros::NodeHandle& nh, const ros::NodeHandle& private_nh)
+    : nonlinear_mpc_(nh, private_nh),
+      controller_dyn_config_server_(private_nh)
+{
+
+}
+
+NonLinearModelPredictiveControllerNode::~NonLinearModelPredictiveControllerNode()
+{
+
+}
+
+};
+
+int main(int argc, char** argv)
+{
+  ros::init(argc, argv, "NonLinearModelPredictiveControllerNode");
+
+  ros::NodeHandle nh, private_nh("~");
+
+  std::shared_ptr<mav_control::NonLinearModelPredictiveControllerNode> mpc(
+      new mav_control::NonLinearModelPredictiveControllerNode(nh, private_nh));
+
+  ros::spin();
+
+  return 0;
+}