Updated simulator with plant time publishing and communication

This commit is contained in:
Nimesh Khandelwal 2024-03-18 15:51:40 -04:00
parent 583330f3ab
commit 8547fe8b10
281 changed files with 124633 additions and 40 deletions

View File

@ -32,18 +32,23 @@ public:
void setJoystickDataPtr(QuadrupedJoystickData* joystick_data_ptr) {
m_joystick_data_ptr = joystick_data_ptr;
}
void setPlantTimePtr(double* time_ptr) {
m_plant_time_ptr = time_ptr;
}
void writeSensorData(const QuadrupedSensorData& sensor_data);
void writeCommandData(const QuadrupedCommandData& cmd_data);
void writeMeasurementData(const QuadrupedMeasurementData& measure_data);
void writeEstimationData(const QuadrupedEstimationData& est_data);
void writeJoystickData(const QuadrupedJoystickData& joy_data);
void writePlantTime(const double& time);
void getSensorData(QuadrupedSensorData& sensor_data);
void getCommandData(QuadrupedCommandData& cmd_data);
void getMeasurememtData(QuadrupedMeasurementData& measure_data);
void getEstimationData(QuadrupedEstimationData& est_data);
void getJoystickData(QuadrupedJoystickData& joy_data);
void getPlantTime(double& time);
void setAccessMode(const DATA_ACCESS_MODE& mode) {
m_mode = mode;
@ -55,6 +60,7 @@ protected:
QuadrupedEstimationData* m_estimation_data_ptr = NULL;
QuadrupedMeasurementData* m_measurement_data_ptr = NULL;
QuadrupedJoystickData* m_joystick_data_ptr = NULL;
double* m_plant_time_ptr = NULL;
int m_mode = DATA_ACCESS_MODE::PLANT;
private:

View File

@ -7,6 +7,16 @@
#include "memory_types.hpp"
#include "utils.hpp"
#include "timer.hpp"
// #include "Iir.h"
#include <qpOASES.hpp>
using namespace qpOASES;
#define MU 0.5
#define GRAVITY 9.8
static const double NEGATIVE_NUMBER = -1000000.0;
static const double POSITIVE_NUMBER = 1000000.0;
class Controller {
public:
@ -16,7 +26,8 @@ public:
~Controller();
vec12 GetDesiredContactForcePGD(const vec6 &b);
vec12 GetDesiredContactForcePGD(const Eigen::MatrixXd& JabT, const vec6 &b);
vec12 getDesiredContactForceqpOASES(const vec6 &b);
virtual vec12 CalculateFeedForwardTorque() {
return vec12::Zero();
@ -76,6 +87,24 @@ protected:
// To read
QuadrupedEstimationData* m_estimation_data_ptr;
QuadrupedPlannerData* m_planner_data_ptr;
void resize_qpOASES_vars();
void resize_eigen_vars();
void update_problem_size();
void print_real_t(real_t *matrix, int nRows, int nCols);
void copy_Eigen_to_real_t(real_t *target, Eigen::MatrixXd &source, int nRows, int nCols);
void copy_real_t_to_Eigen(Eigen::VectorXd &target, real_t *source, int len);
void print_QPData();
Eigen::VectorXd clipVector(const Eigen::VectorXd &b, float F);
void cleanFc(vec12& Fc);
private:
std::string m_name;
@ -89,4 +118,35 @@ private:
bool m_starting_from_sleep = false;
vec12 F_prev;
// float m_loop_rate = 1000;
// Iir::Butterworth::LowPass<2> m_Fc_filter[12];
// qpOASES related variables
real_t *H_qpOASES;
real_t *A_qpOASES;
real_t *g_qpOASES;
real_t *lbA_qpOASES;
real_t *ubA_qpOASES;
real_t *xOpt_qpOASES;
real_t *xOpt_initialGuess;
Eigen::MatrixXd H_eigen, A_eigen, g_eigen, lbA_eigen, ubA_eigen;
Eigen::VectorXd xOpt_eigen;
uint8_t real_allocated, num_vars_qp, num_constr_qp, c_st;
double fz_min, fz_max;
int_t qp_exit_flag;
int_t nWSR_qpOASES;
real_t cpu_time;
};

View File

@ -31,7 +31,7 @@ private:
std::string m_name;
float m_rate = 1000;
float m_dt = 0.001;
float t_curr = 0;
double t_curr = 0;
float t_last = 0;
int delay_ms = 1;
int exec_time_ms = 0;
@ -64,6 +64,7 @@ private:
Gait stance;
Gait trot;
Gait walk;
QuadrupedSensorData m_sensor_data;
QuadrupedCommandData m_cmd_data;
@ -76,4 +77,6 @@ private:
std::chrono::time_point<std::chrono::high_resolution_clock> m_currentTimePoint;
std::chrono::time_point<std::chrono::high_resolution_clock> m_lastTimePoint;
std::thread m_comm_thread;
bool use_plant_time = false;
};

View File

@ -28,6 +28,8 @@ public:
void ShowParams();
void updateInitTime(const float& t0);
Eigen::Array4i GetScheduledContact(const float& t);
float GetStridePhase(const float& t, const int& leg_id);

View File

@ -29,6 +29,7 @@ public:
void setGait(Gait& gait) {
m_gait = gait;
// m_gait.updateInitTime(m_t_curr);
}
void setPlannerDataPtr(QuadrupedPlannerData* pd) {
@ -71,11 +72,11 @@ protected:
double m_a_max_x = 0.2;
double m_a_max_y = 0.2;
double m_a_max_z = 0.2;
double m_a_max_yaw = 1.0;
double m_a_max_yaw = 0.2;
double max_vel_x = 1.0;
double max_vel_y = 1.0;
double max_vel_z = 1.0;
double max_vel_yaw = 3.0;
double max_vel_yaw = 1.0;
double m_loop_rate = 1000;
double m_dt = 0.001;

View File

@ -94,5 +94,13 @@ private:
sensor_msgs::msg::Joy joystick_data;
double m_plant_time = 0;
std_msgs::msg::Float32 plant_time;
rclcpp::Publisher<std_msgs::msg::Float32>::SharedPtr m_plant_time_pub;
rclcpp::Subscription<std_msgs::msg::Float32>::SharedPtr m_plant_time_sub;
void get_plant_time_cb(const std_msgs::msg::Float32::SharedPtr msg);
std::thread m_thread;
};

View File

@ -1,8 +1,10 @@
git submodule update --init --recursive
SOURCE_DIR=$PWD
INSTALL_DIR=$SOURCE_DIR/custom/install
# install eigen3.4
cd $SOURCE_DIR/src/third_party/eigen
git checkout master
mkdir build
cd build
cmake .. -DCMAKE_BUILD_TYPE=Release
@ -12,6 +14,7 @@ make install
# install pinocchio without python and install locally
cd $SOURCE_DIR/src/third_party/pinocchio
git checkout master
mkdir build
cd build
cmake .. -DCMAKE_BUILD_TYPE=Release -DBUILD_UNIT_TESTS=OFF -DBUILD_PYTHON_INTERFACE=OFF -DCMAKE_INSTALL_PREFIX=$INSTALL_DIR
@ -20,6 +23,7 @@ make install
# install mujoco locally
cd $SOURCE_DIR/src/third_party/mujoco
git checkout main
mkdir build
cd build
cmake .. -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=$INSTALL_DIR
@ -27,6 +31,7 @@ cmake --build . -j$(($(nproc) - 2))
make install
cd $SOURCE_DIR/src/third_party/iir
git checkout master
mkdir build
cd build
cmake .. -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=$INSTALL_DIR
@ -34,6 +39,7 @@ make -j$(($(nproc) - 2))
make install
cd $SOURCE_DIR/src/third_party/cyclonedds
git checkout master
mkdir build
cd build
cmake .. -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=$INSTALL_DIR # -DENABLE_TYPE_DISCOVERY=ON -DENABLE_TOPIC_DISCOVERY=ON
@ -41,12 +47,21 @@ cmake --build .
cmake --build . --target install
cd $SOURCE_DIR/src/third_party/cyclonedds-cxx
git checkout master
mkdir build
cd build
cmake .. -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=$INSTALL_DIR -DCMAKE_PREFIX_PATH=$INSTALL_DIR
cmake --build .
cmake --build . --target install
cd $SOURCE_DIR/src/third_party/qpOASES
git checkout master
mkdir build
cd build
cmake .. -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=$INSTALL_DIR
make -j$(($(nproc) - 2))
make install
cd $SOURCE_DIR
# chmod +x compile.sh
# ./compile.sh

View File

@ -28,21 +28,21 @@ elseif($ENV{USE_COMM_TYPE} STREQUAL "ros2")
# find_package(catkin REQUIRED)
# find_package(genmsg REQUIRED)
find_package(rosidl_default_generators REQUIRED)
# find_package(rosidl_default_generators REQUIRED)
# Specify that your package belongs to the rosidl_interface_packages group
# set(ROSIDL_INTERFACE_PACKAGES_GROUP "rosidl_interface_packages" CACHE INTERNAL "")
# set_property(GLOBAL APPEND PROPERTY ${ROSIDL_INTERFACE_PACKAGES_GROUP} ${PROJECT_NAME})
rosidl_generate_interfaces(${PROJECT_NAME}
"msgs/ros/LowCmd.msg"
)
rosidl_get_typesupport_target(cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp")
# rosidl_generate_interfaces(${PROJECT_NAME}
# "msgs/ros/LowCmd.msg"
# )
# rosidl_get_typesupport_target(cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp")
add_custom_target(${PROJECT_NAME}_ros_msgs ALL
DEPENDS ${CMAKE_CURRENT_BINARY_DIR}/rosidl_typesupport_cpp/${PROJECT_NAME}
)
target_link_libraries(${PROJECT_NAME}_ros_msgs "${cpp_typesupport_target}")
# add_custom_target(${PROJECT_NAME}_ros_msgs ALL
# DEPENDS ${CMAKE_CURRENT_BINARY_DIR}/rosidl_typesupport_cpp/${PROJECT_NAME}
# )
# target_link_libraries(${PROJECT_NAME}_ros_msgs "${cpp_typesupport_target}")
# install(DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/rosidl_typesupport_cpp/${PROJECT_NAME}
# DESTINATION ${COMMON_INCLUDE_DIR}
# )

View File

@ -32,18 +32,23 @@ public:
void setJoystickDataPtr(QuadrupedJoystickData* joystick_data_ptr) {
m_joystick_data_ptr = joystick_data_ptr;
}
void setPlantTimePtr(double* time_ptr) {
m_plant_time_ptr = time_ptr;
}
void writeSensorData(const QuadrupedSensorData& sensor_data);
void writeCommandData(const QuadrupedCommandData& cmd_data);
void writeMeasurementData(const QuadrupedMeasurementData& measure_data);
void writeEstimationData(const QuadrupedEstimationData& est_data);
void writeJoystickData(const QuadrupedJoystickData& joy_data);
void writePlantTime(const double& time);
void getSensorData(QuadrupedSensorData& sensor_data);
void getCommandData(QuadrupedCommandData& cmd_data);
void getMeasurememtData(QuadrupedMeasurementData& measure_data);
void getEstimationData(QuadrupedEstimationData& est_data);
void getJoystickData(QuadrupedJoystickData& joy_data);
void getPlantTime(double& time);
void setAccessMode(const DATA_ACCESS_MODE& mode) {
m_mode = mode;
@ -55,6 +60,7 @@ protected:
QuadrupedEstimationData* m_estimation_data_ptr = NULL;
QuadrupedMeasurementData* m_measurement_data_ptr = NULL;
QuadrupedJoystickData* m_joystick_data_ptr = NULL;
double* m_plant_time_ptr = NULL;
int m_mode = DATA_ACCESS_MODE::PLANT;
private:

View File

@ -94,5 +94,13 @@ private:
sensor_msgs::msg::Joy joystick_data;
double m_plant_time = 0;
std_msgs::msg::Float32 plant_time;
rclcpp::Publisher<std_msgs::msg::Float32>::SharedPtr m_plant_time_pub;
rclcpp::Subscription<std_msgs::msg::Float32>::SharedPtr m_plant_time_sub;
void get_plant_time_cb(const std_msgs::msg::Float32::SharedPtr msg);
std::thread m_thread;
};

View File

@ -119,4 +119,24 @@ void CommunicationManager::getJoystickData(QuadrupedJoystickData& joy_data) {
std::cout << "Memory not initialized. Cannot read.\n";
}
joy_data.copy(*m_joystick_data_ptr);
}
void CommunicationManager::getPlantTime(double& time) {
if (m_plant_time_ptr != NULL) {
time = *m_plant_time_ptr;
} else {
std::cout << "Time pointer set to NULL.\n";
}
}
void CommunicationManager::writePlantTime(const double& time) {
if (m_mode == DATA_ACCESS_MODE::EXECUTOR) {
std::cout << "Access mode executor. Cannot set time.\n";
return;
}
if (m_plant_time_ptr != NULL) {
*m_plant_time_ptr = time;
} else {
std::cout << "Time pointer set to NULL.\n";
}
}

View File

@ -78,7 +78,16 @@ void QuadROSComm::initClass() {
m_estimated_fc_pub[i] = this->create_publisher<std_msgs::msg::Float32>("/" + m_name + "/estimation/contact_forces_" + std::to_string(i), 1);
}
m_plant_time_sub = this->create_subscription<std_msgs::msg::Float32>(
"/" + m_name + "/plant_time",
1,
std::bind(&QuadROSComm::get_plant_time_cb, this, std::placeholders::_1)
);
} else if (m_mode == DATA_ACCESS_MODE::PLANT) {
m_plant_time_pub = this->create_publisher<std_msgs::msg::Float32>("/" + m_name + "/plant_time", 1);
m_joint_state_pub = this->create_publisher<sensor_msgs::msg::JointState>("/" + m_name + "/joint_state", 1);
m_imu_pub = this->create_publisher<sensor_msgs::msg::Imu>("/" + m_name + "/imu", 1);
m_odom_pub = this->create_publisher<nav_msgs::msg::Odometry>("/" + m_name + "/odom", 1);
@ -139,6 +148,8 @@ void QuadROSComm::initClass() {
// js_data.velocity.push_back(0);
// js_data.effort.push_back(0);
// }
setPlantTimePtr(&m_plant_time);
}
void QuadROSComm::get_joint_state_cb(const sensor_msgs::msg::JointState::SharedPtr msg) const {
@ -186,8 +197,13 @@ void QuadROSComm::get_joystick_data_cb(const sensor_msgs::msg::Joy::SharedPtr ms
m_joystick_data_ptr -> gait = msg -> axes[4];
}
void QuadROSComm::get_plant_time_cb(const std_msgs::msg::Float32::SharedPtr msg) {
m_plant_time = msg -> data;
}
void QuadROSComm::timer_cb() {
if (m_mode == DATA_ACCESS_MODE::EXECUTOR) {
js_data.header.stamp = this -> now();
for (int i = 0; i < 12; ++i) {
js_data.position[i] = m_joint_command_data_ptr -> q(i);
js_data.velocity[i] = m_joint_command_data_ptr -> qd(i);
@ -213,6 +229,10 @@ void QuadROSComm::timer_cb() {
m_joint_state_pub->publish(js_data);
} else if (m_mode == DATA_ACCESS_MODE::PLANT) {
// double time = 0;
// getPlantTime(time);
plant_time.data = m_plant_time;
m_plant_time_pub -> publish(plant_time);
for (int i = 0; i < 12; ++i) {
js_data.position[i] = m_sensor_data_ptr -> q(i);
js_data.velocity[i] = m_sensor_data_ptr -> qd(i);

View File

@ -38,16 +38,6 @@ target_link_libraries(didc
pd_controller
)
add_library(robust_didc STATIC
src/Controller/RobustDIDC.cpp
)
target_compile_options(robust_didc PRIVATE "-fPIC")
target_link_libraries(robust_didc
quad_dynamics
pd_controller
gp_regressor
)
add_library(quad_estimator SHARED
src/Estimator/Estimator.cpp
src/Estimator/QuadEstimator.cpp
@ -74,7 +64,7 @@ target_link_libraries(reactive_planner
install(TARGETS
pd_controller
didc
robust_didc
# robust_didc
quad_estimator
base_planner
reactive_planner

View File

@ -78,5 +78,5 @@ private:
std::chrono::time_point<std::chrono::high_resolution_clock> m_lastTimePoint;
std::thread m_comm_thread;
bool use_plant_time = true;
bool use_plant_time = false;
};

View File

@ -1,5 +1,7 @@
#pragma once
#include "simulate.h"
#include <chrono>
#include <cstdint>
#include <cstdio>
@ -12,9 +14,13 @@
#include <string>
#include <thread>
#include "lodepng.h"
#include <mujoco/mjdata.h>
#include <mujoco/mjui.h>
#include <mujoco/mjvisualize.h>
#include <mujoco/mjxmacro.h>
#include <mujoco/mujoco.h>
#include "glfw_adapter.h"
#include "simulate.h"
#include "platform_ui_adapter.h"
#include "array_safety.h"
#define MUJOCO_PLUGIN_DIR "mujoco_plugin"
@ -40,13 +46,6 @@ extern "C" {
#include "SHM.hpp"
#endif
// Signal handler to gracefully handle Ctrl+C
void signalHandler(int signum) {
// std::cout << "Interrupt signal (" << signum << ") received.\n";
// Add cleanup or exit logic as needed
exit(signum);
}
// holders of one step history of time and position to calculate dertivatives
mjtNum position_history = 0;
mjtNum previous_time = 0;
@ -69,6 +68,18 @@ std::shared_ptr<QuadDDSComm> comm_data_ptr;
std::shared_ptr<SHM> comm_data_ptr;
#endif
std::chrono::time_point<std::chrono::high_resolution_clock> m_startTimePoint;
double t_curr = 0;
double updateTimer() {
auto currTimePont = std::chrono::high_resolution_clock::now();
auto start = std::chrono::time_point_cast<std::chrono::microseconds>(m_startTimePoint).time_since_epoch().count();
auto curr = std::chrono::time_point_cast<std::chrono::microseconds>(currTimePont).time_since_epoch().count();
auto duration = curr - start;
return duration * double(1e-6);
}
void UpdateSensorData(mjData*);
void CustomController(const mjModel*, mjData*);
@ -398,6 +409,7 @@ void PhysicsLoop(mj::Simulate& sim) {
syncSim = d->time;
sim.speed_changed = false;
// run single step, let next iteration deal with timing
mj_step(m, d);
stepped = true;

View File

@ -17,6 +17,18 @@
#include <filesystem>
#include <csignal>
#include <mujoco/mujoco.h>
#include "glfw_adapter.h"
#include "simulate.h"
#include "array_safety.h"
// Signal handler to gracefully handle Ctrl+C
void signalHandler(int signum) {
// std::cout << "Interrupt signal (" << signum << ") received.\n";
// Add cleanup or exit logic as needed
exit(signum);
}
void UpdateSensorData(mjData* data) {
if (data == NULL) {
return;
@ -60,6 +72,10 @@ void UpdateSensorData(mjData* data) {
}
void CustomController(const mjModel* model, mjData* data) {
// t_curr = updateTimer();
t_curr = data->time;
comm_data_ptr -> writePlantTime(t_curr);
UpdateSensorData(data);
// get joint command
comm_data_ptr->getCommandData(joint_command_data);
@ -69,16 +85,17 @@ void CustomController(const mjModel* model, mjData* data) {
// return;
// }
// std::cout << "cmd js: " << joint_command_data.q.transpose() << "\n";
// std::cout << "kp: " << joint_command_data.kp.transpose() << "\n";
// float Kp = 20;
// float Kd = 0.5;
// float Kp = 60;
// float Kd = 5;
float Kp = 0;
float Kd = 0;
float Kp = 60;
float Kd = 5;
// float Kp = 0;
// float Kd = 0;
// if (data->time - last_update > 1.0/ctrl_update_freq) {
for (int i = 0; i < 12; ++i) {
Kp = joint_command_data.kp(i);
Kd = joint_command_data.kd(i);
// Kp = joint_command_data.kp(i);
// Kd = joint_command_data.kd(i);
float dtheta = joint_command_data.q(i) - sensor_data.q(i);
float dtheta_d = joint_command_data.qd(i) - sensor_data.qd(i);
// data->ctrl[i] = joint_command_data.tau(i) + joint_command_data.kp(i) * dtheta * joint_command_data.kd(i) * dtheta_d;
@ -168,6 +185,7 @@ int main(int argc, char** argv) {
comm_data_ptr->setCommandDataPtr(&joint_command_data);
comm_data_ptr->setSensorDataPtr(&sensor_data);
comm_data_ptr->setMeasurementDataPtr(&measurement_data);
// comm_data_ptr->setPlantTimePtr(&t_curr);
#elif defined(USE_DDS_COMM)
comm_data_ptr = std::make_shared<QuadDDSComm>(m_name, DATA_ACCESS_MODE::PLANT);
comm_data_ptr->setCommandDataPtr(&joint_command_data);
@ -184,6 +202,7 @@ int main(int argc, char** argv) {
comm_data_ptr->start_thread();
#endif
m_startTimePoint = std::chrono::high_resolution_clock::now();
// start physics thread
std::thread physicsthreadhandle(&PhysicsThread, sim.get(), filename);
// physicsthreadhandle.detach();

View File

@ -0,0 +1,60 @@
<?xml version="1.0" encoding="UTF-8"?>
<?xml-stylesheet type = "text/xsl" href = "http://www.coin-or.org/projects/autoGen.xsl"?>
<projectData xmlns="coin-or.org" xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:schemaLocation="coin-or.org http://www.coin-or.org/projects/autoGen.xsd">
<projectBasics>
<projectName>qpOASES</projectName>
<projectDescription>
qpOASES is an open-source C++ implementation of the recently
proposed online active set strategy for solving quadratic
programming (QP) problems. It has several theoretical features
that make it particularly suited for model predictive control
(MPC) applications. Further numerical modifications have made
qpOASES a reliable QP solver, even when tackling semi-definite,
ill-posed or degenerated QP problems. Moreover, several
interfaces to third-party software make qpOASES easy-to-use
even for users without knowledge of C/C++.
</projectDescription>
<projectShortDescription>An open-source C++ implementation of the recently proposed online active set strategy.</projectShortDescription>
<projectManager>Joachim Ferreau</projectManager>
<projectHomePage>https://github.com/coin-or/qpOASES</projectHomePage>
<projectLicense>GNU Lesser General Public License (LGPL), v2.1</projectLicense>
<projectLicenseURL>http://www.gnu.org/licenses/lgpl-2.1.html</projectLicenseURL>
<coinLinkedProjects/>
<otherLinkedPackages>
<otherPackage>
<packageName>BLAS</packageName>
<packageURL>http://www.netlib.org/blas</packageURL>
<requiredOrOptional>Optional</requiredOrOptional>
</otherPackage>
<otherPackage>
<packageName>LAPACK</packageName>
<packageURL>http://www.netlib.org/lapack</packageURL>
<requiredOrOptional>Optional</requiredOrOptional>
</otherPackage>
</otherLinkedPackages>
<projectLanguage>C++</projectLanguage>
<developmentStatus>
<activityStatus>Active</activityStatus>
<maturityLevel>3</maturityLevel>
</developmentStatus>
<testedPlatforms>
<platform>
<operatingSystem>Linux</operatingSystem>
<compiler>g++</compiler>
</platform>
<platform>
<operatingSystem>Microsoft Windows</operatingSystem>
<compiler>CYGWIN/g++</compiler>
</platform>
</testedPlatforms>
<projectCategories>
<category>Optimization deterministic nonlinear</category>
</projectCategories>
</projectBasics>
<leftMenuLinks>
<documentation>http://www.qpOASES.org/go/manual</documentation>
<sourceCodeDownload>https://github.com/coin-or/qpOASES</sourceCodeDownload>
<binaryDownload/>
<mailingList>http://list.coin-or.org/mailman/listinfo/qpOASES</mailingList>
</leftMenuLinks>
</projectData>

View File

@ -0,0 +1,238 @@
* text=auto !eol
.coin-or/projDesc.xml -text
/AUTHORS -text
/AUTHORS.txt -text
/CMakeLists.txt -text
/INSTALL -text
/INSTALL.txt -text
/LICENSE -text
/LICENSE.txt -text
/Makefile -text
/README -text
/README.txt -text
/VERSIONS -text
/VERSIONS.txt -text
doc/DoxygenLayout.xml -text
doc/Makefile -text
doc/doxygen.config -text
doc/mainpage.dox -text
doc/manual.pdf -text svneol=unset#unset
examples/Makefile -text
examples/example1.cpp -text
examples/example1a.cpp -text
examples/example1b.cpp -text
examples/example2.cpp -text
examples/example3.cpp -text
examples/example3b.cpp -text
examples/example4.cpp -text
examples/example4CP.cpp -text
examples/example5.cpp -text
examples/exampleLP.cpp -text
examples/qrecipe.cpp -text
examples/qrecipeSchur.cpp -text
examples/qrecipe_data.hpp -text
include/qpOASES.hpp -text
include/qpOASES/Bounds.hpp -text
include/qpOASES/Bounds.ipp -text
include/qpOASES/Constants.hpp -text
include/qpOASES/ConstraintProduct.hpp -text
include/qpOASES/Constraints.hpp -text
include/qpOASES/Constraints.ipp -text
include/qpOASES/Flipper.hpp -text
include/qpOASES/Indexlist.hpp -text
include/qpOASES/Indexlist.ipp -text
include/qpOASES/LapackBlasReplacement.hpp -text
include/qpOASES/Matrices.hpp -text
include/qpOASES/MessageHandling.hpp -text
include/qpOASES/MessageHandling.ipp -text
include/qpOASES/Options.hpp -text
include/qpOASES/QProblem.hpp -text
include/qpOASES/QProblem.ipp -text
include/qpOASES/QProblemB.hpp -text
include/qpOASES/QProblemB.ipp -text
include/qpOASES/SQProblem.hpp -text
include/qpOASES/SQProblem.ipp -text
include/qpOASES/SQProblemSchur.hpp -text
include/qpOASES/SQProblemSchur.ipp -text
include/qpOASES/SparseSolver.hpp -text
include/qpOASES/SubjectTo.hpp -text
include/qpOASES/SubjectTo.ipp -text
include/qpOASES/Types.hpp -text
include/qpOASES/UnitTesting.hpp -text
include/qpOASES/Utils.hpp -text
include/qpOASES/Utils.ipp -text
include/qpOASES/extras/OQPinterface.hpp -text
include/qpOASES/extras/SolutionAnalysis.hpp -text
include/qpOASES/extras/SolutionAnalysis.ipp -text
interfaces/CUTEst/Makefile -text
interfaces/CUTEst/makeprob -text
interfaces/CUTEst/qpoasesCutest.cpp -text
interfaces/CUTEst/readme.txt -text
interfaces/c/Makefile -text
interfaces/c/c_example1.c -text
interfaces/c/c_example1a.c -text
interfaces/c/c_example1b.c -text
interfaces/c/qpOASES_wrapper.cpp -text
interfaces/c/qpOASES_wrapper.h -text
interfaces/matlab/Makefile -text
interfaces/matlab/example1.mat -text
interfaces/matlab/example1a.mat -text
interfaces/matlab/example1b.mat -text
interfaces/matlab/make.m -text
interfaces/matlab/qpOASES.cpp -text
interfaces/matlab/qpOASES.m -text
interfaces/matlab/qpOASES_auxInput.m -text
interfaces/matlab/qpOASES_matlab_utils.cpp -text
interfaces/matlab/qpOASES_matlab_utils.hpp -text
interfaces/matlab/qpOASES_options.m -text
interfaces/matlab/qpOASES_sequence.cpp -text
interfaces/matlab/qpOASES_sequence.m -text
interfaces/matlab/testQPset.m -text
interfaces/matlab/testSchur.m -text
interfaces/octave/clean -text
interfaces/octave/clean.sh -text
interfaces/octave/example1.mat -text
interfaces/octave/example1a.mat -text
interfaces/octave/example1b.mat -text
interfaces/octave/make.m -text
interfaces/octave/qpOASES.cpp -text
interfaces/octave/qpOASES.m -text
interfaces/octave/qpOASES_auxInput.m -text
interfaces/octave/qpOASES_octave_utils.cpp -text
interfaces/octave/qpOASES_octave_utils.hpp -text
interfaces/octave/qpOASES_options.m -text
interfaces/octave/qpOASES_sequence.cpp -text
interfaces/octave/qpOASES_sequence.m -text
interfaces/python/README.rst -text
interfaces/python/examples/cython/example1.pyx -text
interfaces/python/examples/cython/setup.py -text
interfaces/python/examples/example1.py -text
interfaces/python/examples/example1b.py -text
interfaces/python/examples/example2.py -text
interfaces/python/qpoases.pxd -text
interfaces/python/qpoases.pyx -text
interfaces/python/setup.py -text
interfaces/python/tests/__init__.py -text
interfaces/python/tests/test_examples.py -text
interfaces/scilab/Makefile -text
interfaces/scilab/example1.dat -text
interfaces/scilab/example1a.dat -text
interfaces/scilab/example1b.dat -text
interfaces/scilab/qpOASESinterface.c -text
interfaces/scilab/qpOASESinterface.sce -text
interfaces/scilab/qpOASESroutines.cpp -text
interfaces/simulink/example_QProblem.mdl -text
interfaces/simulink/example_QProblemB.mdl -text
interfaces/simulink/example_SQProblem.mdl -text
interfaces/simulink/load_example_QProblem.m -text
interfaces/simulink/load_example_QProblemB.m -text
interfaces/simulink/load_example_SQProblem.m -text
interfaces/simulink/make.m -text
interfaces/simulink/qpOASES_QProblem.cpp -text
interfaces/simulink/qpOASES_QProblemB.cpp -text
interfaces/simulink/qpOASES_SQProblem.cpp -text
interfaces/simulink/qpOASES_simulink_utils.cpp -text
/make.mk -text
/make_cygwin.mk -text
/make_linux.mk -text
/make_osx.mk -text
/make_windows.mk -text
src/BLASReplacement.cpp -text
src/Bounds.cpp -text
src/Constraints.cpp -text
src/Flipper.cpp -text
src/Indexlist.cpp -text
src/LAPACKReplacement.cpp -text
src/Makefile -text
src/Matrices.cpp -text
src/MessageHandling.cpp -text
src/OQPinterface.cpp -text
src/Options.cpp -text
src/QProblem.cpp -text
src/QProblemB.cpp -text
src/SQProblem.cpp -text
src/SQProblemSchur.cpp -text
src/SolutionAnalysis.cpp -text
src/SparseSolver.cpp -text
src/SubjectTo.cpp -text
src/Utils.cpp -text
testing/c/Makefile -text
testing/c/test_c_example1.c -text
testing/c/test_c_example1a.c -text
testing/c/test_c_example1b.c -text
testing/checkForMemoryLeaks -text
testing/cpp/Makefile -text
testing/cpp/data/fetch_cpp_data -text
testing/cpp/test_bench.cpp -text
testing/cpp/test_constraintProduct1.cpp -text
testing/cpp/test_constraintProduct2.cpp -text
testing/cpp/test_example1.cpp -text
testing/cpp/test_example1a.cpp -text
testing/cpp/test_example1b.cpp -text
testing/cpp/test_example2.cpp -text
testing/cpp/test_example4.cpp -text
testing/cpp/test_example5.cpp -text
testing/cpp/test_example6.cpp -text
testing/cpp/test_example7.cpp -text
testing/cpp/test_exampleLP.cpp -text
testing/cpp/test_externalChol1.cpp -text
testing/cpp/test_gradientShift.cpp -text
testing/cpp/test_guessedWS1.cpp -text
testing/cpp/test_hs268.cpp -text
testing/cpp/test_identitySqproblem.cpp -text
testing/cpp/test_indexlist.cpp -text
testing/cpp/test_infeasible1.cpp -text
testing/cpp/test_janick1.cpp -text
testing/cpp/test_janick2.cpp -text
testing/cpp/test_matrices.cpp -text
testing/cpp/test_matrices2.cpp -text
testing/cpp/test_matrices3.cpp -text
testing/cpp/test_qrecipe.cpp -text
testing/cpp/test_qrecipeSchur.cpp -text
testing/cpp/test_qrecipe_data.hpp -text
testing/cpp/test_runAllOqpExamples.cpp -text
testing/cpp/test_sebastien1.cpp -text
testing/cpp/test_smallSchur.cpp -text
testing/cpp/test_vanBarelsUnboundedQP.cpp -text
testing/matlab/auxFiles/generateExample.m -text
testing/matlab/auxFiles/generateRandomQp.m -text
testing/matlab/auxFiles/getKktResidual.m -text
testing/matlab/auxFiles/isoctave.m -text
testing/matlab/auxFiles/setupQpDataStruct.m -text
testing/matlab/auxFiles/setupQpFeaturesStruct.m -text
testing/matlab/data/fetch_matlab_data -text
testing/matlab/runAllTests.m -text
testing/matlab/setupTestingPaths.m -text
testing/matlab/tests/runAlexInfeas1.m -text
testing/matlab/tests/runAlexInfeas2.m -text
testing/matlab/tests/runAlternativeX0Test.m -text
testing/matlab/tests/runBenchmarkCHAIN1.m -text
testing/matlab/tests/runBenchmarkCHAIN1A.m -text
testing/matlab/tests/runBenchmarkCRANE1.m -text
testing/matlab/tests/runBenchmarkCRANE2.m -text
testing/matlab/tests/runBenchmarkCRANE3.m -text
testing/matlab/tests/runBenchmarkDIESEL.m -text
testing/matlab/tests/runBenchmarkEQUALITY1.m -text
testing/matlab/tests/runBenchmarkEQUALITY2.m -text
testing/matlab/tests/runBenchmarkEXAMPLE1.m -text
testing/matlab/tests/runBenchmarkEXAMPLE1A.m -text
testing/matlab/tests/runBenchmarkEXAMPLE1B.m -text
testing/matlab/tests/runBenchmarkIDHESSIAN1.m -text
testing/matlab/tests/runEmptyHessianTests.m -text
testing/matlab/tests/runExternalCholeskyTests.m -text
testing/matlab/tests/runInterfaceSeqTest.m -text
testing/matlab/tests/runInterfaceTest.m -text
testing/matlab/tests/runQAP8.m -text
testing/matlab/tests/runQSHARE1B.m -text
testing/matlab/tests/runRandomIdHessian.m -text
testing/matlab/tests/runRandomZeroHessian.m -text
testing/matlab/tests/runSimpleSpringExample.m -text
testing/matlab/tests/runTestAPrioriKnownSeq1.m -text
testing/matlab/tests/runTestSeq.m -text
testing/matlab/tests/runTestSparse.m -text
testing/matlab/tests/runTestSparse2.m -text
testing/matlab/tests/runTestSparse3.m -text
testing/matlab/tests/runTestSparse4.m -text
testing/matlab/tests/runTestWorkingSetLI.m -text
testing/matlab/tests/runVanBarelsUnboundedQP.m -text
testing/runUnitTests -text

View File

@ -0,0 +1 @@
/*.mex

View File

@ -0,0 +1,3 @@
[submodule "external/ThirdParty-Mumps"]
path = external/ThirdParty-Mumps
url = https://github.com/coin-or-tools/ThirdParty-Mumps.git

View File

@ -0,0 +1,94 @@
##
## This file is part of qpOASES.
##
## qpOASES -- An Implementation of the Online Active Set Strategy.
## Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
## Christian Kirches 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
##
MAIN AUTHORS
============
qpOASES's core functionality and software design have been developed by the
following main developers (in alphabetical order):
Hans Joachim Ferreau
Christian Kirches
Andreas Potschka
FURTHER AUTHORS
===============
Moreover, the following developers have contributed code to qpOASES's
third-party interfaces or provided additional functionality
(in alphabetical order):
Alexander Buchner
Holger Diedam
Dennis Janka
Manuel Kudruss
Andreas Waechter
Sebastian F. Walter
CONTRIBUTORS
============
Finally, the following people have not contributed to the source code,
but have helped making qpOASES even more useful by testing, reporting
bugs or proposing algorithmic improvements (in alphabetical order):
Eckhard Arnold
Joris Gillis
Boris Houska
D. Kwame Minde Kufoalor
Aude Perrin
Silvio Traversaro
Milan Vukov
Thomas Wiese
Leonard Wirsching
SCIENTIFIC MENTORS
==================
We also would like to thank two persons who had a major share in making
qpOASES a success. Not by writing even a single line of code, but by
establishing the idea of using a homotopy-based approach for high-speed
QP solutions and by excellent scientific guidance during the development
process:
Hans Georg Bock
Moritz Diehl
All users are invited to further improve qpOASES by providing comments,
code enhancements, bug reports, additional documentation or whatever you
feel is missing.
##
## end of file
##

View File

@ -0,0 +1,94 @@
##
## This file is part of qpOASES.
##
## qpOASES -- An Implementation of the Online Active Set Strategy.
## Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
## Christian Kirches 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
##
MAIN AUTHORS
============
qpOASES's core functionality and software design have been developed by the
following main developers (in alphabetical order):
Hans Joachim Ferreau
Christian Kirches
Andreas Potschka
FURTHER AUTHORS
===============
Moreover, the following developers have contributed code to qpOASES's
third-party interfaces or provided additional functionality
(in alphabetical order):
Alexander Buchner
Holger Diedam
Dennis Janka
Manuel Kudruss
Andreas Waechter
Sebastian F. Walter
CONTRIBUTORS
============
Finally, the following people have not contributed to the source code,
but have helped making qpOASES even more useful by testing, reporting
bugs or proposing algorithmic improvements (in alphabetical order):
Eckhard Arnold
Joris Gillis
Boris Houska
D. Kwame Minde Kufoalor
Aude Perrin
Silvio Traversaro
Milan Vukov
Thomas Wiese
Leonard Wirsching
SCIENTIFIC MENTORS
==================
We also would like to thank two persons who had a major share in making
qpOASES a success. Not by writing even a single line of code, but by
establishing the idea of using a homotopy-based approach for high-speed
QP solutions and by excellent scientific guidance during the development
process:
Hans Georg Bock
Moritz Diehl
All users are invited to further improve qpOASES by providing comments,
code enhancements, bug reports, additional documentation or whatever you
feel is missing.
##
## end of file
##

View File

@ -0,0 +1,200 @@
##
## This file is part of qpOASES.
##
## qpOASES -- An Implementation of the Online Active Set Strategy.
## Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
## Christian Kirches 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
##
##
## Filename: CMakeLists.txt
## Author: Hans Joachim Ferreau (thanks to Milan Vukov)
## Version: 3.2
## Date: 2007-2017
##
cmake_minimum_required(VERSION 2.6)
PROJECT(qpOASES CXX)
SET(PACKAGE_NAME "qpOASES")
SET(PACKAGE_VERSION "3.2.2")
SET(PACKAGE_SO_VERSION "3.2")
SET(PACKAGE_DESCRIPTION "An implementation of the online active set strategy")
SET(PACKAGE_AUTHOR "Hans Joachim Ferreau, Andreas Potschka, Christian Kirches et al.")
SET(PACKAGE_MAINTAINER "Hans Joachim Ferreau, Andreas Potschka, Christian Kirches et al.")
SET(PACKAGE_URL "https://projects.coin-or.org/qpOASES")
SET(EXECUTABLE_OUTPUT_PATH ${PROJECT_BINARY_DIR}/bin)
SET(LIBRARY_OUTPUT_PATH ${PROJECT_BINARY_DIR}/libs)
IF(NOT CMAKE_INSTALL_LIBDIR)
SET(CMAKE_INSTALL_LIBDIR lib)
ENDIF(NOT CMAKE_INSTALL_LIBDIR)
IF(NOT CMAKE_INSTALL_BINDIR)
SET(CMAKE_INSTALL_BINDIR ${CMAKE_INSTALL_LIBDIR})
ENDIF(NOT CMAKE_INSTALL_BINDIR)
IF(NOT CMAKE_INSTALL_INCLUDEDIR)
SET(CMAKE_INSTALL_INCLUDEDIR include)
ENDIF(NOT CMAKE_INSTALL_INCLUDEDIR)
IF( NOT CMAKE_VERBOSE_MAKEFILE )
SET( CMAKE_VERBOSE_MAKEFILE OFF )
ENDIF( NOT CMAKE_VERBOSE_MAKEFILE )
IF( NOT CMAKE_BUILD_TYPE )
SET(CMAKE_BUILD_TYPE Release CACHE STRING
"Choose the type of build, options are: None Debug Release RelWithDebInfo MinSizeRel."
FORCE
)
ENDIF( NOT CMAKE_BUILD_TYPE )
option(BUILD_SHARED_LIBS "If ON, build shared library instead of static" OFF)
option(QPOASES_BUILD_EXAMPLES "Build examples." ON)
option(QPOASES_AVOID_LA_NAMING_CONFLICTS "If ON, avoid to re-defined symbols that conflict with Blas/Lapack provided functions." OFF)
IF(BUILD_SHARED_LIBS AND WIN32)
MESSAGE(FATAL_ERROR "Compiling qpOASES as a shared library in Windows is not supported.")
ENDIF()
############################################################
#################### compiler flags ########################
############################################################
SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -D__NO_COPYRIGHT__")
IF(QPOASES_AVOID_LA_NAMING_CONFLICTS)
SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -D__AVOID_LA_NAMING_CONFLICTS__")
ENDIF()
IF ( UNIX )
SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -pedantic -Wfloat-equal -Wshadow -DLINUX")
SET(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_DEBUG} -O3 -finline-functions")
ELSEIF( WINDOWS )
SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -nologo -EHsc -DWIN32")
ENDIF()
SET(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} -D__DEBUG__")
############################################################
######################## rpath #############################
############################################################
# use, i.e. don't skip the full RPATH for the build tree
set(CMAKE_SKIP_BUILD_RPATH FALSE)
# when building, don't use the install RPATH already
# (but later on when installing)
set(CMAKE_BUILD_WITH_INSTALL_RPATH FALSE)
set(CMAKE_INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/lib:${CMAKE_INSTALL_PREFIX}/lib/casadi")
# add the automatically determined parts of the RPATH
# which point to directories outside the build tree to the install RPATH
set(CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE)
# the RPATH to be used when installing, but only if it's not a system directory
list(FIND CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES "${CMAKE_INSTALL_PREFIX}/lib" isSystemDir)
if("${isSystemDir}" STREQUAL "-1")
set(CMAKE_INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/lib:${CMAKE_INSTALL_PREFIX}/lib/casadi")
endif("${isSystemDir}" STREQUAL "-1")
############################################################
#################### build and install #####################
############################################################
INCLUDE_DIRECTORIES(${PROJECT_SOURCE_DIR}/include)
# compile qpOASES libraries
FILE(GLOB SRC src/*.cpp)
# library
ADD_LIBRARY(qpOASES ${SRC})
INSTALL(TARGETS qpOASES
LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR}
ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR}
RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR}
)
SET_TARGET_PROPERTIES(
qpOASES
PROPERTIES
SOVERSION ${PACKAGE_SO_VERSION}
)
# headers
INSTALL(FILES include/qpOASES.hpp
DESTINATION ${CMAKE_INSTALL_INCLUDEDIR})
INSTALL(DIRECTORY include/qpOASES
DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}
FILES_MATCHING PATTERN "*.hpp"
PATTERN "*.ipp"
PATTERN ".svn" EXCLUDE)
############################################################
######################### Package Config ###################
############################################################
include(CMakePackageConfigHelpers)
set(INCLUDE_INSTALL_DIR ${CMAKE_INSTALL_INCLUDEDIR})
set(LIB_INSTALL_DIR ${CMAKE_INSTALL_LIBDIR})
configure_package_config_file(qpOASESConfig.cmake.in
${CMAKE_CURRENT_BINARY_DIR}/qpOASESConfig.cmake
INSTALL_DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/qpOASES
PATH_VARS INCLUDE_INSTALL_DIR LIB_INSTALL_DIR
NO_CHECK_REQUIRED_COMPONENTS_MACRO)
write_basic_package_version_file(
${CMAKE_CURRENT_BINARY_DIR}/qpOASESConfigVersion.cmake
VERSION ${PACKAGE_VERSION}
COMPATIBILITY SameMajorVersion)
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/qpOASESConfig.cmake
${CMAKE_CURRENT_BINARY_DIR}/qpOASESConfigVersion.cmake
DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/qpOASES
COMPONENT qpOASES)
############################################################
######################### examples #########################
############################################################
if (QPOASES_BUILD_EXAMPLES)
# compile qpOASES examples
SET(EXAMPLE_NAMES
example1
example1a
example1b
example2
example3
example3b
example4
example5
exampleLP
qrecipe
qrecipeSchur
)
FOREACH(ELEMENT ${EXAMPLE_NAMES})
ADD_EXECUTABLE(${ELEMENT} examples/${ELEMENT}.cpp)
TARGET_LINK_LIBRARIES(${ELEMENT} qpOASES)
ENDFOREACH(ELEMENT ${EXAMPLE_NAMES})
endif(QPOASES_BUILD_EXAMPLES)
##
## end of file
##

View File

@ -0,0 +1,79 @@
##
## This file is part of qpOASES.
##
## qpOASES -- An Implementation of the Online Active Set Strategy.
## Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
## Christian Kirches 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
##
INSTALLATION UNDER LINUX
========================
0. Obtain qpOASES from COIN-OR:
Download a zipped archive containg the latest stable release and unpack it
into <install-dir>. Alternatively, you check out the latest stable branch,
e.g. by running
svn co https://projects.coin-or.org/svn/qpOASES/stable/3.2 <install-dir>
from your shell.
1. Compilation of the qpOASES library libqpOASES.a (or .so) and test examples:
cd <install-dir>
make
The library libqpOASES.a (or .so) provides the complete functionality of the
qpOASES software package. It can be used by, e.g., linking it against a main
function from the examples folder. The make also compiles a couple of test
examples; executables are stored within the directory <install-dir>/bin.
2. Running a simple test example:
Among others, an executable called example1 should have been created; run
it in order to test your installation:
cd <install-dir>/bin
./example1
If it terminates after successfully solving two QP problems, qpOASES has been
successfully installed!
3. Optional, create source code documentation (using doxygen):
cd <install-dir>/doc
doxygen doxygen.config
Afterwards, you can open the file <install-dir>/doc/html/index.html with
your favorite browser in order to view qpOASES's source code documentation.
NOTE: More detailed installation instructions, including information on how
to run unit tests can be found in the qpOASES User's Manual located
at <install-dir>/doc/manual.pdf!
##
## end of file
##

View File

@ -0,0 +1,79 @@
##
## This file is part of qpOASES.
##
## qpOASES -- An Implementation of the Online Active Set Strategy.
## Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
## Christian Kirches 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
##
INSTALLATION UNDER LINUX
========================
0. Obtain qpOASES from COIN-OR:
Download a zipped archive containg the latest stable release and unpack it
into <install-dir>. Alternatively, you check out the latest stable branch,
e.g. by running
svn co https://projects.coin-or.org/svn/qpOASES/stable/3.2 <install-dir>
from your shell.
1. Compilation of the qpOASES library libqpOASES.a (or .so) and test examples:
cd <install-dir>
make
The library libqpOASES.a (or .so) provides the complete functionality of the
qpOASES software package. It can be used by, e.g., linking it against a main
function from the examples folder. The make also compiles a couple of test
examples; executables are stored within the directory <install-dir>/bin.
2. Running a simple test example:
Among others, an executable called example1 should have been created; run
it in order to test your installation:
cd <install-dir>/bin
./example1
If it terminates after successfully solving two QP problems, qpOASES has been
successfully installed!
3. Optional, create source code documentation (using doxygen):
cd <install-dir>/doc
doxygen doxygen.config
Afterwards, you can open the file <install-dir>/doc/html/index.html with
your favorite browser in order to view qpOASES's source code documentation.
NOTE: More detailed installation instructions, including information on how
to run unit tests can be found in the qpOASES User's Manual located
at <install-dir>/doc/manual.pdf!
##
## end of file
##

View File

@ -0,0 +1,503 @@
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!

View File

@ -0,0 +1,503 @@
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!

View File

@ -0,0 +1,118 @@
##
## This file is part of qpOASES.
##
## qpOASES -- An Implementation of the Online Active Set Strategy.
## Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
## Christian Kirches 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
##
##
## Filename: Makefile
## Author: Hans Joachim Ferreau
## Version: 3.2
## Date: 2007-2017
##
include make.mk
##
## targets
##
ifeq ($(DEF_SOLVER), SOLVER_MUMPS)
EXTERNAL = mumps
else
EXTERNAL =
endif
all: $(EXTERNAL) bin src examples
#src_aw testing
ifeq ($(DEF_SOLVER), SOLVER_MUMPS)
mumps:
@echo $(QPOASESROOT)
@cd external/ThirdParty-Mumps; \
if [ -d "MUMPS" ]; then \
echo "Found MUMPS source code."; \
else get.Mumps; ./configure --prefix=$(PWD)/external/mumps_installation; fi; \
make && make install
endif
src: $(EXTERNAL)
@cd $@; ${MAKE} -s
bin:
mkdir bin
#src_aw:
# @cd $@; ${MAKE} -s
examples: src
@cd $@; ${MAKE} -s
doc:
@cd $@; ${MAKE} -s
testing: src
@cd testing/cpp; ${MAKE} -s
test: testing
@cd testing/cpp; ${MAKE} -s runTests
debugging:
@cd $@; ${MAKE} -s
clean:
ifeq ($(DEF_SOLVER), SOLVER_MUMPS)
@echo Cleaning up \(mumps\)
@cd external/ThirdParty-Mumps && ${MAKE} -s clean
@cd external && ${RM} -rf mumps_installation
endif
@cd src && ${MAKE} -s clean
@cd examples && ${MAKE} -s clean
@cd bin && ${RM} -f *.* *{EXE}
@cd testing/cpp && ${MAKE} -s clean
# && cd src_aw && ${MAKE} -s clean && cd .. \
# && cd debugging && ${MAKE} -s clean && cd .. \
clobber: clean
scilab:
@echo Compiling Scilab interface...
@cd ./interfaces/scilab/; ${MAKE} -s
python: all
cd ./interfaces/python/ && python setup.py build_ext --inplace
pythoninstall: all
cd ./interfaces/python/ && python setup.py install
c_wrapper:
@echo Compiling C interface...
@cd ./interfaces/c/; ${MAKE} -s
.PHONY : all src examples doc testing debugging clean clobber scilab python phythoninstall c_wrapper
##
## end of file
##

View File

@ -0,0 +1,84 @@
##
## This file is part of qpOASES.
##
## qpOASES -- An Implementation of the Online Active Set Strategy.
## Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
## Christian Kirches 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, which was inspired by important observations
from the field of parametric quadratic programming (QP). It has several
theoretical features that make it particularly suited for model predictive
control (MPC) applications. Further numerical modifications have made
qpOASES a reliable QP solver, even when tackling semi-definite, ill-posed or
degenerated QP problems. Moreover, several interfaces to third-party software
like Matlab or Simulink are provided that make qpOASES easy-to-use even for
users without knowledge of C/C++.
GETTING STARTED
===============
1. For installation, usage and additional information on this software package
see the qpOASES User's Manual located at doc/manual.pdf or check its
source code documentation!
2. The file LICENSE.txt contains a copy of the GNU Lesser General Public
License (v2.1). Please read it carefully before using qpOASES!
3. The whole software package can be obtained from
http://www.qpOASES.org/ or
https://github.com/coin-or/qpOASES/
On this webpage you will also find further support such as a list of
questions posed by other users.
CONTACT THE AUTHORS
===================
If you have got questions, remarks or comments on qpOASES, it is strongly
encouraged to report them by creating a new ticket at the qpOASES webpage.
In case you do not want to disclose your feedback to the public, you may
send an e-mail to
support@qpOASES.org
Finally, you may contact one of the main authors directly:
Hans Joachim Ferreau, joachim.ferreau@ch.abb.com
Andreas Potschka, potschka@iwr.uni-heidelberg.de
Christian Kirches, christian.kirches@iwr.uni-heidelberg.de
Also bug reports, source code enhancements or success stories are most welcome!
##
## end of file
##

View File

@ -0,0 +1,84 @@
##
## This file is part of qpOASES.
##
## qpOASES -- An Implementation of the Online Active Set Strategy.
## Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
## Christian Kirches 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, which was inspired by important observations
from the field of parametric quadratic programming (QP). It has several
theoretical features that make it particularly suited for model predictive
control (MPC) applications. Further numerical modifications have made
qpOASES a reliable QP solver, even when tackling semi-definite, ill-posed or
degenerated QP problems. Moreover, several interfaces to third-party software
like Matlab or Simulink are provided that make qpOASES easy-to-use even for
users without knowledge of C/C++.
GETTING STARTED
===============
1. For installation, usage and additional information on this software package
see the qpOASES User's Manual located at doc/manual.pdf or check its
source code documentation!
2. The file LICENSE.txt contains a copy of the GNU Lesser General Public
License (v2.1). Please read it carefully before using qpOASES!
3. The whole software package can be obtained from
http://www.qpOASES.org/ or
https://projects.coin-or.org/qpOASES/
On this webpage you will also find further support such as a list of
questions posed by other users.
CONTACT THE AUTHORS
===================
If you have got questions, remarks or comments on qpOASES, it is strongly
encouraged to report them by creating a new ticket at the qpOASES webpage.
In case you do not want to disclose your feedback to the public, you may
send an e-mail to
support@qpOASES.org
Finally, you may contact one of the main authors directly:
Hans Joachim Ferreau, joachim.ferreau@ch.abb.com
Andreas Potschka, potschka@iwr.uni-heidelberg.de
Christian Kirches, christian.kirches@iwr.uni-heidelberg.de
Also bug reports, source code enhancements or success stories are most welcome!
##
## end of file
##

View File

@ -0,0 +1,124 @@
##
## This file is part of qpOASES.
##
## qpOASES -- An Implementation of the Online Active Set Strategy.
## Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
## Christian Kirches 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
===============
3.2 (released on 1st September 2015, last updated on 26th April 2017):
----------------------------------------------------------------------
+ Addition of SQProblemSchur class implementing Schur complement approach
for sparse QP problems
+ Introduction of data types int_t and uint_t for integer-valued numbers
+ Minor source code clean-up and bugfixes
3.1 (released on 11th February 2015):
-------------------------------------
+ Addition of C interface
+ Further improved Matlab, Simulink, octave and Python interfaces
+ Possibility to provide pre-computed Cholesky factor of Hessian matrix
+ Source code clean-up and bugfixes
3.0 (released on 29th July 2014, last updated on 17th December 2014):
---------------------------------------------------------------------
+ Addition of unit testing
+ Several bugfixes
3.0beta (released on 16th August 2011, last updated on 4th April 2014):
-----------------------------------------------------------------------
+ Improved ratio tests and termination check for increased reliabilty
+ Introduction of iterative refinement in step determination and
drift correction to handle ill-conditioned QPs
+ Introduction of ramping strategy to handle degenerated QPs
+ Addition of far bounds and flipping bounds strategy to handle
semi-definite and unbounded QPs more reliably
+ Limited support of sparse QP matrices (also in Matlab interface)
+ Optional linking of LAPACK/BLAS for linear algebra operations
+ Addition of a number of algorithmic options, summarised in an option struct
+ Improved Matlab interface
+ Python interface added
+ Several bugfixes
2.0 (released on 10th February 2009, last updated on 7th December 2009):
------------------------------------------------------------------------
+ Implementation of regularisation scheme for treating QPs with
semi-definite Hessians
+ Addition of convenience functionality for Bounds and Constraints
objects for specifying guessed active sets
+ Allows to specify a CPU time in addition to an iteration limit
+ Improved efficiency for QPs comprising many constraints
+ Source code cleanup and bugfixing
1.3 (released on 2nd June 2008, last updated on 13th August 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
##

View File

@ -0,0 +1,124 @@
##
## This file is part of qpOASES.
##
## qpOASES -- An Implementation of the Online Active Set Strategy.
## Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
## Christian Kirches 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
===============
3.2 (released on 1st September 2015, last updated on 26th April 2017):
----------------------------------------------------------------------
+ Addition of SQProblemSchur class implementing Schur complement approach
for sparse QP problems
+ Introduction of data types int_t and uint_t for integer-valued numbers
+ Minor source code clean-up and bugfixes
3.1 (released on 11th February 2015):
-------------------------------------
+ Addition of C interface
+ Further improved Matlab, Simulink, octave and Python interfaces
+ Possibility to provide pre-computed Cholesky factor of Hessian matrix
+ Source code clean-up and bugfixes
3.0 (released on 29th July 2014, last updated on 17th December 2014):
---------------------------------------------------------------------
+ Addition of unit testing
+ Several bugfixes
3.0beta (released on 16th August 2011, last updated on 4th April 2014):
-----------------------------------------------------------------------
+ Improved ratio tests and termination check for increased reliabilty
+ Introduction of iterative refinement in step determination and
drift correction to handle ill-conditioned QPs
+ Introduction of ramping strategy to handle degenerated QPs
+ Addition of far bounds and flipping bounds strategy to handle
semi-definite and unbounded QPs more reliably
+ Limited support of sparse QP matrices (also in Matlab interface)
+ Optional linking of LAPACK/BLAS for linear algebra operations
+ Addition of a number of algorithmic options, summarised in an option struct
+ Improved Matlab interface
+ Python interface added
+ Several bugfixes
2.0 (released on 10th February 2009, last updated on 7th December 2009):
------------------------------------------------------------------------
+ Implementation of regularisation scheme for treating QPs with
semi-definite Hessians
+ Addition of convenience functionality for Bounds and Constraints
objects for specifying guessed active sets
+ Allows to specify a CPU time in addition to an iteration limit
+ Improved efficiency for QPs comprising many constraints
+ Source code cleanup and bugfixes
1.3 (released on 2nd June 2008, last updated on 13th August 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
##

View File

@ -0,0 +1,189 @@
<doxygenlayout version="1.0">
<!-- Navigation index tabs for HTML output -->
<navindex>
<tab type="mainpage" visible="yes" title=""/>
<tab type="pages" visible="yes" title="" intro=""/>
<tab type="modules" visible="yes" title="" intro=""/>
<tab type="namespaces" visible="yes" title="">
<tab type="namespacelist" visible="yes" title="" intro=""/>
<tab type="namespacemembers" visible="yes" title="" intro=""/>
</tab>
<tab type="classes" visible="yes" title="">
<tab type="classlist" visible="yes" title="" intro=""/>
<tab type="classindex" visible="$ALPHABETICAL_INDEX" title=""/>
<tab type="hierarchy" visible="yes" title="" intro=""/>
<tab type="classmembers" visible="yes" title="" intro=""/>
</tab>
<tab type="files" visible="yes" title="">
<tab type="filelist" visible="yes" title="" intro=""/>
<tab type="globals" visible="yes" title="" intro=""/>
</tab>
<tab type="dirs" visible="yes" title="" intro=""/>
<tab type="examples" visible="yes" title="" intro=""/>
<tab type="user" visible="yes" url="../manual.pdf" title="Manual" intro=""/>
</navindex>
<!-- Layout definition for a class page -->
<class>
<briefdescription visible="yes"/>
<includes visible="$SHOW_INCLUDE_FILES"/>
<inheritancegraph visible="$CLASS_GRAPH"/>
<collaborationgraph visible="$COLLABORATION_GRAPH"/>
<allmemberslink visible="yes"/>
<memberdecl>
<nestedclasses visible="yes" title=""/>
<publictypes title=""/>
<publicslots title=""/>
<signals title=""/>
<publicmethods title=""/>
<publicstaticmethods title=""/>
<publicattributes title=""/>
<publicstaticattributes title=""/>
<protectedtypes title=""/>
<protectedslots title=""/>
<protectedmethods title=""/>
<protectedstaticmethods title=""/>
<protectedattributes title=""/>
<protectedstaticattributes title=""/>
<packagetypes title=""/>
<packagemethods title=""/>
<packagestaticmethods title=""/>
<packageattributes title=""/>
<packagestaticattributes title=""/>
<properties title=""/>
<events title=""/>
<privatetypes title=""/>
<privateslots title=""/>
<privatemethods title=""/>
<privatestaticmethods title=""/>
<privateattributes title=""/>
<privatestaticattributes title=""/>
<friends title=""/>
<related title="" subtitle=""/>
<membergroups visible="yes"/>
</memberdecl>
<detaileddescription title=""/>
<memberdef>
<inlineclasses title=""/>
<typedefs title=""/>
<enums title=""/>
<constructors title=""/>
<functions title=""/>
<related title=""/>
<variables title=""/>
<properties title=""/>
<events title=""/>
</memberdef>
<usedfiles visible="$SHOW_USED_FILES"/>
<authorsection visible="yes"/>
</class>
<!-- Layout definition for a namespace page -->
<namespace>
<briefdescription visible="yes"/>
<memberdecl>
<nestednamespaces visible="yes" title=""/>
<classes visible="yes" title=""/>
<typedefs title=""/>
<enums title=""/>
<functions title=""/>
<variables title=""/>
<membergroups visible="yes"/>
</memberdecl>
<detaileddescription title=""/>
<memberdef>
<inlineclasses title=""/>
<typedefs title=""/>
<enums title=""/>
<functions title=""/>
<variables title=""/>
</memberdef>
<authorsection visible="yes"/>
</namespace>
<!-- Layout definition for a file page -->
<file>
<briefdescription visible="yes"/>
<includes visible="$SHOW_INCLUDE_FILES"/>
<includegraph visible="$INCLUDE_GRAPH"/>
<includedbygraph visible="$INCLUDED_BY_GRAPH"/>
<sourcelink visible="yes"/>
<memberdecl>
<classes visible="yes" title=""/>
<namespaces visible="yes" title=""/>
<defines title=""/>
<typedefs title=""/>
<enums title=""/>
<functions title=""/>
<variables title=""/>
<membergroups visible="yes"/>
</memberdecl>
<detaileddescription title=""/>
<memberdef>
<inlineclasses title=""/>
<defines title=""/>
<typedefs title=""/>
<enums title=""/>
<functions title=""/>
<variables title=""/>
</memberdef>
<authorsection/>
</file>
<!-- Layout definition for a group page -->
<group>
<briefdescription visible="yes"/>
<groupgraph visible="$GROUP_GRAPHS"/>
<memberdecl>
<classes visible="yes" title=""/>
<namespaces visible="yes" title=""/>
<dirs visible="yes" title=""/>
<nestedgroups visible="yes" title=""/>
<files visible="yes" title=""/>
<defines title=""/>
<typedefs title=""/>
<enums title=""/>
<enumvalues title=""/>
<functions title=""/>
<variables title=""/>
<signals title=""/>
<publicslots title=""/>
<protectedslots title=""/>
<privateslots title=""/>
<events title=""/>
<properties title=""/>
<friends title=""/>
<membergroups visible="yes"/>
</memberdecl>
<detaileddescription title=""/>
<memberdef>
<pagedocs/>
<inlineclasses title=""/>
<defines title=""/>
<typedefs title=""/>
<enums title=""/>
<enumvalues title=""/>
<functions title=""/>
<variables title=""/>
<signals title=""/>
<publicslots title=""/>
<protectedslots title=""/>
<privateslots title=""/>
<events title=""/>
<properties title=""/>
<friends title=""/>
</memberdef>
<authorsection visible="yes"/>
</group>
<!-- Layout definition for a directory page -->
<directory>
<briefdescription visible="yes"/>
<directorygraph visible="yes"/>
<memberdecl>
<dirs visible="yes"/>
<files visible="yes"/>
</memberdecl>
<detaileddescription title=""/>
</directory>
</doxygenlayout>

View File

@ -0,0 +1,66 @@
##
## This file is part of qpOASES.
##
## qpOASES -- An Implementation of the Online Active Set Strategy.
## Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
## Christian Kirches 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
##
##
## Filename: Makefile
## Author: Hans Joachim Ferreau
## Version: 3.2
## Date: 2007-2017
##
##
## settings
##
MAKEPDF = pdflatex
LATEX = latex
##
## targets
##
all: doc
.PHONY: doc
doc:
@ echo "Creating doxygen documentation "
@ doxygen doxygen.config
.PHONY: clean
clean:
@ ${RM} -rf ./html
.PHONY: clobber
clobber: clean
##
## end of file
##

View File

@ -0,0 +1,310 @@
#---------------------------------------------------------------------------
# Project related configuration options
#---------------------------------------------------------------------------
DOXYFILE_ENCODING = UTF-8
PROJECT_NAME = qpOASES
PROJECT_NUMBER = 3.2.1
PROJECT_BRIEF = "An Implementation of the Online Active Set Strategy"
PROJECT_LOGO =
OUTPUT_DIRECTORY =
CREATE_SUBDIRS = NO
OUTPUT_LANGUAGE = English
BRIEF_MEMBER_DESC = YES
REPEAT_BRIEF = NO
ABBREVIATE_BRIEF =
ALWAYS_DETAILED_SEC = NO
INLINE_INHERITED_MEMB = YES
FULL_PATH_NAMES = YES
STRIP_FROM_PATH = ..
STRIP_FROM_INC_PATH =
SHORT_NAMES = NO
JAVADOC_AUTOBRIEF = NO
QT_AUTOBRIEF = NO
MULTILINE_CPP_IS_BRIEF = NO
INHERIT_DOCS = YES
SEPARATE_MEMBER_PAGES = NO
TAB_SIZE = 4
ALIASES =
TCL_SUBST =
OPTIMIZE_OUTPUT_FOR_C = NO
OPTIMIZE_OUTPUT_JAVA = NO
OPTIMIZE_FOR_FORTRAN = NO
OPTIMIZE_OUTPUT_VHDL = NO
EXTENSION_MAPPING =
MARKDOWN_SUPPORT = YES
AUTOLINK_SUPPORT = YES
BUILTIN_STL_SUPPORT = NO
CPP_CLI_SUPPORT = NO
SIP_SUPPORT = NO
IDL_PROPERTY_SUPPORT = YES
DISTRIBUTE_GROUP_DOC = NO
SUBGROUPING = YES
INLINE_GROUPED_CLASSES = NO
INLINE_SIMPLE_STRUCTS = NO
TYPEDEF_HIDES_STRUCT = NO
SYMBOL_CACHE_SIZE = 0
LOOKUP_CACHE_SIZE = 0
#---------------------------------------------------------------------------
# Build related configuration options
#---------------------------------------------------------------------------
EXTRACT_ALL = NO
EXTRACT_PRIVATE = YES
EXTRACT_PACKAGE = NO
EXTRACT_STATIC = NO
EXTRACT_LOCAL_CLASSES = YES
EXTRACT_LOCAL_METHODS = NO
EXTRACT_ANON_NSPACES = NO
HIDE_UNDOC_MEMBERS = NO
HIDE_UNDOC_CLASSES = NO
HIDE_FRIEND_COMPOUNDS = NO
HIDE_IN_BODY_DOCS = NO
INTERNAL_DOCS = NO
CASE_SENSE_NAMES = YES
HIDE_SCOPE_NAMES = NO
SHOW_INCLUDE_FILES = YES
FORCE_LOCAL_INCLUDES = NO
INLINE_INFO = YES
SORT_MEMBER_DOCS = YES
SORT_BRIEF_DOCS = NO
SORT_MEMBERS_CTORS_1ST = NO
SORT_GROUP_NAMES = NO
SORT_BY_SCOPE_NAME = NO
STRICT_PROTO_MATCHING = NO
GENERATE_TODOLIST = NO
GENERATE_TESTLIST = NO
GENERATE_BUGLIST = NO
GENERATE_DEPRECATEDLIST= YES
ENABLED_SECTIONS =
MAX_INITIALIZER_LINES = 30
SHOW_USED_FILES = YES
SHOW_FILES = YES
SHOW_NAMESPACES = YES
FILE_VERSION_FILTER =
LAYOUT_FILE = DoxygenLayout.xml
CITE_BIB_FILES =
#---------------------------------------------------------------------------
# configuration options related to warning and progress messages
#---------------------------------------------------------------------------
QUIET = NO
WARNINGS = YES
WARN_IF_UNDOCUMENTED = YES
WARN_IF_DOC_ERROR = YES
WARN_NO_PARAMDOC = NO
WARN_FORMAT = "$file:$line: $text"
WARN_LOGFILE =
#---------------------------------------------------------------------------
# configuration options related to the input files
#---------------------------------------------------------------------------
INPUT = ./mainpage.dox \
../src \
../include/qpOASES \
../include/qpOASES/extras \
../examples
INPUT_ENCODING = UTF-8
FILE_PATTERNS = *.cpp \
*.ipp \
*.hpp \
*.c
RECURSIVE = YES
EXCLUDE =
EXCLUDE_SYMLINKS = NO
EXCLUDE_PATTERNS =
EXCLUDE_SYMBOLS =
EXAMPLE_PATH = ../examples
EXAMPLE_PATTERNS =
EXAMPLE_RECURSIVE = NO
IMAGE_PATH =
INPUT_FILTER =
FILTER_PATTERNS =
FILTER_SOURCE_FILES = NO
FILTER_SOURCE_PATTERNS =
#---------------------------------------------------------------------------
# configuration options related to source browsing
#---------------------------------------------------------------------------
SOURCE_BROWSER = NO
INLINE_SOURCES = NO
STRIP_CODE_COMMENTS = YES
REFERENCED_BY_RELATION = YES
REFERENCES_RELATION = YES
REFERENCES_LINK_SOURCE = YES
USE_HTAGS = NO
VERBATIM_HEADERS = YES
#---------------------------------------------------------------------------
# configuration options related to the alphabetical class index
#---------------------------------------------------------------------------
ALPHABETICAL_INDEX = NO
COLS_IN_ALPHA_INDEX = 5
IGNORE_PREFIX =
#---------------------------------------------------------------------------
# configuration options related to the HTML output
#---------------------------------------------------------------------------
GENERATE_HTML = YES
HTML_OUTPUT = html
HTML_FILE_EXTENSION = .html
HTML_HEADER =
HTML_FOOTER =
HTML_STYLESHEET =
HTML_EXTRA_STYLESHEET =
HTML_EXTRA_FILES =
HTML_COLORSTYLE_HUE = 220
HTML_COLORSTYLE_SAT = 100
HTML_COLORSTYLE_GAMMA = 80
HTML_TIMESTAMP = YES
HTML_DYNAMIC_SECTIONS = NO
HTML_INDEX_NUM_ENTRIES = 100
GENERATE_DOCSET = NO
DOCSET_FEEDNAME = "Doxygen generated docs"
DOCSET_BUNDLE_ID = org.doxygen.Project
DOCSET_PUBLISHER_ID = org.doxygen.Publisher
DOCSET_PUBLISHER_NAME = Publisher
GENERATE_HTMLHELP = NO
CHM_FILE =
HHC_LOCATION =
GENERATE_CHI = NO
CHM_INDEX_ENCODING =
BINARY_TOC = NO
TOC_EXPAND = NO
GENERATE_QHP = NO
QCH_FILE =
QHP_NAMESPACE = org.doxygen.Project
QHP_VIRTUAL_FOLDER = doc
QHP_CUST_FILTER_NAME =
QHP_CUST_FILTER_ATTRS =
QHP_SECT_FILTER_ATTRS =
QHG_LOCATION =
GENERATE_ECLIPSEHELP = NO
ECLIPSE_DOC_ID = org.doxygen.Project
DISABLE_INDEX = NO
GENERATE_TREEVIEW = NO
ENUM_VALUES_PER_LINE = 4
TREEVIEW_WIDTH = 250
EXT_LINKS_IN_WINDOW = NO
FORMULA_FONTSIZE = 10
FORMULA_TRANSPARENT = YES
USE_MATHJAX = NO
MATHJAX_RELPATH = http://cdn.mathjax.org/mathjax/latest
MATHJAX_EXTENSIONS =
SEARCHENGINE = NO
SERVER_BASED_SEARCH = NO
#---------------------------------------------------------------------------
# configuration options related to the LaTeX output
#---------------------------------------------------------------------------
GENERATE_LATEX = NO
LATEX_OUTPUT = latex
LATEX_CMD_NAME = latex
MAKEINDEX_CMD_NAME = makeindex
COMPACT_LATEX = NO
PAPER_TYPE = a4wide
EXTRA_PACKAGES =
LATEX_HEADER =
LATEX_FOOTER =
PDF_HYPERLINKS = YES
USE_PDFLATEX = NO
LATEX_BATCHMODE = NO
LATEX_HIDE_INDICES = NO
LATEX_SOURCE_CODE = NO
LATEX_BIB_STYLE = plain
#---------------------------------------------------------------------------
# configuration options related to the RTF output
#---------------------------------------------------------------------------
GENERATE_RTF = NO
RTF_OUTPUT = RTF
COMPACT_RTF = NO
RTF_HYPERLINKS = NO
RTF_STYLESHEET_FILE =
RTF_EXTENSIONS_FILE =
#---------------------------------------------------------------------------
# configuration options related to the man page output
#---------------------------------------------------------------------------
GENERATE_MAN = NO
MAN_OUTPUT = MAN
MAN_EXTENSION = .3
MAN_LINKS = NO
#---------------------------------------------------------------------------
# configuration options related to the XML output
#---------------------------------------------------------------------------
GENERATE_XML = NO
XML_OUTPUT = XML
XML_SCHEMA =
XML_DTD =
XML_PROGRAMLISTING = YES
#---------------------------------------------------------------------------
# configuration options for the AutoGen Definitions output
#---------------------------------------------------------------------------
GENERATE_AUTOGEN_DEF = NO
#---------------------------------------------------------------------------
# configuration options related to the Perl module output
#---------------------------------------------------------------------------
GENERATE_PERLMOD = NO
PERLMOD_LATEX = NO
PERLMOD_PRETTY = YES
PERLMOD_MAKEVAR_PREFIX =
#---------------------------------------------------------------------------
# Configuration options related to the preprocessor
#---------------------------------------------------------------------------
ENABLE_PREPROCESSING = YES
MACRO_EXPANSION = NO
EXPAND_ONLY_PREDEF = NO
SEARCH_INCLUDES = YES
INCLUDE_PATH =
INCLUDE_FILE_PATTERNS =
PREDEFINED =
EXPAND_AS_DEFINED =
SKIP_FUNCTION_MACROS = YES
#---------------------------------------------------------------------------
# Configuration::additions related to external references
#---------------------------------------------------------------------------
TAGFILES =
GENERATE_TAGFILE =
ALLEXTERNALS = NO
EXTERNAL_GROUPS = YES
PERL_PATH = /usr/bin/perl
#---------------------------------------------------------------------------
# Configuration options related to the dot tool
#---------------------------------------------------------------------------
CLASS_DIAGRAMS = YES
MSCGEN_PATH =
HIDE_UNDOC_RELATIONS = YES
HAVE_DOT = NO
DOT_NUM_THREADS = 0
DOT_FONTNAME = Helvetica
DOT_FONTSIZE = 10
DOT_FONTPATH =
CLASS_GRAPH = YES
COLLABORATION_GRAPH = NO
GROUP_GRAPHS = YES
UML_LOOK = NO
UML_LIMIT_NUM_FIELDS = 10
TEMPLATE_RELATIONS = NO
INCLUDE_GRAPH = YES
INCLUDED_BY_GRAPH = YES
CALL_GRAPH = NO
CALLER_GRAPH = NO
GRAPHICAL_HIERARCHY = YES
DIRECTORY_GRAPH = YES
DOT_IMAGE_FORMAT = png
INTERACTIVE_SVG = NO
DOT_PATH =
DOTFILE_DIRS =
MSCFILE_DIRS =
DOT_GRAPH_MAX_NODES = 50
MAX_DOT_GRAPH_DEPTH = 0
DOT_TRANSPARENT = NO
DOT_MULTI_TARGETS = NO
GENERATE_LEGEND = YES
DOT_CLEANUP = YES

View File

@ -0,0 +1,135 @@
/**
* \mainpage Main Page
*
* <p>&nbsp;</p>
*
* \section sec_copyright Copyright
*
* qpOASES -- An Implementation of the Online Active Set Strategy. \n
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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
* <p>&nbsp;</p>
*
*
* \section sec_developers Authors and Contributors
*
* qpOASES's core functionality and software design have been developed by
* the following main developers (in alphabetical order):
* <ul>
* <li>Hans Joachim Ferreau
* <li>Christian Kirches
* <li>Andreas Potschka
* </ul>
*
* Moreover, the following developers have contributed code to qpOASES's
* third-party interfaces or provided additional functionality
* (in alphabetical order):
* <ul>
* <li>Alexander Buchner
* <li>Holger Diedam
* <li>Dennis Janka
* <li>Manuel Kudruss
* <li>Andreas Waechter
* <li>Sebastian F. Walter
* </ul>
*
* Finally, the following people have not contributed to the source code,
* but have helped making qpOASES even more useful by testing, reporting
* bugs or proposing algorithmic improvements (in alphabetical order):
* <ul>
* <li>Eckhard Arnold
* <li>Joris Gillis
* <li>Boris Houska
* <li>D. Kwame Minde Kufoalor
* <li>Aude Perrin
* <li>Milan Vukov
* <li>Thomas Wiese
* <li>Leonard Wirsching
* </ul>
*
* We also would like to thank two persons who had a major share in making
* qpOASES a success. Not by writing even a single line of code, but by
* establishing the idea of using a homotopy-based approach for high-speed
* QP solutions and by excellent scientific guidance during the development
* process:
* <ul>
* <li>Hans Georg Bock
* <li>Moritz Diehl
* </ul>
*
* All users are invited to further improve qpOASES by providing comments, code enhancements,
* bug reports, additional documentation or whatever you feel is missing. The preferred way
* of doing so is to <b>create a <a href="https://projects.coin-or.org/qpOASES/newticket">new ticket</a>
* at the qpOASES webpage</b>. In case you do not want to disclose your feedback to the public,
* you may send an e-mail to <a href="mailto:support@qpOASES.org">support@qpOASES.org</a>
* or contact one of the main developers directly.
* <p>&nbsp;</p>
*
*
* \section sec_citing Citing qpOASES
*
* If you use qpOASES within your scientific work, we strongly encourage you to cite at least
* one of the following publications:
*
* <ul>
* <li>Reference to the <b>software</b>:
* \code
* @ARTICLE{Ferreau2014,
* author = {H.J. Ferreau and C. Kirches and A. Potschka and H.G. Bock and M. Diehl},
* title = {{qpOASES}: A parametric active-set algorithm for quadratic programming},
* journal = {Mathematical Programming Computation},
* year = {2014},
* volume = {6},
* number = {4},
* pages = {327--363},
* keywords = {qpOASES, parametric quadratic programming, active set method, model predictive control}
* }
* \endcode
*
* <li>Reference to the <b>online active set strategy</b>:
* \code
* @ARTICLE{Ferreau2008,
* author = {H.J. Ferreau and H.G. Bock and M. Diehl},
* title = {An online active set strategy to overcome the limitations of explicit MPC},
* journal = {International Journal of Robust and Nonlinear Control},
* year = {2008},
* volume = {18},
* number = {8},
* pages = {816--830},
* keywords = {model predictive control, parametric quadratic programming, online active set strategy}
* }
* \endcode
*
* <li>Reference to the <b>webpage</b>:
* \code
* @MISC{qpOASES2017,
* author = {H.J. Ferreau and A. Potschka and C. Kirches},
* title = {{qpOASES} webpage},
* howpublished = {http://www.qpOASES.org/},
* year = {2007--2017},
* keywords = {qpOASES, model predictive control, parametric quadratic programming, online active set strategy}
* }
* \endcode
* </ul>
* <p>&nbsp;</p>
*
* \section sec_moreinfo More Information
*
* More information can be found on <a href="http://www.qpOASES.org/">http://www.qpOASES.org/</a>
* and in the <a href="../manual.pdf">qpOASES User's Manual</a>.
* <p>&nbsp;</p>
*/

Binary file not shown.

View File

@ -0,0 +1,107 @@
##
## This file is part of qpOASES.
##
## qpOASES -- An Implementation of the Online Active Set Strategy.
## Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
## Christian Kirches 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
##
##
## Filename: examples/Makefile
## Author: Hans Joachim Ferreau
## Version: 3.2
## Date: 2007-2017
##
include ../make.mk
##
## flags
##
IFLAGS = -I. \
-I${IDIR}
QPOASES_EXES = \
${BINDIR}/example1${EXE} \
${BINDIR}/example1a${EXE} \
${BINDIR}/example1b${EXE} \
${BINDIR}/example2${EXE} \
${BINDIR}/example3${EXE} \
${BINDIR}/example3b${EXE} \
${BINDIR}/example4${EXE} \
${BINDIR}/example5${EXE} \
${BINDIR}/exampleLP${EXE} \
${BINDIR}/qrecipe${EXE} \
${BINDIR}/qrecipeSchur${EXE}
##
## targets
##
all: ${QPOASES_EXES}
${BINDIR}/%${EXE}: %.${OBJEXT} ${LINK_DEPENDS}
@${ECHO} "Creating" $@
@${CPP} ${DEF_TARGET} ${CPPFLAGS} $< ${QPOASES_LINK} ${LINK_LIBRARIES}
${BINDIR}/example4${EXE}: example4.${OBJEXT} example4CP.cpp ${LINK_DEPENDS}
@${ECHO} "Creating" $@
@${CPP} ${DEF_TARGET} ${CPPFLAGS} $< ${QPOASES_LINK} ${LINK_LIBRARIES}
${BINDIR}/qrecipe${EXE}: qrecipe.${OBJEXT} qrecipe_data.hpp ${LINK_DEPENDS}
@${ECHO} "Creating" $@
@${CPP} ${DEF_TARGET} ${CPPFLAGS} $< ${QPOASES_LINK} ${LINK_LIBRARIES}
${BINDIR}/qrecipeSchur${EXE}: qrecipeSchur.${OBJEXT} qrecipe_data.hpp ${LINK_DEPENDS}
@${ECHO} "Creating" $@
@${CPP} ${DEF_TARGET} ${CPPFLAGS} $< ${QPOASES_LINK} ${LINK_LIBRARIES}
clean:
@${ECHO} "Cleaning up (examples)"
@${RM} -f *.${OBJEXT} ${QPOASES_EXES}
clobber: clean
${LINK_DEPENDS}:
@cd ..; ${MAKE} -s src
example4.${OBJEXT}: example4.cpp example4CP.cpp
@${ECHO} "Creating" $@
@${CPP} ${DEF_TARGET} -c ${IFLAGS} ${CPPFLAGS} $<
qrecipe.${OBJEXT}: qrecipe.cpp qrecipe_data.hpp
@${ECHO} "Creating" $@
@${CPP} ${DEF_TARGET} ${IFLAGS} ${CPPFLAGS} -c $<
qrecipeSchur.${OBJEXT}: qrecipeSchur.cpp qrecipe_data.hpp
@${ECHO} "Creating" $@
@${CPP} ${DEF_TARGET} ${IFLAGS} ${CPPFLAGS} -c $<
%.${OBJEXT}: %.cpp
@${ECHO} "Creating" $@
@${CPP} ${DEF_TARGET} -c ${IFLAGS} ${CPPFLAGS} $<
##
## end of file
##

View File

@ -0,0 +1,100 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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 3.2
* \date 2007-2017
*
* Very simple example for testing qpOASES using the QProblem class.
*/
#include <qpOASES.hpp>
/** Example for qpOASES main function using the QProblem class. */
int main( )
{
USING_NAMESPACE_QPOASES
/* 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 );
Options options;
example.setOptions( options );
/* Solve first QP. */
int_t nWSR = 10;
example.init( H,g,A,lb,ub,lbA,ubA, nWSR );
/* Get and print solution of first QP. */
real_t xOpt[2];
real_t yOpt[2+1];
example.getPrimalSolution( xOpt );
example.getDualSolution( yOpt );
printf( "\nxOpt = [ %e, %e ]; yOpt = [ %e, %e, %e ]; objVal = %e\n\n",
xOpt[0],xOpt[1],yOpt[0],yOpt[1],yOpt[2],example.getObjVal() );
/* Solve second QP. */
nWSR = 10;
example.hotstart( g_new,lb_new,ub_new,lbA_new,ubA_new, nWSR );
/* Get and print solution of second QP. */
example.getPrimalSolution( xOpt );
example.getDualSolution( yOpt );
printf( "\nxOpt = [ %e, %e ]; yOpt = [ %e, %e, %e ]; objVal = %e\n\n",
xOpt[0],xOpt[1],yOpt[0],yOpt[1],yOpt[2],example.getObjVal() );
example.printOptions();
/*example.printProperties();*/
/*getGlobalMessageHandler()->listAllMessages();*/
return 0;
}
/*
* end of file
*/

View File

@ -0,0 +1,85 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/example1a.cpp
* \author Hans Joachim Ferreau
* \version 3.2
* \date 2007-2017
*
* Very simple example for testing qpOASES using the SQProblem class.
*/
#include <qpOASES.hpp>
/** Example for qpOASES main function using the SQProblem class. */
int main( )
{
USING_NAMESPACE_QPOASES
/* 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 H_new[2*2] = { 1.0, 0.5, 0.5, 0.5 };
real_t A_new[1*2] = { 1.0, 5.0 };
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 SQProblem object. */
SQProblem example( 2,1 );
/* Solve first QP. */
int_t nWSR = 10;
example.init( H,g,A,lb,ub,lbA,ubA, nWSR,0 );
/* Solve second QP. */
nWSR = 10;
example.hotstart( H_new,g_new,A_new,lb_new,ub_new,lbA_new,ubA_new, nWSR,0 );
/* Get and print solution of second QP. */
real_t xOpt[2];
example.getPrimalSolution( xOpt );
printf( "\nxOpt = [ %e, %e ]; objVal = %e\n\n", xOpt[0],xOpt[1],example.getObjVal() );
return 0;
}
/*
* end of file
*/

View File

@ -0,0 +1,90 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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 3.2
* \date 2007-2017
*
* Very simple example for testing qpOASES using the QProblemB class.
*/
#include <qpOASES.hpp>
/** Example for qpOASES main function using the QProblemB class. */
int main( )
{
USING_NAMESPACE_QPOASES
/* 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 );
Options options;
//options.enableFlippingBounds = BT_FALSE;
options.initialStatusBounds = ST_INACTIVE;
options.numRefinementSteps = 1;
options.enableCholeskyRefactorisation = 1;
example.setOptions( options );
/* Solve first QP. */
int_t nWSR = 10;
example.init( H,g,lb,ub, nWSR,0 );
/* Get and print solution of first QP. */
real_t xOpt[2];
example.getPrimalSolution( xOpt );
printf( "\nxOpt = [ %e, %e ]; objVal = %e\n\n", xOpt[0],xOpt[1],example.getObjVal() );
/* Solve second QP. */
nWSR = 10;
example.hotstart( g_new,lb_new,ub_new, nWSR,0 );
// printf( "\nnWSR = %d\n\n", nWSR );
/* Get and print solution of second QP. */
example.getPrimalSolution( xOpt );
printf( "\nxOpt = [ %e, %e ]; objVal = %e\n\n", xOpt[0],xOpt[1],example.getObjVal() );
return 0;
}
/*
* end of file
*/

View File

@ -0,0 +1,123 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/example2.cpp
* \author Hans Joachim Ferreau (thanks to Boris Houska)
* \version 3.2
* \date 2008-2017
*
* Very simple example for testing qpOASES in combination
* with the SolutionAnalysis class.
*/
#include <qpOASES.hpp>
/** Example for qpOASES main function using the SolutionAnalysis class. */
int main( )
{
USING_NAMESPACE_QPOASES
/* 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 H_new[2*2] = { 1.0, 0.5, 0.5, 0.5 };
real_t A_new[1*2] = { 1.0, 5.0 };
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 SQProblem object and solution analyser. */
SQProblem example( 2,1 );
SolutionAnalysis analyser;
/* Solve first QP ... */
int_t nWSR = 10;
example.init( H,g,A,lb,ub,lbA,ubA, nWSR,0 );
/* ... and analyse it. */
real_t maxKktViolation = analyser.getKktViolation( &example );
printf( "maxKktViolation: %e\n", maxKktViolation );
/* Solve second QP ... */
nWSR = 10;
example.hotstart( H_new,g_new,A_new,lb_new,ub_new,lbA_new,ubA_new, nWSR,0 );
/* ... and analyse it. */
maxKktViolation = analyser.getKktViolation( &example );
printf( "maxKktViolation: %e\n", maxKktViolation );
// ------------ VARIANCE-COVARIANCE EVALUATION --------------------
real_t *Var = new real_t[5*5];
real_t *Primal_Dual_Var = new real_t[5*5];
int_t run1, run2;
for( run1 = 0; run1 < 5*5; run1++ )
Var[run1] = 0.0;
Var[0] = 1.0;
Var[6] = 1.0;
// ( 1 0 0 0 0 )
// ( 0 1 0 0 0 )
// Var = ( 0 0 0 0 0 )
// ( 0 0 0 0 0 )
// ( 0 0 0 0 0 )
analyser.getVarianceCovariance( &example, Var,Primal_Dual_Var );
printf("\nPrimal_Dual_VAR = \n");
for( run1 = 0; run1 < 5; run1++ ){
for( run2 = 0; run2 < 5; run2++ ){
printf(" %10f", Primal_Dual_Var[run1*5+run2]);
}
printf("\n");
}
delete[] Primal_Dual_Var;
delete[] Var;
return 0;
}
/*
* end of file
*/

View File

@ -0,0 +1,88 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/example3.cpp
* \author Hans Joachim Ferreau
* \version 3.2
* \date 2008-2017
*
* Example demonstrating usage of qpOASES for solving a QP sequence of the
* Online QP Benchmark Collection. In order to run it, you have to download
* "Example 02" from from http://www.qpOASES.org/onlineQP/ and store it into
* the directory bin/chain80w/.
*/
#include <qpOASES.hpp>
/** Example for qpOASES main function using the OQP interface. */
int main( )
{
USING_NAMESPACE_QPOASES
/* 1) Define benchmark arguments. */
BooleanType isSparse = BT_FALSE;
Options options;
options.setToMPC();
options.printLevel = PL_NONE;
int_t nWSR = 600;
real_t maxCPUtime = 10.0; /* seconds */
real_t maxStationarity, maxFeasibility, maxComplementarity;
/* 2) Run benchmark. */
if ( runOqpBenchmark( "./chain80w/",
isSparse,
options,
nWSR,
maxCPUtime,
maxStationarity,
maxFeasibility,
maxComplementarity
) != SUCCESSFUL_RETURN )
{
myPrintf( "In order to run this example, you need to download example no. 02\nfrom the Online QP Benchmark Collection website first!\n" );
return -1;
}
/* 3) Print results. */
printf( "\n\n" );
printf( "OQP Benchmark Results:\n" );
printf( "======================\n\n" );
printf( "maximum violation stationarity: %.3e\n",maxStationarity );
printf( "maximum violation feasibility: %.3e\n",maxFeasibility );
printf( "maximum violation complementarity: %.3e\n",maxComplementarity );
printf( "\n" );
printf( "maximum CPU time: %.3f milliseconds\n\n",1000.0*maxCPUtime );
return 0;
}
/*
* end of file
*/

View File

@ -0,0 +1,88 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/example3b.cpp
* \author Hans Joachim Ferreau
* \version 3.2
* \date 2008-2017
*
* Example demonstrating usage of qpOASES for solving a QP sequence of the
* Online QP Benchmark Collection. In order to run it, you have to download
* "Example 02" from http://www.qpOASES.org/onlineQP/ and store it into
* the directory bin/chain80/.
*/
#include <qpOASES.hpp>
/** Example for qpOASES main function using the OQP interface. */
int main( )
{
USING_NAMESPACE_QPOASES
/* 1) Define benchmark arguments. */
BooleanType isSparse = BT_FALSE;
Options options;
options.setToMPC();
options.printLevel = PL_NONE;
int_t nWSR = 300;
real_t maxCPUtime = 10.0; /* seconds */
real_t maxStationarity, maxFeasibility, maxComplementarity;
/* 2) Run benchmark. */
if ( runOqpBenchmark( "./chain80/",
isSparse,
options,
nWSR,
maxCPUtime,
maxStationarity,
maxFeasibility,
maxComplementarity
) != SUCCESSFUL_RETURN )
{
myPrintf( "In order to run this example, you need to download example no. 02\nfrom the Online QP Benchmark Collection website first!\n" );
return -1;
}
/* 3) Print results. */
printf( "\n\n" );
printf( "OQP Benchmark Results:\n" );
printf( "======================\n\n" );
printf( "maximum violation stationarity: %.3e\n",maxStationarity );
printf( "maximum violation feasibility: %.3e\n",maxFeasibility );
printf( "maximum violation complementarity: %.3e\n",maxComplementarity );
printf( "\n" );
printf( "maximum CPU time: %.3f milliseconds\n\n",1000.0*maxCPUtime );
return 0;
}
/*
* end of file
*/

View File

@ -0,0 +1,172 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/example4.cpp
* \author Hans Joachim Ferreau
* \version 3.2
* \date 2009-2017
*
* Very simple example for testing qpOASES (using the possibility to specify
* user-defined constraint product function).
*/
#include <stdlib.h>
#include <qpOASES.hpp>
#include "example4CP.cpp"
/** Example for qpOASES main function using the possibility to specify
* user-defined constraint product function. */
int main( )
{
USING_NAMESPACE_QPOASES
int_t i,j;
/* Setup data of first QP... */
real_t H[7*7];
real_t A[50*7];
real_t g[7];
real_t lbA[50];
/* ( 1.0 0.5 | )
* ( 0.5 2.0 | )
* ( --------+------------------- )
* H = ( | 1e-6 )
* ( | 1e-6 )
* ( | ... )
* ( | 1e-6 ) */
for( i=0; i<7*7; ++i )
H[i] = 0.0;
for( i=2; i<7; ++i )
H[i*7+i] = 1.0e-6;
H[0] = 1.0;
H[1] = 0.5;
H[7] = 0.5;
H[8] = 2.0;
/* ( x.x x.x | 1.0 )
* ( x.x x.x | ... )
* ( x.x x.x | 1.0 )
* ( x.x x.x | 1.0 )
* A = ( x.x x.x | ... )
* ( x.x x.x | 1.0 )
* ( x.x x.x | ... )
* ( x.x x.x | 1.0 )
* ( x.x x.x | ... )
* ( x.x x.x | 1.0 ) */
for( i=0; i<50*7; ++i )
A[i] = 0.0;
for( i=0; i<50; ++i )
{
for( j=0; j<2; ++j )
A[i*7+j] = (real_t)rand() / (real_t)RAND_MAX;
A[i*7 + (i/10)+2] = 1.0;
}
/* ( -1.0 )
* ( -0.5 )
* ( ---- )
* g = ( )
* ( )
* ( )
* ( ) */
for( i=0; i<7; ++i )
g[i] = 0.0;
g[0] = -1.0;
g[1] = -0.5;
for( i=0; i<50; ++i )
lbA[i] = 1.0;
/* ... and setting up user-defined constraint product function. */
MyConstraintProduct myCP( 7,50,A );
/* Setting up QProblem object and set construct product function. */
QProblem exampleCP( 7,50 );
exampleCP.setPrintLevel( PL_NONE );
exampleCP.setConstraintProduct( &myCP );
/* Solve first QP. */
real_t cputime = 1.0;
int_t nWSR = 100;
exampleCP.init( H,g,A,0,0,lbA,0, nWSR,&cputime );
/* Solve second QP using a modified gradient. */
g[0] = -2.0;
g[1] = 0.5;
cputime = 1.0;
nWSR = 100;
exampleCP.hotstart( g,0,0,lbA,0, nWSR,&cputime );
/* Get and print solution of second QP. */
real_t xOpt[7];
exampleCP.getPrimalSolution( xOpt );
printf( "\nxOpt = [ %e, %e, %e ... ]; objVal = %e\n", xOpt[0],xOpt[1],xOpt[2],exampleCP.getObjVal() );
printf( "CPU time: %.3f microseconds\n\n", cputime*1.0e6 );
/* Do the same without specifying constraint product. */
QProblem example( 7,50 );
example.setPrintLevel( PL_NONE );
/* Solve first QP. */
g[0] = -1.0;
g[1] = -0.5;
cputime = 1.0;
nWSR = 100;
example.init( H,g,A,0,0,lbA,0, nWSR,&cputime );
/* Solve second QP using a modified gradient. */
g[0] = -2.0;
g[1] = 0.5;
cputime = 1.0;
nWSR = 100;
example.hotstart( g,0,0,lbA,0, nWSR,&cputime );
/* Get and print solution of second QP. */
example.getPrimalSolution( xOpt );
printf( "\nxOpt = [ %e, %e, %e ... ]; objVal = %e\n", xOpt[0],xOpt[1],xOpt[2],example.getObjVal() );
printf( "CPU time: %.3f microseconds\n\n", cputime*1.0e6 );
return 0;
}
/*
* end of file
*/

View File

@ -0,0 +1,112 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/example4CP.cpp
* \author Hans Joachim Ferreau
* \version 3.2
* \date 2009-2017
*
* Sample implementation of the ConstraintProduct class tailored for Example4.
*/
BEGIN_NAMESPACE_QPOASES
/**
* \brief Example illustrating the use of the \a ConstraintProduct class.
*
* Example illustrating the use of the \a ConstraintProduct class.
*
* \author Hans Joachim Ferreau
* \version 3.2
* \date 2007-2017
*/
class MyConstraintProduct : public ConstraintProduct
{
public:
/** Default constructor. */
MyConstraintProduct( ) {};
/** Constructor. */
MyConstraintProduct( int_t _nV,
int_t _nC,
real_t* _A
)
{
nV = _nV;
nC = _nC;
A = _A;
};
/** Copy constructor (flat copy). */
MyConstraintProduct( const MyConstraintProduct& rhs
)
{
nV = rhs.nV;
nC = rhs.nC;
A = rhs.A;
};
/** Destructor. */
virtual ~MyConstraintProduct( ) {};
/** Assignment operator (flat copy). */
MyConstraintProduct& operator=( const MyConstraintProduct& rhs
)
{
if ( this != &rhs )
{
nV = rhs.nV;
nC = rhs.nC;
A = rhs.A;
}
return *this;
};
virtual int_t operator() ( int_t constrIndex,
const real_t* const x,
real_t* const constrValue
) const
{
int_t i;
constrValue[0] = 1.0 * x[(constrIndex/10)+2];
for( i=0; i<2; ++i )
constrValue[0] += A[constrIndex*nV + i] * x[i];
return 0;
};
protected:
int_t nV; /**< Number of variables. */
int_t nC; /**< Number of constraints. */
real_t* A; /**< Pointer to full constraint matrix (typically not needed!). */
};
END_NAMESPACE_QPOASES

View File

@ -0,0 +1,200 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/example5.cpp
* \author Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2011-2017
*
* Very simple example for testing qpOASES (using the possibility to
* compute the local linear feedback law)
*/
#include <stdlib.h>
#include <qpOASES.hpp>
#include "example4CP.cpp"
/** Example for qpOASES main function using the possibility to specify
* user-defined constraint product function. */
int main( )
{
USING_NAMESPACE_QPOASES
int_t i,j,jj;
real_t d = 0.0;
/* Setup data of first QP... */
real_t H[7*7];
real_t A[50*7];
real_t g[7];
real_t lbA[50];
/* ( 1.0 0.5 | )
* ( 0.5 2.0 | )
* ( --------+------------------- )
* H = ( | 1e-6 )
* ( | 1e-6 )
* ( | ... )
* ( | 1e-6 ) */
for( i=0; i<7*7; ++i )
H[i] = 0.0;
for( i=2; i<7; ++i )
H[i*7+i] = 1.0e-6;
H[0] = 1.0;
H[1] = 0.5;
H[7] = 0.5;
H[8] = 2.0;
/* ( x.x x.x | 1.0 )
* ( x.x x.x | ... )
* ( x.x x.x | 1.0 )
* ( x.x x.x | 1.0 )
* A = ( x.x x.x | ... )
* ( x.x x.x | 1.0 )
* ( x.x x.x | ... )
* ( x.x x.x | 1.0 )
* ( x.x x.x | ... )
* ( x.x x.x | 1.0 ) */
for( i=0; i<50*7; ++i )
A[i] = 0.0;
for( i=0; i<50; ++i )
{
for( j=0; j<2; ++j )
A[i*7+j] = (real_t)rand() / (real_t)RAND_MAX;
A[i*7 + (i/10)+2] = 1.0;
}
/* ( -1.0 )
* ( -0.5 )
* ( ---- )
* g = ( )
* ( )
* ( )
* ( ) */
for( i=0; i<7; ++i )
g[i] = 0.0;
g[0] = -1.0;
g[1] = -0.5;
for( i=0; i<50; ++i )
lbA[i] = 1.0;
/* ... and setting up user-defined constraint product function. */
MyConstraintProduct myCP( 7,50,A );
/* Setting up QProblem object and set construct product function. */
QProblem example( 7,50 );
example.setConstraintProduct( &myCP );
/* Solve first QP. */
real_t cputime = 1.0;
int_t nWSR = 100;
example.init( H,g,A,0,0,lbA,0, nWSR,&cputime );
/* Get and print solution of QP. */
real_t xOpt[7], yOpt[7+50];
example.getPrimalSolution( xOpt );
example.getDualSolution( yOpt );
/* Compute local linear feedback law */
const int_t n_rhs = 7+7+50;
real_t g_in[7*n_rhs];
real_t b_in[7*n_rhs];
real_t bA_in[50*n_rhs];
real_t x_out[7*n_rhs];
real_t y_out[(7+50)*n_rhs];
int_t ii;
memset (g_in, 0, sizeof (g_in));
memset (b_in, 0, sizeof (b_in));
memset (bA_in, 0, sizeof (bA_in));
for ( ii = 0; ii < 7; ++ii )
g_in[ii*7 + ii] = 1.0;
for ( ii = 0; ii < 7; ++ii )
b_in[(ii+7)*7 + ii] = 1.0;
for ( ii = 0; ii < 50; ++ii )
bA_in[(ii+14)*50 + ii] = 1.0;
example.solveCurrentEQP ( n_rhs, g_in, b_in, b_in, bA_in, bA_in, x_out, y_out );
/* Verify validity of local feedback law by perturbation and hot starts */
real_t perturb = 1.0e-6;
real_t nrm = 0.0;
for ( ii = 0; ii < n_rhs; ++ii )
{
for ( jj = 0; jj < 7; ++jj )
g_in[ii*7 + jj] = g[jj] + g_in[ii*7+jj]*perturb;
for ( jj = 0; jj < 50; ++jj )
bA_in[ii*50 + jj] = lbA[jj] + bA_in[ii*50+jj]*perturb;
nWSR = 100;
example.hotstart( &g_in[ii*7],0,0,&bA_in[ii*50],0, nWSR, 0 );
real_t xPer[7], yPer[7+50];
example.getPrimalSolution( xPer );
example.getDualSolution( yPer );
for ( jj = 0; jj < 7; ++jj )
{
d = getAbs (x_out[ii*7+jj]*perturb - (xPer[jj]-xOpt[jj]) );
if (nrm < d) nrm=d;
}
for ( jj = 0; jj < 7+50; ++jj )
{
d = getAbs (y_out[ii*(7+50)+jj]*perturb - (yPer[jj]-yOpt[jj]) );
if (nrm < d) nrm=d;
}
}
printf ("Maximum perturbation over all directions: %e\n", nrm);
/* // print feedback matrix
for (ii = 0; ii < n_rhs; ++ii)
{
printf ("x: ");
for (jj = 0; jj < 7; ++jj )
printf ("%8.2e ", x_out[ii*7+jj]);
printf (" y: ");
for (jj = 0; jj < 7+50; ++jj )
printf ("%8.2e ", y_out[ii*(7+50)+jj]);
printf("\n");
}
*/
return 0;
}
/*
* end of file
*/

View File

@ -0,0 +1,87 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/exampleLP.cpp
* \author Hans Joachim Ferreau
* \version 3.2
* \date 2008-2017
*
* Very simple example for solving a LP sequence using qpOASES.
*/
#include <qpOASES.hpp>
/** Example for qpOASES main function solving LPs. */
int main( )
{
USING_NAMESPACE_QPOASES
/* Setup data of first LP. */
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 LP. */
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 with zero Hessian matrix. */
QProblem example( 2,1,HST_ZERO );
Options options;
//options.setToMPC();
example.setOptions( options );
/* Solve first LP. */
int_t nWSR = 10;
example.init( 0,g,A,lb,ub,lbA,ubA, nWSR,0 );
/* Solve second LP. */
nWSR = 10;
example.hotstart( g_new,lb_new,ub_new,lbA_new,ubA_new, nWSR,0 );
/* Get and print solution of second LP. */
real_t xOpt[2];
example.getPrimalSolution( xOpt );
printf( "\nxOpt = [ %e, %e ]; objVal = %e\n\n", xOpt[0],xOpt[1],example.getObjVal() );
return 0;
}
/*
* end of file
*/

View File

@ -0,0 +1,58 @@
import numpy as np
import scipy as sp
from scipy.sparse import csc_matrix, coo_matrix, csr_matrix, lil_matrix, random
from jinja2 import Environment
from jinja2.loaders import FileSystemLoader
import os
seed = 42
density = 0.1
gamma = 0.01
out_file_name = 'qp_data.hpp'
in_file_name = 'qp_data.in.hpp'
NV = 100
NC = 10
H = csc_matrix((NV, NV))
A = csc_matrix((NV, NV))
myinf = 1e10
for i in range(NV):
H[i,i] = 1.0
# H = H + gamma*random(NV, NV, density=density, format='csc', random_state=seed)
# H = H.T*H
for i in range(NC):
A[i,i] = 1.0
H_ri = H.indices
H_cp = H.indptr
H_val = H.data
H_nnz = H.nnz
A_ri = A.indices
A_cp = A.indptr
A_val = A.data
A_nnz = A.nnz
g = np.ones((NV,1))
lb = -myinf*np.ones((NV, 1))
ub = myinf*np.ones((NV, 1))
lbA = -np.ones((NC, 1))
ubA = np.ones((NC, 1))
print('rendering templated C++ code...')
env = Environment(loader=FileSystemLoader(os.path.dirname(os.path.abspath(__file__))))
tmpl = env.get_template(in_file_name)
code = tmpl.render(NV = NV, NC = NC, H_cp = H_cp, H_ri = H_ri, H_val = H_val, H_nnz = H_nnz, \
A_cp = A_cp, A_ri = A_ri, A_val = A_val, A_nnz = A_nnz, g = g, lb = lb, ub = ub, lbA = lbA, ubA = ubA)
with open(out_file_name, "w+") as f:
f.write(code.replace('inf', 'Inf'))

View File

@ -0,0 +1,108 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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
*
*/
/**
* \author Andrea Zanelli
* \version 3.2
* \date 2022
*
* QP data generated by a Python script for testing purposes.
*/
USING_NAMESPACE_QPOASES
#define NV {{NV}}
#define NC {{NC}}
const real_t Inf = INFTY;
sparse_int_t H_ri[] = {
{% for d in H_ri %}
{{ d }},
{%- endfor %}
};
sparse_int_t H_cp[] = {
{% for d in H_cp %}
{{ d }},
{%- endfor %}
};
real_t H_val[] = {
{% for d in H_val %}
{{ d }},
{%- endfor %}
};
sparse_int_t A_ri[] = {
{% for d in A_ri %}
{{ d }},
{%- endfor %}
};
sparse_int_t A_cp[] = {
{% for d in A_cp %}
{{ d }},
{%- endfor %}
};
real_t A_val[] = {
{% for d in A_val %}
{{ d }},
{%- endfor %}
};
real_t g[] = {
{% for d in g %}
{{ d[0] }},
{%- endfor %}
};
real_t lb[] = {
{% for d in lb %}
{{ d[0] }},
{%- endfor %}
};
real_t ub[] = {
{% for d in ub %}
{{ d[0] }},
{%- endfor %}
};
real_t lbA[] = {
{% for d in lbA %}
{{ d[0] }},
{%- endfor %}
};
real_t ubA[] = {
{% for d in ubA %}
{{ d[0] }},
{%- endfor %}
};
long H_nnz = {{ H_nnz }};
long A_nnz = {{ A_nnz }};

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,828 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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
*
*/
/**
* \author Andrea Zanelli
* \version 3.2
* \date 2022
*
* QP data generated by a Python script for testing purposes.
*/
USING_NAMESPACE_QPOASES
#define NV 100
#define NC 10
const real_t Inf = INFTY;
sparse_int_t H_ri[] = {
0,
1,
2,
3,
4,
5,
6,
7,
8,
9,
10,
11,
12,
13,
14,
15,
16,
17,
18,
19,
20,
21,
22,
23,
24,
25,
26,
27,
28,
29,
30,
31,
32,
33,
34,
35,
36,
37,
38,
39,
40,
41,
42,
43,
44,
45,
46,
47,
48,
49,
50,
51,
52,
53,
54,
55,
56,
57,
58,
59,
60,
61,
62,
63,
64,
65,
66,
67,
68,
69,
70,
71,
72,
73,
74,
75,
76,
77,
78,
79,
80,
81,
82,
83,
84,
85,
86,
87,
88,
89,
90,
91,
92,
93,
94,
95,
96,
97,
98,
99,
};
sparse_int_t H_cp[] = {
0,
1,
2,
3,
4,
5,
6,
7,
8,
9,
10,
11,
12,
13,
14,
15,
16,
17,
18,
19,
20,
21,
22,
23,
24,
25,
26,
27,
28,
29,
30,
31,
32,
33,
34,
35,
36,
37,
38,
39,
40,
41,
42,
43,
44,
45,
46,
47,
48,
49,
50,
51,
52,
53,
54,
55,
56,
57,
58,
59,
60,
61,
62,
63,
64,
65,
66,
67,
68,
69,
70,
71,
72,
73,
74,
75,
76,
77,
78,
79,
80,
81,
82,
83,
84,
85,
86,
87,
88,
89,
90,
91,
92,
93,
94,
95,
96,
97,
98,
99,
100,
};
real_t H_val[] = {
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
};
sparse_int_t A_ri[] = {
0,
1,
2,
3,
4,
5,
6,
7,
8,
9,
};
sparse_int_t A_cp[] = {
0,
1,
2,
3,
4,
5,
6,
7,
8,
9,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
10,
};
real_t A_val[] = {
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
};
real_t g[] = {
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
};
real_t lb[] = {
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
-10000000000.0,
};
real_t ub[] = {
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
10000000000.0,
};
real_t lbA[] = {
-1.0,
-1.0,
-1.0,
-1.0,
-1.0,
-1.0,
-1.0,
-1.0,
-1.0,
-1.0,
};
real_t ubA[] = {
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
1.0,
};
long H_nnz = 100;
long A_nnz = 10;

View File

@ -0,0 +1,118 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qrecipe.cpp
* \author Andreas Potschka
* \version 3.2
* \date 2007-2017
*
* QRECIPE example from the CUTEr test set with sparse matrices.
*/
#include <qpOASES.hpp>
#include "qrecipe_data.hpp"
int main( )
{
USING_NAMESPACE_QPOASES
long i;
int_t nWSR;
real_t err, tic, toc;
real_t *x1 = new real_t[180];
real_t *y1 = new real_t[271];
real_t *x2 = new real_t[180];
real_t *y2 = new real_t[271];
/* create sparse matrices */
SymSparseMat *H = new SymSparseMat(180, 180, H_ri, H_cp, H_val);
SparseMatrix *A = new SparseMatrix(91, 180, A_ri, A_cp, A_val);
H->createDiagInfo();
real_t* H_full = H->full();
real_t* A_full = A->full();
SymDenseMat *Hd = new SymDenseMat(180,180,180,H_full);
DenseMatrix *Ad = new DenseMatrix(91,180,180,A_full);
/* solve with dense matrices */
nWSR = 1000;
QProblem qrecipeD(180, 91);
tic = getCPUtime();
qrecipeD.init(Hd, g, Ad, lb, ub, lbA, ubA, nWSR, 0);
toc = getCPUtime();
qrecipeD.getPrimalSolution(x1);
qrecipeD.getDualSolution(y1);
fprintf(stdFile, "Solved dense problem in %d iterations, %.3f seconds.\n", (int)nWSR, toc-tic);
/* solve with sparse matrices */
nWSR = 1000;
QProblem qrecipeS(180, 91);
tic = getCPUtime();
qrecipeS.init(H, g, A, lb, ub, lbA, ubA, nWSR, 0);
toc = getCPUtime();
qrecipeS.getPrimalSolution(x2);
qrecipeS.getDualSolution(y2);
fprintf(stdFile, "Solved sparse problem in %d iterations, %.3f seconds.\n", (int)nWSR, toc-tic);
/* check distance of solutions */
err = 0.0;
for (i = 0; i < 180; i++)
if (getAbs(x1[i] - x2[i]) > err)
err = getAbs(x1[i] - x2[i]);
fprintf(stdFile, "Primal error: %9.2e\n", err);
err = 0.0;
for (i = 0; i < 271; i++)
if (getAbs(y1[i] - y2[i]) > err)
err = getAbs(y1[i] - y2[i]);
fprintf(stdFile, "Dual error: %9.2e (might not be unique)\n", err);
delete H;
delete A;
delete[] H_full;
delete[] A_full;
delete Hd;
delete Ad;
delete[] y2;
delete[] x2;
delete[] y1;
delete[] x1;
return 0;
}
/*
* end of file
*/

View File

@ -0,0 +1,165 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qrecipeSchur.cpp
* \author Dennis Janka
* \version 3.2
* \date 2007-2017
*
* QRECIPE example from the CUTEr test set with sparse matrices.
* Comparison between nullspace factorization (dense and sparse) and
* Schur complement approach.
*/
#include <qpOASES.hpp>
#include "qrecipe_data.hpp"
// #include "generate_sparse_qp/qp_data.hpp"
// #include "generate_sparse_qp/simple_qp_data.hpp"
// #include "generate_sparse_qp/trivial_qp_data.hpp"
int main( )
{
USING_NAMESPACE_QPOASES
long i;
int_t nWSR;
real_t errP1, errP2, errP3, errD1, errD2, errD3, tic, toc;
real_t *x1 = new real_t[NV];
real_t *y1 = new real_t[NV+NC];
real_t *x2 = new real_t[NV];
real_t *y2 = new real_t[NV+NC];
real_t *x3 = new real_t[NV];
real_t *y3 = new real_t[NV+NC];
/* create sparse matrices */
SymSparseMat *H = new SymSparseMat(NV, NV, H_ri, H_cp, H_val);
SparseMatrix *A = new SparseMatrix(NC, NV, A_ri, A_cp, A_val);
H->createDiagInfo();
real_t* H_full = H->full();
for (int i = 0; i < NV; i++)
for (int j = 0; j < NV; j++)
printf("H[%i,%i] = %f\n", i, j, H_full[i*NV+j]);
real_t* A_full = A->full();
SymDenseMat *Hd = new SymDenseMat(NV, NV, NV, H_full);
DenseMatrix *Ad = new DenseMatrix(NC, NV, NV, A_full);
/* solve with dense matrices */
nWSR = 1000;
QProblem qrecipeD(NV, NC);
tic = getCPUtime();
qrecipeD.init(Hd, g, Ad, lb, ub, lbA, ubA, nWSR, 0);
toc = getCPUtime();
qrecipeD.getPrimalSolution(x1);
qrecipeD.getDualSolution(y1);
fprintf(stdFile, "Solved dense problem in %d iterations, %.3f seconds.\n", (int)nWSR, toc-tic);
/* solve with sparse matrices (nullspace factorization) */
nWSR = 1000;
QProblem qrecipeS(NV, NC);
tic = getCPUtime();
qrecipeS.init(H, g, A, lb, ub, lbA, ubA, nWSR, 0);
toc = getCPUtime();
qrecipeS.getPrimalSolution(x2);
qrecipeS.getDualSolution(y2);
fprintf(stdFile, "Solved sparse problem in %d iterations, %.3f seconds.\n", (int)nWSR, toc-tic);
/* solve with sparse matrices (Schur complement) */
nWSR = 1000;
SQProblemSchur qrecipeSchur(NV, NC);
tic = getCPUtime();
qrecipeSchur.init(H, g, A, lb, ub, lbA, ubA, nWSR, 0);
toc = getCPUtime();
qrecipeSchur.getPrimalSolution(x3);
qrecipeSchur.getDualSolution(y3);
fprintf(stdFile, "Solved sparse problem (Schur complement approach) in %d iterations, %.3f seconds.\n", (int)nWSR, toc-tic);
/* check distance of solutions */
errP1 = 0.0;
errP2 = 0.0;
errP3 = 0.0;
#ifndef SOLVER_NONE
for (i = 0; i < NV; i++)
{
fprintf(stdFile, "x3[%i]=%f\n", i, x3[i]);
if (getAbs(x1[i] - x2[i]) > errP1)
errP1 = getAbs(x1[i] - x2[i]);
}
for (i = 0; i < NV; i++)
if (getAbs(x1[i] - x3[i]) > errP2)
errP2 = getAbs(x1[i] - x3[i]);
for (i = 0; i < NV; i++)
if (getAbs(x2[i] - x3[i]) > errP3)
errP3 = getAbs(x2[i] - x3[i]);
#endif /* SOLVER_NONE */
fprintf(stdFile, "Primal error (dense and sparse): %9.2e\n", errP1);
fprintf(stdFile, "Primal error (dense and Schur): %9.2e\n", errP2);
fprintf(stdFile, "Primal error (sparse and Schur): %9.2e\n", errP3);
errD1 = 0.0;
errD2 = 0.0;
errD3 = 0.0;
for (i = 0; i < NV+NC; i++)
if (getAbs(y1[i] - y2[i]) > errD1)
errD1 = getAbs(y1[i] - y2[i]);
#ifndef SOLVER_NONE
for (i = 0; i < NV+NC; i++)
if (getAbs(y1[i] - y3[i]) > errD2)
errD2 = getAbs(y1[i] - y3[i]);
for (i = 0; i < NV+NC; i++)
if (getAbs(y2[i] - y3[i]) > errD3)
errD3 = getAbs(y2[i] - y3[i]);
#endif /* SOLVER_NONE */
fprintf(stdFile, "Dual error (dense and sparse): %9.2e (might not be unique)\n", errD1);
fprintf(stdFile, "Dual error (dense and Schur): %9.2e (might not be unique)\n", errD2);
fprintf(stdFile, "Dual error (sparse and Schur): %9.2e (might not be unique)\n", errD3);
delete H;
delete A;
delete[] H_full;
delete[] A_full;
delete Hd;
delete Ad;
delete[] y3;
delete[] x3;
delete[] y2;
delete[] x2;
delete[] y1;
delete[] x1;
return 0;
}
/*
* end of file
*/

View File

@ -0,0 +1,404 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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 testing/cpp/test_qrecipe.cpp
* \author Andreas Potschka
* \version 3.2
* \date 2007-2017
*
* QRECIPE example from the CUTEr test set with sparse matrices.
*/
USING_NAMESPACE_QPOASES
#define NV 180
#define NC 91
const real_t Inf = INFTY;
sparse_int_t H_cp[] = { 0, 4, 8, 12, 16, 20, 20, 20, 20, 20, 20,
24, 28, 32, 36, 40, 40, 40, 40, 40, 40,
44, 48, 52, 56, 60, 60, 60, 60, 60, 60, 60, 60, 60, 60,
64, 68, 72, 76, 80, 80, 80, 80, 80, 80,
80, 80, 80, 80, 80, 80, 80, 80, 80, 80,
80, 80, 80, 80, 80, 80, 80, 80, 80, 80,
80, 80, 80, 80, 80, 80, 80, 80, 80, 80,
80, 80, 80, 80, 80, 80, 80, 80, 80, 80,
80, 80, 80, 80, 80, 80, 80, 80, 80, 80,
80, 80, 80, 80, 80, 80, 80, 80, 80, 80,
80, 80, 80, 80, 80, 80, 80, 80, 80, 80,
80, 80, 80, 80, 80, 80, 80, 80, 80, 80,
80, 80, 80, 80, 80, 80, 80, 80, 80, 80,
80, 80, 80, 80, 80, 80, 80, 80, 80, 80,
80, 80, 80, 80, 80, 80, 80, 80, 80, 80,
80, 80, 80, 80, 80, 80, 80, 80, 80, 80,
80, 80, 80, 80, 80, 80, 80, 80, 80, 80,
80, 80, 80, 80, 80, 80 };
sparse_int_t H_ri[] = {
0, 10, 20, 34, 1, 11, 21, 35, 2, 12, 22, 36, 3, 13, 23, 37, 4, 14, 24, 38,
0, 10, 20, 34, 1, 11, 21, 35, 2, 12, 22, 36, 3, 13, 23, 37, 4, 14, 24, 38,
0, 10, 20, 34, 1, 11, 21, 35, 2, 12, 22, 36, 3, 13, 23, 37, 4, 14, 24, 38,
0, 10, 20, 34, 1, 11, 21, 35, 2, 12, 22, 36, 3, 13, 23, 37, 4, 14, 24, 38};
real_t H_val[] = {10, 1, 1, 1, 10, 1, 1, 1, 10, 1, 1, 1, 10, 1, 1, 1, 10, 1, 1,
1, 1, 10, 1, 1, 1, 10, 1, 1, 1, 10, 1, 1, 1, 10, 1, 1, 1, 10, 1, 1, 1, 1,
10, 1, 1, 1, 10, 1, 1, 1, 10, 1, 1, 1, 10, 1, 1, 1, 10, 1, 1, 1, 1, 10, 1,
1, 1, 10, 1, 1, 1, 10, 1, 1, 1, 10, 1, 1, 1, 10};
sparse_int_t A_cp[] = {
0, 10, 20, 30, 40, 50, 60, 70, 80, 90, 100, 110, 120,
130, 140, 150, 160, 170, 180, 190, 200, 210, 220, 230, 240, 250, 260, 270,
280, 290, 300, 301, 302, 303, 304, 305, 306, 307, 308, 309, 310, 311, 312,
313, 314, 318, 319, 320, 321, 322, 323, 324, 325, 326, 327, 328, 329, 331,
333, 335, 337, 339, 341, 343, 345, 347, 349, 351, 353, 355, 357, 359, 361,
363, 365, 367, 369, 371, 373, 383, 393, 403, 405, 408, 410, 413, 415, 418,
420, 422, 424, 426, 428, 430, 432, 434, 436, 438, 440, 442, 444, 446, 448,
450, 452, 454, 456, 458, 460, 462, 472, 482, 492, 494, 497, 499, 502, 504,
507, 509, 511, 513, 515, 517, 519, 521, 523, 525, 527, 529, 531, 533, 535,
537, 539, 541, 543, 545, 547, 549, 551, 561, 571, 581, 583, 586, 588, 591,
593, 596, 597, 598, 599, 600, 601, 602, 603, 604, 605, 606, 607, 608, 609,
610, 611, 612, 613, 614, 615, 616, 617, 618, 628, 638, 648, 650, 653, 655,
658, 660, 663};
sparse_int_t A_ri[] = {0, 14, 35, 36, 71, 72, 85, 86, 87, 88, 1, 14, 35, 36, 71, 72, 85,
86, 87, 88, 2, 14, 35, 36, 71, 72, 85, 86, 87, 88, 3, 14, 35, 36, 71, 72,
85, 86, 87, 88, 4, 14, 35, 36, 71, 72, 85, 86, 87, 88, 5, 14, 35, 36, 71,
72, 85, 86, 87, 88, 6, 14, 35, 36, 71, 72, 85, 86, 87, 88, 7, 14, 35, 36,
71, 72, 85, 86, 87, 88, 8, 14, 35, 36, 71, 72, 85, 86, 87, 88, 9, 14, 35,
36, 71, 72, 85, 86, 87, 88, 0, 15, 37, 38, 69, 70, 79, 80, 81, 82, 1, 15,
37, 38, 69, 70, 79, 80, 81, 82, 2, 15, 37, 38, 69, 70, 79, 80, 81, 82, 3,
15, 37, 38, 69, 70, 79, 80, 81, 82, 4, 15, 37, 38, 69, 70, 79, 80, 81, 82,
5, 15, 37, 38, 69, 70, 79, 80, 81, 82, 6, 15, 37, 38, 69, 70, 79, 80, 81,
82, 7, 15, 37, 38, 69, 70, 79, 80, 81, 82, 8, 15, 37, 38, 69, 70, 79, 80,
81, 82, 9, 15, 37, 38, 69, 70, 79, 80, 81, 82, 0, 16, 39, 40, 67, 68, 73,
74, 75, 76, 1, 16, 39, 40, 67, 68, 73, 74, 75, 76, 2, 16, 39, 40, 67, 68,
73, 74, 75, 76, 3, 16, 39, 40, 67, 68, 73, 74, 75, 76, 4, 16, 39, 40, 67,
68, 73, 74, 75, 76, 5, 16, 39, 40, 67, 68, 73, 74, 75, 76, 6, 16, 39, 40,
67, 68, 73, 74, 75, 76, 7, 16, 39, 40, 67, 68, 73, 74, 75, 76, 8, 16, 39,
40, 67, 68, 73, 74, 75, 76, 9, 16, 39, 40, 67, 68, 73, 74, 75, 76, 10, 11,
12, 13, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 47, 48, 49, 50, 51,
52, 53, 54, 55, 56, 57, 47, 58, 48, 59, 49, 60, 50, 61, 51, 62, 52, 63, 53,
64, 54, 65, 55, 66, 46, 56, 45, 57, 47, 58, 48, 59, 49, 60, 50, 61, 51, 62,
52, 63, 53, 64, 54, 65, 55, 66, 46, 56, 45, 57, 10, 14, 71, 72, 85, 86, 87,
88, 89, 90, 11, 15, 69, 70, 79, 80, 81, 82, 83, 84, 12, 16, 67, 68, 73, 74,
75, 76, 77, 78, 35, 90, 36, 89, 90, 37, 84, 38, 83, 84, 39, 78, 40, 77, 78,
44, 58, 43, 59, 42, 60, 41, 61, 34, 62, 33, 63, 32, 64, 31, 65, 30, 66, 29,
46, 28, 45, 44, 58, 43, 59, 42, 60, 41, 61, 34, 62, 33, 63, 32, 64, 31, 65,
30, 66, 29, 46, 28, 45, 10, 14, 71, 72, 85, 86, 87, 88, 89, 90, 11, 15, 69,
70, 79, 80, 81, 82, 83, 84, 12, 16, 67, 68, 73, 74, 75, 76, 77, 78, 35, 90,
36, 89, 90, 37, 84, 38, 83, 84, 39, 78, 40, 77, 78, 27, 44, 26, 43, 25, 42,
24, 41, 23, 34, 22, 33, 21, 32, 20, 31, 19, 30, 18, 29, 17, 28, 27, 44, 26,
43, 25, 42, 24, 41, 23, 34, 22, 33, 21, 32, 20, 31, 19, 30, 18, 29, 17, 28,
10, 14, 71, 72, 85, 86, 87, 88, 89, 90, 11, 15, 69, 70, 79, 80, 81, 82, 83,
84, 12, 16, 67, 68, 73, 74, 75, 76, 77, 78, 35, 90, 36, 89, 90, 37, 84, 38,
83, 84, 39, 78, 40, 77, 78, 27, 26, 25, 24, 23, 22, 21, 20, 19, 18, 17, 27,
26, 25, 24, 23, 22, 21, 20, 19, 18, 17, 10, 14, 71, 72, 85, 86, 87, 88, 89,
90, 11, 15, 69, 70, 79, 80, 81, 82, 83, 84, 12, 16, 67, 68, 73, 74, 75, 76,
77, 78, 35, 90, 36, 89, 90, 37, 84, 38, 83, 84, 39, 78, 40, 77, 78};
real_t A_val[] = {
-1.0000000000000000e+00, 1.0000000000000000e+00, 8.8678200000000004e+01,
9.3617050000000006e+01, 1.6000000000000000e+01, 8.1999999999999993e+00,
9.9000000000000000e+01, 8.0000000000000000e+01, 1.2000000000000000e+01,
9.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
8.0062830000000005e+01, 9.9224010000000007e+01, 1.0000000000000000e+02,
2.1100000000000001e+01, 1.0000000000000000e+02, 1.0000000000000000e+02,
1.1400000000000000e+02, 1.1680000000000000e+02, -1.0000000000000000e+00,
1.0000000000000000e+00, 7.4697360000000003e+01, 8.3801220000000001e+01,
-8.1999999999999993e+00, 2.0000000000000000e+00, 9.0000000000000000e+01,
2.3999999999999999e+00, -1.2000000000000000e+01, -1.4800000000000001e+01,
-1.0000000000000000e+00, 1.0000000000000000e+00, 7.9194209999999998e+01,
9.0175110000000004e+01, 4.3000000000000000e+01, 8.0000000000000000e+00,
1.0000000000000000e+02, 9.5000000000000000e+01, 9.0000000000000000e+00,
2.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
7.8568219999999997e+01, 8.5996200000000002e+01, -1.2500000000000000e+01,
1.0000000000000000e+00, 9.6500000000000000e+01, 4.0000000000000000e+00,
-1.8000000000000000e+01, -2.1899999999999999e+01, -1.0000000000000000e+00,
1.0000000000000000e+00, 8.2922240000000002e+01, 8.6963380000000001e+01,
6.5000000000000000e+01, 1.2500000000000000e+01, 1.0000000000000000e+02,
9.8000000000000000e+01, 4.9000000000000000e+01, 3.7000000000000000e+01,
-1.0000000000000000e+00, 1.0000000000000000e+00, 8.2592740000000006e+01,
9.3147599999999997e+01, -1.2000000000000000e+01, 1.0000000000000000e+00,
9.6500000000000000e+01, 4.0000000000000000e+00, -1.8000000000000000e+01,
-2.1899999999999999e+01, -1.0000000000000000e+00, 1.0000000000000000e+00,
7.6506460000000004e+01, 7.8210250000000002e+01, 7.9000000000000000e+01,
1.2000000000000000e+01, 1.0000000000000000e+02, 9.5000000000000000e+01,
6.8000000000000000e+01, 6.1000000000000000e+01, -1.0000000000000000e+00,
1.0000000000000000e+00, 8.8357460000000003e+01, 9.4257840000000002e+01,
1.2500000000000000e+02, 6.1299999999999997e+01, 1.0000000000000000e+02,
1.0000000000000000e+02, 1.4500000000000000e+02, 1.4500000000000000e+02,
-1.0000000000000000e+00, 1.0000000000000000e+00, 9.0590469999999996e+01,
1.0582863000000000e+02, 6.2000000000000002e+00, 6.0000000000000000e+00,
9.7000000000000000e+01, 2.8500000000000000e+01, 4.0000000000000000e+00,
3.6000000000000001e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
8.8678200000000004e+01, 9.3617050000000006e+01, 1.6000000000000000e+01,
8.1999999999999993e+00, 9.9000000000000000e+01, 8.0000000000000000e+01,
1.2000000000000000e+01, 9.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, 8.0062830000000005e+01, 9.9224010000000007e+01,
1.0000000000000000e+02, 2.1100000000000001e+01, 1.0000000000000000e+02,
1.0000000000000000e+02, 1.1400000000000000e+02, 1.1680000000000000e+02,
-1.0000000000000000e+00, 1.0000000000000000e+00, 7.4697360000000003e+01,
8.3801220000000001e+01, -8.1999999999999993e+00, 2.0000000000000000e+00,
9.0000000000000000e+01, 2.3999999999999999e+00, -1.2000000000000000e+01,
-1.4800000000000001e+01, -1.0000000000000000e+00, 1.0000000000000000e+00,
7.9194209999999998e+01, 9.0175110000000004e+01, 4.3000000000000000e+01,
8.0000000000000000e+00, 1.0000000000000000e+02, 9.5000000000000000e+01,
9.0000000000000000e+00, 2.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, 7.8568219999999997e+01, 8.5996200000000002e+01,
-1.2500000000000000e+01, 1.0000000000000000e+00, 9.6500000000000000e+01,
4.0000000000000000e+00, -1.8000000000000000e+01, -2.1899999999999999e+01,
-1.0000000000000000e+00, 1.0000000000000000e+00, 8.2922240000000002e+01,
8.6963380000000001e+01, 6.5000000000000000e+01, 1.2500000000000000e+01,
1.0000000000000000e+02, 9.8000000000000000e+01, 4.9000000000000000e+01,
3.7000000000000000e+01, -1.0000000000000000e+00, 1.0000000000000000e+00,
8.2592740000000006e+01, 9.3147599999999997e+01, -1.2000000000000000e+01,
1.0000000000000000e+00, 9.6500000000000000e+01, 4.0000000000000000e+00,
-1.8000000000000000e+01, -2.1899999999999999e+01, -1.0000000000000000e+00,
1.0000000000000000e+00, 7.6506460000000004e+01, 7.8210250000000002e+01,
7.9000000000000000e+01, 1.2000000000000000e+01, 1.0000000000000000e+02,
9.5000000000000000e+01, 6.8000000000000000e+01, 6.1000000000000000e+01,
-1.0000000000000000e+00, 1.0000000000000000e+00, 8.8357460000000003e+01,
9.4257840000000002e+01, 1.2500000000000000e+02, 6.1299999999999997e+01,
1.0000000000000000e+02, 1.0000000000000000e+02, 1.4500000000000000e+02,
1.4500000000000000e+02, -1.0000000000000000e+00, 1.0000000000000000e+00,
9.0590469999999996e+01, 1.0582863000000000e+02, 6.2000000000000002e+00,
6.0000000000000000e+00, 9.7000000000000000e+01, 2.8500000000000000e+01,
4.0000000000000000e+00, 3.6000000000000001e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, 8.8678200000000004e+01, 9.3617050000000006e+01,
1.6000000000000000e+01, 8.1999999999999993e+00, 9.9000000000000000e+01,
8.0000000000000000e+01, 1.2000000000000000e+01, 9.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, 8.0062830000000005e+01,
9.9224010000000007e+01, 1.0000000000000000e+02, 2.1100000000000001e+01,
1.0000000000000000e+02, 1.0000000000000000e+02, 1.1400000000000000e+02,
1.1680000000000000e+02, -1.0000000000000000e+00, 1.0000000000000000e+00,
7.4697360000000003e+01, 8.3801220000000001e+01, -8.1999999999999993e+00,
2.0000000000000000e+00, 9.0000000000000000e+01, 2.3999999999999999e+00,
-1.2000000000000000e+01, -1.4800000000000001e+01, -1.0000000000000000e+00,
1.0000000000000000e+00, 7.9194209999999998e+01, 9.0175110000000004e+01,
4.3000000000000000e+01, 8.0000000000000000e+00, 1.0000000000000000e+02,
9.5000000000000000e+01, 9.0000000000000000e+00, 2.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, 7.8568219999999997e+01,
8.5996200000000002e+01, -1.2500000000000000e+01, 1.0000000000000000e+00,
9.6500000000000000e+01, 4.0000000000000000e+00, -1.8000000000000000e+01,
-2.1899999999999999e+01, -1.0000000000000000e+00, 1.0000000000000000e+00,
8.2922240000000002e+01, 8.6963380000000001e+01, 6.5000000000000000e+01,
1.2500000000000000e+01, 1.0000000000000000e+02, 9.8000000000000000e+01,
4.9000000000000000e+01, 3.7000000000000000e+01, -1.0000000000000000e+00,
1.0000000000000000e+00, 8.2592740000000006e+01, 9.3147599999999997e+01,
-1.2000000000000000e+01, 1.0000000000000000e+00, 9.6500000000000000e+01,
4.0000000000000000e+00, -1.8000000000000000e+01, -2.1899999999999999e+01,
-1.0000000000000000e+00, 1.0000000000000000e+00, 7.6506460000000004e+01,
7.8210250000000002e+01, 7.9000000000000000e+01, 1.2000000000000000e+01,
1.0000000000000000e+02, 9.5000000000000000e+01, 6.8000000000000000e+01,
6.1000000000000000e+01, -1.0000000000000000e+00, 1.0000000000000000e+00,
8.8357460000000003e+01, 9.4257840000000002e+01, 1.2500000000000000e+02,
6.1299999999999997e+01, 1.0000000000000000e+02, 1.0000000000000000e+02,
1.4500000000000000e+02, 1.4500000000000000e+02, -1.0000000000000000e+00,
1.0000000000000000e+00, 9.0590469999999996e+01, 1.0582863000000000e+02,
6.2000000000000002e+00, 6.0000000000000000e+00, 9.7000000000000000e+01,
2.8500000000000000e+01, 4.0000000000000000e+00, 3.6000000000000001e+00,
-1.0000000000000000e+00, -1.0000000000000000e+00, -1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, 1.0000000000000000e+00,
1.0000000000000000e+00, 1.0000000000000000e+00, 1.0000000000000000e+00,
1.0000000000000000e+00, 1.0000000000000000e+00, 1.0000000000000000e+00,
1.0000000000000000e+00, 1.0000000000000000e+00, -1.2000000000000000e-01,
-3.8000000000000000e-01, -5.0000000000000000e-01, 1.0000000000000000e+00,
1.0000000000000000e+00, 1.0000000000000000e+00, 1.0000000000000000e+00,
1.0000000000000000e+00, 1.0000000000000000e+00, 1.0000000000000000e+00,
1.0000000000000000e+00, 1.0000000000000000e+00, 1.0000000000000000e+00,
1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
-4.7000000000000000e+01, -8.6999999999999993e+00, -9.0000000000000000e+01,
-5.0000000000000000e+01, -1.0000000000000000e+01, -1.0000000000000000e+01,
-9.3000000000000000e+01, -8.9000000000000000e+01, 1.0000000000000000e+00,
-1.0000000000000000e+00, -4.7000000000000000e+01, -8.6999999999999993e+00,
-9.0000000000000000e+01, -5.0000000000000000e+01, -1.0000000000000000e+01,
-1.0000000000000000e+01, -8.9000000000000000e+01, -8.5000000000000000e+01,
1.0000000000000000e+00, -1.0000000000000000e+00, -4.7000000000000000e+01,
-8.6999999999999993e+00, -9.0000000000000000e+01, -5.0000000000000000e+01,
-1.0000000000000000e+01, -1.0000000000000000e+01, -9.1000000000000000e+01,
-8.8000000000000000e+01, -1.0000000000000000e+00, 5.0000000000000000e-01,
-1.0000000000000000e+00, 1.0000000000000000e+00, 5.0000000000000000e-01,
-1.0000000000000000e+00, 5.0000000000000000e-01, -1.0000000000000000e+00,
1.0000000000000000e+00, 5.0000000000000000e-01, -1.0000000000000000e+00,
5.0000000000000000e-01, -1.0000000000000000e+00, 1.0000000000000000e+00,
5.0000000000000000e-01, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, -4.7000000000000000e+01,
-8.6999999999999993e+00, -9.0000000000000000e+01, -5.0000000000000000e+01,
-1.0000000000000000e+01, -1.0000000000000000e+01, -9.3000000000000000e+01,
-8.9000000000000000e+01, 1.0000000000000000e+00, -1.0000000000000000e+00,
-4.7000000000000000e+01, -8.6999999999999993e+00, -9.0000000000000000e+01,
-5.0000000000000000e+01, -1.0000000000000000e+01, -1.0000000000000000e+01,
-8.9000000000000000e+01, -8.5000000000000000e+01, 1.0000000000000000e+00,
-1.0000000000000000e+00, -4.7000000000000000e+01, -8.6999999999999993e+00,
-9.0000000000000000e+01, -5.0000000000000000e+01, -1.0000000000000000e+01,
-1.0000000000000000e+01, -9.1000000000000000e+01, -8.8000000000000000e+01,
-1.0000000000000000e+00, 5.0000000000000000e-01, -1.0000000000000000e+00,
1.0000000000000000e+00, 5.0000000000000000e-01, -1.0000000000000000e+00,
5.0000000000000000e-01, -1.0000000000000000e+00, 1.0000000000000000e+00,
5.0000000000000000e-01, -1.0000000000000000e+00, 5.0000000000000000e-01,
-1.0000000000000000e+00, 1.0000000000000000e+00, 5.0000000000000000e-01,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, 1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, 1.0000000000000000e+00,
-1.0000000000000000e+00, -4.7000000000000000e+01, -8.6999999999999993e+00,
-9.0000000000000000e+01, -5.0000000000000000e+01, -1.0000000000000000e+01,
-1.0000000000000000e+01, -9.3000000000000000e+01, -8.9000000000000000e+01,
1.0000000000000000e+00, -1.0000000000000000e+00, -4.7000000000000000e+01,
-8.6999999999999993e+00, -9.0000000000000000e+01, -5.0000000000000000e+01,
-1.0000000000000000e+01, -1.0000000000000000e+01, -8.9000000000000000e+01,
-8.5000000000000000e+01, 1.0000000000000000e+00, -1.0000000000000000e+00,
-4.7000000000000000e+01, -8.6999999999999993e+00, -9.0000000000000000e+01,
-5.0000000000000000e+01, -1.0000000000000000e+01, -1.0000000000000000e+01,
-9.1000000000000000e+01, -8.8000000000000000e+01, -1.0000000000000000e+00,
5.0000000000000000e-01, -1.0000000000000000e+00, 1.0000000000000000e+00,
5.0000000000000000e-01, -1.0000000000000000e+00, 5.0000000000000000e-01,
-1.0000000000000000e+00, 1.0000000000000000e+00, 5.0000000000000000e-01,
-1.0000000000000000e+00, 5.0000000000000000e-01, -1.0000000000000000e+00,
1.0000000000000000e+00, 5.0000000000000000e-01, -1.0000000000000000e+00,
-1.0000000000000000e+00, -1.0000000000000000e+00, -1.0000000000000000e+00,
-1.0000000000000000e+00, -1.0000000000000000e+00, -1.0000000000000000e+00,
-1.0000000000000000e+00, -1.0000000000000000e+00, -1.0000000000000000e+00,
-1.0000000000000000e+00, -1.0000000000000000e+00, -1.0000000000000000e+00,
-1.0000000000000000e+00, -1.0000000000000000e+00, -1.0000000000000000e+00,
-1.0000000000000000e+00, -1.0000000000000000e+00, -1.0000000000000000e+00,
-1.0000000000000000e+00, -1.0000000000000000e+00, -1.0000000000000000e+00,
1.0000000000000000e+00, -1.0000000000000000e+00, -4.7000000000000000e+01,
-8.6999999999999993e+00, -9.0000000000000000e+01, -5.0000000000000000e+01,
-1.0000000000000000e+01, -1.0000000000000000e+01, -9.3000000000000000e+01,
-8.9000000000000000e+01, 1.0000000000000000e+00, -1.0000000000000000e+00,
-4.7000000000000000e+01, -8.6999999999999993e+00, -9.0000000000000000e+01,
-5.0000000000000000e+01, -1.0000000000000000e+01, -1.0000000000000000e+01,
-8.9000000000000000e+01, -8.5000000000000000e+01, 1.0000000000000000e+00,
-1.0000000000000000e+00, -4.7000000000000000e+01, -8.6999999999999993e+00,
-9.0000000000000000e+01, -5.0000000000000000e+01, -1.0000000000000000e+01,
-1.0000000000000000e+01, -9.1000000000000000e+01, -8.8000000000000000e+01,
-1.0000000000000000e+00, 5.0000000000000000e-01, -1.0000000000000000e+00,
1.0000000000000000e+00, 5.0000000000000000e-01, -1.0000000000000000e+00,
5.0000000000000000e-01, -1.0000000000000000e+00, 1.0000000000000000e+00,
5.0000000000000000e-01, -1.0000000000000000e+00, 5.0000000000000000e-01,
-1.0000000000000000e+00, 1.0000000000000000e+00, 5.0000000000000000e-01};
real_t g[] = {+0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00,
+0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00,
+0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00,
+0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00,
+0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00,
+0e+00, +0e+00, -2e+00, -2e+00, -2e+00, -2e+00, -2e+00, -2e+00, -2e+00,
-2e+00, +0e+00, -2e+00, +0e+00, +2e-03, +2e-03, +2e-03, +2e-03, +2e-03,
+2e-03, +1e-03, +2e-03, +2e-03, +2e-03, +0e+00, -2e-03, -2e-03, -2e-03,
-2e-03, -2e-03, -2e-03, -1e-03, -2e-03, -2e-03, -2e-03, +0e+00, +0e+00,
+0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +2e-03,
+2e-03, +2e-03, +2e-03, +2e-03, +2e-03, +1e-03, +2e-03, +2e-03, +2e-03,
+0e+00, -2e-03, -2e-03, -2e-03, -2e-03, -2e-03, -2e-03, -1e-03, -2e-03,
-2e-03, -2e-03, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00,
+0e+00, +0e+00, +0e+00, +2e-03, +2e-03, +2e-03, +2e-03, +2e-03, +2e-03,
+1e-03, +2e-03, +2e-03, +2e-03, +0e+00, -2e-03, -2e-03, -2e-03, -2e-03,
-2e-03, -2e-03, -1e-03, -2e-03, -2e-03, -2e-03, +0e+00, +0e+00, +0e+00,
+0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +1e-01, +1e-01,
+1e-01, +1e-01, +1e-01, +1e-01, +1e-01, +1e-01, +1e-01, +1e-01, +0e+00,
-1e-01, -1e-01, -1e-01, -1e-01, -1e-01, -1e-01, -1e-01, -1e-01, -1e-01,
-1e-01, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00, +0e+00,
+0e+00};
real_t lb[] = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, -Inf, 0, -Inf, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 10, 5,
10, 5, 0, 10, 0, 2, 0, 10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 10, 5, 10, 5, 0, 10, 0, 5, 0, 10, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 10, 5, 10, 5, 0, 10, 0, 5, 0, 10, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
real_t ub[] = {Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf,
Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf,
Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf,
Inf, Inf, 0, 92, 39, 87, 29, 0, 20, 0, 28, 20, 71, Inf, 130, 45, 53, 55, 75,
112, 0, 73, 480, 154, 121, 50, 30, 77, 20, 0, 18, 0, 5, 20, 71, Inf, Inf,
Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, 130, 55, 93, 60, 75, 115, 0, 67,
480, 154, 121, 50, 20, 37, 15, 0, 15, 0, 8, 20, 71, Inf, Inf, Inf, Inf, Inf,
Inf, Inf, Inf, Inf, Inf, 130, 55, 93, 60, 75, 105, 0, 67, 4980, 154, 110,
50, 20, 37, 15, 0, 25, 0, 8, 20, 71, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf,
Inf, Inf, 20, 20, 20, 20, 0, 20, 0, 20, 0, 20, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf};
real_t lbA[] = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, -Inf, -Inf,
-Inf, -Inf, -Inf, -Inf, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0};
real_t ubA[] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf, Inf,
Inf, Inf, Inf, Inf};
long H_nnz = (long) sizeof(H_val) / (long) sizeof(real_t);
long A_nnz = (long) sizeof(A_val) / (long) sizeof(real_t);

View File

@ -0,0 +1,18 @@
* text=auto !eol
/INSTALL.MUMPS -text
/LICENSE -text
/ar-lib -text
/coinmumps.pc.in -text
/compile -text
/config.guess -text
/config.h.in -text
/config.sub -text
/configure -text
/depcomp -text
/get.Mumps -text
/install-sh -text
/ltmain.sh -text
/missing -text
/mumps_compat.h.in -text
/mumps_int_def.h.in -text
/mumps_mpi.patch -text

View File

@ -0,0 +1 @@
/MUMPS

View File

@ -0,0 +1,87 @@
Eclipse Public License - v 1.0
THE ACCOMPANYING PROGRAM IS PROVIDED UNDER THE TERMS OF THIS ECLIPSE PUBLIC LICENSE ("AGREEMENT"). ANY USE, REPRODUCTION OR DISTRIBUTION OF THE PROGRAM CONSTITUTES RECIPIENT'S ACCEPTANCE OF THIS AGREEMENT.
1. DEFINITIONS
"Contribution" means:
a) in the case of the initial Contributor, the initial code and documentation distributed under this Agreement, and
b) in the case of each subsequent Contributor:
i) changes to the Program, and
ii) additions to the Program;
where such changes and/or additions to the Program originate from and are distributed by that particular Contributor. A Contribution 'originates' from a Contributor if it was added to the Program by such Contributor itself or anyone acting on such Contributor's behalf. Contributions do not include additions to the Program which: (i) are separate modules of software distributed in conjunction with the Program under their own license agreement, and (ii) are not derivative works of the Program.
"Contributor" means any person or entity that distributes the Program.
"Licensed Patents" mean patent claims licensable by a Contributor which are necessarily infringed by the use or sale of its Contribution alone or when combined with the Program.
"Program" means the Contributions distributed in accordance with this Agreement.
"Recipient" means anyone who receives the Program under this Agreement, including all Contributors.
2. GRANT OF RIGHTS
a) Subject to the terms of this Agreement, each Contributor hereby grants Recipient a non-exclusive, worldwide, royalty-free copyright license to reproduce, prepare derivative works of, publicly display, publicly perform, distribute and sublicense the Contribution of such Contributor, if any, and such derivative works, in source code and object code form.
b) Subject to the terms of this Agreement, each Contributor hereby grants Recipient a non-exclusive, worldwide, royalty-free patent license under Licensed Patents to make, use, sell, offer to sell, import and otherwise transfer the Contribution of such Contributor, if any, in source code and object code form. This patent license shall apply to the combination of the Contribution and the Program if, at the time the Contribution is added by the Contributor, such addition of the Contribution causes such combination to be covered by the Licensed Patents. The patent license shall not apply to any other combinations which include the Contribution. No hardware per se is licensed hereunder.
c) Recipient understands that although each Contributor grants the licenses to its Contributions set forth herein, no assurances are provided by any Contributor that the Program does not infringe the patent or other intellectual property rights of any other entity. Each Contributor disclaims any liability to Recipient for claims brought by any other entity based on infringement of intellectual property rights or otherwise. As a condition to exercising the rights and licenses granted hereunder, each Recipient hereby assumes sole responsibility to secure any other intellectual property rights needed, if any. For example, if a third party patent license is required to allow Recipient to distribute the Program, it is Recipient's responsibility to acquire that license before distributing the Program.
d) Each Contributor represents that to its knowledge it has sufficient copyright rights in its Contribution, if any, to grant the copyright license set forth in this Agreement.
3. REQUIREMENTS
A Contributor may choose to distribute the Program in object code form under its own license agreement, provided that:
a) it complies with the terms and conditions of this Agreement; and
b) its license agreement:
i) effectively disclaims on behalf of all Contributors all warranties and conditions, express and implied, including warranties or conditions of title and non-infringement, and implied warranties or conditions of merchantability and fitness for a particular purpose;
ii) effectively excludes on behalf of all Contributors all liability for damages, including direct, indirect, special, incidental and consequential damages, such as lost profits;
iii) states that any provisions which differ from this Agreement are offered by that Contributor alone and not by any other party; and
iv) states that source code for the Program is available from such Contributor, and informs licensees how to obtain it in a reasonable manner on or through a medium customarily used for software exchange.
When the Program is made available in source code form:
a) it must be made available under this Agreement; and
b) a copy of this Agreement must be included with each copy of the Program.
Contributors may not remove or alter any copyright notices contained within the Program.
Each Contributor must identify itself as the originator of its Contribution, if any, in a manner that reasonably allows subsequent Recipients to identify the originator of the Contribution.
4. COMMERCIAL DISTRIBUTION
Commercial distributors of software may accept certain responsibilities with respect to end users, business partners and the like. While this license is intended to facilitate the commercial use of the Program, the Contributor who includes the Program in a commercial product offering should do so in a manner which does not create potential liability for other Contributors. Therefore, if a Contributor includes the Program in a commercial product offering, such Contributor ("Commercial Contributor") hereby agrees to defend and indemnify every other Contributor ("Indemnified Contributor") against any losses, damages and costs (collectively "Losses") arising from claims, lawsuits and other legal actions brought by a third party against the Indemnified Contributor to the extent caused by the acts or omissions of such Commercial Contributor in connection with its distribution of the Program in a commercial product offering. The obligations in this section do not apply to any claims or Losses relating to any actual or alleged intellectual property infringement. In order to qualify, an Indemnified Contributor must: a) promptly notify the Commercial Contributor in writing of such claim, and b) allow the Commercial Contributor to control, and cooperate with the Commercial Contributor in, the defense and any related settlement negotiations. The Indemnified Contributor may participate in any such claim at its own expense.
For example, a Contributor might include the Program in a commercial product offering, Product X. That Contributor is then a Commercial Contributor. If that Commercial Contributor then makes performance claims, or offers warranties related to Product X, those performance claims and warranties are such Commercial Contributor's responsibility alone. Under this section, the Commercial Contributor would have to defend claims against the other Contributors related to those performance claims and warranties, and if a court requires any other Contributor to pay any damages as a result, the Commercial Contributor must pay those damages.
5. NO WARRANTY
EXCEPT AS EXPRESSLY SET FORTH IN THIS AGREEMENT, THE PROGRAM IS PROVIDED 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. Each Recipient is solely responsible for determining the appropriateness of using and distributing the Program and assumes all risks associated with its exercise of rights under this Agreement , including but not limited to the risks and costs of program errors, compliance with applicable laws, damage to or loss of data, programs or equipment, and unavailability or interruption of operations.
6. DISCLAIMER OF LIABILITY
EXCEPT AS EXPRESSLY SET FORTH IN THIS AGREEMENT, NEITHER RECIPIENT NOR ANY CONTRIBUTORS SHALL HAVE ANY LIABILITY FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING WITHOUT LIMITATION LOST PROFITS), 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 OR DISTRIBUTION OF THE PROGRAM OR THE EXERCISE OF ANY RIGHTS GRANTED HEREUNDER, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGES.
7. GENERAL
If any provision of this Agreement is invalid or unenforceable under applicable law, it shall not affect the validity or enforceability of the remainder of the terms of this Agreement, and without further action by the parties hereto, such provision shall be reformed to the minimum extent necessary to make such provision valid and enforceable.
If Recipient institutes patent litigation against any entity (including a cross-claim or counterclaim in a lawsuit) alleging that the Program itself (excluding combinations of the Program with other software or hardware) infringes such Recipient's patent(s), then such Recipient's rights granted under Section 2(b) shall terminate as of the date such litigation is filed.
All Recipient's rights under this Agreement shall terminate if it fails to comply with any of the material terms or conditions of this Agreement and does not cure such failure in a reasonable period of time after becoming aware of such noncompliance. If all Recipient's rights under this Agreement terminate, Recipient agrees to cease use and distribution of the Program as soon as reasonably practicable. However, Recipient's obligations under this Agreement and any licenses granted by Recipient relating to the Program shall continue and survive.
Everyone is permitted to copy and distribute copies of this Agreement, but in order to avoid inconsistency the Agreement is copyrighted and may only be modified in the following manner. The Agreement Steward reserves the right to publish new versions (including revisions) of this Agreement from time to time. No one other than the Agreement Steward has the right to modify this Agreement. The Eclipse Foundation is the initial Agreement Steward. The Eclipse Foundation may assign the responsibility to serve as the Agreement Steward to a suitable separate entity. Each new version of the Agreement will be given a distinguishing version number. The Program (including Contributions) may always be distributed subject to the version of the Agreement under which it was received. In addition, after a new version of the Agreement is published, Contributor may elect to distribute the Program (including its Contributions) under the new version. Except as expressly stated in Sections 2(a) and 2(b) above, Recipient receives no rights or licenses to the intellectual property of any Contributor under this Agreement, whether expressly, by implication, estoppel or otherwise. All rights in the Program not expressly granted under this Agreement are reserved.
This Agreement is governed by the laws of the State of New York and the intellectual property laws of the United States of America. No party to this Agreement will bring a legal action under this Agreement more than one year after the cause of action arose. Each party waives its rights to a jury trial in any resulting litigation.

View File

@ -0,0 +1,937 @@
# Copyright (C) 2007-2010 International Business Machines and others.
# All Rights Reserved.
# This file is distributed under the Eclipse Public License.
lib_LTLIBRARIES = libcoinmumps.la
BUILT_SOURCES =
libcoinmumps_la_SOURCES = \
MUMPS/src/ana_AMDMF.F \
MUMPS/src/ana_blk.F \
MUMPS/src/ana_blk_m.F \
MUMPS/src/ana_omp_m.F \
MUMPS/src/ana_orderings.F \
MUMPS/src/ana_orderings_wrappers_m.F \
MUMPS/src/ana_set_ordering.F \
MUMPS/src/bcast_errors.F \
MUMPS/src/double_linked_list.F \
MUMPS/src/estim_flops.F \
MUMPS/src/fac_asm_build_sort_index_ELT_m.F \
MUMPS/src/fac_asm_build_sort_index_m.F \
MUMPS/src/fac_descband_data_m.F \
MUMPS/src/fac_future_niv2_mod.F \
MUMPS/src/fac_ibct_data_m.F \
MUMPS/src/fac_maprow_data_m.F \
MUMPS/src/front_data_mgt_m.F \
MUMPS/src/lr_common.F \
MUMPS/src/mumps_comm_ibcast.F \
MUMPS/src/mumps_common.c \
MUMPS/src/mumps_config_file_C.c \
MUMPS/src/mumps_io_basic.c \
MUMPS/src/mumps_io.c \
MUMPS/src/mumps_io_err.c \
MUMPS/src/mumps_io_thread.c \
MUMPS/src/mumps_l0_omp_m.F \
MUMPS/src/mumps_memory_mod.F \
MUMPS/src/mumps_metis64.c \
MUMPS/src/mumps_metis.c \
MUMPS/src/mumps_metis_int.c \
MUMPS/src/mumps_mpitoomp_m.F \
MUMPS/src/mumps_numa.c \
MUMPS/src/mumps_ooc_common.F \
MUMPS/src/mumps_pord.c \
MUMPS/src/mumps_print_defined.F \
MUMPS/src/mumps_save_restore_C.c \
MUMPS/src/mumps_scotch64.c \
MUMPS/src/mumps_scotch.c \
MUMPS/src/mumps_scotch_int.c \
MUMPS/src/mumps_size.c \
MUMPS/src/mumps_static_mapping.F \
MUMPS/src/mumps_thread_affinity.c \
MUMPS/src/mumps_register_thread.c \
MUMPS/src/mumps_thread.c \
MUMPS/src/mumps_type2_blocking.F \
MUMPS/src/mumps_type_size.F \
MUMPS/src/mumps_version.F \
MUMPS/src/omp_tps_common_m.F \
MUMPS/src/sol_common.F \
MUMPS/src/tools_common.F \
MUMPS/libseq/mpi.f \
MUMPS/libseq/mpic.c \
MUMPS/libseq/elapse.c
if MUMPS_DOUBLE
BUILT_SOURCES += dmumps_c.c
libcoinmumps_la_SOURCES += \
dmumps_c.c \
MUMPS/src/dana_aux_ELT.F \
MUMPS/src/dana_aux.F \
MUMPS/src/dana_aux_par.F \
MUMPS/src/dana_dist_m.F \
MUMPS/src/dana_driver.F \
MUMPS/src/dana_LDLT_preprocess.F \
MUMPS/src/dana_lr.F \
MUMPS/src/dana_mtrans.F \
MUMPS/src/dana_reordertree.F \
MUMPS/src/darrowheads.F \
MUMPS/src/dbcast_int.F \
MUMPS/src/dend_driver.F \
MUMPS/src/dfac_asm_ELT.F \
MUMPS/src/dfac_asm.F \
MUMPS/src/dfac_asm_master_ELT_m.F \
MUMPS/src/dfac_asm_master_m.F \
MUMPS/src/dfac_b.F \
MUMPS/src/dfac_determinant.F \
MUMPS/src/dfac_distrib_distentry.F \
MUMPS/src/dfac_distrib_ELT.F \
MUMPS/src/dfac_driver.F \
MUMPS/src/dfac_front_aux.F \
MUMPS/src/dfac_front_LDLT_type1.F \
MUMPS/src/dfac_front_LDLT_type2.F \
MUMPS/src/dfac_front_LU_type1.F \
MUMPS/src/dfac_front_LU_type2.F \
MUMPS/src/dfac_front_type2_aux.F \
MUMPS/src/dfac_lastrtnelind.F \
MUMPS/src/dfac_lr.F \
MUMPS/src/dfac_mem_alloc_cb.F \
MUMPS/src/dfac_mem_compress_cb.F \
MUMPS/src/dfac_mem_dynamic.F \
MUMPS/src/dfac_mem_free_block_cb.F \
MUMPS/src/dfac_mem_stack_aux.F \
MUMPS/src/dfac_mem_stack.F \
MUMPS/src/dfac_omp_m.F \
MUMPS/src/dfac_par_m.F \
MUMPS/src/dfac_process_band.F \
MUMPS/src/dfac_process_bf.F \
MUMPS/src/dfac_process_blfac_slave.F \
MUMPS/src/dfac_process_blocfacto.F \
MUMPS/src/dfac_process_blocfacto_LDLT.F \
MUMPS/src/dfac_process_contrib_type1.F \
MUMPS/src/dfac_process_contrib_type2.F \
MUMPS/src/dfac_process_contrib_type3.F \
MUMPS/src/dfac_process_end_facto_slave.F \
MUMPS/src/dfac_process_maprow.F \
MUMPS/src/dfac_process_master2.F \
MUMPS/src/dfac_process_message.F \
MUMPS/src/dfac_process_root2slave.F \
MUMPS/src/dfac_process_root2son.F \
MUMPS/src/dfac_process_rtnelind.F \
MUMPS/src/dfac_root_parallel.F \
MUMPS/src/dfac_scalings.F \
MUMPS/src/dfac_scalings_simScaleAbs.F \
MUMPS/src/dfac_scalings_simScale_util.F \
MUMPS/src/dfac_sispointers_m.F \
MUMPS/src/dfac_sol_l0omp_m.F \
MUMPS/src/dfac_sol_pool.F \
MUMPS/src/dfac_type3_symmetrize.F \
MUMPS/src/dini_defaults.F \
MUMPS/src/dini_driver.F \
MUMPS/src/dlr_core.F \
MUMPS/src/dlr_stats.F \
MUMPS/src/dlr_type.F \
MUMPS/src/dmumps_comm_buffer.F \
MUMPS/src/dmumps_config_file.F \
MUMPS/src/dmumps_driver.F \
MUMPS/src/dmumps_f77.F \
MUMPS/src/dmumps_gpu.c \
MUMPS/src/dmumps_iXamax.F \
MUMPS/src/dmumps_load.F \
MUMPS/src/dmumps_lr_data_m.F \
MUMPS/src/dmumps_ooc_buffer.F \
MUMPS/src/dmumps_ooc.F \
MUMPS/src/dmumps_save_restore.F \
MUMPS/src/dmumps_save_restore_files.F \
MUMPS/src/dmumps_sol_es.F \
MUMPS/src/dmumps_struc_def.F \
MUMPS/src/domp_tps_m.F \
MUMPS/src/dooc_panel_piv.F \
MUMPS/src/drank_revealing.F \
MUMPS/src/dsol_aux.F \
MUMPS/src/dsol_bwd_aux.F \
MUMPS/src/dsol_bwd.F \
MUMPS/src/dsol_c.F \
MUMPS/src/dsol_distrhs.F \
MUMPS/src/dsol_driver.F \
MUMPS/src/dsol_fwd_aux.F \
MUMPS/src/dsol_fwd.F \
MUMPS/src/dsol_lr.F \
MUMPS/src/dsol_matvec.F \
MUMPS/src/dsol_omp_m.F \
MUMPS/src/dsol_root_parallel.F \
MUMPS/src/dstatic_ptr_m.F \
MUMPS/src/dtools.F \
MUMPS/src/dtype3_root.F
endif
if MUMPS_SINGLE
BUILT_SOURCES += smumps_c.c
libcoinmumps_la_SOURCES += \
smumps_c.c \
MUMPS/src/sana_aux_ELT.F \
MUMPS/src/sana_aux.F \
MUMPS/src/sana_aux_par.F \
MUMPS/src/sana_dist_m.F \
MUMPS/src/sana_driver.F \
MUMPS/src/sana_LDLT_preprocess.F \
MUMPS/src/sana_lr.F \
MUMPS/src/sana_mtrans.F \
MUMPS/src/sana_reordertree.F \
MUMPS/src/sarrowheads.F \
MUMPS/src/sbcast_int.F \
MUMPS/src/send_driver.F \
MUMPS/src/sfac_asm_ELT.F \
MUMPS/src/sfac_asm.F \
MUMPS/src/sfac_asm_master_ELT_m.F \
MUMPS/src/sfac_asm_master_m.F \
MUMPS/src/sfac_b.F \
MUMPS/src/sfac_determinant.F \
MUMPS/src/sfac_distrib_distentry.F \
MUMPS/src/sfac_distrib_ELT.F \
MUMPS/src/sfac_driver.F \
MUMPS/src/sfac_front_aux.F \
MUMPS/src/sfac_front_LDLT_type1.F \
MUMPS/src/sfac_front_LDLT_type2.F \
MUMPS/src/sfac_front_LU_type1.F \
MUMPS/src/sfac_front_LU_type2.F \
MUMPS/src/sfac_front_type2_aux.F \
MUMPS/src/sfac_lastrtnelind.F \
MUMPS/src/sfac_lr.F \
MUMPS/src/sfac_mem_alloc_cb.F \
MUMPS/src/sfac_mem_compress_cb.F \
MUMPS/src/sfac_mem_dynamic.F \
MUMPS/src/sfac_mem_free_block_cb.F \
MUMPS/src/sfac_mem_stack_aux.F \
MUMPS/src/sfac_mem_stack.F \
MUMPS/src/sfac_omp_m.F \
MUMPS/src/sfac_par_m.F \
MUMPS/src/sfac_process_band.F \
MUMPS/src/sfac_process_bf.F \
MUMPS/src/sfac_process_blfac_slave.F \
MUMPS/src/sfac_process_blocfacto.F \
MUMPS/src/sfac_process_blocfacto_LDLT.F \
MUMPS/src/sfac_process_contrib_type1.F \
MUMPS/src/sfac_process_contrib_type2.F \
MUMPS/src/sfac_process_contrib_type3.F \
MUMPS/src/sfac_process_end_facto_slave.F \
MUMPS/src/sfac_process_maprow.F \
MUMPS/src/sfac_process_master2.F \
MUMPS/src/sfac_process_message.F \
MUMPS/src/sfac_process_root2slave.F \
MUMPS/src/sfac_process_root2son.F \
MUMPS/src/sfac_process_rtnelind.F \
MUMPS/src/sfac_root_parallel.F \
MUMPS/src/sfac_scalings.F \
MUMPS/src/sfac_scalings_simScaleAbs.F \
MUMPS/src/sfac_scalings_simScale_util.F \
MUMPS/src/sfac_sispointers_m.F \
MUMPS/src/sfac_sol_l0omp_m.F \
MUMPS/src/sfac_sol_pool.F \
MUMPS/src/sfac_type3_symmetrize.F \
MUMPS/src/sini_defaults.F \
MUMPS/src/sini_driver.F \
MUMPS/src/slr_core.F \
MUMPS/src/slr_stats.F \
MUMPS/src/slr_type.F \
MUMPS/src/smumps_comm_buffer.F \
MUMPS/src/smumps_config_file.F \
MUMPS/src/smumps_driver.F \
MUMPS/src/smumps_f77.F \
MUMPS/src/smumps_gpu.c \
MUMPS/src/smumps_iXamax.F \
MUMPS/src/smumps_load.F \
MUMPS/src/smumps_lr_data_m.F \
MUMPS/src/smumps_ooc_buffer.F \
MUMPS/src/smumps_ooc.F \
MUMPS/src/smumps_save_restore.F \
MUMPS/src/smumps_save_restore_files.F \
MUMPS/src/smumps_sol_es.F \
MUMPS/src/smumps_struc_def.F \
MUMPS/src/somp_tps_m.F \
MUMPS/src/sooc_panel_piv.F \
MUMPS/src/srank_revealing.F \
MUMPS/src/ssol_aux.F \
MUMPS/src/ssol_bwd_aux.F \
MUMPS/src/ssol_bwd.F \
MUMPS/src/ssol_c.F \
MUMPS/src/ssol_distrhs.F \
MUMPS/src/ssol_driver.F \
MUMPS/src/ssol_fwd_aux.F \
MUMPS/src/ssol_fwd.F \
MUMPS/src/ssol_lr.F \
MUMPS/src/ssol_matvec.F \
MUMPS/src/ssol_omp_m.F \
MUMPS/src/ssol_root_parallel.F \
MUMPS/src/sstatic_ptr_m.F \
MUMPS/src/stools.F \
MUMPS/src/stype3_root.F
endif
# this is to compile mumps_c.c once for each precision with different setting for MUMPS_ARITH
dmumps_c.c : $(srcdir)/MUMPS/src/mumps_c.c
echo "#define MUMPS_ARITH MUMPS_ARITH_d" > $@
cat $< >> $@
smumps_c.c : $(srcdir)/MUMPS/src/mumps_c.c
echo "#define MUMPS_ARITH MUMPS_ARITH_s" > $@
cat $< >> $@
libcoinmumps_la_LIBADD = $(MUMPS_LFLAGS)
AM_CPPFLAGS = -I$(srcdir)/MUMPS/src -I$(srcdir)/MUMPS/libseq -I$(srcdir)/MUMPS/include
AM_LDFLAGS = $(LT_LDFLAGS)
# Dependencies between modules:
# i) arithmetic-dependent modules:
MUMPS/src/dana_aux.lo: \
MUMPS/src/dmumps_struc_def.lo \
MUMPS/src/mumps_static_mapping.lo \
MUMPS/src/ana_blk_m.lo \
MUMPS/src/ana_orderings_wrappers_m.lo
MUMPS/src/dana_aux_par.lo: \
MUMPS/src/dmumps_struc_def.lo \
MUMPS/src/mumps_memory_mod.lo \
MUMPS/src/ana_orderings_wrappers_m.lo
MUMPS/src/dana_lr.lo: MUMPS/src/dlr_core.lo \
MUMPS/src/dlr_stats.lo \
MUMPS/src/lr_common.lo \
MUMPS/src/ana_orderings_wrappers_m.lo
MUMPS/src/dfac_asm_master_ELT_m.lo: \
MUMPS/src/omp_tps_common_m.lo \
MUMPS/src/fac_ibct_data_m.lo \
MUMPS/src/fac_asm_build_sort_index_ELT_m.lo \
MUMPS/src/lr_common.lo \
MUMPS/src/dfac_mem_dynamic.lo \
MUMPS/src/dlr_core.lo \
MUMPS/src/dana_lr.lo \
MUMPS/src/dmumps_lr_data_m.lo \
MUMPS/src/dmumps_struc_def.lo \
MUMPS/src/domp_tps_m.lo \
MUMPS/src/dmumps_comm_buffer.lo \
MUMPS/src/dmumps_load.lo
MUMPS/src/dfac_asm_master_m.lo: \
MUMPS/src/omp_tps_common_m.lo \
MUMPS/src/fac_ibct_data_m.lo \
MUMPS/src/fac_asm_build_sort_index_m.lo \
MUMPS/src/lr_common.lo \
MUMPS/src/dfac_mem_dynamic.lo \
MUMPS/src/dlr_core.lo \
MUMPS/src/dana_lr.lo \
MUMPS/src/dmumps_lr_data_m.lo \
MUMPS/src/dmumps_struc_def.lo \
MUMPS/src/domp_tps_m.lo \
MUMPS/src/dmumps_comm_buffer.lo \
MUMPS/src/dmumps_load.lo
MUMPS/src/dfac_b.lo: \
MUMPS/src/dfac_sispointers_m.lo
MUMPS/src/dfac_front_aux.lo: \
MUMPS/src/dlr_type.lo \
MUMPS/src/dlr_stats.lo \
MUMPS/src/dmumps_comm_buffer.lo \
MUMPS/src/dmumps_load.lo \
MUMPS/src/dmumps_ooc.lo \
MUMPS/src/mumps_ooc_common.lo \
MUMPS/src/mumps_l0_omp_m.lo
MUMPS/src/dfac_front_LU_type1.lo : \
MUMPS/src/dfac_front_aux.lo \
MUMPS/src/dmumps_ooc.lo \
MUMPS/src/dfac_lr.lo \
MUMPS/src/dlr_type.lo \
MUMPS/src/dlr_stats.lo \
MUMPS/src/dana_lr.lo \
MUMPS/src/dmumps_lr_data_m.lo \
MUMPS/src/mumps_l0_omp_m.lo
MUMPS/src/dfac_front_LU_type2.lo : \
MUMPS/src/dfac_front_aux.lo \
MUMPS/src/dfac_front_type2_aux.lo \
MUMPS/src/dmumps_ooc.lo \
MUMPS/src/dmumps_comm_buffer.lo \
MUMPS/src/mumps_comm_ibcast.lo \
MUMPS/src/dfac_lr.lo \
MUMPS/src/dlr_core.lo \
MUMPS/src/dlr_type.lo \
MUMPS/src/dlr_stats.lo \
MUMPS/src/dana_lr.lo \
MUMPS/src/dmumps_lr_data_m.lo \
MUMPS/src/dmumps_struc_def.lo
MUMPS/src/dfac_front_LDLT_type1.lo : \
MUMPS/src/dfac_front_aux.lo \
MUMPS/src/dmumps_ooc.lo \
MUMPS/src/dfac_lr.lo \
MUMPS/src/dlr_type.lo \
MUMPS/src/dlr_stats.lo \
MUMPS/src/dana_lr.lo \
MUMPS/src/dmumps_lr_data_m.lo \
MUMPS/src/mumps_l0_omp_m.lo
MUMPS/src/dfac_front_LDLT_type2.lo : \
MUMPS/src/dfac_front_aux.lo \
MUMPS/src/dfac_front_type2_aux.lo \
MUMPS/src/dmumps_ooc.lo \
MUMPS/src/dmumps_comm_buffer.lo \
MUMPS/src/dmumps_load.lo \
MUMPS/src/dfac_lr.lo \
MUMPS/src/dlr_type.lo \
MUMPS/src/dlr_stats.lo \
MUMPS/src/dana_lr.lo \
MUMPS/src/dmumps_lr_data_m.lo \
MUMPS/src/dmumps_struc_def.lo
MUMPS/src/dfac_front_type2_aux.lo : \
MUMPS/src/mumps_ooc_common.lo \
MUMPS/src/dfac_front_aux.lo \
MUMPS/src/dlr_type.lo \
MUMPS/src/dmumps_struc_def.lo \
MUMPS/src/dmumps_comm_buffer.lo \
MUMPS/src/dmumps_load.lo \
MUMPS/src/mumps_comm_ibcast.lo \
MUMPS/src/fac_ibct_data_m.lo
MUMPS/src/dfac_lr.lo: \
MUMPS/src/dlr_core.lo \
MUMPS/src/dlr_type.lo \
MUMPS/src/dmumps_lr_data_m.lo \
MUMPS/src/dlr_stats.lo
MUMPS/src/dfac_mem_dynamic.lo: \
MUMPS/src/dmumps_load.lo \
MUMPS/src/dstatic_ptr_m.lo
MUMPS/src/dfac_omp_m.lo: \
MUMPS/src/dfac_asm_master_m.lo \
MUMPS/src/dfac_asm_master_ELT_m.lo \
MUMPS/src/dfac_front_LU_type1.lo \
MUMPS/src/dfac_front_LDLT_type1.lo \
MUMPS/src/dmumps_load.lo \
MUMPS/src/domp_tps_m.lo \
MUMPS/src/dlr_stats.lo \
MUMPS/src/dmumps_struc_def.lo \
MUMPS/src/omp_tps_common_m.lo \
MUMPS/src/mumps_l0_omp_m.lo
MUMPS/src/dfac_par_m.lo: \
MUMPS/src/dmumps_load.lo \
MUMPS/src/dmumps_ooc.lo \
MUMPS/src/dfac_asm_master_m.lo \
MUMPS/src/dfac_asm_master_ELT_m.lo \
MUMPS/src/domp_tps_m.lo \
MUMPS/src/dfac_front_LU_type1.lo \
MUMPS/src/dfac_front_LU_type2.lo \
MUMPS/src/dfac_front_LDLT_type1.lo \
MUMPS/src/dfac_front_LDLT_type2.lo \
MUMPS/src/dfac_mem_dynamic.lo \
MUMPS/src/dmumps_struc_def.lo \
MUMPS/src/dlr_stats.lo \
MUMPS/src/omp_tps_common_m.lo \
MUMPS/src/mumps_l0_omp_m.lo
MUMPS/src/dlr_core.lo: \
MUMPS/src/dlr_type.lo \
MUMPS/src/dmumps_lr_data_m.lo \
MUMPS/src/dlr_stats.lo \
MUMPS/src/lr_common.lo
MUMPS/src/dlr_stats.lo: MUMPS/src/dlr_type.lo \
MUMPS/src/dmumps_struc_def.lo
MUMPS/src/dmumps_comm_buffer.lo: \
MUMPS/src/mumps_comm_ibcast.lo \
MUMPS/src/dlr_type.lo \
MUMPS/src/dlr_core.lo \
MUMPS/src/dmumps_lr_data_m.lo \
MUMPS/src/fac_ibct_data_m.lo
MUMPS/src/dmumps_config_file.lo: MUMPS/src/dmumps_struc_def.lo
MUMPS/src/dmumps_load.lo: \
MUMPS/src/dmumps_comm_buffer.lo \
MUMPS/src/dmumps_struc_def.lo \
MUMPS/src/fac_future_niv2_mod.lo
MUMPS/src/dmumps_lr_data_m.lo: \
MUMPS/src/dlr_type.lo \
MUMPS/src/front_data_mgt_m.lo
MUMPS/src/dmumps_ooc_buffer.lo: MUMPS/src/mumps_ooc_common.lo
MUMPS/src/dmumps_ooc.lo: \
MUMPS/src/dmumps_struc_def.lo \
MUMPS/src/dmumps_ooc_buffer.lo \
MUMPS/src/mumps_ooc_common.lo
MUMPS/src/dmumps_sol_es.lo: \
MUMPS/src/dlr_type.lo \
MUMPS/src/dmumps_lr_data_m.lo
MUMPS/src/dmumps_save_restore.lo: \
MUMPS/src/dfac_sol_l0omp_m.lo \
MUMPS/src/dmumps_struc_def.lo \
MUMPS/src/dmumps_save_restore_files.lo \
MUMPS/src/dmumps_lr_data_m.lo \
MUMPS/src/dmumps_ooc.lo \
MUMPS/src/front_data_mgt_m.lo
MUMPS/src/dmumps_save_restore_files.lo : MUMPS/src/dmumps_struc_def.lo
MUMPS/src/dsol_lr.lo: \
MUMPS/src/dlr_type.lo \
MUMPS/src/dlr_stats.lo \
MUMPS/src/dmumps_lr_data_m.lo
MUMPS/src/sana_aux.lo: \
MUMPS/src/smumps_struc_def.lo \
MUMPS/src/mumps_static_mapping.lo \
MUMPS/src/ana_blk_m.lo \
MUMPS/src/ana_orderings_wrappers_m.lo
MUMPS/src/sana_aux_par.lo: \
MUMPS/src/smumps_struc_def.lo \
MUMPS/src/mumps_memory_mod.lo \
MUMPS/src/ana_orderings_wrappers_m.lo
MUMPS/src/sana_lr.lo: MUMPS/src/slr_core.lo \
MUMPS/src/slr_stats.lo \
MUMPS/src/lr_common.lo \
MUMPS/src/ana_orderings_wrappers_m.lo
MUMPS/src/sfac_asm_master_ELT_m.lo: \
MUMPS/src/omp_tps_common_m.lo \
MUMPS/src/fac_ibct_data_m.lo \
MUMPS/src/fac_asm_build_sort_index_ELT_m.lo \
MUMPS/src/lr_common.lo \
MUMPS/src/sfac_mem_dynamic.lo \
MUMPS/src/slr_core.lo \
MUMPS/src/sana_lr.lo \
MUMPS/src/smumps_lr_data_m.lo \
MUMPS/src/smumps_struc_def.lo \
MUMPS/src/somp_tps_m.lo \
MUMPS/src/smumps_comm_buffer.lo \
MUMPS/src/smumps_load.lo
MUMPS/src/sfac_asm_master_m.lo: \
MUMPS/src/omp_tps_common_m.lo \
MUMPS/src/fac_ibct_data_m.lo \
MUMPS/src/fac_asm_build_sort_index_m.lo \
MUMPS/src/lr_common.lo \
MUMPS/src/sfac_mem_dynamic.lo \
MUMPS/src/slr_core.lo \
MUMPS/src/sana_lr.lo \
MUMPS/src/smumps_lr_data_m.lo \
MUMPS/src/smumps_struc_def.lo \
MUMPS/src/somp_tps_m.lo \
MUMPS/src/smumps_comm_buffer.lo \
MUMPS/src/smumps_load.lo
MUMPS/src/sfac_b.lo: \
MUMPS/src/sfac_sispointers_m.lo
MUMPS/src/sfac_front_aux.lo: \
MUMPS/src/slr_type.lo \
MUMPS/src/slr_stats.lo \
MUMPS/src/smumps_comm_buffer.lo \
MUMPS/src/smumps_load.lo \
MUMPS/src/smumps_ooc.lo \
MUMPS/src/mumps_ooc_common.lo \
MUMPS/src/mumps_l0_omp_m.lo
MUMPS/src/sfac_front_LU_type1.lo : \
MUMPS/src/sfac_front_aux.lo \
MUMPS/src/smumps_ooc.lo \
MUMPS/src/sfac_lr.lo \
MUMPS/src/slr_type.lo \
MUMPS/src/slr_stats.lo \
MUMPS/src/sana_lr.lo \
MUMPS/src/smumps_lr_data_m.lo \
MUMPS/src/mumps_l0_omp_m.lo
MUMPS/src/sfac_front_LU_type2.lo : \
MUMPS/src/sfac_front_aux.lo \
MUMPS/src/sfac_front_type2_aux.lo \
MUMPS/src/smumps_ooc.lo \
MUMPS/src/smumps_comm_buffer.lo \
MUMPS/src/mumps_comm_ibcast.lo \
MUMPS/src/sfac_lr.lo \
MUMPS/src/slr_core.lo \
MUMPS/src/slr_type.lo \
MUMPS/src/slr_stats.lo \
MUMPS/src/sana_lr.lo \
MUMPS/src/smumps_lr_data_m.lo \
MUMPS/src/smumps_struc_def.lo
MUMPS/src/sfac_front_LDLT_type1.lo : \
MUMPS/src/sfac_front_aux.lo \
MUMPS/src/smumps_ooc.lo \
MUMPS/src/sfac_lr.lo \
MUMPS/src/slr_type.lo \
MUMPS/src/slr_stats.lo \
MUMPS/src/sana_lr.lo \
MUMPS/src/smumps_lr_data_m.lo \
MUMPS/src/mumps_l0_omp_m.lo
MUMPS/src/sfac_front_LDLT_type2.lo : \
MUMPS/src/sfac_front_aux.lo \
MUMPS/src/sfac_front_type2_aux.lo \
MUMPS/src/smumps_ooc.lo \
MUMPS/src/smumps_comm_buffer.lo \
MUMPS/src/smumps_load.lo \
MUMPS/src/sfac_lr.lo \
MUMPS/src/slr_type.lo \
MUMPS/src/slr_stats.lo \
MUMPS/src/sana_lr.lo \
MUMPS/src/smumps_lr_data_m.lo \
MUMPS/src/smumps_struc_def.lo
MUMPS/src/sfac_front_type2_aux.lo : \
MUMPS/src/mumps_ooc_common.lo \
MUMPS/src/sfac_front_aux.lo \
MUMPS/src/slr_type.lo \
MUMPS/src/smumps_struc_def.lo \
MUMPS/src/smumps_comm_buffer.lo \
MUMPS/src/smumps_load.lo \
MUMPS/src/mumps_comm_ibcast.lo \
MUMPS/src/fac_ibct_data_m.lo
MUMPS/src/sfac_lr.lo: \
MUMPS/src/slr_core.lo \
MUMPS/src/slr_type.lo \
MUMPS/src/smumps_lr_data_m.lo \
MUMPS/src/slr_stats.lo
MUMPS/src/sfac_mem_dynamic.lo: \
MUMPS/src/smumps_load.lo \
MUMPS/src/sstatic_ptr_m.lo
MUMPS/src/sfac_omp_m.lo: \
MUMPS/src/sfac_asm_master_m.lo \
MUMPS/src/sfac_asm_master_ELT_m.lo \
MUMPS/src/sfac_front_LU_type1.lo \
MUMPS/src/sfac_front_LDLT_type1.lo \
MUMPS/src/smumps_load.lo \
MUMPS/src/somp_tps_m.lo \
MUMPS/src/slr_stats.lo \
MUMPS/src/smumps_struc_def.lo \
MUMPS/src/omp_tps_common_m.lo \
MUMPS/src/mumps_l0_omp_m.lo
MUMPS/src/sfac_par_m.lo: \
MUMPS/src/smumps_load.lo \
MUMPS/src/smumps_ooc.lo \
MUMPS/src/sfac_asm_master_m.lo \
MUMPS/src/sfac_asm_master_ELT_m.lo \
MUMPS/src/somp_tps_m.lo \
MUMPS/src/sfac_front_LU_type1.lo \
MUMPS/src/sfac_front_LU_type2.lo \
MUMPS/src/sfac_front_LDLT_type1.lo \
MUMPS/src/sfac_front_LDLT_type2.lo \
MUMPS/src/sfac_mem_dynamic.lo \
MUMPS/src/smumps_struc_def.lo \
MUMPS/src/slr_stats.lo \
MUMPS/src/omp_tps_common_m.lo \
MUMPS/src/mumps_l0_omp_m.lo
MUMPS/src/slr_core.lo: \
MUMPS/src/slr_type.lo \
MUMPS/src/smumps_lr_data_m.lo \
MUMPS/src/slr_stats.lo \
MUMPS/src/lr_common.lo
MUMPS/src/slr_stats.lo: MUMPS/src/slr_type.lo \
MUMPS/src/smumps_struc_def.lo
MUMPS/src/smumps_comm_buffer.lo: \
MUMPS/src/mumps_comm_ibcast.lo \
MUMPS/src/slr_type.lo \
MUMPS/src/slr_core.lo \
MUMPS/src/smumps_lr_data_m.lo \
MUMPS/src/fac_ibct_data_m.lo
MUMPS/src/smumps_config_file.lo: MUMPS/src/smumps_struc_def.lo
MUMPS/src/smumps_load.lo: \
MUMPS/src/smumps_comm_buffer.lo \
MUMPS/src/smumps_struc_def.lo \
MUMPS/src/fac_future_niv2_mod.lo
MUMPS/src/smumps_lr_data_m.lo: \
MUMPS/src/slr_type.lo \
MUMPS/src/front_data_mgt_m.lo
MUMPS/src/smumps_ooc_buffer.lo: MUMPS/src/mumps_ooc_common.lo
MUMPS/src/smumps_ooc.lo: \
MUMPS/src/smumps_struc_def.lo \
MUMPS/src/smumps_ooc_buffer.lo \
MUMPS/src/mumps_ooc_common.lo
MUMPS/src/smumps_sol_es.lo: \
MUMPS/src/slr_type.lo \
MUMPS/src/smumps_lr_data_m.lo
MUMPS/src/smumps_save_restore.lo: \
MUMPS/src/sfac_sol_l0omp_m.lo \
MUMPS/src/smumps_struc_def.lo \
MUMPS/src/smumps_save_restore_files.lo \
MUMPS/src/smumps_lr_data_m.lo \
MUMPS/src/smumps_ooc.lo \
MUMPS/src/front_data_mgt_m.lo
MUMPS/src/smumps_save_restore_files.lo : MUMPS/src/smumps_struc_def.lo
MUMPS/src/ssol_lr.lo: \
MUMPS/src/slr_type.lo \
MUMPS/src/slr_stats.lo \
MUMPS/src/smumps_lr_data_m.lo
# Dependencies between modules:
# ii) arithmetic-independent modules:
MUMPS/src/ana_omp_m.lo: MUMPS/src/double_linked_list.lo
MUMPS/src/fac_asm_build_sort_index_ELT_m.lo: MUMPS/src/omp_tps_common_m.lo
MUMPS/src/fac_asm_build_sort_index_m.lo: MUMPS/src/omp_tps_common_m.lo
MUMPS/src/fac_descband_data_m.lo: MUMPS/src/front_data_mgt_m.lo
MUMPS/src/fac_ibct_data_m.lo: MUMPS/src/front_data_mgt_m.lo
MUMPS/src/fac_maprow_data_m.lo: MUMPS/src/front_data_mgt_m.lo
MUMPS/src/mumps_comm_ibcast.lo: MUMPS/src/fac_future_niv2_mod.lo
MUMPS/src/mumps_static_mapping.lo: MUMPS/src/lr_common.lo
# iii) compile modules before others
OBJS_COMMON_MOD = \
MUMPS/src/ana_blk_m.lo \
MUMPS/src/ana_omp_m.lo \
MUMPS/src/ana_orderings_wrappers_m.lo \
MUMPS/src/double_linked_list.lo \
MUMPS/src/fac_asm_build_sort_index_ELT_m.lo \
MUMPS/src/fac_asm_build_sort_index_m.lo \
MUMPS/src/fac_descband_data_m.lo \
MUMPS/src/fac_future_niv2_mod.lo \
MUMPS/src/fac_ibct_data_m.lo \
MUMPS/src/fac_maprow_data_m.lo \
MUMPS/src/front_data_mgt_m.lo \
MUMPS/src/lr_common.lo \
MUMPS/src/mumps_comm_ibcast.lo \
MUMPS/src/mumps_l0_omp_m.lo \
MUMPS/src/mumps_memory_mod.lo \
MUMPS/src/mumps_mpitoomp_m.lo \
MUMPS/src/mumps_ooc_common.lo \
MUMPS/src/mumps_static_mapping.lo \
MUMPS/src/omp_tps_common_m.lo
OBJS_COMMON_OTHER = \
MUMPS/src/ana_blk.lo \
MUMPS/src/ana_orderings.lo \
MUMPS/src/ana_set_ordering.lo \
MUMPS/src/ana_AMDMF.lo \
MUMPS/src/bcast_errors.lo \
MUMPS/src/estim_flops.lo \
MUMPS/src/mumps_type_size.lo \
MUMPS/src/mumps_type2_blocking.lo \
MUMPS/src/mumps_version.lo \
MUMPS/src/mumps_print_defined.lo \
MUMPS/src/mumps_common.lo \
MUMPS/src/mumps_pord.lo \
MUMPS/src/mumps_metis.lo \
MUMPS/src/mumps_metis64.lo \
MUMPS/src/mumps_metis_int.lo \
MUMPS/src/mumps_scotch.lo \
MUMPS/src/mumps_scotch64.lo \
MUMPS/src/mumps_scotch_int.lo \
MUMPS/src/mumps_size.lo \
MUMPS/src/mumps_io.lo \
MUMPS/src/mumps_io_basic.lo \
MUMPS/src/mumps_io_thread.lo \
MUMPS/src/mumps_io_err.lo \
MUMPS/src/mumps_numa.lo \
MUMPS/src/mumps_thread.lo \
MUMPS/src/mumps_save_restore_C.lo \
MUMPS/src/mumps_config_file_C.lo \
MUMPS/src/mumps_thread_affinity.lo \
MUMPS/src/tools_common.lo \
MUMPS/src/sol_common.lo
DOBJS_MOD = \
MUMPS/src/dana_aux.lo \
MUMPS/src/dana_aux_par.lo \
MUMPS/src/dana_lr.lo \
MUMPS/src/dfac_asm_master_ELT_m.lo \
MUMPS/src/dfac_asm_master_m.lo \
MUMPS/src/dfac_front_aux.lo \
MUMPS/src/dfac_front_LU_type1.lo \
MUMPS/src/dfac_front_LU_type2.lo \
MUMPS/src/dfac_front_LDLT_type1.lo \
MUMPS/src/dfac_front_LDLT_type2.lo \
MUMPS/src/dfac_front_type2_aux.lo \
MUMPS/src/dfac_lr.lo \
MUMPS/src/dfac_mem_dynamic.lo \
MUMPS/src/dfac_omp_m.lo \
MUMPS/src/dfac_par_m.lo \
MUMPS/src/dlr_core.lo \
MUMPS/src/dlr_stats.lo \
MUMPS/src/dlr_type.lo \
MUMPS/src/dmumps_comm_buffer.lo \
MUMPS/src/dmumps_config_file.lo \
MUMPS/src/dmumps_load.lo \
MUMPS/src/dmumps_lr_data_m.lo \
MUMPS/src/dmumps_ooc_buffer.lo \
MUMPS/src/dmumps_ooc.lo \
MUMPS/src/dmumps_sol_es.lo \
MUMPS/src/dmumps_save_restore.lo \
MUMPS/src/dmumps_save_restore_files.lo \
MUMPS/src/dmumps_struc_def.lo \
MUMPS/src/domp_tps_m.lo \
MUMPS/src/dsol_lr.lo \
MUMPS/src/dsol_omp_m.lo \
MUMPS/src/dstatic_ptr_m.lo
DOBJS_OTHER = \
MUMPS/src/dini_driver.lo \
MUMPS/src/dana_driver.lo \
MUMPS/src/dfac_driver.lo \
MUMPS/src/dsol_driver.lo \
MUMPS/src/dsol_distrhs.lo \
MUMPS/src/dend_driver.lo \
MUMPS/src/dana_aux_ELT.lo \
MUMPS/src/dana_dist_m.lo \
MUMPS/src/dana_LDLT_preprocess.lo \
MUMPS/src/dana_reordertree.lo \
MUMPS/src/darrowheads.lo \
MUMPS/src/dbcast_int.lo \
MUMPS/src/dfac_asm_ELT.lo \
MUMPS/src/dfac_asm.lo \
MUMPS/src/dfac_b.lo \
MUMPS/src/dfac_distrib_distentry.lo \
MUMPS/src/dfac_distrib_ELT.lo \
MUMPS/src/dfac_lastrtnelind.lo \
MUMPS/src/dfac_mem_alloc_cb.lo \
MUMPS/src/dfac_mem_compress_cb.lo \
MUMPS/src/dfac_mem_free_block_cb.lo \
MUMPS/src/dfac_mem_stack_aux.lo \
MUMPS/src/dfac_mem_stack.lo \
MUMPS/src/dfac_process_band.lo \
MUMPS/src/dfac_process_blfac_slave.lo \
MUMPS/src/dfac_process_blocfacto_LDLT.lo \
MUMPS/src/dfac_process_blocfacto.lo \
MUMPS/src/dfac_process_bf.lo \
MUMPS/src/dfac_process_end_facto_slave.lo \
MUMPS/src/dfac_process_contrib_type1.lo \
MUMPS/src/dfac_process_contrib_type2.lo \
MUMPS/src/dfac_process_contrib_type3.lo \
MUMPS/src/dfac_process_maprow.lo \
MUMPS/src/dfac_process_master2.lo \
MUMPS/src/dfac_process_message.lo \
MUMPS/src/dfac_process_root2slave.lo \
MUMPS/src/dfac_process_root2son.lo \
MUMPS/src/dfac_process_rtnelind.lo \
MUMPS/src/dfac_root_parallel.lo \
MUMPS/src/dfac_scalings.lo \
MUMPS/src/dfac_determinant.lo \
MUMPS/src/dfac_scalings_simScaleAbs.lo \
MUMPS/src/dfac_scalings_simScale_util.lo \
MUMPS/src/dfac_sol_pool.lo \
MUMPS/src/dfac_type3_symmetrize.lo \
MUMPS/src/dini_defaults.lo \
MUMPS/src/dmumps_c.lo \
MUMPS/src/dmumps_driver.lo \
MUMPS/src/dmumps_f77.lo \
MUMPS/src/dmumps_gpu.lo \
MUMPS/src/dmumps_iXamax.lo \
MUMPS/src/dana_mtrans.lo \
MUMPS/src/dooc_panel_piv.lo \
MUMPS/src/drank_revealing.lo \
MUMPS/src/dsol_aux.lo \
MUMPS/src/dsol_bwd_aux.lo \
MUMPS/src/dsol_bwd.lo \
MUMPS/src/dsol_c.lo \
MUMPS/src/dsol_fwd_aux.lo \
MUMPS/src/dsol_fwd.lo \
MUMPS/src/dsol_matvec.lo \
MUMPS/src/dsol_root_parallel.lo \
MUMPS/src/dtools.lo \
MUMPS/src/dtype3_root.lo
SOBJS_MOD = \
MUMPS/src/sana_aux.lo \
MUMPS/src/sana_aux_par.lo \
MUMPS/src/sana_lr.lo \
MUMPS/src/sfac_asm_master_ELT_m.lo \
MUMPS/src/sfac_asm_master_m.lo \
MUMPS/src/sfac_front_aux.lo \
MUMPS/src/sfac_front_LU_type1.lo \
MUMPS/src/sfac_front_LU_type2.lo \
MUMPS/src/sfac_front_LDLT_type1.lo \
MUMPS/src/sfac_front_LDLT_type2.lo \
MUMPS/src/sfac_front_type2_aux.lo \
MUMPS/src/sfac_lr.lo \
MUMPS/src/sfac_mem_dynamic.lo \
MUMPS/src/sfac_omp_m.lo \
MUMPS/src/sfac_par_m.lo \
MUMPS/src/slr_core.lo \
MUMPS/src/slr_stats.lo \
MUMPS/src/slr_type.lo \
MUMPS/src/smumps_comm_buffer.lo \
MUMPS/src/smumps_config_file.lo \
MUMPS/src/smumps_load.lo \
MUMPS/src/smumps_lr_data_m.lo \
MUMPS/src/smumps_ooc_buffer.lo \
MUMPS/src/smumps_ooc.lo \
MUMPS/src/smumps_sol_es.lo \
MUMPS/src/smumps_save_restore.lo \
MUMPS/src/smumps_save_restore_files.lo \
MUMPS/src/smumps_struc_def.lo \
MUMPS/src/somp_tps_m.lo \
MUMPS/src/ssol_lr.lo \
MUMPS/src/ssol_omp_m.lo \
MUMPS/src/sstatic_ptr_m.lo
SOBJS_OTHER = \
MUMPS/src/sini_driver.lo \
MUMPS/src/sana_driver.lo \
MUMPS/src/sfac_driver.lo \
MUMPS/src/ssol_driver.lo \
MUMPS/src/ssol_distrhs.lo \
MUMPS/src/send_driver.lo \
MUMPS/src/sana_aux_ELT.lo \
MUMPS/src/sana_dist_m.lo \
MUMPS/src/sana_LDLT_preprocess.lo \
MUMPS/src/sana_reordertree.lo \
MUMPS/src/sarrowheads.lo \
MUMPS/src/sbcast_int.lo \
MUMPS/src/sfac_asm_ELT.lo \
MUMPS/src/sfac_asm.lo \
MUMPS/src/sfac_b.lo \
MUMPS/src/sfac_distrib_distentry.lo \
MUMPS/src/sfac_distrib_ELT.lo \
MUMPS/src/sfac_lastrtnelind.lo \
MUMPS/src/sfac_mem_alloc_cb.lo \
MUMPS/src/sfac_mem_compress_cb.lo \
MUMPS/src/sfac_mem_free_block_cb.lo \
MUMPS/src/sfac_mem_stack_aux.lo \
MUMPS/src/sfac_mem_stack.lo \
MUMPS/src/sfac_process_band.lo \
MUMPS/src/sfac_process_blfac_slave.lo \
MUMPS/src/sfac_process_blocfacto_LDLT.lo \
MUMPS/src/sfac_process_blocfacto.lo \
MUMPS/src/sfac_process_bf.lo \
MUMPS/src/sfac_process_end_facto_slave.lo \
MUMPS/src/sfac_process_contrib_type1.lo \
MUMPS/src/sfac_process_contrib_type2.lo \
MUMPS/src/sfac_process_contrib_type3.lo \
MUMPS/src/sfac_process_maprow.lo \
MUMPS/src/sfac_process_master2.lo \
MUMPS/src/sfac_process_message.lo \
MUMPS/src/sfac_process_root2slave.lo \
MUMPS/src/sfac_process_root2son.lo \
MUMPS/src/sfac_process_rtnelind.lo \
MUMPS/src/sfac_root_parallel.lo \
MUMPS/src/sfac_scalings.lo \
MUMPS/src/sfac_determinant.lo \
MUMPS/src/sfac_scalings_simScaleAbs.lo \
MUMPS/src/sfac_scalings_simScale_util.lo \
MUMPS/src/sfac_sol_pool.lo \
MUMPS/src/sfac_type3_symmetrize.lo \
MUMPS/src/sini_defaults.lo \
MUMPS/src/smumps_c.lo \
MUMPS/src/smumps_driver.lo \
MUMPS/src/smumps_f77.lo \
MUMPS/src/smumps_gpu.lo \
MUMPS/src/smumps_iXamax.lo \
MUMPS/src/sana_mtrans.lo \
MUMPS/src/sooc_panel_piv.lo \
MUMPS/src/srank_revealing.lo \
MUMPS/src/ssol_aux.lo \
MUMPS/src/ssol_bwd_aux.lo \
MUMPS/src/ssol_bwd.lo \
MUMPS/src/ssol_c.lo \
MUMPS/src/ssol_fwd_aux.lo \
MUMPS/src/ssol_fwd.lo \
MUMPS/src/ssol_matvec.lo \
MUMPS/src/ssol_root_parallel.lo \
MUMPS/src/stools.lo \
MUMPS/src/stype3_root.lo
$(OBJS_COMMON_OTHER) : $(OBJS_COMMON_MOD)
if MUMPS_DOUBLE
$(DOBJS_OTHER) : $(OBJS_COMMON_MOD) $(DOBJS_MOD)
endif
if MUMPS_SINGLE
$(SOBJS_OTHER) : $(OBJS_COMMON_MOD) $(SOBJS_MOD)
endif
# Module files that need to be deleted
CLEANFILES = *.mod
AM_CFLAGS = $(MY_DEFS) $(MUMPS_CFLAGS)
FCFLAGS += $(MY_FDEFS)
# automake thinks that the .F files are F77, not F95, and requires F77 to be set
# set it to FC, and same for FFLAGS
F77 = $(FC)
FFLAGS = $(FCFLAGS)
thirdpartyincludedir = $(includedir)/coin-or/mumps
thirdpartyinclude_HEADERS = \
MUMPS/include/mumps_c_types.h \
MUMPS/libseq/mumps_mpi.h \
mumps_compat.h \
mumps_int_def.h
if MUMPS_DOUBLE
thirdpartyinclude_HEADERS += MUMPS/include/dmumps_c.h
endif
if MUMPS_SINGLE
thirdpartyinclude_HEADERS += MUMPS/include/smumps_c.h
endif
pkgconfiglibdir = $(libdir)/pkgconfig
pkgconfiglib_DATA = coinmumps.pc
test:
@echo "No test available for Mumps."

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,76 @@
# ThirdParty-Mumps
This is an autotools-based build system to build and install
[MUltifrontal Massively Parallel sparse direct Solver](http://mumps.enseeiht.fr/) (MUMPS).
This installation of MUMPS is used by some other COIN-OR projects.
This version of ThirdParty-Mumps retrieves and builds MUMPS 5.5.0.
## Dependencies
- MUMPS source requires a Fortran 90 compiler.
- MUMPS requires LAPACK to be available. `configure` will look for a Lapack
installation, but if that does not succeed, the flags to link with Lapack
should be specified with the `--with-lapack-lflags` argument of `configure`.
- MUMPS can make use of METIS. `configure` will look for a METIS library and
header, but if that does not succeed, the arguments `--with-metis-lflags`
and `--with-metis-cflags` can be specified for `configure`.
Both Metis 4 and Metis 5 can be used with ThirdParty-Mumps.
## Installation steps
1. Obtain the MUMPS source code.
**********************************************************************
Note: It is YOUR RESPONSIBILITY to ensure that you are entitled to
download and use this third party package.
**********************************************************************
The shell script `get.Mumps` can be used to automatically download and
extract the correct version of the MUMPS source code. The script will
first try to download from from https://coin-or-tools.github.io/ThirdParty-Mumps.
If this fails, it will attempt to download from the MUMPS website: http://mumps.enseeiht.fr/
The script requires wget, curl, or fetch to be available on the system
and in the shells search path (`$PATH`).
2. Run `./configure`. Use `./configure --help` to see available options.
If using GFortran 10, add `ADD_FCFLAGS=-fallow-argument-mismatch` to
your configure call (see above)
3. Run `make` to build the MUMPS library.
4. Run `make install` to install the MUMPS library and header files.
## NOTE for GFortran users
MUMPS source does not compile out of the box when using GFortran 10, probably
due to some incompatibilities between assumed Fortran language standards,
see also [issue #4](https://github.com/coin-or-tools/ThirdParty-Mumps/issues/4).
As a workaround, `configure` adds `-std=legacy` to the Fortran compiler flags
if `$FC` matches `*gfortran*`.
## Single-precision codes
This buildsystem can also build a single-precision version of MUMPS.
To do so, use the configure option `--with-precision=single`.
It is also possible to build both single- and double-precision variants
of MUMPS into the same library by using `--with-precision=all`.
## 64-bit integers
This buildsystem can be instructed to change the integer type of MUMPS to
have a size of 64-bit by using the configure option `--with-intsize=64`.
This defines `MUMPS_INTSIZE64` instead of `MUMPS_INTSIZE32` in
`mumps_int_def.h` and instructs the Fortran compiler to use 8-byte integers.
The latter requires that the Fortran compiler is either GNU Fortran or
Intel Fortran.
When MUMPS uses 64-bit integers, also Lapack and METIS need to use 64-bit
integers. For METIS, this means that `IDXTYPEWIDTH` needs to be set to 8
instead of 4.

View File

@ -0,0 +1,15 @@
@COIN_RELOCATABLE_FALSE@prefix=@prefix@
@COIN_RELOCATABLE_TRUE@prefix=${pcfiledir}/../..
exec_prefix=@exec_prefix@
libdir=@libdir@
includedir=@includedir@/coin-or/mumps
Name: Mumps
Description: Multifrontal Massively Parallel sparse direct Solver
URL: @PACKAGE_URL@
Version: @PACKAGE_VERSION@
Cflags: -I${includedir}
@COIN_STATIC_BUILD_FALSE@Libs: -L${libdir} -lcoinmumps
@COIN_STATIC_BUILD_FALSE@Requires.private: @MUMPS_PCFILES@
@COIN_STATIC_BUILD_TRUE@Libs: -L${libdir} -lcoinmumps @MUMPS_LFLAGS_NOPC@
@COIN_STATIC_BUILD_TRUE@Requires: @MUMPS_PCFILES@

View File

@ -0,0 +1,384 @@
#! /bin/sh
# Wrapper for compilers which do not understand '-c -o'.
scriptversion=2018-03-07.03; # UTC
# Copyright (C) 1999-2020 Free Software Foundation, Inc.
# Written by Tom Tromey <tromey@cygnus.com>.
#
# This program is free software; you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
# the Free Software Foundation; either version 2, or (at your option)
# any later version.
#
# This program 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 General Public License for more details.
#
# You should have received a copy of the GNU General Public License
# along with this program. If not, see <https://www.gnu.org/licenses/>.
# As a special exception to the GNU General Public License, if you
# distribute this file as part of a program that contains a
# configuration script generated by Autoconf, you may include it under
# the same distribution terms that you use for the rest of that program.
# This file is maintained in Automake, please report
# bugs to <bug-automake@gnu.org> or send patches to
# <automake-patches@gnu.org>.
nl='
'
# We need space, tab and new line, in precisely that order. Quoting is
# there to prevent tools from complaining about whitespace usage.
IFS=" "" $nl"
file_conv=
# func_file_conv build_file lazy
# Convert a $build file to $host form and store it in $file
# Currently only supports Windows hosts. If the determined conversion
# type is listed in (the comma separated) LAZY, no conversion will
# take place.
func_file_conv ()
{
file=$1
case $file in
/ | /[!/]*) # absolute file, and not a UNC file
if test -z "$file_conv"; then
# lazily determine how to convert abs files
case `uname -s` in
MINGW*)
file_conv=mingw
;;
CYGWIN* | MSYS*)
file_conv=cygwin
;;
*)
file_conv=wine
;;
esac
fi
case $file_conv/,$2, in
*,$file_conv,*)
;;
mingw/*)
file=`cmd //C echo "$file " | sed -e 's/"\(.*\) " *$/\1/'`
;;
cygwin/* | msys/*)
file=`cygpath -m "$file" || echo "$file"`
;;
wine/*)
file=`winepath -w "$file" || echo "$file"`
;;
esac
;;
esac
}
# func_cl_dashL linkdir
# Make cl look for libraries in LINKDIR
func_cl_dashL ()
{
func_file_conv "$1"
if test -z "$lib_path"; then
lib_path=$file
else
lib_path="$lib_path;$file"
fi
linker_opts="$linker_opts -LIBPATH:$file"
}
# func_cl_dashl library
# Do a library search-path lookup for cl
func_cl_dashl ()
{
lib=$1
found=no
save_IFS=$IFS
IFS=';'
for dir in $lib_path $LIB
do
IFS=$save_IFS
if $shared && test -f "$dir/$lib.dll.lib"; then
found=yes
lib=$dir/$lib.dll.lib
break
fi
if test -f "$dir/$lib.lib"; then
found=yes
lib=$dir/$lib.lib
break
fi
if test -f "$dir/lib$lib.a"; then
found=yes
lib=$dir/lib$lib.a
break
fi
done
IFS=$save_IFS
if test "$found" != yes; then
lib=$lib.lib
fi
}
# func_cl_wrapper cl arg...
# Adjust compile command to suit cl
func_cl_wrapper ()
{
# Assume a capable shell
lib_path=
shared=:
linker_opts=
outfile=
implib=
linking=1
for arg
do
if test -n "$eat"; then
eat=
else
case $1 in
-o)
# configure might choose to run compile as 'compile cc -o foo foo.c'.
eat=1
case $2 in
*.o | *.[oO][bB][jJ])
func_file_conv "$2"
set x "$@" -Fo"$file"
shift
outfile="$file"
;;
*)
func_file_conv "$2"
set x "$@" -Fe"$file"
shift
outfile="$file"
;;
esac
;;
-I)
eat=1
func_file_conv "$2" mingw
set x "$@" -I"$file"
shift
;;
-I*)
func_file_conv "${1#-I}" mingw
set x "$@" -I"$file"
shift
;;
-l)
eat=1
func_cl_dashl "$2"
set x "$@" "$lib"
shift
;;
-l*)
func_cl_dashl "${1#-l}"
set x "$@" "$lib"
shift
;;
-L)
eat=1
func_cl_dashL "$2"
;;
-L*)
func_cl_dashL "${1#-L}"
;;
-static)
shared=false
;;
-Wl,*)
arg=${1#-Wl,}
save_ifs="$IFS"; IFS=','
for flag in $arg; do
IFS="$save_ifs"
linker_opts="$linker_opts $flag"
case "$flag" in -IMPLIB:*) implib=${flag#-IMPLIB:} ;; esac
done
IFS="$save_ifs"
;;
-Xlinker)
eat=1
linker_opts="$linker_opts $2"
;;
-std=*)
set x "$@" -std:"${1#-std=}"
shift
;;
-*)
set x "$@" "$1"
shift
;;
*.cc | *.CC | *.cxx | *.CXX | *.[cC]++)
func_file_conv "$1"
set x "$@" -Tp"$file"
shift
;;
*.c | *.cpp | *.CPP | *.lib | *.LIB | *.Lib | *.OBJ | *.obj | *.[oO])
func_file_conv "$1" mingw
set x "$@" "$file"
shift
;;
-c)
linking=0
set x "$@" "$1"
shift
;;
*)
set x "$@" "$1"
shift
;;
esac
fi
shift
done
if test -n "$linker_opts"; then
linker_opts="-link$linker_opts"
fi
# remove old $implib, so we can distinguish between generated and not-generated implib below
if test -n "$implib" && test -f "$implib" ; then rm "$implib" ; fi
# add path to MSVC link in front on PATH if we seem to link (check isn't so accurate, but some false-positives shouldn't matter)
# compiler will call the link it finds in the PATH, and we don't want it to use MSYS' /bin/link
# we assume that MSVC link is in same directory as cl and that cl is found in PATH
if test "$linking" = 1 && comppath=`which cl 2>/dev/null` ; then
comppath=`dirname "$comppath"`
#echo "Adding $comppath to front of PATH"
PATH="$comppath:$PATH"
fi
#echo "compile: $@ $linker_opts"
"$@" $linker_opts || exit $?
# if -implib got lost or ignored, then the lib should be named ${outfile/.dll/.lib} and we rename that file
if test -n "$implib" && test ! -f "$implib" ; then
echo "compile: mv ${outfile/.dll/.lib} $implib"
mv "${outfile/.dll/.lib}" "$implib"
fi
exit 0
}
eat=
case $1 in
'')
echo "$0: No command. Try '$0 --help' for more information." 1>&2
exit 1;
;;
-h | --h*)
cat <<\EOF
Usage: compile [--help] [--version] PROGRAM [ARGS]
Wrapper for compilers which do not understand '-c -o'.
Remove '-o dest.o' from ARGS, run PROGRAM with the remaining
arguments, and rename the output as expected.
If you are trying to build a whole package this is not the
right script to run: please start by reading the file 'INSTALL'.
Report bugs to <bug-automake@gnu.org>.
EOF
exit $?
;;
-v | --v*)
echo "compile $scriptversion"
exit $?
;;
cl | *[/\\]cl | cl.exe | *[/\\]cl.exe | \
icl | *[/\\]icl | icl.exe | *[/\\]icl.exe | \
ifort | *[/\\]ifort | ifort.exe | *[/\\]ifort.exe )
func_cl_wrapper "$@" # Doesn't return...
;;
esac
ofile=
cfile=
for arg
do
if test -n "$eat"; then
eat=
else
case $1 in
-o)
# configure might choose to run compile as 'compile cc -o foo foo.c'.
# So we strip '-o arg' only if arg is an object.
eat=1
case $2 in
*.o | *.obj)
ofile=$2
;;
*)
set x "$@" -o "$2"
shift
;;
esac
;;
*.c)
cfile=$1
set x "$@" "$1"
shift
;;
*)
set x "$@" "$1"
shift
;;
esac
fi
shift
done
if test -z "$ofile" || test -z "$cfile"; then
# If no '-o' option was seen then we might have been invoked from a
# pattern rule where we don't need one. That is ok -- this is a
# normal compilation that the losing compiler can handle. If no
# '.c' file was seen then we are probably linking. That is also
# ok.
exec "$@"
fi
# Name of file we expect compiler to create.
cofile=`echo "$cfile" | sed 's|^.*[\\/]||; s|^[a-zA-Z]:||; s/\.c$/.o/'`
# Create the lock directory.
# Note: use '[/\\:.-]' here to ensure that we don't use the same name
# that we are using for the .o file. Also, base the name on the expected
# object file name, since that is what matters with a parallel build.
lockdir=`echo "$cofile" | sed -e 's|[/\\:.-]|_|g'`.d
while true; do
if mkdir "$lockdir" >/dev/null 2>&1; then
break
fi
sleep 1
done
# FIXME: race condition here if user kills between mkdir and trap.
trap "rmdir '$lockdir'; exit 1" 1 2 15
# Run the compile.
"$@"
ret=$?
if test -f "$cofile"; then
test "$cofile" = "$ofile" || mv "$cofile" "$ofile"
elif test -f "${cofile}bj"; then
test "${cofile}bj" = "$ofile" || mv "${cofile}bj" "$ofile"
fi
rmdir "$lockdir"
exit $ret
# Local Variables:
# mode: shell-script
# sh-indentation: 2
# eval: (add-hook 'before-save-hook 'time-stamp)
# time-stamp-start: "scriptversion="
# time-stamp-format: "%:y-%02m-%02d.%02H"
# time-stamp-time-zone: "UTC0"
# time-stamp-end: "; # UTC"
# End:

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,112 @@
/* config.h.in. Generated from configure.ac by autoheader. */
/* Define to dummy `main' function (if any) required to link to the Fortran
libraries. */
#undef FC_DUMMY_MAIN
/* Define if F77 and FC dummy `main' functions are identical. */
#undef FC_DUMMY_MAIN_EQ_F77
/* Define to a macro mangling the given C identifier (in lower and upper
case), which must not contain underscores, for linking with Fortran. */
#undef FC_FUNC
/* As FC_FUNC, but for C identifiers containing underscores. */
#undef FC_FUNC_
/* Define to 1 if your Fortran compiler doesn't accept -c and -o together. */
#undef FC_NO_MINUS_C_MINUS_O
/* Define to 1 if you have the <dlfcn.h> header file. */
#undef HAVE_DLFCN_H
/* Define to 1 if you have the <inttypes.h> header file. */
#undef HAVE_INTTYPES_H
/* Define to 1 if you have the <stdint.h> header file. */
#undef HAVE_STDINT_H
/* Define to 1 if you have the <stdio.h> header file. */
#undef HAVE_STDIO_H
/* Define to 1 if you have the <stdlib.h> header file. */
#undef HAVE_STDLIB_H
/* Define to 1 if you have the <strings.h> header file. */
#undef HAVE_STRINGS_H
/* Define to 1 if you have the <string.h> header file. */
#undef HAVE_STRING_H
/* Define to 1 if you have the <sys/stat.h> header file. */
#undef HAVE_SYS_STAT_H
/* Define to 1 if you have the <sys/types.h> header file. */
#undef HAVE_SYS_TYPES_H
/* Define to 1 if you have the <unistd.h> header file. */
#undef HAVE_UNISTD_H
/* Define to the sub-directory where libtool stores uninstalled libraries. */
#undef LT_OBJDIR
/* Library Visibility Attribute */
#undef MUMPS_CALL
/* Library Visibility Attribute */
#undef MUMPS_EXPORT
/* Define if MUMPS integers have a size of 32-bit */
#undef MUMPS_INTSIZE32
/* Define if MUMPS integers have a size of 64-bit */
#undef MUMPS_INTSIZE64
/* Define to the address where bug reports for this package should be sent. */
#undef PACKAGE_BUGREPORT
/* Define to the full name of this package. */
#undef PACKAGE_NAME
/* Define to the full name and version of this package. */
#undef PACKAGE_STRING
/* Define to the one symbol short name of this package. */
#undef PACKAGE_TARNAME
/* Define to the home page for this package. */
#undef PACKAGE_URL
/* Define to the version of this package. */
#undef PACKAGE_VERSION
/* Define to 1 if all of the C90 standard headers exist (not just the ones
required in a freestanding environment). This macro is provided for
backward compatibility; new code need not use it. */
#undef STDC_HEADERS
/* Define to 1 if the LAPACK package is available */
#undef THIRDPARTYMUMPS_HAS_LAPACK
/* Define to 1 if the Metis package is available */
#undef THIRDPARTYMUMPS_HAS_METIS
/* Define to a macro mangling the given C identifier (in lower and upper
case). */
#undef THIRDPARTYMUMPS_LAPACK_FUNC
/* As THIRDPARTYMUMPS_LAPACK_FUNC, but for C identifiers containing
underscores. */
#undef THIRDPARTYMUMPS_LAPACK_FUNC_
/* Version number of project */
#undef THIRDPARTYMUMPS_VERSION
/* Major version number of project. */
#undef THIRDPARTYMUMPS_VERSION_MAJOR
/* Minor version number of project. */
#undef THIRDPARTYMUMPS_VERSION_MINOR
/* Release version number of project. */
#undef THIRDPARTYMUMPS_VERSION_RELEASE

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,242 @@
# Copyright (C) 2007-2009 International Business Machines.
# All Rights Reserved.
# This file is distributed under the Eclipse Public License.
#
# Author: Andreas Waechter IBM 2006-04-13
#############################################################################
# Names and other basic things #
#############################################################################
AC_INIT([ThirdPartyMumps],[3.0.3],[https://github.com/coin-or-tools/ThirdParty-Mumps/issues/new],[],[https://github.com/coin-or-tools/ThirdParty-Mumps])
AC_COPYRIGHT([
Copyright 2007-2009 International Business Machines and others.
All Rights Reserved.
This file is part of the open source package Coin which is distributed
under the Eclipse Public License.])
# List one file in the package so that the configure script can test
# whether the package is actually there
AC_CONFIG_SRCDIR(MUMPS/src/mumps_common.c)
AC_COIN_INITIALIZE
#############################################################################
# Standard build tool stuff #
#############################################################################
# Get the name of the C compiler and appropriate compiler options
AC_COIN_PROG_CC
# Get the name of the Fortran compiler and appropriate compiler options
AC_COIN_PROG_FC
if test -z "$FC" ; then
AC_MSG_ERROR([No Fortran 90 compiler found. Try setting environment variable FC.])
fi
# Initialize libtool
AC_COIN_PROG_LIBTOOL
# Figure out name mangling that Fortran objects will have and translate
# them to what MUMPS wants, this also includes AC_FC_LIBRARY_LDFLAGS
AC_FC_WRAPPERS
case "$ac_cv_fc_mangling" in
"lower case, no underscore, no extra underscore" ) ;;
"lower case, underscore, no extra underscore" ) MY_DEFS="-DAdd_" ;;
"lower case, no underscore, extra underscore" ) MY_DEFS="-DAdd_" ;;
"lower case, underscore, extra underscore" ) MY_DEFS="-DAdd__" ;;
"upper case, no underscore, no extra underscore" ) MY_DEFS="-DUPPER" ;;
"upper case, no underscore, extra underscore" ) MY_DEFS="-DUPPER" ;;
"upper case, underscore, no extra underscore" ) MY_DEFS="-DUPPER" ;;
"upper case, underscore, extra underscore" ) MY_DEFS="-DUPPER" ;;
esac
AC_SUBST(MY_DEFS)
# Add FCLIBS to MUMPS_LFLAGS, so that they get into the .pc files section for static builds
MUMPS_LFLAGS="$MUMPS_LFLAGS $FCLIBS"
# check which floating-point precision to build
AC_ARG_WITH([precision],
[AS_HELP_STRING([--with-precision],[floating-point precision to build: single, double (default), or all])],
[precision=$withval
case "$precision" in
single | double | all ) ;;
*) AC_MSG_ERROR([unsupported value $precision for option --with-precision]) ;;
esac],
[precision=double])
AM_CONDITIONAL([MUMPS_SINGLE],[test "$precision" = single || test "$precision" = all])
AM_CONDITIONAL([MUMPS_DOUBLE],[test "$precision" = double || test "$precision" = all])
# check which integer size to build
AC_ARG_WITH([intsize],
[AS_HELP_STRING([--with-intsize],[integer size in bits to use: 32 or 64])],
[intsize=$withval],
[intsize=32])
case "$intsize" in
32 ) AC_DEFINE(MUMPS_INTSIZE32, [], [Define if MUMPS integers have a size of 32-bit]) ;;
64 ) AC_DEFINE(MUMPS_INTSIZE64, [], [Define if MUMPS integers have a size of 64-bit]) ;;
*) AC_MSG_ERROR([unsupported value $intsize for option --with-intsize]) ;;
esac
# Mumps can make use of pthreads
# check for pthread.h header file and library
AC_ARG_ENABLE([pthread-mumps],
[AS_HELP_STRING([--disable-pthread-mumps],[disable use of pthread library])],
[enable_pthread_mumps=$enableval],
[enable_pthread_mumps=yes])
if test $enable_pthread_mumps = yes ; then
AC_CHECK_HEADER([pthread.h],[],[enable_pthread_mumps=no])
fi
if test $enable_pthread_mumps = yes ; then
AC_CHECK_LIB([pthread],[pthread_create],
[MUMPS_LFLAGS="$MUMPS_LFLAGS -lpthread"],
[enable_pthread_mumps=no])
fi
if test $enable_pthread_mumps = no ; then
MY_DEFS="$MY_DEFS -DWITHOUT_PTHREAD=1"
fi
# Mumps can use OpenMP
# but if single threaded, then it (5.2.1) seems to become slower within Ipopt, so disable by default
if test -z "$enable_openmp" ; then
enable_openmp=no
fi
AC_LANG_PUSH(Fortran)
AC_OPENMP
FCFLAGS="$FCFLAGS $OPENMP_FCFLAGS"
MUMPS_LFLAGS="$MUMPS_LFLAGS $OPENMP_FCFLAGS"
AC_LANG_POP(Fortran)
AC_COIN_CHK_LAPACK(MUMPS, int$intsize)
if test $coin_has_lapack != yes; then
AC_MSG_ERROR([Required package LAPACK not found.])
fi
# if the BLAS library includes the GEMMT level-3 BLAS extension, it is strongly recommend to use it
AC_COIN_TRY_LINK([dgemmt],[$lapack_lflags],[$lapack_pcfiles],[MY_FDEFS="$MY_FDEFS -DGEMMT_AVAILABLE"])
AC_COIN_CHK_LIBM(METISCHECK)
AC_LANG_PUSH(C)
AC_COIN_CHK_LIBHDR(Metis,[MUMPS],[-lmetis "$METISCHECK_LFLAGS"],[],[],
[#if METIS_VER_MAJOR < 5
metis_nodend((int*)0, (int*)0, (int*)0, (int*)0, (int*)0, (int*)0, (int*)0);
#else
METIS_NodeND((int*)0, (int*)0, (int*)0, (int*)0, (int*)0, (int*)0, (int*)0);
#endif
],
[#define __STDC_WANT_IEC_60559_BFP_EXT__
#ifdef __STDC__
#include <limits.h>
#endif
#include "metis.h"
#ifndef METIS_VER_MAJOR
#define METIS_VER_MAJOR 4
#ifdef IDXTYPE_INT
#define IDXTYPEWIDTH 32
#else
#define IDXTYPEWIDTH 64
#endif
#endif
#if defined(MUMPS_INTSIZE32) && defined(INT_WIDTH) && INT_WIDTH != IDXTYPEWIDTH
#error "Metis does not use int type for idx_t, but this build of MUMPS requires it"
#endif
#if defined(MUMPS_INTSIZE64) && IDXTYPEWIDTH != 64
#error "Metis does not use 64-bit integers for idx_t, but this build of MUMPS requires it"
#endif
])
# check that Metis flags also work with Fortran compiler
if test "$coin_has_metis" = yes ; then
AC_MSG_CHECKING([whether Metis library is linkable with Fortran compiler])
AC_LANG_PUSH(Fortran)
orig_LIBS="$LIBS"
LIBS="$LIBS $metis_lflags"
AC_COMPILE_IFELSE([AC_LANG_PROGRAM([],[])],
[AC_MSG_RESULT([yes])],
[AC_MSG_RESULT([no])
if test "$metis_userflags" = yes ; then
AC_MSG_ERROR([Metis linker flags $metis_lflags worked with C compiler, but failed with Fortran compiler. Check config.log for details.])
else
AC_MSG_WARN([Metis linker flags $metis_lflags worked with C compiler, but failed with Fortran compiler. Check config.log for details. Disabling Metis.])
coin_has_metis=no
fi])
LIBS="$orig_LIBS"
AC_LANG_POP(Fortran)
fi
AM_CONDITIONAL(COIN_HAS_METIS, [test $coin_has_metis = yes])
if test "$coin_has_metis" = yes; then
AC_MSG_CHECKING([Metis version])
ac_save_CPPFLAGS=$CPPFLAGS
CPPFLAGS="$MUMPS_CFLAGS"
AC_COMPILE_IFELSE([AC_LANG_PROGRAM([
#include "metis.h"
#ifndef METIS_VER_MAJOR
#error metis4
#endif
],[])],
[MY_DEFS="$MY_DEFS -Dmetis"
MY_FDEFS="$MY_FDEFS -Dmetis"
AC_MSG_RESULT([5])
],
[MY_DEFS="$MY_DEFS -Dmetis4"
MY_FDEFS="$MY_FDEFS -Dmetis4"
AC_MSG_RESULT([4])
])
CPPFLAGS=$ac_save_CPPFLAGS
fi
AC_LANG_POP(C)
# Adjust Fortran preprocessor flags for IBM compiler
case $FC in *xlf*)
fdefs=
if test -n "$MY_FDEFS"; then
for flag in $MY_FDEFS; do
fdefs="$fdefs -WF,$flag"
done
fi
MY_FDEFS="$fdefs"
;;
esac
# Add workaround for incompatibility with Fortran 2003 (https://github.com/coin-or-tools/ThirdParty-Mumps/issues/4)
case $FC in *gfortran*) MY_FDEFS="$MY_FDEFS -std=legacy" ;; esac
# Specify 8-byte integers if intsize=64 (TODO This should become a macro in BuildTools that figures out the right flag to use)
if test $intsize = 64 ; then
case $FC in
*gfortran*) MY_FDEFS="$MY_FDEFS -fdefault-integer-8" ;;
*ifort*)
case $build in
*-cygwin* | *-mingw* | *-msys* ) MY_FDEFS="$MY_FDEFS -integer-size:64" ;;
*) MY_FDEFS="$MY_FDEFS -integer-size 64" ;;
esac
;;
*) AC_MSG_ERROR([Do not know how to select 8-byte integers for Fortran compiler $FC]) ;;
esac
fi
AC_SUBST(MY_FDEFS)
AC_COIN_FINALIZE_FLAGS([MUMPS])
# if libexport_attribute is set by COIN_FINALIZE_FLAGS to __declspec(dllimport)
# then we want to use MUMPS_CALL=__declspec(dllexport) when building Mumps
# and users should use __declspec(dllimport), but the parenthesis are difficult
# to pass on via compiler flags
# so also create and install our own version of mumps_compat.h instead
if test "$libexport_attribute" = "__declspec(dllimport)" ; then
MY_DEFS="$MY_DEFS -DMUMPS_CALL=\"__declspec(dllexport)\""
fi
AC_DEFINE_UNQUOTED(MUMPS_CALL, [$libexport_attribute], [Library Visibility Attribute])
AC_MSG_NOTICE([additional C preprocessor flags: $MY_DEFS])
AC_MSG_NOTICE([additional Fortran preprocessor flags: $MY_FDEFS])
AC_CONFIG_FILES([Makefile coinmumps.pc])
AC_CONFIG_HEADERS([config.h mumps_compat.h mumps_int_def.h])
AC_COIN_FINALIZE

View File

@ -0,0 +1,791 @@
#! /bin/sh
# depcomp - compile a program generating dependencies as side-effects
scriptversion=2018-03-07.03; # UTC
# Copyright (C) 1999-2020 Free Software Foundation, Inc.
# This program is free software; you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
# the Free Software Foundation; either version 2, or (at your option)
# any later version.
# This program 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 General Public License for more details.
# You should have received a copy of the GNU General Public License
# along with this program. If not, see <https://www.gnu.org/licenses/>.
# As a special exception to the GNU General Public License, if you
# distribute this file as part of a program that contains a
# configuration script generated by Autoconf, you may include it under
# the same distribution terms that you use for the rest of that program.
# Originally written by Alexandre Oliva <oliva@dcc.unicamp.br>.
case $1 in
'')
echo "$0: No command. Try '$0 --help' for more information." 1>&2
exit 1;
;;
-h | --h*)
cat <<\EOF
Usage: depcomp [--help] [--version] PROGRAM [ARGS]
Run PROGRAMS ARGS to compile a file, generating dependencies
as side-effects.
Environment variables:
depmode Dependency tracking mode.
source Source file read by 'PROGRAMS ARGS'.
object Object file output by 'PROGRAMS ARGS'.
DEPDIR directory where to store dependencies.
depfile Dependency file to output.
tmpdepfile Temporary file to use when outputting dependencies.
libtool Whether libtool is used (yes/no).
Report bugs to <bug-automake@gnu.org>.
EOF
exit $?
;;
-v | --v*)
echo "depcomp $scriptversion"
exit $?
;;
esac
# Get the directory component of the given path, and save it in the
# global variables '$dir'. Note that this directory component will
# be either empty or ending with a '/' character. This is deliberate.
set_dir_from ()
{
case $1 in
*/*) dir=`echo "$1" | sed -e 's|/[^/]*$|/|'`;;
*) dir=;;
esac
}
# Get the suffix-stripped basename of the given path, and save it the
# global variable '$base'.
set_base_from ()
{
base=`echo "$1" | sed -e 's|^.*/||' -e 's/\.[^.]*$//'`
}
# If no dependency file was actually created by the compiler invocation,
# we still have to create a dummy depfile, to avoid errors with the
# Makefile "include basename.Plo" scheme.
make_dummy_depfile ()
{
echo "#dummy" > "$depfile"
}
# Factor out some common post-processing of the generated depfile.
# Requires the auxiliary global variable '$tmpdepfile' to be set.
aix_post_process_depfile ()
{
# If the compiler actually managed to produce a dependency file,
# post-process it.
if test -f "$tmpdepfile"; then
# Each line is of the form 'foo.o: dependency.h'.
# Do two passes, one to just change these to
# $object: dependency.h
# and one to simply output
# dependency.h:
# which is needed to avoid the deleted-header problem.
{ sed -e "s,^.*\.[$lower]*:,$object:," < "$tmpdepfile"
sed -e "s,^.*\.[$lower]*:[$tab ]*,," -e 's,$,:,' < "$tmpdepfile"
} > "$depfile"
rm -f "$tmpdepfile"
else
make_dummy_depfile
fi
}
# A tabulation character.
tab=' '
# A newline character.
nl='
'
# Character ranges might be problematic outside the C locale.
# These definitions help.
upper=ABCDEFGHIJKLMNOPQRSTUVWXYZ
lower=abcdefghijklmnopqrstuvwxyz
digits=0123456789
alpha=${upper}${lower}
if test -z "$depmode" || test -z "$source" || test -z "$object"; then
echo "depcomp: Variables source, object and depmode must be set" 1>&2
exit 1
fi
# Dependencies for sub/bar.o or sub/bar.obj go into sub/.deps/bar.Po.
depfile=${depfile-`echo "$object" |
sed 's|[^\\/]*$|'${DEPDIR-.deps}'/&|;s|\.\([^.]*\)$|.P\1|;s|Pobj$|Po|'`}
tmpdepfile=${tmpdepfile-`echo "$depfile" | sed 's/\.\([^.]*\)$/.T\1/'`}
rm -f "$tmpdepfile"
# Avoid interferences from the environment.
gccflag= dashmflag=
# Some modes work just like other modes, but use different flags. We
# parameterize here, but still list the modes in the big case below,
# to make depend.m4 easier to write. Note that we *cannot* use a case
# here, because this file can only contain one case statement.
if test "$depmode" = hp; then
# HP compiler uses -M and no extra arg.
gccflag=-M
depmode=gcc
fi
if test "$depmode" = dashXmstdout; then
# This is just like dashmstdout with a different argument.
dashmflag=-xM
depmode=dashmstdout
fi
cygpath_u="cygpath -u -f -"
if test "$depmode" = msvcmsys; then
# This is just like msvisualcpp but w/o cygpath translation.
# Just convert the backslash-escaped backslashes to single forward
# slashes to satisfy depend.m4
cygpath_u='sed s,\\\\,/,g'
depmode=msvisualcpp
fi
if test "$depmode" = msvc7msys; then
# This is just like msvc7 but w/o cygpath translation.
# Just convert the backslash-escaped backslashes to single forward
# slashes to satisfy depend.m4
cygpath_u='sed s,\\\\,/,g'
depmode=msvc7
fi
if test "$depmode" = xlc; then
# IBM C/C++ Compilers xlc/xlC can output gcc-like dependency information.
gccflag=-qmakedep=gcc,-MF
depmode=gcc
fi
case "$depmode" in
gcc3)
## gcc 3 implements dependency tracking that does exactly what
## we want. Yay! Note: for some reason libtool 1.4 doesn't like
## it if -MD -MP comes after the -MF stuff. Hmm.
## Unfortunately, FreeBSD c89 acceptance of flags depends upon
## the command line argument order; so add the flags where they
## appear in depend2.am. Note that the slowdown incurred here
## affects only configure: in makefiles, %FASTDEP% shortcuts this.
for arg
do
case $arg in
-c) set fnord "$@" -MT "$object" -MD -MP -MF "$tmpdepfile" "$arg" ;;
*) set fnord "$@" "$arg" ;;
esac
shift # fnord
shift # $arg
done
"$@"
stat=$?
if test $stat -ne 0; then
rm -f "$tmpdepfile"
exit $stat
fi
mv "$tmpdepfile" "$depfile"
;;
gcc)
## Note that this doesn't just cater to obsosete pre-3.x GCC compilers.
## but also to in-use compilers like IMB xlc/xlC and the HP C compiler.
## (see the conditional assignment to $gccflag above).
## There are various ways to get dependency output from gcc. Here's
## why we pick this rather obscure method:
## - Don't want to use -MD because we'd like the dependencies to end
## up in a subdir. Having to rename by hand is ugly.
## (We might end up doing this anyway to support other compilers.)
## - The DEPENDENCIES_OUTPUT environment variable makes gcc act like
## -MM, not -M (despite what the docs say). Also, it might not be
## supported by the other compilers which use the 'gcc' depmode.
## - Using -M directly means running the compiler twice (even worse
## than renaming).
if test -z "$gccflag"; then
gccflag=-MD,
fi
"$@" -Wp,"$gccflag$tmpdepfile"
stat=$?
if test $stat -ne 0; then
rm -f "$tmpdepfile"
exit $stat
fi
rm -f "$depfile"
echo "$object : \\" > "$depfile"
# The second -e expression handles DOS-style file names with drive
# letters.
sed -e 's/^[^:]*: / /' \
-e 's/^['$alpha']:\/[^:]*: / /' < "$tmpdepfile" >> "$depfile"
## This next piece of magic avoids the "deleted header file" problem.
## The problem is that when a header file which appears in a .P file
## is deleted, the dependency causes make to die (because there is
## typically no way to rebuild the header). We avoid this by adding
## dummy dependencies for each header file. Too bad gcc doesn't do
## this for us directly.
## Some versions of gcc put a space before the ':'. On the theory
## that the space means something, we add a space to the output as
## well. hp depmode also adds that space, but also prefixes the VPATH
## to the object. Take care to not repeat it in the output.
## Some versions of the HPUX 10.20 sed can't process this invocation
## correctly. Breaking it into two sed invocations is a workaround.
tr ' ' "$nl" < "$tmpdepfile" \
| sed -e 's/^\\$//' -e '/^$/d' -e "s|.*$object$||" -e '/:$/d' \
| sed -e 's/$/ :/' >> "$depfile"
rm -f "$tmpdepfile"
;;
hp)
# This case exists only to let depend.m4 do its work. It works by
# looking at the text of this script. This case will never be run,
# since it is checked for above.
exit 1
;;
sgi)
if test "$libtool" = yes; then
"$@" "-Wp,-MDupdate,$tmpdepfile"
else
"$@" -MDupdate "$tmpdepfile"
fi
stat=$?
if test $stat -ne 0; then
rm -f "$tmpdepfile"
exit $stat
fi
rm -f "$depfile"
if test -f "$tmpdepfile"; then # yes, the sourcefile depend on other files
echo "$object : \\" > "$depfile"
# Clip off the initial element (the dependent). Don't try to be
# clever and replace this with sed code, as IRIX sed won't handle
# lines with more than a fixed number of characters (4096 in
# IRIX 6.2 sed, 8192 in IRIX 6.5). We also remove comment lines;
# the IRIX cc adds comments like '#:fec' to the end of the
# dependency line.
tr ' ' "$nl" < "$tmpdepfile" \
| sed -e 's/^.*\.o://' -e 's/#.*$//' -e '/^$/ d' \
| tr "$nl" ' ' >> "$depfile"
echo >> "$depfile"
# The second pass generates a dummy entry for each header file.
tr ' ' "$nl" < "$tmpdepfile" \
| sed -e 's/^.*\.o://' -e 's/#.*$//' -e '/^$/ d' -e 's/$/:/' \
>> "$depfile"
else
make_dummy_depfile
fi
rm -f "$tmpdepfile"
;;
xlc)
# This case exists only to let depend.m4 do its work. It works by
# looking at the text of this script. This case will never be run,
# since it is checked for above.
exit 1
;;
aix)
# The C for AIX Compiler uses -M and outputs the dependencies
# in a .u file. In older versions, this file always lives in the
# current directory. Also, the AIX compiler puts '$object:' at the
# start of each line; $object doesn't have directory information.
# Version 6 uses the directory in both cases.
set_dir_from "$object"
set_base_from "$object"
if test "$libtool" = yes; then
tmpdepfile1=$dir$base.u
tmpdepfile2=$base.u
tmpdepfile3=$dir.libs/$base.u
"$@" -Wc,-M
else
tmpdepfile1=$dir$base.u
tmpdepfile2=$dir$base.u
tmpdepfile3=$dir$base.u
"$@" -M
fi
stat=$?
if test $stat -ne 0; then
rm -f "$tmpdepfile1" "$tmpdepfile2" "$tmpdepfile3"
exit $stat
fi
for tmpdepfile in "$tmpdepfile1" "$tmpdepfile2" "$tmpdepfile3"
do
test -f "$tmpdepfile" && break
done
aix_post_process_depfile
;;
tcc)
# tcc (Tiny C Compiler) understand '-MD -MF file' since version 0.9.26
# FIXME: That version still under development at the moment of writing.
# Make that this statement remains true also for stable, released
# versions.
# It will wrap lines (doesn't matter whether long or short) with a
# trailing '\', as in:
#
# foo.o : \
# foo.c \
# foo.h \
#
# It will put a trailing '\' even on the last line, and will use leading
# spaces rather than leading tabs (at least since its commit 0394caf7
# "Emit spaces for -MD").
"$@" -MD -MF "$tmpdepfile"
stat=$?
if test $stat -ne 0; then
rm -f "$tmpdepfile"
exit $stat
fi
rm -f "$depfile"
# Each non-empty line is of the form 'foo.o : \' or ' dep.h \'.
# We have to change lines of the first kind to '$object: \'.
sed -e "s|.*:|$object :|" < "$tmpdepfile" > "$depfile"
# And for each line of the second kind, we have to emit a 'dep.h:'
# dummy dependency, to avoid the deleted-header problem.
sed -n -e 's|^ *\(.*\) *\\$|\1:|p' < "$tmpdepfile" >> "$depfile"
rm -f "$tmpdepfile"
;;
## The order of this option in the case statement is important, since the
## shell code in configure will try each of these formats in the order
## listed in this file. A plain '-MD' option would be understood by many
## compilers, so we must ensure this comes after the gcc and icc options.
pgcc)
# Portland's C compiler understands '-MD'.
# Will always output deps to 'file.d' where file is the root name of the
# source file under compilation, even if file resides in a subdirectory.
# The object file name does not affect the name of the '.d' file.
# pgcc 10.2 will output
# foo.o: sub/foo.c sub/foo.h
# and will wrap long lines using '\' :
# foo.o: sub/foo.c ... \
# sub/foo.h ... \
# ...
set_dir_from "$object"
# Use the source, not the object, to determine the base name, since
# that's sadly what pgcc will do too.
set_base_from "$source"
tmpdepfile=$base.d
# For projects that build the same source file twice into different object
# files, the pgcc approach of using the *source* file root name can cause
# problems in parallel builds. Use a locking strategy to avoid stomping on
# the same $tmpdepfile.
lockdir=$base.d-lock
trap "
echo '$0: caught signal, cleaning up...' >&2
rmdir '$lockdir'
exit 1
" 1 2 13 15
numtries=100
i=$numtries
while test $i -gt 0; do
# mkdir is a portable test-and-set.
if mkdir "$lockdir" 2>/dev/null; then
# This process acquired the lock.
"$@" -MD
stat=$?
# Release the lock.
rmdir "$lockdir"
break
else
# If the lock is being held by a different process, wait
# until the winning process is done or we timeout.
while test -d "$lockdir" && test $i -gt 0; do
sleep 1
i=`expr $i - 1`
done
fi
i=`expr $i - 1`
done
trap - 1 2 13 15
if test $i -le 0; then
echo "$0: failed to acquire lock after $numtries attempts" >&2
echo "$0: check lockdir '$lockdir'" >&2
exit 1
fi
if test $stat -ne 0; then
rm -f "$tmpdepfile"
exit $stat
fi
rm -f "$depfile"
# Each line is of the form `foo.o: dependent.h',
# or `foo.o: dep1.h dep2.h \', or ` dep3.h dep4.h \'.
# Do two passes, one to just change these to
# `$object: dependent.h' and one to simply `dependent.h:'.
sed "s,^[^:]*:,$object :," < "$tmpdepfile" > "$depfile"
# Some versions of the HPUX 10.20 sed can't process this invocation
# correctly. Breaking it into two sed invocations is a workaround.
sed 's,^[^:]*: \(.*\)$,\1,;s/^\\$//;/^$/d;/:$/d' < "$tmpdepfile" \
| sed -e 's/$/ :/' >> "$depfile"
rm -f "$tmpdepfile"
;;
hp2)
# The "hp" stanza above does not work with aCC (C++) and HP's ia64
# compilers, which have integrated preprocessors. The correct option
# to use with these is +Maked; it writes dependencies to a file named
# 'foo.d', which lands next to the object file, wherever that
# happens to be.
# Much of this is similar to the tru64 case; see comments there.
set_dir_from "$object"
set_base_from "$object"
if test "$libtool" = yes; then
tmpdepfile1=$dir$base.d
tmpdepfile2=$dir.libs/$base.d
"$@" -Wc,+Maked
else
tmpdepfile1=$dir$base.d
tmpdepfile2=$dir$base.d
"$@" +Maked
fi
stat=$?
if test $stat -ne 0; then
rm -f "$tmpdepfile1" "$tmpdepfile2"
exit $stat
fi
for tmpdepfile in "$tmpdepfile1" "$tmpdepfile2"
do
test -f "$tmpdepfile" && break
done
if test -f "$tmpdepfile"; then
sed -e "s,^.*\.[$lower]*:,$object:," "$tmpdepfile" > "$depfile"
# Add 'dependent.h:' lines.
sed -ne '2,${
s/^ *//
s/ \\*$//
s/$/:/
p
}' "$tmpdepfile" >> "$depfile"
else
make_dummy_depfile
fi
rm -f "$tmpdepfile" "$tmpdepfile2"
;;
tru64)
# The Tru64 compiler uses -MD to generate dependencies as a side
# effect. 'cc -MD -o foo.o ...' puts the dependencies into 'foo.o.d'.
# At least on Alpha/Redhat 6.1, Compaq CCC V6.2-504 seems to put
# dependencies in 'foo.d' instead, so we check for that too.
# Subdirectories are respected.
set_dir_from "$object"
set_base_from "$object"
if test "$libtool" = yes; then
# Libtool generates 2 separate objects for the 2 libraries. These
# two compilations output dependencies in $dir.libs/$base.o.d and
# in $dir$base.o.d. We have to check for both files, because
# one of the two compilations can be disabled. We should prefer
# $dir$base.o.d over $dir.libs/$base.o.d because the latter is
# automatically cleaned when .libs/ is deleted, while ignoring
# the former would cause a distcleancheck panic.
tmpdepfile1=$dir$base.o.d # libtool 1.5
tmpdepfile2=$dir.libs/$base.o.d # Likewise.
tmpdepfile3=$dir.libs/$base.d # Compaq CCC V6.2-504
"$@" -Wc,-MD
else
tmpdepfile1=$dir$base.d
tmpdepfile2=$dir$base.d
tmpdepfile3=$dir$base.d
"$@" -MD
fi
stat=$?
if test $stat -ne 0; then
rm -f "$tmpdepfile1" "$tmpdepfile2" "$tmpdepfile3"
exit $stat
fi
for tmpdepfile in "$tmpdepfile1" "$tmpdepfile2" "$tmpdepfile3"
do
test -f "$tmpdepfile" && break
done
# Same post-processing that is required for AIX mode.
aix_post_process_depfile
;;
msvc7)
if test "$libtool" = yes; then
showIncludes=-Wc,-showIncludes
else
showIncludes=-showIncludes
fi
"$@" $showIncludes > "$tmpdepfile"
stat=$?
grep -v '^Note: including file: ' "$tmpdepfile"
if test $stat -ne 0; then
rm -f "$tmpdepfile"
exit $stat
fi
rm -f "$depfile"
echo "$object : \\" > "$depfile"
# The first sed program below extracts the file names and escapes
# backslashes for cygpath. The second sed program outputs the file
# name when reading, but also accumulates all include files in the
# hold buffer in order to output them again at the end. This only
# works with sed implementations that can handle large buffers.
sed < "$tmpdepfile" -n '
/^Note: including file: *\(.*\)/ {
s//\1/
s/\\/\\\\/g
p
}' | $cygpath_u | sort -u | sed -n '
s/ /\\ /g
s/\(.*\)/'"$tab"'\1 \\/p
s/.\(.*\) \\/\1:/
H
$ {
s/.*/'"$tab"'/
G
p
}' >> "$depfile"
echo >> "$depfile" # make sure the fragment doesn't end with a backslash
rm -f "$tmpdepfile"
;;
msvc7msys)
# This case exists only to let depend.m4 do its work. It works by
# looking at the text of this script. This case will never be run,
# since it is checked for above.
exit 1
;;
#nosideeffect)
# This comment above is used by automake to tell side-effect
# dependency tracking mechanisms from slower ones.
dashmstdout)
# Important note: in order to support this mode, a compiler *must*
# always write the preprocessed file to stdout, regardless of -o.
"$@" || exit $?
# Remove the call to Libtool.
if test "$libtool" = yes; then
while test "X$1" != 'X--mode=compile'; do
shift
done
shift
fi
# Remove '-o $object'.
IFS=" "
for arg
do
case $arg in
-o)
shift
;;
$object)
shift
;;
*)
set fnord "$@" "$arg"
shift # fnord
shift # $arg
;;
esac
done
test -z "$dashmflag" && dashmflag=-M
# Require at least two characters before searching for ':'
# in the target name. This is to cope with DOS-style filenames:
# a dependency such as 'c:/foo/bar' could be seen as target 'c' otherwise.
"$@" $dashmflag |
sed "s|^[$tab ]*[^:$tab ][^:][^:]*:[$tab ]*|$object: |" > "$tmpdepfile"
rm -f "$depfile"
cat < "$tmpdepfile" > "$depfile"
# Some versions of the HPUX 10.20 sed can't process this sed invocation
# correctly. Breaking it into two sed invocations is a workaround.
tr ' ' "$nl" < "$tmpdepfile" \
| sed -e 's/^\\$//' -e '/^$/d' -e '/:$/d' \
| sed -e 's/$/ :/' >> "$depfile"
rm -f "$tmpdepfile"
;;
dashXmstdout)
# This case only exists to satisfy depend.m4. It is never actually
# run, as this mode is specially recognized in the preamble.
exit 1
;;
makedepend)
"$@" || exit $?
# Remove any Libtool call
if test "$libtool" = yes; then
while test "X$1" != 'X--mode=compile'; do
shift
done
shift
fi
# X makedepend
shift
cleared=no eat=no
for arg
do
case $cleared in
no)
set ""; shift
cleared=yes ;;
esac
if test $eat = yes; then
eat=no
continue
fi
case "$arg" in
-D*|-I*)
set fnord "$@" "$arg"; shift ;;
# Strip any option that makedepend may not understand. Remove
# the object too, otherwise makedepend will parse it as a source file.
-arch)
eat=yes ;;
-*|$object)
;;
*)
set fnord "$@" "$arg"; shift ;;
esac
done
obj_suffix=`echo "$object" | sed 's/^.*\././'`
touch "$tmpdepfile"
${MAKEDEPEND-makedepend} -o"$obj_suffix" -f"$tmpdepfile" "$@"
rm -f "$depfile"
# makedepend may prepend the VPATH from the source file name to the object.
# No need to regex-escape $object, excess matching of '.' is harmless.
sed "s|^.*\($object *:\)|\1|" "$tmpdepfile" > "$depfile"
# Some versions of the HPUX 10.20 sed can't process the last invocation
# correctly. Breaking it into two sed invocations is a workaround.
sed '1,2d' "$tmpdepfile" \
| tr ' ' "$nl" \
| sed -e 's/^\\$//' -e '/^$/d' -e '/:$/d' \
| sed -e 's/$/ :/' >> "$depfile"
rm -f "$tmpdepfile" "$tmpdepfile".bak
;;
cpp)
# Important note: in order to support this mode, a compiler *must*
# always write the preprocessed file to stdout.
"$@" || exit $?
# Remove the call to Libtool.
if test "$libtool" = yes; then
while test "X$1" != 'X--mode=compile'; do
shift
done
shift
fi
# Remove '-o $object'.
IFS=" "
for arg
do
case $arg in
-o)
shift
;;
$object)
shift
;;
*)
set fnord "$@" "$arg"
shift # fnord
shift # $arg
;;
esac
done
"$@" -E \
| sed -n -e '/^# [0-9][0-9]* "\([^"]*\)".*/ s:: \1 \\:p' \
-e '/^#line [0-9][0-9]* "\([^"]*\)".*/ s:: \1 \\:p' \
| sed '$ s: \\$::' > "$tmpdepfile"
rm -f "$depfile"
echo "$object : \\" > "$depfile"
cat < "$tmpdepfile" >> "$depfile"
sed < "$tmpdepfile" '/^$/d;s/^ //;s/ \\$//;s/$/ :/' >> "$depfile"
rm -f "$tmpdepfile"
;;
msvisualcpp)
# Important note: in order to support this mode, a compiler *must*
# always write the preprocessed file to stdout.
"$@" || exit $?
# Remove the call to Libtool.
if test "$libtool" = yes; then
while test "X$1" != 'X--mode=compile'; do
shift
done
shift
fi
IFS=" "
for arg
do
case "$arg" in
-o)
shift
;;
$object)
shift
;;
"-Gm"|"/Gm"|"-Gi"|"/Gi"|"-ZI"|"/ZI")
set fnord "$@"
shift
shift
;;
*)
set fnord "$@" "$arg"
shift
shift
;;
esac
done
"$@" -E 2>/dev/null |
sed -n '/^#line [0-9][0-9]* "\([^"]*\)"/ s::\1:p' | $cygpath_u | sort -u > "$tmpdepfile"
rm -f "$depfile"
echo "$object : \\" > "$depfile"
sed < "$tmpdepfile" -n -e 's% %\\ %g' -e '/^\(.*\)$/ s::'"$tab"'\1 \\:p' >> "$depfile"
echo "$tab" >> "$depfile"
sed < "$tmpdepfile" -n -e 's% %\\ %g' -e '/^\(.*\)$/ s::\1\::p' >> "$depfile"
rm -f "$tmpdepfile"
;;
msvcmsys)
# This case exists only to let depend.m4 do its work. It works by
# looking at the text of this script. This case will never be run,
# since it is checked for above.
exit 1
;;
none)
exec "$@"
;;
*)
echo "Unknown depmode $depmode" 1>&2
exit 1
;;
esac
exit 0
# Local Variables:
# mode: shell-script
# sh-indentation: 2
# eval: (add-hook 'before-save-hook 'time-stamp)
# time-stamp-start: "scriptversion="
# time-stamp-format: "%:y-%02m-%02d.%02H"
# time-stamp-time-zone: "UTC0"
# time-stamp-end: "; # UTC"
# End:

View File

@ -0,0 +1,70 @@
#!/bin/sh
# Set the following to the latest MUMPS version.
# THERE MUST BE NO SPACE BEFORE AND AFTER THE EQUAL (=) OPERATOR.
mumps_ver=5.5.0
set -e
wgetcount=`which wget 2>/dev/null | wc -l`
if test ! $wgetcount = 1; then
curlcount=`which curl 2>/dev/null | wc -l`
if test ! $curlcount = 1; then
fetchcount=`which fetch 2>/dev/null | wc -l`
if test ! $fetchcount = 1; then
echo "None of the utilities, wget, curl, or fetch found in PATH. Cannot download source."
exit -1
else
wgetcmd=fetch
fi
else
wgetcmd="curl -L -O"
fi
else
wgetcmd="wget"
fi
echo " "
echo "Running script for downloading the source code for MUMPS"
echo " "
rm -f MUMPS*.tgz
echo "Downloading the source code from coin-or-tools.github.io..."
if $wgetcmd http://coin-or-tools.github.io/ThirdParty-Mumps/MUMPS_${mumps_ver}.tar.gz ;
then
echo "Download finished."
else
echo
echo "Downloading from GitHub failed, trying mumps.enseeiht.fr..."
if $wgetcmd http://mumps.enseeiht.fr/MUMPS_${mumps_ver}.tar.gz ;
then
echo "Download finished."
else
echo "Download failed...exiting"
fi
fi
echo "Uncompressing the tarball..."
gunzip -f MUMPS_${mumps_ver}.tar.gz
echo "Unpacking the source code..."
tar xf MUMPS_${mumps_ver}.tar
echo "Deleting the tar file..."
rm MUMPS_${mumps_ver}.tar
rm -rf MUMPS
mv MUMPS_${mumps_ver} MUMPS
echo " "
echo "Done downloading the source code for MUMPS."
echo " "
echo "Apply a patch to improve MPI compatibility."
echo " "
patch -p0 < mumps_mpi.patch
mv MUMPS/libseq/mpi.h MUMPS/libseq/mumps_mpi.h
echo " "
echo "Verify that there are no error message in the output above."

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,215 @@
#! /bin/sh
# Common wrapper for a few potentially missing GNU programs.
scriptversion=2018-03-07.03; # UTC
# Copyright (C) 1996-2020 Free Software Foundation, Inc.
# Originally written by Fran,cois Pinard <pinard@iro.umontreal.ca>, 1996.
# This program is free software; you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
# the Free Software Foundation; either version 2, or (at your option)
# any later version.
# This program 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 General Public License for more details.
# You should have received a copy of the GNU General Public License
# along with this program. If not, see <https://www.gnu.org/licenses/>.
# As a special exception to the GNU General Public License, if you
# distribute this file as part of a program that contains a
# configuration script generated by Autoconf, you may include it under
# the same distribution terms that you use for the rest of that program.
if test $# -eq 0; then
echo 1>&2 "Try '$0 --help' for more information"
exit 1
fi
case $1 in
--is-lightweight)
# Used by our autoconf macros to check whether the available missing
# script is modern enough.
exit 0
;;
--run)
# Back-compat with the calling convention used by older automake.
shift
;;
-h|--h|--he|--hel|--help)
echo "\
$0 [OPTION]... PROGRAM [ARGUMENT]...
Run 'PROGRAM [ARGUMENT]...', returning a proper advice when this fails due
to PROGRAM being missing or too old.
Options:
-h, --help display this help and exit
-v, --version output version information and exit
Supported PROGRAM values:
aclocal autoconf autoheader autom4te automake makeinfo
bison yacc flex lex help2man
Version suffixes to PROGRAM as well as the prefixes 'gnu-', 'gnu', and
'g' are ignored when checking the name.
Send bug reports to <bug-automake@gnu.org>."
exit $?
;;
-v|--v|--ve|--ver|--vers|--versi|--versio|--version)
echo "missing $scriptversion (GNU Automake)"
exit $?
;;
-*)
echo 1>&2 "$0: unknown '$1' option"
echo 1>&2 "Try '$0 --help' for more information"
exit 1
;;
esac
# Run the given program, remember its exit status.
"$@"; st=$?
# If it succeeded, we are done.
test $st -eq 0 && exit 0
# Also exit now if we it failed (or wasn't found), and '--version' was
# passed; such an option is passed most likely to detect whether the
# program is present and works.
case $2 in --version|--help) exit $st;; esac
# Exit code 63 means version mismatch. This often happens when the user
# tries to use an ancient version of a tool on a file that requires a
# minimum version.
if test $st -eq 63; then
msg="probably too old"
elif test $st -eq 127; then
# Program was missing.
msg="missing on your system"
else
# Program was found and executed, but failed. Give up.
exit $st
fi
perl_URL=https://www.perl.org/
flex_URL=https://github.com/westes/flex
gnu_software_URL=https://www.gnu.org/software
program_details ()
{
case $1 in
aclocal|automake)
echo "The '$1' program is part of the GNU Automake package:"
echo "<$gnu_software_URL/automake>"
echo "It also requires GNU Autoconf, GNU m4 and Perl in order to run:"
echo "<$gnu_software_URL/autoconf>"
echo "<$gnu_software_URL/m4/>"
echo "<$perl_URL>"
;;
autoconf|autom4te|autoheader)
echo "The '$1' program is part of the GNU Autoconf package:"
echo "<$gnu_software_URL/autoconf/>"
echo "It also requires GNU m4 and Perl in order to run:"
echo "<$gnu_software_URL/m4/>"
echo "<$perl_URL>"
;;
esac
}
give_advice ()
{
# Normalize program name to check for.
normalized_program=`echo "$1" | sed '
s/^gnu-//; t
s/^gnu//; t
s/^g//; t'`
printf '%s\n' "'$1' is $msg."
configure_deps="'configure.ac' or m4 files included by 'configure.ac'"
case $normalized_program in
autoconf*)
echo "You should only need it if you modified 'configure.ac',"
echo "or m4 files included by it."
program_details 'autoconf'
;;
autoheader*)
echo "You should only need it if you modified 'acconfig.h' or"
echo "$configure_deps."
program_details 'autoheader'
;;
automake*)
echo "You should only need it if you modified 'Makefile.am' or"
echo "$configure_deps."
program_details 'automake'
;;
aclocal*)
echo "You should only need it if you modified 'acinclude.m4' or"
echo "$configure_deps."
program_details 'aclocal'
;;
autom4te*)
echo "You might have modified some maintainer files that require"
echo "the 'autom4te' program to be rebuilt."
program_details 'autom4te'
;;
bison*|yacc*)
echo "You should only need it if you modified a '.y' file."
echo "You may want to install the GNU Bison package:"
echo "<$gnu_software_URL/bison/>"
;;
lex*|flex*)
echo "You should only need it if you modified a '.l' file."
echo "You may want to install the Fast Lexical Analyzer package:"
echo "<$flex_URL>"
;;
help2man*)
echo "You should only need it if you modified a dependency" \
"of a man page."
echo "You may want to install the GNU Help2man package:"
echo "<$gnu_software_URL/help2man/>"
;;
makeinfo*)
echo "You should only need it if you modified a '.texi' file, or"
echo "any other file indirectly affecting the aspect of the manual."
echo "You might want to install the Texinfo package:"
echo "<$gnu_software_URL/texinfo/>"
echo "The spurious makeinfo call might also be the consequence of"
echo "using a buggy 'make' (AIX, DU, IRIX), in which case you might"
echo "want to install GNU make:"
echo "<$gnu_software_URL/make/>"
;;
*)
echo "You might have modified some files without having the proper"
echo "tools for further handling them. Check the 'README' file, it"
echo "often tells you about the needed prerequisites for installing"
echo "this package. You may also peek at any GNU archive site, in"
echo "case some other package contains this missing '$1' program."
;;
esac
}
give_advice "$1" | sed -e '1s/^/WARNING: /' \
-e '2,$s/^/ /' >&2
# Propagate the correct exit status (expected to be 127 for a program
# not found, 63 for a program that failed due to version mismatch).
exit $st
# Local variables:
# eval: (add-hook 'before-save-hook 'time-stamp)
# time-stamp-start: "scriptversion="
# time-stamp-format: "%:y-%02m-%02d.%02H"
# time-stamp-time-zone: "UTC0"
# time-stamp-end: "; # UTC"
# End:

View File

@ -0,0 +1,26 @@
/* mumps_compat.h.in. */
#ifndef MUMPS_COMPAT_H
#define MUMPS_COMPAT_H
#ifndef MUMPS_CALL
/* Define Mumps calling convention. */
#undef MUMPS_CALL
#endif
/* tell using codes that we changed mpi.h to mumps_mpi.h */
#define COIN_USE_MUMPS_MPI_H
/* copied from MUMPS' own mumps_compat.h */
#if defined(_WIN32) && ! defined(__MINGW32__)
# define MUMPS_WIN32 1
#endif
#if (__STDC_VERSION__ >= 199901L)
# define MUMPS_INLINE static inline
#else
# define MUMPS_INLINE
#endif
#endif /* MUMPS_COMPAT_H */

View File

@ -0,0 +1,10 @@
#ifndef MUMPS_INT_H
#define MUMPS_INT_H
/* Define if MUMPS integers have a size of 32-bit */
#undef MUMPS_INTSIZE32
/* Define if MUMPS integers have a size of 64-bit */
#undef MUMPS_INTSIZE64
#endif

View File

@ -0,0 +1,57 @@
diff -ur MUMPS_5.4.0/libseq/mpic.c MUMPS/libseq/mpic.c
--- MUMPS_5.4.0/libseq/mpic.c 2021-04-13 17:26:34.000000000 +0200
+++ MUMPS/libseq/mpic.c 2021-05-12 16:25:49.708906988 +0200
@@ -13,7 +13,7 @@
* https://cecill.info/licences/Licence_CeCILL-C_V1-en.html)
*
*/
-#include "mpi.h"
+#include "mumps_mpi.h"
LIBSEQ_INT LIBSEQ_CALL MPI_Init(LIBSEQ_INT *pargc, char ***pargv)
{
return 0;
diff -ur MUMPS_5.4.0/src/mumps_metis64.h MUMPS/src/mumps_metis64.h
--- MUMPS_5.4.0/src/mumps_metis64.h 2021-04-13 17:26:35.000000000 +0200
+++ MUMPS/src/mumps_metis64.h 2021-05-12 16:25:49.708906988 +0200
@@ -18,7 +18,11 @@
/* Interfacing with 64-bit (par)metis, for METIS 4 or METIS 5 */
#include "mumps_common.h" /* includes mumps_compat.h and mumps_c_types.h */
#if defined(parmetis) || defined(parmetis3)
+#ifdef MPI
#include "mpi.h"
+#else
+#include "mumps_mpi.h"
+#endif
#define MUMPS_PARMETIS_64 \
F_SYMBOL(parmetis_64,PARMETIS_64)
void MUMPS_CALL
diff -ur MUMPS_5.4.0/src/mumps_metis.h MUMPS/src/mumps_metis.h
--- MUMPS_5.4.0/src/mumps_metis.h 2021-04-13 17:26:35.000000000 +0200
+++ MUMPS/src/mumps_metis.h 2021-05-12 16:25:49.708906988 +0200
@@ -18,7 +18,11 @@
/* Interfacing with 32-bit (par)metis, for METIS 4 or METIS 5 */
#include "mumps_common.h" /* includes mumps_compat.h and mumps_c_types.h */
#if defined(parmetis) || defined(parmetis3)
+#ifdef MPI
#include "mpi.h"
+#else
+#include "mumps_mpi.h"
+#endif
#define MUMPS_PARMETIS \
F_SYMBOL(parmetis,PARMETIS)
void MUMPS_CALL
diff -ur MUMPS_5.4.0/src/mumps_scotch.h MUMPS/src/mumps_scotch.h
--- MUMPS_5.4.0/src/mumps_scotch.h 2021-04-13 17:26:35.000000000 +0200
+++ MUMPS/src/mumps_scotch.h 2021-05-12 16:25:49.708906988 +0200
@@ -72,7 +72,11 @@
MUMPS_SCOTCH_SET_PTHREAD_NUMBER (MUMPS_INT *PTHREAD_NUMBER);
#endif /*scotch or ptscotch*/
#if defined(ptscotch)
+#ifdef MPI
#include "mpi.h"
+#else
+#include "mumps_mpi.h"
+#endif
#include "ptscotch.h"
#define MUMPS_DGRAPHINIT \
F_SYMBOL(dgraphinit,DGRAPHINIT)

View File

@ -0,0 +1,73 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES.hpp
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2007-2017
*/
#if defined(__SINGLE_OBJECT__) || defined(__C_WRAPPER__)
#include <MessageHandling.cpp>
#include <Utils.cpp>
#include <Indexlist.cpp>
#include <SubjectTo.cpp>
#include <Bounds.cpp>
#include <Constraints.cpp>
#if !defined(__MATLAB__) || defined(WIN32)
#include <BLASReplacement.cpp>
#include <LAPACKReplacement.cpp>
#endif
#include <Matrices.cpp>
#include <Options.cpp>
#include <QProblemB.cpp>
#include <Flipper.cpp>
#include <QProblem.cpp>
#include <SQProblem.cpp>
#if defined(SOLVER_MA27) || defined(SOLVER_MA57)
#include <SparseSolver.cpp>
#include <SQProblemSchur.cpp>
#endif
#if !defined(__C_WRAPPER__) && !defined(__MATLAB__)
#include <OQPinterface.cpp>
#include <SolutionAnalysis.cpp>
#endif
#else /* default compilation mode */
#include <qpOASES/QProblemB.hpp>
#include <qpOASES/QProblem.hpp>
#include <qpOASES/SQProblem.hpp>
#include <qpOASES/SQProblemSchur.hpp>
#include <qpOASES/extras/OQPinterface.hpp>
#include <qpOASES/extras/SolutionAnalysis.hpp>
#endif

View File

@ -0,0 +1,256 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/Bounds.hpp
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2007-2017
*
* Declaration of the Bounds class designed to manage working sets of
* bounds within a QProblem.
*/
#ifndef QPOASES_BOUNDS_HPP
#define QPOASES_BOUNDS_HPP
#include <qpOASES/SubjectTo.hpp>
BEGIN_NAMESPACE_QPOASES
/**
* \brief Manages working sets of bounds (i.e. box constraints).
*
* This class manages working sets of bounds (= box constraints)
* by storing index sets and other status information.
*
* \author Hans Joachim Ferreau
* \version 3.2
* \date 2007-2017
*/
class Bounds : public SubjectTo
{
/*
* PUBLIC MEMBER FUNCTIONS
*/
public:
/** Default constructor. */
Bounds( );
/** Constructor which takes the number of bounds. */
Bounds( int_t _n /**< Number of bounds. */
);
/** Copy constructor (deep copy). */
Bounds( const Bounds& rhs /**< Rhs object. */
);
/** Destructor. */
virtual ~Bounds( );
/** Assignment operator (deep copy). */
Bounds& operator=( const Bounds& rhs /**< Rhs object. */
);
/** Initialises object with given number of bounds.
* \return SUCCESSFUL_RETURN \n
RET_INVALID_ARGUMENTS */
returnValue init( int_t _n = 0 /**< 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_t 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( );
/** Initially adds all numbers of new (i.e. not yet in the list) bounds to
* to the index set of fixed bounds (on their lower bounds);
* the order depends on the SujectToType of each index.
* \return SUCCESSFUL_RETURN \n
RET_SETUP_BOUND_FAILED */
returnValue setupAllLower( );
/** Initially adds all numbers of new (i.e. not yet in the list) bounds to
* to the index set of fixed bounds (on their upper bounds);
* the order depends on the SujectToType of each index.
* \return SUCCESSFUL_RETURN \n
RET_SETUP_BOUND_FAILED */
returnValue setupAllUpper( );
/** 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_t 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_t number, /**< Number of bound to be fixed. */
SubjectToStatus _status /**< Status of bound to be fixed. */
);
/** Flip fixed bound.
* \return SUCCESSFUL_RETURN \n
RET_MOVING_BOUND_FAILED \n
RET_INDEX_OUT_OF_BOUNDS */
returnValue flipFixed( int_t number );
/** Swaps the indices of two free bounds within the index set.
* \return SUCCESSFUL_RETURN \n
RET_SWAPINDEX_FAILED */
returnValue swapFree( int_t number1, /**< Number of first constraint or bound. */
int_t number2 /**< Number of second constraint or bound. */
);
/** Returns number of variables.
* \return Number of variables. */
inline int_t getNV( ) const;
/** Returns number of implicitly fixed variables.
* \return Number of implicitly fixed variables. */
inline int_t getNFV( ) const;
/** Returns number of bounded (but possibly free) variables.
* \return Number of bounded (but possibly free) variables. */
inline int_t getNBV( ) const;
/** Returns number of unbounded variables.
* \return Number of unbounded variables. */
inline int_t getNUV( ) const;
/** Returns number of free variables.
* \return Number of free variables. */
inline int_t getNFR( ) const;
/** Returns number of fixed variables.
* \return Number of fixed variables. */
inline int_t getNFX( ) const;
/** 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( );
/** Shifts forward type and status of all bounds by a given
* offset. This offset has to lie within the range [0,n/2] and has to
* be an integer divisor of the total number of bounds n.
* Type and status of the first \<offset\> bounds is thrown away,
* type and status of the last \<offset\> bounds is doubled,
* e.g. for offset = 2: \n
* shift( {b1,b2,b3,b4,b5,b6} ) = {b3,b4,b5,b6,b5,b6}
* \return SUCCESSFUL_RETURN \n
RET_INDEX_OUT_OF_BOUNDS \n
RET_INVALID_ARGUMENTS \n
RET_SHIFTING_FAILED */
virtual returnValue shift( int_t offset /**< Shift offset within the range [0,n/2] and integer divisor of n. */
);
/** Rotates forward type and status of all bounds by a given
* offset. This offset has to lie within the range [0,n].
* Example for offset = 2: \n
* rotate( {b1,b2,b3,b4,b5,b6} ) = {b3,b4,b5,b6,b1,b2}
* \return SUCCESSFUL_RETURN \n
RET_INDEX_OUT_OF_BOUNDS \n
RET_ROTATING_FAILED */
virtual returnValue rotate( int_t offset /**< Rotation offset within the range [0,n]. */
);
/** Prints information on bounds object
* (in particular, lists of free and fixed bounds.
* \return SUCCESSFUL_RETURN \n
RET_INDEXLIST_CORRUPTED */
returnValue print( );
/*
* PROTECTED MEMBER FUNCTIONS
*/
protected:
/** Frees all allocated memory.
* \return SUCCESSFUL_RETURN */
returnValue clear( );
/** Copies all members from given rhs object.
* \return SUCCESSFUL_RETURN */
returnValue copy( const Bounds& rhs /**< Rhs object. */
);
/** Initially adds all numbers of new (i.e. not yet in the list) bounds to
* to the index set corresponding to the desired status;
* the order depends on the SujectToType of each index.
* \return SUCCESSFUL_RETURN \n
RET_SETUP_BOUND_FAILED */
returnValue setupAll( SubjectToStatus _status /**< Desired initial status for all bounds. */
);
/*
* PROTECTED MEMBER VARIABLES
*/
protected:
Indexlist freee; /**< Index list of free variables. */
Indexlist fixed; /**< Index list of fixed variables. */
};
END_NAMESPACE_QPOASES
#include <qpOASES/Bounds.ipp>
#endif /* QPOASES_BOUNDS_HPP */
/*
* end of file
*/

View File

@ -0,0 +1,120 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/Bounds.ipp
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2007-2017
*
* Implementation of inlined member functions of the Bounds class designed
* to manage working sets of bounds within a QProblem.
*/
BEGIN_NAMESPACE_QPOASES
/*****************************************************************************
* P U B L I C *
*****************************************************************************/
/*
* g e t N V
*/
inline int_t Bounds::getNV( ) const
{
return n;
}
/*
* g e t N F V
*/
inline int_t Bounds::getNFV( ) const
{
return getNumberOfType( ST_EQUALITY );
}
/*
* g e t N B V
*/
inline int_t Bounds::getNBV( ) const
{
return getNumberOfType( ST_BOUNDED );
}
/*
* g e t N U V
*/
inline int_t Bounds::getNUV( ) const
{
return getNumberOfType( ST_UNBOUNDED );
}
/*
* g e t N F R
*/
inline int_t Bounds::getNFR( ) const
{
return freee.getLength( );
}
/*
* g e t N F X
*/
inline int_t Bounds::getNFX( ) const
{
return fixed.getLength( );
}
/*
* g e t F r e e
*/
inline Indexlist* Bounds::getFree( )
{
return &freee;
}
/*
* g e t F i x e d
*/
inline Indexlist* Bounds::getFixed( )
{
return &fixed;
}
END_NAMESPACE_QPOASES
/*
* end of file
*/

View File

@ -0,0 +1,77 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/Constants.hpp
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2007-2017
*
* Definition of all global constants.
*/
#ifndef QPOASES_CONSTANTS_HPP
#define QPOASES_CONSTANTS_HPP
#include <qpOASES/Types.hpp>
BEGIN_NAMESPACE_QPOASES
/** Numerical value of machine precision (min eps, s.t. 1+eps > 1).
* Note: this value has to be positive! */
#ifdef __USE_SINGLE_PRECISION__
const real_t EPS = 1.193e-07f;
#else
const real_t EPS = 2.221e-16;
#endif /* __USE_SINGLE_PRECISION__ */
/** 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 = 1.0e-25;
/** Numerical value of infinity (e.g. for non-existing bounds).
Note: this value has to be positive! */
const real_t INFTY = 1.0e20;
/** Maximum number of characters within a string.
* Note: this value should be at least 41! */
const uint_t MAX_STRING_LENGTH = 160;
END_NAMESPACE_QPOASES
#endif /* QPOASES_CONSTANTS_HPP */
/*
* end of file
*/

View File

@ -0,0 +1,91 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/ConstraintProduct.hpp
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2009-2017
*
* Declaration of the ConstraintProduct class which allows to specify a
* user-defined function for evaluating the constraint product at the
* current iterate to speed-up QP solution in case of a specially structured
* constraint matrix.
*/
#ifndef QPOASES_CONSTRAINT_PRODUCT_HPP
#define QPOASES_CONSTRAINT_PRODUCT_HPP
BEGIN_NAMESPACE_QPOASES
/**
* \brief Interface for specifying user-defined evaluations of constraint products.
*
* A class which allows to specify a user-defined function for evaluating the
* constraint product at the current iterate to speed-up QP solution in case
* of a specially structured constraint matrix.
*
* \author Hans Joachim Ferreau
* \version 3.2
* \date 2009-2017
*/
class ConstraintProduct
{
public:
/** Default constructor. */
ConstraintProduct( ) {};
/** Copy constructor. */
ConstraintProduct( const ConstraintProduct &toCopy /**< Rhs object. */
) {};
/** Destructor. */
virtual ~ConstraintProduct( ) {};
/** Assignment operator. */
ConstraintProduct &operator=( const ConstraintProduct &toCopy /**< Rhs object. */
)
{
return *this;
}
/** Evaluates the product of a given constraint with the current iterate.
* This function needs to be implemented in a derived class for the
* user-defined constraint product function.
* \return 0: successful \n
otherwise: not successful */
virtual int_t operator() ( int_t constrIndex, /**< Number of constraint to be evaluated. */
const real_t* const x, /**< Array containing current primal iterate. */
real_t* const constrValue /**< Output: Scalar value of the evaluated constraint. */
) const = 0;
};
END_NAMESPACE_QPOASES
#endif /* QPOASES_CONSTRAINT_PRODUCT_HPP */

View File

@ -0,0 +1,246 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/Constraints.hpp
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2007-2017
*
* Declaration of the Constraints class designed to manage working sets of
* constraints within a QProblem.
*/
#ifndef QPOASES_CONSTRAINTS_HPP
#define QPOASES_CONSTRAINTS_HPP
#include <qpOASES/SubjectTo.hpp>
BEGIN_NAMESPACE_QPOASES
/**
* \brief Manages working sets of constraints.
*
* This class manages working sets of constraints by storing
* index sets and other status information.
*
* \author Hans Joachim Ferreau
* \version 3.2
* \date 2007-2017
*/
class Constraints : public SubjectTo
{
/*
* PUBLIC MEMBER FUNCTIONS
*/
public:
/** Default constructor. */
Constraints( );
/** Constructor which takes the number of constraints. */
Constraints( int_t _n /**< Number of constraints. */
);
/** Copy constructor (deep copy). */
Constraints( const Constraints& rhs /**< Rhs object. */
);
/** Destructor. */
virtual ~Constraints( );
/** Assignment operator (deep copy). */
Constraints& operator=( const Constraints& rhs /**< Rhs object. */
);
/** Initialises object with given number of constraints.
* \return SUCCESSFUL_RETURN \n
RET_INVALID_ARGUMENTS */
returnValue init( int_t _n = 0 /**< 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_t 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( );
/** Initially adds all enabled numbers of new (i.e. not yet in the list) constraints to
* to the index set of active constraints (on their lower bounds); 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 setupAllLower( );
/** Initially adds all enabled numbers of new (i.e. not yet in the list) constraints to
* to the index set of active constraints (on their upper bounds); 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 setupAllUpper( );
/** 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_t 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_t number, /**< Number of constraint to become active. */
SubjectToStatus _status /**< Status of constraint to become active. */
);
/** Flip fixed constraint.
* \return SUCCESSFUL_RETURN \n
RET_MOVING_CONSTRAINT_FAILED \n
RET_INDEX_OUT_OF_BOUNDS */
returnValue flipFixed( int_t number );
/** Returns the number of constraints.
* \return Number of constraints. */
inline int_t getNC( ) const;
/** Returns the number of implicit equality constraints.
* \return Number of implicit equality constraints. */
inline int_t getNEC( ) const;
/** Returns the number of "real" inequality constraints.
* \return Number of "real" inequality constraints. */
inline int_t 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_t getNUC( ) const;
/** Returns the number of active constraints.
* \return Number of active constraints. */
inline int_t getNAC( ) const;
/** Returns the number of inactive constraints.
* \return Number of inactive constraints. */
inline int_t getNIAC( ) const;
/** 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( );
/** Shifts forward type and status of all constraints by a given
* offset. This offset has to lie within the range [0,n/2] and has to
* be an integer divisor of the total number of constraints n.
* Type and status of the first \<offset\> constraints is thrown away,
* type and status of the last \<offset\> constraints is doubled,
* e.g. for offset = 2: \n
* shift( {c1,c2,c3,c4,c5,c6} ) = {c3,c4,c5,c6,c5,c6}
* \return SUCCESSFUL_RETURN \n
RET_INDEX_OUT_OF_BOUNDS \n
RET_INVALID_ARGUMENTS \n
RET_SHIFTING_FAILED */
virtual returnValue shift( int_t offset /**< Shift offset within the range [0,n/2] and integer divisor of n. */
);
/** Rotates forward type and status of all constraints by a given
* offset. This offset has to lie within the range [0,n].
* Example for offset = 2: \n
* rotate( {c1,c2,c3,c4,c5,c6} ) = {c3,c4,c5,c6,c1,c2}
* \return SUCCESSFUL_RETURN \n
RET_INDEX_OUT_OF_BOUNDS \n
RET_ROTATING_FAILED */
virtual returnValue rotate( int_t offset /**< Rotation offset within the range [0,n]. */
);
/** Prints information on constraints object
* (in particular, lists of inactive and active constraints.
* \return SUCCESSFUL_RETURN \n
RET_INDEXLIST_CORRUPTED */
returnValue print( );
/*
* PROTECTED MEMBER FUNCTIONS
*/
protected:
/** Frees all allocated memory.
* \return SUCCESSFUL_RETURN */
returnValue clear( );
/** Copies all members from given rhs object.
* \return SUCCESSFUL_RETURN */
returnValue copy( const Constraints& rhs /**< Rhs object. */
);
/** Initially adds all numbers of new (i.e. not yet in the list) bounds to
* to the index set corresponding to the desired status;
* the order depends on the SujectToType of each index.
* \return SUCCESSFUL_RETURN \n
RET_SETUP_CONSTRAINT_FAILED */
returnValue setupAll( SubjectToStatus _status /**< Desired initial status for all bounds. */
);
/*
* PROTECTED MEMBER VARIABLES
*/
protected:
Indexlist active; /**< Index list of active constraints. */
Indexlist inactive; /**< Index list of inactive constraints. */
};
END_NAMESPACE_QPOASES
#include <qpOASES/Constraints.ipp>
#endif /* QPOASES_CONSTRAINTS_HPP */
/*
* end of file
*/

View File

@ -0,0 +1,122 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/Constraints.ipp
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2007-2017
*
* Declaration of inlined member functions of the Constraints class designed
* to manage working sets of constraints within a QProblem.
*/
BEGIN_NAMESPACE_QPOASES
/*****************************************************************************
* P U B L I C *
*****************************************************************************/
/*
* g e t N C
*/
inline int_t Constraints::getNC( ) const
{
return n;
}
/*
* g e t N E C
*/
inline int_t Constraints::getNEC( ) const
{
return getNumberOfType( ST_EQUALITY );
}
/*
* g e t N I C
*/
inline int_t Constraints::getNIC( ) const
{
return getNumberOfType( ST_BOUNDED );
}
/*
* g e t N U C
*/
inline int_t Constraints::getNUC( ) const
{
return getNumberOfType( ST_UNBOUNDED );
}
/*
* g e t N A C
*/
inline int_t Constraints::getNAC( ) const
{
return active.getLength( );
}
/*
* g e t N I A C
*/
inline int_t Constraints::getNIAC( ) const
{
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_NAMESPACE_QPOASES
/*
* end of file
*/

View File

@ -0,0 +1,155 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/Flipper.hpp
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2007-2017
*
* Declaration of the Options class designed to manage user-specified
* options for solving a QProblem.
*/
#ifndef QPOASES_FLIPPER_HPP
#define QPOASES_FLIPPER_HPP
#include <qpOASES/Bounds.hpp>
#include <qpOASES/Constraints.hpp>
BEGIN_NAMESPACE_QPOASES
/**
* \brief Auxiliary class for storing a copy of the current matrix factorisations.
*
* This auxiliary class stores a copy of the current matrix factorisations. It
* is used by the classe QProblemB and QProblem in case flipping bounds are enabled.
*
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2007-2017
*/
class Flipper
{
friend class QProblemB;
friend class QProblem;
/*
* PUBLIC MEMBER FUNCTIONS
*/
public:
/** Default constructor. */
Flipper( );
/** Constructor which takes the number of bounds and constraints. */
Flipper( uint_t _nV, /**< Number of bounds. */
uint_t _nC = 0 /**< Number of constraints. */
);
/** Copy constructor (deep copy). */
Flipper( const Flipper& rhs /**< Rhs object. */
);
/** Destructor. */
~Flipper( );
/** Assignment operator (deep copy). */
Flipper& operator=( const Flipper& rhs /**< Rhs object. */
);
/** Initialises object with given number of bounds and constraints.
* \return SUCCESSFUL_RETURN \n
RET_INVALID_ARGUMENTS */
returnValue init( uint_t _nV = 0, /**< Number of bounds. */
uint_t _nC = 0 /**< Number of constraints. */
);
/** Copies current values to non-null arguments (assumed to be allocated with consistent size).
* \return SUCCESSFUL_RETURN */
returnValue get( Bounds* const _bounds, /**< Pointer to new bounds. */
real_t* const R, /**< New matrix R. */
Constraints* const _constraints = 0, /**< Pointer to new constraints. */
real_t* const _Q = 0, /**< New matrix Q. */
real_t* const _T = 0 /**< New matrix T. */
) const;
/** Assigns new values to non-null arguments.
* \return SUCCESSFUL_RETURN */
returnValue set( const Bounds* const _bounds, /**< Pointer to new bounds. */
const real_t* const _R, /**< New matrix R. */
const Constraints* const _constraints = 0, /**< Pointer to new constraints. */
const real_t* const _Q = 0, /**< New matrix Q. */
const real_t* const _T = 0 /**< New matrix T. */
);
/*
* PROTECTED MEMBER FUNCTIONS
*/
protected:
/** Frees all allocated memory.
* \return SUCCESSFUL_RETURN */
returnValue clear( );
/** Copies all members from given rhs object.
* \return SUCCESSFUL_RETURN */
returnValue copy( const Flipper& rhs /**< Rhs object. */
);
/** Returns dimension of matrix T.
* \return Dimension of matrix T. */
uint_t getDimT( ) const;
/*
* PROTECTED MEMBER VARIABLES
*/
protected:
uint_t nV; /**< Number of variables. */
uint_t nC; /**< Number of constraints. */
Bounds bounds; /**< Data structure for problem's bounds. */
Constraints constraints; /**< Data structure for problem's constraints. */
real_t* R; /**< Cholesky factor of H (i.e. H = R^T*R). */
real_t* Q; /**< Orthonormal quadratic matrix, A = [0 T]*Q'. */
real_t* T; /**< Reverse triangular matrix, A = [0 T]*Q'. */
};
END_NAMESPACE_QPOASES
#endif /* QPOASES_FLIPPER_HPP */
/*
* end of file
*/

View File

@ -0,0 +1,199 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/Indexlist.hpp
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2007-2017
*
* 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 <qpOASES/Utils.hpp>
BEGIN_NAMESPACE_QPOASES
/**
* \brief Stores and manages index lists.
*
* This class manages index lists of active/inactive bounds/constraints.
*
* \author Hans Joachim Ferreau
* \version 3.2
* \date 2007-2017
*/
class Indexlist
{
/*
* FRIENDS
*/
friend class DenseMatrix;
friend class SymDenseMat;
friend class SparseMatrix;
friend class SparseMatrixRow;
friend class SymSparseMat;
/*
* PUBLIC MEMBER FUNCTIONS
*/
public:
/** Default constructor. */
Indexlist( );
/** Constructor which takes the desired physical length of the index list. */
Indexlist( int_t n /**< Physical length of index list. */
);
/** Copy constructor (deep copy). */
Indexlist( const Indexlist& rhs /**< Rhs object. */
);
/** Destructor. */
~Indexlist( );
/** Assingment operator (deep copy). */
Indexlist& operator=( const Indexlist& rhs /**< Rhs object. */
);
/** Initialises index list of desired physical length.
* \return SUCCESSFUL_RETURN \n
RET_INVALID_ARGUMENTS */
returnValue init( int_t n = 0 /**< Physical length of index list. */
);
/** Creates an array of all numbers within the index set in correct order.
* \return SUCCESSFUL_RETURN \n
RET_INDEXLIST_CORRUPTED */
returnValue getNumberArray( int_t** const numberarray /**< Output: Array of numbers (NULL on error). */
) const;
/** Creates an array of all numbers within the index set in correct order.
* \return SUCCESSFUL_RETURN \n
RET_INDEXLIST_CORRUPTED */
returnValue getISortArray( int_t** const iSortArray /**< Output: iSort Array. */
) const;
/** Determines the index within the index list at which a given number is stored.
* \return >= 0: Index of given number. \n
-1: Number not found. */
int_t getIndex( int_t givennumber /**< Number whose 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_t getNumber( int_t 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_t getLength( ) const;
/** Returns last number within the index list.
* \return Last number within the index list. */
inline int_t 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_t addnumber /**< Number to be added. */
);
/** Removes number from index list.
* \return SUCCESSFUL_RETURN */
returnValue removeNumber( int_t removenumber /**< Number to be removed. */
);
/** Swaps two numbers within index list.
* \return SUCCESSFUL_RETURN */
returnValue swapNumbers( int_t number1, /**< First number for swapping. */
int_t 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_t _number /**< Number to be tested for membership. */
) const;
/*
* PROTECTED MEMBER FUNCTIONS
*/
protected:
/** Frees all allocated memory.
* \return SUCCESSFUL_RETURN */
returnValue clear( );
/** Copies all members from given rhs object.
* \return SUCCESSFUL_RETURN */
returnValue copy( const Indexlist& rhs /**< Rhs object. */
);
/** Find first index j between -1 and length in sorted list of indices
* iSort such that numbers[iSort[j]] <= i < numbers[iSort[j+1]]. Uses
* bisection.
* \return j. */
int_t findInsert( int_t i
) const;
/*
* PROTECTED MEMBER VARIABLES
*/
protected:
int_t* number; /**< Array to store numbers of constraints or bounds. */
int_t* iSort; /**< Index list to sort vector \a number */
int_t length; /**< Length of index list. */
int_t first; /**< Physical index of first element. */
int_t last; /**< Physical index of last element. */
int_t lastusedindex; /**< Physical index of last entry in index list. */
int_t physicallength; /**< Physical length of index list. */
};
END_NAMESPACE_QPOASES
#include <qpOASES/Indexlist.ipp>
#endif /* QPOASES_INDEXLIST_HPP */
/*
* end of file
*/

View File

@ -0,0 +1,92 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/Indexlist.ipp
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2007-2017
*
* Implementation of inlined member functions of the Indexlist class designed
* to manage index lists of constraints and bounds within a QProblem_SubjectTo.
*/
BEGIN_NAMESPACE_QPOASES
/*****************************************************************************
* P U B L I C *
*****************************************************************************/
/*
* g e t N u m b e r
*/
inline int_t Indexlist::getNumber( int_t 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_t Indexlist::getLength( ) const
{
return length;
}
/*
* g e t L a s t N u m b e r
*/
inline int_t Indexlist::getLastNumber( ) const
{
return number[length-1];
}
/*
* g e t L a s t N u m b e r
*/
inline BooleanType Indexlist::isMember( int_t _number ) const
{
if ( getIndex( _number ) >= 0 )
return BT_TRUE;
else
return BT_FALSE;
}
END_NAMESPACE_QPOASES
/*
* end of file
*/

View File

@ -0,0 +1,128 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/LapackBlasReplacement.hpp
* \author Andreas Potschka, Hans Joachim Ferreau, Christian Kirches
* \version 3.2
* \date 2009-2017
*
* Declarations for external LAPACK/BLAS functions.
*/
#ifndef QPOASES_LAPACKBLASREPLACEMENT_HPP
#define QPOASES_LAPACKBLASREPLACEMENT_HPP
#ifdef __AVOID_LA_NAMING_CONFLICTS__
#define SGEMM qpOASES_sgemm
#define DGEMM qpOASES_gemm
#define SPOTRF qpOASES_spotrf
#define DPOTRF qpOASES_dpotrf
#define STRTRS qpOASES_strtrs
#define DTRTRS qpOASES_dtrtrs
#define STRCON qpOASES_strcon
#define DTRCON qpOASES_dtrcon
#else
#define SGEMM sgemm_
#define DGEMM dgemm_
#define SPOTRF spotrf_
#define DPOTRF dpotrf_
#define STRTRS strtrs_
#define DTRTRS dtrtrs_
#define STRCON strcon_
#define DTRCON dtrcon_
#endif
#ifdef __USE_SINGLE_PRECISION__
/** Macro for calling level 3 BLAS operation in single precision. */
#define GEMM SGEMM
/** Macro for calling level 3 BLAS operation in single precision. */
#define POTRF SPOTRF
/** Macro for calling level 3 BLAS operation in single precision. */
#define TRTRS STRTRS
/** Macro for calling level 3 BLAS operation in single precision. */
#define TRCON strcon_
#else
/** Macro for calling level 3 BLAS operation in double precision. */
#define GEMM DGEMM
/** Macro for calling level 3 BLAS operation in double precision. */
#define POTRF DPOTRF
/** Macro for calling level 3 BLAS operation in double precision. */
#define TRTRS DTRTRS
/** Macro for calling level 3 BLAS operation in double precision. */
#define TRCON DTRCON
#endif /* __USE_SINGLE_PRECISION__ */
extern "C"
{
/** Performs one of the matrix-matrix operation in double precision. */
void DGEMM( const char*, const char*, const la_uint_t*, const la_uint_t*, const la_uint_t*,
const double*, const double*, const la_uint_t*, const double*, const la_uint_t*,
const double*, double*, const la_uint_t* );
/** Performs one of the matrix-matrix operation in single precision. */
void SGEMM( const char*, const char*, const la_uint_t*, const la_uint_t*, const la_uint_t*,
const float*, const float*, const la_uint_t*, const float*, const la_uint_t*,
const float*, float*, const la_uint_t* );
/** Calculates the Cholesky factorization of a real symmetric positive definite matrix in double precision. */
void DPOTRF( const char*, const la_uint_t*, double*, const la_uint_t*, la_int_t* );
/** Calculates the Cholesky factorization of a real symmetric positive definite matrix in single precision. */
void SPOTRF( const char*, const la_uint_t*, float*, const la_uint_t*, la_int_t* );
/** Solves a triangular system (double precision) */
void DTRTRS( const char* UPLO, const char* TRANS, const char* DIAG, const la_uint_t* N, const la_uint_t* NRHS,
double* A, const la_uint_t* LDA, double* B, const la_uint_t* LDB, la_int_t* INFO );
/** Solves a triangular system (single precision) */
void STRTRS( const char* UPLO, const char* TRANS, const char* DIAG, const la_uint_t* N, const la_uint_t* NRHS,
float* A, const la_uint_t* LDA, float* B, const la_uint_t* LDB, la_int_t* INFO );
/** Estimate the reciprocal of the condition number of a triangular matrix in double precision */
void DTRCON( const char* NORM, const char* UPLO, const char* DIAG, const la_uint_t* N, double* A, const la_uint_t* LDA,
double* RCOND, double* WORK, const la_uint_t* IWORK, la_int_t* INFO );
/** Estimate the reciprocal of the condition number of a triangular matrix in single precision */
void STRCON( const char* NORM, const char* UPLO, const char* DIAG, const la_uint_t* N, float* A, const la_uint_t* LDA,
float* RCOND, float* WORK, const la_uint_t* IWORK, la_int_t* INFO );
}
#endif /* QPOASES_LAPACKBLASREPLACEMENT_HPP */
/*
* end of file
*/

View File

@ -0,0 +1,984 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/Matrices.hpp
* \author Andreas Potschka, Hans Joachim Ferreau, Christian Kirches
* \version 3.2
* \date 2009-2017
*
* Various matrix classes: Abstract base matrix class, dense and sparse matrices,
* including symmetry exploiting specializations.
*/
#ifndef QPOASES_MATRICES_HPP
#define QPOASES_MATRICES_HPP
#include <qpOASES/Utils.hpp>
#include <qpOASES/Indexlist.hpp>
BEGIN_NAMESPACE_QPOASES
/**
* \brief Abstract base class for interfacing tailored matrix-vector operations.
*
* Abstract base matrix class. Supplies interface to matrix vector
* products, including products with submatrices given by (ordered) working set
* index lists (see \a SubjectTo).
*
* \author Andreas Potschka, Christian Kirches, Hans Joachim Ferreau
* \version 3.2
* \date 2011-2017
*/
class Matrix
{
public:
/** Default constructor. */
Matrix( ) { doNotFreeMemory(); };
/** Destructor. */
virtual ~Matrix( ) { };
/** Frees all internal memory. */
virtual void free( ) = 0;
/** Returns a deep-copy of the Matrix object.
* \return Deep-copy of Matrix object */
virtual Matrix* duplicate( ) const = 0;
/** Returns i-th diagonal entry.
* \return i-th diagonal entry */
virtual real_t diag( int_t i /**< Index. */
) const = 0;
/** Checks whether matrix is square and diagonal.
* \return BT_TRUE iff matrix is square and diagonal; \n
* BT_FALSE otherwise. */
virtual BooleanType isDiag( ) const = 0;
/** Get the N-norm of the matrix
* \return N-norm of the matrix
*/
virtual real_t getNorm( int_t type = 2 /**< Norm type, 1: one-norm, 2: Euclidean norm. */
) const = 0;
/** Get the N-norm of a row
* \return N-norm of row \a rNum
*/
virtual real_t getRowNorm( int_t rNum, /**< Row number. */
int_t type = 2 /**< Norm type, 1: one-norm, 2: Euclidean norm. */
) const = 0;
/** Get the N-norm of all rows
* \return SUCCESSFUL_RETURN */
virtual returnValue getRowNorm( real_t* norm, /**< Norm of each row. */
int_t type = 2 /**< Norm type, 1: one-norm, 2: Euclidean norm. */
) const = 0;
/** Retrieve indexed entries of matrix row multiplied by alpha.
* \return SUCCESSFUL_RETURN */
virtual returnValue getRow( int_t rNum, /**< Row number. */
const Indexlist* const icols, /**< Index list specifying columns. */
real_t alpha, /**< Scalar factor. */
real_t* row /**< Output row vector. */
) const = 0;
/** Retrieve indexed entries of matrix column multiplied by alpha.
* \return SUCCESSFUL_RETURN */
virtual returnValue getCol( int_t cNum, /**< Column number. */
const Indexlist* const irows, /**< Index list specifying rows. */
real_t alpha, /**< Scalar factor. */
real_t* col /**< Output column vector. */
) const = 0;
/** Retrieve entries of submatrix in Harwell-Boeing sparse format.
* If irn, jcn, and avals are null, this only counts the number of nonzeros.
* Otherwise, numNonzeros containts the size of irn, jcn, and avals on entry,
* and the written number of entries on return.
* \return SUCCESSFUL_RETURN */
virtual returnValue getSparseSubmatrix(
const Indexlist* const irows, /**< Index list specifying rows. */
const Indexlist* const icols, /**< Index list specifying columns. */
int_t rowoffset, /**< Offset for row entries. */
int_t coloffset, /**< Offset for row entries. */
int_t& numNonzeros, /**< Number of nonzeros in submatrix. */
int_t* irn, /**< Row position of entries (as position in irows) plus rowoffset. */
int_t* jcn, /**< Column position of entries (as position in irows) plus coloffset. */
real_t* avals, /**< Numerical values of the entries. */
BooleanType only_lower_triangular = BT_FALSE /**< if true, only the lower triangular portion is returned. This can only be true for symmetric matrices and if irows==jcols. */
) const;
/** Retrieve entries of submatrix in Harwell-Boeing sparse format.
* If irn, jcn, and avals are null, this only counts the number of nonzeros.
* Otherwise, numNonzeros containts the size of irn, jcn, and avals on entry,
* and the written number of entries on return. This version retrieves one
* column.
* \return SUCCESSFUL_RETURN */
virtual returnValue getSparseSubmatrix(
const Indexlist* const irows, /**< Index list specifying rows. */
int_t idx_icol, /**< Index list specifying columns. */
int_t rowoffset, /**< Offset for row entries. */
int_t coloffset, /**< Offset for row entries. */
int_t& numNonzeros, /**< Number of nonzeros in submatrix. */
int_t* irn, /**< Row position of entries (as position in irows) plus rowoffset. */
int_t* jcn, /**< Column position of entries (as position in irows) plus coloffset. */
real_t* avals, /**< Numerical values of the entries. */
BooleanType only_lower_triangular = BT_FALSE /**< if true, only the lower triangular portion is returned. This can only be true for symmetric matrices and if irows==jcols. */
) const;
/** Retrieve entries of submatrix in Harwell-Boeing sparse format.
* If irn, jcn, and avals are null, this only counts the number of nonzeros.
* Otherwise, numNonzeros containts the size of irn, jcn, and avals on entry,
* and the written number of entries on return. This version retrieves one row.
* \return SUCCESSFUL_RETURN */
virtual returnValue getSparseSubmatrix(
int_t idx_row, /**< Row number. */
const Indexlist* const icols, /**< Index list specifying columns. */
int_t rowoffset, /**< Offset for row entries. */
int_t coloffset, /**< Offset for row entries. */
int_t& numNonzeros, /**< Number of nonzeros in submatrix. */
int_t* irn, /**< Row position of entries (as position in irows) plus rowoffset. */
int_t* jcn, /**< Column position of entries (as position in irows) plus coloffset. */
real_t* avals, /**< Numerical values of the entries. */
BooleanType only_lower_triangular = BT_FALSE /**< if true, only the lower triangular portion is returned. This can only be true for symmetric matrices and if irows==jcols. */
) const;
/** Retrieve entries of submatrix in Harwell-Boeing sparse format.
* If irn, jcn, and avals are null, this only counts the number of nonzeros.
* Otherwise, numNonzeros containts the size of irn, jcn, and avals on entry,
* and the written number of entries on return.
* \return SUCCESSFUL_RETURN */
virtual returnValue getSparseSubmatrix(
int_t irowsLength, /**< Number of rows. */
const int_t* const irowsNumber, /**< Array with row numbers. */
int_t icolsLength, /**< Number of columns. */
const int_t* const icolsNumber, /**< Array with column numbers. */
int_t rowoffset, /**< Offset for row entries. */
int_t coloffset, /**< Offset for row entries. */
int_t& numNonzeros, /**< Number of nonzeros in submatrix. */
int_t* irn, /**< Row position of entries (as position in irows) plus rowoffset. */
int_t* jcn, /**< Column position of entries (as position in irows) plus coloffset. */
real_t* avals, /**< Numerical values of the entries. */
BooleanType only_lower_triangular = BT_FALSE /**< if true, only the lower triangular portion is returned. This can only be true for symmetric matrices and if irows==jcols. */
) const = 0;
/** Evaluate Y=alpha*A*X + beta*Y.
* \return SUCCESSFUL_RETURN */
virtual returnValue times ( int_t xN, /**< Number of vectors to multiply. */
real_t alpha, /**< Scalar factor for matrix vector product. */
const real_t* x, /**< Input vector to be multiplied. */
int_t xLD, /**< Leading dimension of input x. */
real_t beta, /**< Scalar factor for y. */
real_t* y, /**< Output vector of results. */
int_t yLD /**< Leading dimension of output y. */
) const = 0;
/** Evaluate Y=alpha*A'*X + beta*Y.
* \return SUCCESSFUL_RETURN */
virtual returnValue transTimes ( int_t xN, /**< Number of vectors to multiply. */
real_t alpha, /**< Scalar factor for matrix vector product. */
const real_t* x, /**< Input vector to be multiplied. */
int_t xLD, /**< Leading dimension of input x. */
real_t beta, /**< Scalar factor for y. */
real_t* y, /**< Output vector of results. */
int_t yLD /**< Leading dimension of output y. */
) const = 0;
/** Evaluate matrix vector product with submatrix given by Indexlist.
* \return SUCCESSFUL_RETURN */
virtual returnValue times ( const Indexlist* const irows, /**< Index list specifying rows. */
const Indexlist* const icols, /**< Index list specifying columns. */
int_t xN, /**< Number of vectors to multiply. */
real_t alpha, /**< Scalar factor for matrix vector product. */
const real_t* x, /**< Input vector to be multiplied. */
int_t xLD, /**< Leading dimension of input x. */
real_t beta, /**< Scalar factor for y. */
real_t* y, /**< Output vector of results. */
int_t yLD, /**< Leading dimension of output y. */
BooleanType yCompr = BT_TRUE /**< Compressed storage for y. */
) const = 0;
/** Evaluate matrix transpose vector product.
* \return SUCCESSFUL_RETURN */
virtual returnValue transTimes ( const Indexlist* const irows, /**< Index list specifying rows. */
const Indexlist* const icols, /**< Index list specifying columns. */
int_t xN, /**< Number of vectors to multiply. */
real_t alpha, /**< Scalar factor for matrix vector product. */
const real_t* x, /**< Input vector to be multiplied. */
int_t xLD, /**< Leading dimension of input x. */
real_t beta, /**< Scalar factor for y. */
real_t* y, /**< Output vector of results. */
int_t yLD /**< Leading dimension of output y. */
) const = 0;
/** Adds given offset to diagonal of matrix.
* \return SUCCESSFUL_RETURN \n
RET_NO_DIAGONAL_AVAILABLE */
virtual returnValue addToDiag( real_t alpha /**< Diagonal offset. */
) = 0;
/** Allocates and creates dense matrix array in row major format.
*
* Note: Calling function has to free allocated memory!
*
* \return Pointer to matrix array.
*/
virtual real_t* full() const = 0;
/** Prints matrix to screen.
* \return SUCCESSFUL_RETURN */
virtual returnValue print( const char* name = 0 /** Name of matrix. */
) const = 0;
/** Write matrix to file.
* \return SUCCESSFUL_RETURN */
virtual returnValue writeToFile( FILE* output_file, const char* prefix ) const = 0;
/** Returns whether internal memory needs to be de-allocated.
* \return BT_TRUE iff internal memory needs to be de-allocated, \n
BT_FALSE otherwise */
BooleanType needToFreeMemory( ) const { return freeMemory; };
/** Enables de-allocation of internal memory. */
void doFreeMemory( ) { freeMemory = BT_TRUE; };
/** Disables de-allocation of internal memory. */
void doNotFreeMemory( ) { freeMemory = BT_FALSE; };
protected:
BooleanType freeMemory; /**< Indicating whether internal memory needs to be de-allocated. */
};
/**
* \brief Abstract base class for interfacing matrix-vector operations tailored to symmetric matrices.
*
* Abstract base class for symmetric matrices. Extends Matrix interface with
* bilinear form evaluation.
*
* \author Andreas Potschka, Christian Kirches, Hans Joachim Ferreau
* \version 3.2
* \date 2011-2017
*/
class SymmetricMatrix : public virtual Matrix
{
public:
/** Default constructor. */
SymmetricMatrix( ) { };
/** Destructor. */
virtual ~SymmetricMatrix( ) { };
/** Returns a deep-copy of the SymmetricMatrix object.
* \return Deep-copy of SymmetricMatrix object */
virtual SymmetricMatrix* duplicateSym( ) const = 0;
/** Compute bilinear form y = x'*H*x using submatrix given by index list.
* \return SUCCESSFUL_RETURN */
virtual returnValue bilinear( const Indexlist* const icols, /**< Index list specifying columns of x. */
int_t xN, /**< Number of vectors to multiply. */
const real_t* x, /**< Input vector to be multiplied (uncompressed). */
int_t xLD, /**< Leading dimension of input x. */
real_t* y, /**< Output vector of results (compressed). */
int_t yLD /**< Leading dimension of output y. */
) const = 0;
};
/**
* \brief Interfaces matrix-vector operations tailored to general dense matrices.
*
* Dense matrix class (row major format).
*
* \author Andreas Potschka, Christian Kirches, Hans Joachim Ferreau
* \version 3.2
* \date 2011-2017
*/
class DenseMatrix : public virtual Matrix
{
public:
/** Default constructor. */
DenseMatrix( ) : nRows(0), nCols(0), leaDim(0), val(0) { };
/** Constructor from vector of values.
* Caution: Data pointer must be valid throughout lifetime
*/
DenseMatrix( int_t m, /**< Number of rows. */
int_t n, /**< Number of columns. */
int_t lD, /**< Leading dimension. */
real_t* v /**< Values. */
) : nRows(m), nCols(n), leaDim(lD), val(v) {}
/** Destructor. */
virtual ~DenseMatrix( );
/** Frees all internal memory. */
virtual void free( );
/** Returns a deep-copy of the Matrix object.
* \return Deep-copy of Matrix object */
virtual Matrix *duplicate( ) const;
/** Returns i-th diagonal entry.
* \return i-th diagonal entry */
virtual real_t diag( int_t i /**< Index. */
) const;
/** Checks whether matrix is square and diagonal.
* \return BT_TRUE iff matrix is square and diagonal; \n
* BT_FALSE otherwise. */
virtual BooleanType isDiag( ) const;
/** Get the N-norm of the matrix
* \return N-norm of the matrix
*/
virtual real_t getNorm( int_t type = 2 /**< Norm type, 1: one-norm, 2: Euclidean norm. */
) const;
/** Get the N-norm of a row
* \return N-norm of row \a rNum
*/
virtual real_t getRowNorm( int_t rNum, /**< Row number. */
int_t type = 2 /**< Norm type, 1: one-norm, 2: Euclidean norm. */
) const;
/** Get the N-norm of all rows
* \return SUCCESSFUL_RETURN */
virtual returnValue getRowNorm( real_t* norm, /**< Norm of each row. */
int_t type = 2 /**< Norm type, 1: one-norm, 2: Euclidean norm. */
) const;
/** Retrieve indexed entries of matrix row multiplied by alpha.
* \return SUCCESSFUL_RETURN */
virtual returnValue getRow( int_t rNum, /**< Row number. */
const Indexlist* const icols, /**< Index list specifying columns. */
real_t alpha, /**< Scalar factor. */
real_t* row /**< Output row vector. */
) const;
/** Retrieve indexed entries of matrix column multiplied by alpha.
* \return SUCCESSFUL_RETURN */
virtual returnValue getCol(
int_t cNum, /**< Column number. */
const Indexlist* const irows, /**< Index list specifying rows. */
real_t alpha, /**< Scalar factor. */
real_t* col /**< Output column vector. */
) const;
/** Retrieve entries of submatrix in Harwell-Boeing sparse format.
* If irn, jcn, and avals are null, this only counts the number of nonzeros.
* Otherwise, numNonzeros containts the size of irn, jcn, and avals on entry,
* and the written number of entries on return.
* \return SUCCESSFUL_RETURN */
virtual returnValue getSparseSubmatrix(
int_t irowsLength, /**< Number of rows. */
const int_t* const irowsNumber, /**< Array with row numbers. */
int_t icolsLength, /**< Number of columns. */
const int_t* const icolsNumber, /**< Array with column numbers. */
int_t rowoffset, /**< Offset for row entries. */
int_t coloffset, /**< Offset for row entries. */
int_t& numNonzeros, /**< Number of nonzeros in submatrix. */
int_t* irn, /**< Row position of entries (as position in irows) plus rowoffset. */
int_t* jcn, /**< Column position of entries (as position in irows) plus coloffset. */
real_t* avals, /**< Numerical values of the entries. */
BooleanType only_lower_triangular = BT_FALSE /**< if true, only the lower triangular portion is returned. This can only be true for symmetric matrices and if irows==jcols. */
) const;
/** Evaluate Y=alpha*A*X + beta*Y.
* \return SUCCESSFUL_RETURN. */
virtual returnValue times( int_t xN, /**< Number of vectors to multiply. */
real_t alpha, /**< Scalar factor for matrix vector product. */
const real_t* x, /**< Input vector to be multiplied. */
int_t xLD, /**< Leading dimension of input x. */
real_t beta, /**< Scalar factor for y. */
real_t* y, /**< Output vector of results. */
int_t yLD /**< Leading dimension of output y. */
) const;
/** Evaluate Y=alpha*A'*X + beta*Y.
* \return SUCCESSFUL_RETURN. */
virtual returnValue transTimes( int_t xN, /**< Number of vectors to multiply. */
real_t alpha, /**< Scalar factor for matrix vector product. */
const real_t* x, /**< Input vector to be multiplied. */
int_t xLD, /**< Leading dimension of input x. */
real_t beta, /**< Scalar factor for y. */
real_t* y, /**< Output vector of results. */
int_t yLD /**< Leading dimension of output y. */
) const;
/** Evaluate matrix vector product with submatrix given by Indexlist.
* \return SUCCESSFUL_RETURN */
virtual returnValue times( const Indexlist* const irows, /**< Index list specifying rows. */
const Indexlist* const icols, /**< Index list specifying columns. */
int_t xN, /**< Number of vectors to multiply. */
real_t alpha, /**< Scalar factor for matrix vector product. */
const real_t* x, /**< Input vector to be multiplied. */
int_t xLD, /**< Leading dimension of input x. */
real_t beta, /**< Scalar factor for y. */
real_t* y, /**< Output vector of results. */
int_t yLD, /**< Leading dimension of output y. */
BooleanType yCompr = BT_TRUE /**< Compressed storage for y. */
) const;
/** Evaluate matrix transpose vector product.
* \return SUCCESSFUL_RETURN */
virtual returnValue transTimes( const Indexlist* const irows, /**< Index list specifying rows. */
const Indexlist* const icols, /**< Index list specifying columns. */
int_t xN, /**< Number of vectors to multiply. */
real_t alpha, /**< Scalar factor for matrix vector product. */
const real_t* x, /**< Input vector to be multiplied. */
int_t xLD, /**< Leading dimension of input x. */
real_t beta, /**< Scalar factor for y. */
real_t* y, /**< Output vector of results. */
int_t yLD /**< Leading dimension of output y. */
) const;
/** Adds given offset to diagonal of matrix.
* \return SUCCESSFUL_RETURN \n
RET_NO_DIAGONAL_AVAILABLE */
virtual returnValue addToDiag( real_t alpha /**< Diagonal offset. */
);
/** Allocates and creates dense matrix array in row major format.
*
* Note: Calling function has to free allocated memory!
*
* \return Pointer to matrix array.
*/
virtual real_t* full() const;
/** Prints matrix to screen.
* \return SUCCESSFUL_RETURN */
virtual returnValue print( const char* name = 0 /** Name of matrix. */
) const;
/** Write matrix to file.
* \return SUCCESSFUL_RETURN */
virtual returnValue writeToFile( FILE* output_file, const char* prefix ) const;
protected:
int_t nRows; /**< Number of rows. */
int_t nCols; /**< Number of columns. */
int_t leaDim; /**< Leading dimension. */
real_t* val; /**< Vector of entries. */
};
/**
* \brief Interfaces matrix-vector operations tailored to symmetric dense matrices.
*
* Symmetric dense matrix class.
*
* \author Andreas Potschka, Christian Kirches, Hans Joachim Ferreau
* \version 3.2
* \date 2011-2017
*/
class SymDenseMat : public DenseMatrix, public SymmetricMatrix
{
public:
/** Default constructor. */
SymDenseMat() : DenseMatrix() { };
/** Constructor from vector of values. */
SymDenseMat( int_t m, /**< Number of rows. */
int_t n, /**< Number of columns. */
int_t lD, /**< Leading dimension. */
real_t* v /**< Values. */
) : DenseMatrix(m, n, lD, v) { };
/** Destructor. */
virtual ~SymDenseMat() { };
/** Returns a deep-copy of the Matrix object.
* \return Deep-copy of Matrix object */
virtual Matrix *duplicate( ) const;
/** Returns a deep-copy of the SymmetricMatrix object.
* \return Deep-copy of SymmetricMatrix object */
virtual SymmetricMatrix* duplicateSym( ) const;
/** Compute bilinear form y = x'*H*x using submatrix given by index list.
* \return SUCCESSFUL_RETURN */
virtual returnValue bilinear( const Indexlist* const icols, /**< Index list specifying columns of x. */
int_t xN, /**< Number of vectors to multiply. */
const real_t* x, /**< Input vector to be multiplied (uncompressed). */
int_t xLD, /**< Leading dimension of input x. */
real_t* y, /**< Output vector of results (compressed). */
int_t yLD /**< Leading dimension of output y. */
) const;
};
/**
* \brief Interfaces matrix-vector operations tailored to general sparse matrices.
*
* Sparse matrix class (col compressed format).
*
* \author Andreas Potschka, Christian Kirches, Hans Joachim Ferreau
* \version 3.2
* \date 2011-2017
*/
class SparseMatrix : public virtual Matrix
{
public:
/** Default constructor. */
SparseMatrix( );
/** Constructor with arguments. */
SparseMatrix( int_t nr, /**< Number of rows. */
int_t nc, /**< Number of columns. */
sparse_int_t* r, /**< Row indices (length). */
sparse_int_t* c, /**< Indices to first entry of columns (nCols+1). */
real_t* v /**< Vector of entries (length). */
);
/** Constructor from dense matrix. */
SparseMatrix( int_t nr, /**< Number of rows. */
int_t nc, /**< Number of columns. */
int_t ld, /**< Leading dimension. */
const real_t* const v /**< Row major stored matrix elements. */
);
/** Destructor. */
virtual ~SparseMatrix( );
/** Frees all internal memory. */
virtual void free( );
/** Returns a deep-copy of the Matrix object.
* \return Deep-copy of Matrix object */
virtual Matrix *duplicate( ) const;
/** Sets value array.
*
* Thanks to Frank Chuang.
*/
virtual void setVal( const real_t* newVal /**< ... */
);
/** Returns i-th diagonal entry.
* \return i-th diagonal entry (or INFTY if diagonal does not exist)*/
virtual real_t diag( int_t i /**< Index. */
) const;
/** Checks whether matrix is square and diagonal.
* \return BT_TRUE iff matrix is square and diagonal; \n
* BT_FALSE otherwise. */
virtual BooleanType isDiag( ) const;
/** Get the N-norm of the matrix
* \return N-norm of the matrix
*/
virtual real_t getNorm( int_t type = 2 /**< Norm type, 1: one-norm, 2: Euclidean norm. */
) const;
/** Get the N-norm of a row
* \return N-norm of row \a rNum
*/
virtual real_t getRowNorm( int_t rNum, /**< Row number. */
int_t type = 2 /**< Norm type, 1: one-norm, 2: Euclidean norm. */
) const;
/** Get the N-norm of all rows
* \return SUCCESSFUL_RETURN */
virtual returnValue getRowNorm( real_t* norm, /**< Norm of each row. */
int_t type = 2 /**< Norm type, 1: one-norm, 2: Euclidean norm. */
) const;
/** Retrieve indexed entries of matrix row multiplied by alpha. */
virtual returnValue getRow( int_t rNum, /**< Row number. */
const Indexlist* const icols, /**< Index list specifying columns. */
real_t alpha, /**< Scalar factor. */
real_t* row /**< Output row vector. */
) const;
/** Retrieve indexed entries of matrix column multiplied by alpha. */
virtual returnValue getCol( int_t cNum, /**< Column number. */
const Indexlist* const irows, /**< Index list specifying rows. */
real_t alpha, /**< Scalar factor. */
real_t* col /**< Output column vector. */
) const;
/** Retrieve entries of submatrix in Harwell-Boeing sparse format.
* If irn, jcn, and avals are null, this only counts the number of nonzeros.
* Otherwise, numNonzeros containts the size of irn, jcn, and avals on entry,
* and the written number of entries on return.
* \return SUCCESSFUL_RETURN */
virtual returnValue getSparseSubmatrix(
int_t irowsLength, /**< Number of rows. */
const int_t* const irowsNumber, /**< Array with row numbers. */
int_t icolsLength, /**< Number of columns. */
const int_t* const icolsNumber, /**< Array with column numbers. */
int_t rowoffset, /**< Offset for row entries. */
int_t coloffset, /**< Offset for row entries. */
int_t& numNonzeros, /**< Number of nonzeros in submatrix. */
int_t* irn, /**< Row position of entries (as position in irows) plus rowoffset. */
int_t* jcn, /**< Column position of entries (as position in irows) plus coloffset. */
real_t* avals, /**< Numerical values of the entries. */
BooleanType only_lower_triangular = BT_FALSE /**< if true, only the lower triangular portion is returned. This can only be true for symmetric matrices and if irows==jcols. */
) const;
/** Evaluate Y=alpha*A*X + beta*Y. */
virtual returnValue times ( int_t xN, /**< Number of vectors to multiply. */
real_t alpha, /**< Scalar factor for matrix vector product. */
const real_t* x, /**< Input vector to be multiplied. */
int_t xLD, /**< Leading dimension of input x. */
real_t beta, /**< Scalar factor for y. */
real_t* y, /**< Output vector of results. */
int_t yLD /**< Leading dimension of output y. */
) const;
/** Evaluate Y=alpha*A'*X + beta*Y. */
virtual returnValue transTimes ( int_t xN, /**< Number of vectors to multiply. */
real_t alpha, /**< Scalar factor for matrix vector product. */
const real_t* x, /**< Input vector to be multiplied. */
int_t xLD, /**< Leading dimension of input x. */
real_t beta, /**< Scalar factor for y. */
real_t* y, /**< Output vector of results. */
int_t yLD /**< Leading dimension of output y. */
) const;
/** Evaluate matrix vector product with submatrix given by Indexlist. */
virtual returnValue times ( const Indexlist* const irows, /**< Index list specifying rows. */
const Indexlist* const icols, /**< Index list specifying columns. */
int_t xN, /**< Number of vectors to multiply. */
real_t alpha, /**< Scalar factor for matrix vector product. */
const real_t* x, /**< Input vector to be multiplied. */
int_t xLD, /**< Leading dimension of input x. */
real_t beta, /**< Scalar factor for y. */
real_t* y, /**< Output vector of results. */
int_t yLD, /**< Leading dimension of output y. */
BooleanType yCompr = BT_TRUE /**< Compressed storage for y. */
) const;
/** Evaluate matrix transpose vector product. */
virtual returnValue transTimes ( const Indexlist* const irows, /**< Index list specifying rows. */
const Indexlist* const icols, /**< Index list specifying columns. */
int_t xN, /**< Number of vectors to multiply. */
real_t alpha, /**< Scalar factor for matrix vector product. */
const real_t* x, /**< Input vector to be multiplied. */
int_t xLD, /**< Leading dimension of input x. */
real_t beta, /**< Scalar factor for y. */
real_t* y, /**< Output vector of results. */
int_t yLD /**< Leading dimension of output y. */
) const;
/** Adds given offset to diagonal of matrix.
* \return SUCCESSFUL_RETURN \n
RET_NO_DIAGONAL_AVAILABLE */
virtual returnValue addToDiag( real_t alpha /**< Diagonal offset. */
);
/** Create jd field from ir and jc.
* \return Pointer to jd. */
sparse_int_t* createDiagInfo();
/** Allocates and creates dense matrix array in row major format.
*
* Note: Calling function has to free allocated memory!
*
* \return Pointer to matrix array.
*/
virtual real_t* full() const;
/** Prints matrix to screen.
* \return SUCCESSFUL_RETURN */
virtual returnValue print( const char* name = 0 /** Name of matrix. */
) const;
/** Write matrix to file.
* \return SUCCESSFUL_RETURN */
virtual returnValue writeToFile( FILE* output_file, const char* prefix ) const;
protected:
int_t nRows; /**< Number of rows. */
int_t nCols; /**< Number of columns. */
sparse_int_t* ir; /**< Row indices (length). */
sparse_int_t* jc; /**< Indices to first entry of columns (nCols+1). */
sparse_int_t* jd; /**< Indices to first entry of lower triangle (including diagonal) (nCols). */
real_t* val; /**< Vector of entries (length). */
};
/**
* \brief Interfaces matrix-vector operations tailored to general sparse matrices.
*
* Sparse matrix class (row compressed format).
*
* \author Andreas Potschka, Christian Kirches, Hans Joachim Ferreau
* \version 3.2
* \date 2011-2017
*/
class SparseMatrixRow : public virtual Matrix
{
public:
/** Default constructor. */
SparseMatrixRow( );
/** Constructor with arguments. */
SparseMatrixRow( int_t nr, /**< Number of rows. */
int_t nc, /**< Number of columns. */
sparse_int_t* r, /**< Indices to first entry of rows (nRows+1). */
sparse_int_t* c, /**< Column indices (length). */
real_t* v /**< Vector of entries (length). */
);
/** Constructor from dense matrix. */
SparseMatrixRow( int_t nr, /**< Number of rows. */
int_t nc, /**< Number of columns. */
int_t ld, /**< Leading dimension. */
const real_t* const v /**< Row major stored matrix elements. */
);
/** Destructor. */
virtual ~SparseMatrixRow( );
/** Frees all internal memory. */
virtual void free( );
/** Returns a deep-copy of the Matrix object.
* \return Deep-copy of Matrix object */
virtual Matrix *duplicate( ) const;
/** Returns i-th diagonal entry.
* \return i-th diagonal entry (or INFTY if diagonal does not exist)*/
virtual real_t diag( int_t i /**< Index. */
) const;
/** Checks whether matrix is square and diagonal.
* \return BT_TRUE iff matrix is square and diagonal; \n
* BT_FALSE otherwise. */
virtual BooleanType isDiag( ) const;
/** Get the N-norm of the matrix
* \return N-norm of the matrix
*/
virtual real_t getNorm( int_t type = 2 /**< Norm type, 1: one-norm, 2: Euclidean norm. */
) const;
/** Get the N-norm of a row
* \return N-norm of row \a rNum
*/
virtual real_t getRowNorm( int_t rNum, /**< Row number. */
int_t type = 2 /**< Norm type, 1: one-norm, 2: Euclidean norm. */
) const;
/** Get the N-norm of all rows
* \return SUCCESSFUL_RETURN */
virtual returnValue getRowNorm( real_t* norm, /**< Norm of each row. */
int_t type = 2 /**< Norm type, 1: one-norm, 2: Euclidean norm. */
) const;
/** Retrieve indexed entries of matrix row multiplied by alpha. */
virtual returnValue getRow ( int_t rNum, /**< Row number. */
const Indexlist* const icols, /**< Index list specifying columns. */
real_t alpha, /**< Scalar factor. */
real_t* row /**< Output row vector. */
) const;
/** Retrieve indexed entries of matrix column multiplied by alpha. */
virtual returnValue getCol ( int_t cNum, /**< Column number. */
const Indexlist* const irows, /**< Index list specifying rows. */
real_t alpha, /**< Scalar factor. */
real_t* col /**< Output column vector. */
) const;
/** Retrieve entries of submatrix in Harwell-Boeing sparse format.
* If irn, jcn, and avals are null, this only counts the number of nonzeros.
* Otherwise, numNonzeros containts the size of irn, jcn, and avals on entry,
* and the written number of entries on return.
* \return SUCCESSFUL_RETURN */
virtual returnValue getSparseSubmatrix(
int_t irowsLength, /**< Number of rows. */
const int_t* const irowsNumber, /**< Array with row numbers. */
int_t icolsLength, /**< Number of columns. */
const int_t* const icolsNumber, /**< Array with column numbers. */
int_t rowoffset, /**< Offset for row entries. */
int_t coloffset, /**< Offset for row entries. */
int_t& numNonzeros, /**< Number of nonzeros in submatrix. */
int_t* irn, /**< Row position of entries (as position in irows) plus rowoffset. */
int_t* jcn, /**< Column position of entries (as position in irows) plus coloffset. */
real_t* avals, /**< Numerical values of the entries. */
BooleanType only_lower_triangular = BT_FALSE /**< if true, only the lower triangular portion is returned. This can only be true for symmetric matrices and if irows==jcols. */
) const;
/** Evaluate Y=alpha*A*X + beta*Y. */
virtual returnValue times( int_t xN, /**< Number of vectors to multiply. */
real_t alpha, /**< Scalar factor for matrix vector product. */
const real_t* x, /**< Input vector to be multiplied. */
int_t xLD, /**< Leading dimension of input x. */
real_t beta, /**< Scalar factor for y. */
real_t* y, /**< Output vector of results. */
int_t yLD /**< Leading dimension of output y. */
) const;
/** Evaluate Y=alpha*A'*X + beta*Y. */
virtual returnValue transTimes( int_t xN, /**< Number of vectors to multiply. */
real_t alpha, /**< Scalar factor for matrix vector product. */
const real_t* x, /**< Input vector to be multiplied. */
int_t xLD, /**< Leading dimension of input x. */
real_t beta, /**< Scalar factor for y. */
real_t* y, /**< Output vector of results. */
int_t yLD /**< Leading dimension of output y. */
) const;
/** Evaluate matrix vector product with submatrix given by Indexlist. */
virtual returnValue times( const Indexlist* const irows, /**< Index list specifying rows. */
const Indexlist* const icols, /**< Index list specifying columns. */
int_t xN, /**< Number of vectors to multiply. */
real_t alpha, /**< Scalar factor for matrix vector product. */
const real_t* x, /**< Input vector to be multiplied. */
int_t xLD, /**< Leading dimension of input x. */
real_t beta, /**< Scalar factor for y. */
real_t* y, /**< Output vector of results. */
int_t yLD, /**< Leading dimension of output y. */
BooleanType yCompr = BT_TRUE /**< Compressed storage for y. */
) const;
/** Evaluate matrix transpose vector product. */
virtual returnValue transTimes( const Indexlist* const irows, /**< Index list specifying rows. */
const Indexlist* const icols, /**< Index list specifying columns. */
int_t xN, /**< Number of vectors to multiply. */
real_t alpha, /**< Scalar factor for matrix vector product. */
const real_t* x, /**< Input vector to be multiplied. */
int_t xLD, /**< Leading dimension of input x. */
real_t beta, /**< Scalar factor for y. */
real_t* y, /**< Output vector of results. */
int_t yLD /**< Leading dimension of output y. */
) const;
/** Adds given offset to diagonal of matrix.
* \return SUCCESSFUL_RETURN \n
RET_NO_DIAGONAL_AVAILABLE */
virtual returnValue addToDiag( real_t alpha /**< Diagonal offset. */
);
/** Create jd field from ir and jc.
* \return Pointer to jd. */
sparse_int_t* createDiagInfo();
/** Allocates and creates dense matrix array in row major format.
*
* Note: Calling function has to free allocated memory!
*
* \return Pointer to matrix array.
*/
virtual real_t* full() const;
/** Prints matrix to screen.
* \return SUCCESSFUL_RETURN */
virtual returnValue print( const char* name = 0 /** Name of matrix. */
) const;
/** Write matrix to file.
* \return SUCCESSFUL_RETURN */
virtual returnValue writeToFile( FILE* output_file, const char* prefix ) const;
protected:
int_t nRows; /**< Number of rows. */
int_t nCols; /**< Number of columns. */
sparse_int_t* jr; /**< Indices to first entry of row (nRows+1). */
sparse_int_t* ic; /**< Column indices (length). */
sparse_int_t* jd; /**< Indices to first entry of upper triangle (including diagonal) (nRows). */
real_t* val; /**< Vector of entries (length). */
};
/**
* \brief Interfaces matrix-vector operations tailored to symmetric sparse matrices.
*
* Symmetric sparse matrix class (column compressed format).
*
* \author Andreas Potschka, Christian Kirches, Hans Joachim Ferreau
* \version 3.2
* \date 2011-2017
*/
class SymSparseMat : public SymmetricMatrix, public SparseMatrix
{
public:
/** Default constructor. */
SymSparseMat( ) : SparseMatrix( ) { };
/** Constructor with arguments. */
SymSparseMat( int_t nr, /**< Number of rows. */
int_t nc, /**< Number of columns. */
sparse_int_t* r, /**< Row indices (length). */
sparse_int_t* c, /**< Indices to first entry of columns (nCols+1). */
real_t* v /**< Vector of entries (length). */
) : SparseMatrix(nr, nc, r, c, v) { };
/** Constructor from dense matrix. */
SymSparseMat( int_t nr, /**< Number of rows. */
int_t nc, /**< Number of columns. */
int_t ld, /**< Leading dimension. */
const real_t* const v /**< Row major stored matrix elements. */
) : SparseMatrix(nr, nc, ld, v) { };
/** Destructor. */
virtual ~SymSparseMat( ) { };
/** Returns a deep-copy of the Matrix object.
* \return Deep-copy of Matrix object */
virtual Matrix *duplicate( ) const;
/** Returns a deep-copy of the SymmetricMatrix object.
* \return Deep-copy of SymmetricMatrix object */
virtual SymmetricMatrix* duplicateSym( ) const;
/** Compute bilinear form y = x'*H*x using submatrix given by index list.
* \return SUCCESSFUL_RETURN */
virtual returnValue bilinear( const Indexlist* const icols, /**< Index list specifying columns of x. */
int_t xN, /**< Number of vectors to multiply. */
const real_t* x, /**< Input vector to be multiplied (uncompressed). */
int_t xLD, /**< Leading dimension of input x. */
real_t* y, /**< Output vector of results (compressed). */
int_t yLD /**< Leading dimension of output y. */
) const;
};
END_NAMESPACE_QPOASES
#endif /* QPOASES_MATRICES_HPP */

View File

@ -0,0 +1,480 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/MessageHandling.hpp
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches (thanks to Leonard Wirsching)
* \version 3.2
* \date 2007-2017
*
* Declaration of the MessageHandling class including global return values.
*/
#ifndef QPOASES_MESSAGEHANDLING_HPP
#define QPOASES_MESSAGEHANDLING_HPP
#include <stdio.h>
#include <string.h>
#ifdef __DEBUG__
#include <assert.h>
#endif
#include <qpOASES/Constants.hpp>
BEGIN_NAMESPACE_QPOASES
/** Default file to display messages. */
extern FILE* stdFile;
/**
* \brief Defines all symbols for global return values.
*
* The enumeration returnValueType defines all symbols for global return values.
* Important: All return values are assumed to be nonnegative!
*
* \author Hans Joachim Ferreau
*/
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 occurred is not yet known. */
RET_PRINTLEVEL_CHANGED, /**< Print level changed. (10) */
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. (18) */
RET_ADDINDEX_FAILED, /**< Adding index to index set failed. */
RET_REMOVEINDEX_FAILED, /**< Removing index from index set failed. (20) */
RET_SWAPINDEX_FAILED, /**< Cannot swap between different indexsets. */
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. */
RET_SHIFTING_FAILED, /**< Shifting of bounds/constraints failed. */
RET_ROTATING_FAILED, /**< Rotating of bounds/constraints failed. */
/* QProblem */
RET_QPOBJECT_NOT_SETUP, /**< The QP object has not been setup correctly, use another constructor. */
RET_QP_ALREADY_INITIALISED, /**< QProblem has already been initialised. (30) */
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, /**< 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_FAILED_REGULARISATION, /**< Initialisation failed as Hessian matrix could not be regularised. */
RET_INIT_SUCCESSFUL, /**< Initialisation done. (40) */
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_CHOLESKY_WITH_INITIAL_GUESS, /**< Externally computed Cholesky factor cannot be combined with an initial guess. */
RET_NO_EXTERN_SOLVER, /**< No extern QP solver available. */
RET_QP_UNBOUNDED, /**< QP is unbounded. */
RET_QP_INFEASIBLE, /**< QP is infeasible. */
RET_QP_NOT_SOLVED, /**< Problems occurred while solving QP with standard solver. */
RET_QP_SOLVED, /**< QP successfully solved. */
RET_UNABLE_TO_SOLVE_QP, /**< Problems occurred while solving QP. (50) */
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, /**< 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. (60) */
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, /**< 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. (70) */
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, /**< 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. (80) */
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, /**< 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 constraint matrix successfully resolved. (90) */
RET_ENSURELI_FAILED, /**< Failed to ensure linear independence of active constraint matrix. */
RET_ENSURELI_FAILED_TQ, /**< Abnormal termination due to TQ factorisation. */
RET_ENSURELI_FAILED_NOINDEX, /**< QP is infeasible. */
RET_ENSURELI_FAILED_CYCLING, /**< QP is infeasible. */
RET_BOUND_ALREADY_ACTIVE, /**< Bound is already active. */
RET_ALL_BOUNDS_ACTIVE, /**< 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_HESSIAN_INDEFINITE, /**< Hessian matrix is indefinite. (100) */
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. */
RET_DISABLECONSTRAINTS_FAILED, /**< Unable to disbable constraints. */
RET_ENABLECONSTRAINTS_FAILED, /**< Unable to enbable constraints. */
RET_ALREADY_ENABLED, /**< Bound or constraint is already enabled. */
RET_ALREADY_DISABLED, /**< Bound or constraint is already disabled. */
RET_NO_HESSIAN_SPECIFIED, /**< No Hessian matrix has been specified. */
RET_USING_REGULARISATION, /**< Using regularisation as Hessian matrix is not positive definite. (110) */
RET_EPS_MUST_BE_POSITVE, /**< Eps for regularisation must be sufficiently positive. */
RET_REGSTEPS_MUST_BE_POSITVE, /**< Maximum number of regularisation steps must be non-negative. */
RET_HESSIAN_ALREADY_REGULARISED, /**< Hessian has been already regularised. */
RET_CANNOT_REGULARISE_IDENTITY, /**< Identity Hessian matrix cannot be regularised. */
RET_CANNOT_REGULARISE_SPARSE, /**< Sparse matrix cannot be regularised as diagonal entry is missing. */
RET_NO_REGSTEP_NWSR, /**< No additional regularisation step could be performed due to limits. */
RET_FEWER_REGSTEPS_NWSR, /**< Fewer additional regularisation steps have been performed due to limits. */
RET_CHOLESKY_OF_ZERO_HESSIAN, /**< Cholesky decomposition of (unregularised) zero Hessian matrix. */
RET_ZERO_HESSIAN_ASSUMED, /**< Zero Hessian matrix assumed as null pointer passed without specifying hessianType. */
RET_CONSTRAINTS_ARE_NOT_SCALED, /**< (no longer in use) (120) */
RET_INITIAL_BOUNDS_STATUS_NYI, /**< (no longer in use) */
RET_ERROR_IN_CONSTRAINTPRODUCT, /**< Error in user-defined constraint product function. */
RET_FIX_BOUNDS_FOR_LP, /**< All initial bounds must be fixed when solving an (unregularised) LP. */
RET_USE_REGULARISATION_FOR_LP, /**< Set options.enableRegularisation=BT_TRUE for solving LPs. */
/* SQProblem */
RET_UPDATEMATRICES_FAILED, /**< Unable to update QP matrices. */
RET_UPDATEMATRICES_FAILED_AS_QP_NOT_SOLVED, /**< Unable to update matrices as previous QP is not solved. */
/* 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, /**< Unable to read from file. */
RET_FILEDATA_INCONSISTENT, /**< File contains inconsistent data. (130) */
/* Options */
RET_OPTIONS_ADJUSTED, /**< Options needed to be adjusted for consistency reasons. */
/* SolutionAnalysis */
RET_UNABLE_TO_ANALYSE_QPROBLEM, /**< Unable to analyse (S)QProblem(B) object. */
/* Benchmark */
RET_NWSR_SET_TO_ONE, /**< Maximum number of working set changes was set to 1. */
RET_UNABLE_TO_READ_BENCHMARK, /**< Unable to read benchmark data. */
RET_BENCHMARK_ABORTED, /**< Benchmark aborted. */
RET_INITIAL_QP_SOLVED, /**< Initial QP solved. */
RET_QP_SOLUTION_STARTED, /**< Solving QP... */
RET_BENCHMARK_SUCCESSFUL, /**< Benchmark terminated successfully. */
/* Sparse matrices */
RET_NO_DIAGONAL_AVAILABLE, /**< Sparse matrix does not have entries on full diagonal. */
RET_DIAGONAL_NOT_INITIALISED, /**< Diagonal data of sparse matrix has not been initialised. (140) */
/* Dropping of infeasible constraints */
RET_ENSURELI_DROPPED, /**< Linear independence resolved by dropping blocking constraint. */
/* Schur complement computations */
RET_KKT_MATRIX_SINGULAR, /**< KKT matrix is singular. */
RET_QR_FACTORISATION_FAILED, /**< QR factorization of Schur complement failed. */
RET_INERTIA_CORRECTION_FAILED, /**< Inertia correction failed after KKT matrix had too many negative eigenvalues. */
RET_NO_SPARSE_SOLVER, /**< No factorization routine for the KKT matrix installed. */
/* Simple exitflags */
RET_SIMPLE_STATUS_P1, /**< QP problem could not be solved within given number of iterations. */
RET_SIMPLE_STATUS_P0, /**< QP problem solved. */
RET_SIMPLE_STATUS_M1, /**< QP problem could not be solved due to an internal error. */
RET_SIMPLE_STATUS_M2, /**< QP problem is infeasible (and thus could not be solved). */
RET_SIMPLE_STATUS_M3 /**< QP problem is unbounded (and thus could not be solved). (150) */
};
/**
* \brief Handles all kind of error messages, warnings and other information.
*
* This class handles all kinds of messages (errors, warnings, infos) initiated
* by qpOASES modules and stores the corresponding global preferences.
*
* \author Hans Joachim Ferreau (thanks to Leonard Wirsching)
* \version 3.2
* \date 2007-2017
*/
class MessageHandling
{
/*
* INTERNAL DATA STRUCTURES
*/
public:
/**
* \brief Data structure for entries in global message list.
*
* Data structure for entries in global message list.
*
* \author Hans Joachim Ferreau
*/
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( FILE* _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( FILE* _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 defined 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 stdFile.
* 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 stdFile.
* 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 stdFile.
* 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 FILE* getOutputFile( ) const;
/** Returns error count value.
* \return Error count value. */
inline int_t 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( FILE* _outputFile /**< New output file for messages. */
);
/** Changes error count.
* \return SUCCESSFUL_RETURN \n
* RET_INVALID_ARGUMENT */
inline returnValue setErrorCount( int_t _errorCount /**< New error count value. */
);
/** Provides message text corresponding to given \a returnValue.
* \return String containing message text. */
static const char* getErrorCodeMessage( const returnValue _returnValue
);
/*
* PROTECTED MEMBER FUNCTIONS
*/
protected:
/** Prints a info message to stdFile (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 stdFile.
* 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? */
FILE* outputFile; /**< Output file for messages. */
int_t errorCount; /**< Counts number of errors (for nicer output only). */
};
#ifndef __FILE__
/** Ensures that __FILE__ macro is defined. */
#define __FILE__ 0
#endif
#ifndef __LINE__
/** Ensures that __LINE__ macro is defined. */
#define __LINE__ 0
#endif
/** Define __FUNC__ macro providing current function for debugging. */
/*#define __FUNC__ 0*/
#define __FUNC__ ("(no function name provided)")
/*#define __FUNC__ __func__*/
/*#define __FUNC__ __FUNCTION__*/
/** Short version of throwError with default values, only returnValue is needed */
#define THROWERROR(retval) ( getGlobalMessageHandler( )->throwError((retval),0,__FUNC__,__FILE__,__LINE__,VS_VISIBLE) )
/** Short version of throwWarning with default values, only returnValue is needed */
#define THROWWARNING(retval) ( getGlobalMessageHandler( )->throwWarning((retval),0,__FUNC__,__FILE__,__LINE__,VS_VISIBLE) )
/** Short version of throwInfo with default values, only returnValue is needed */
#define THROWINFO(retval) ( getGlobalMessageHandler( )->throwInfo((retval),0,__FUNC__,__FILE__,__LINE__,VS_VISIBLE) )
/** Returns a pointer to global message handler.
* \return Pointer to global message handler.
*/
MessageHandling* getGlobalMessageHandler( );
END_NAMESPACE_QPOASES
#include <qpOASES/MessageHandling.ipp>
#endif /* QPOASES_MESSAGEHANDLING_HPP */
/*
* end of file
*/

View File

@ -0,0 +1,144 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/MessageHandling.ipp
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2007-2017
*
* Implementation of inlined member functions of the MessageHandling class.
*/
BEGIN_NAMESPACE_QPOASES
/*****************************************************************************
* 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 FILE* MessageHandling::getOutputFile( ) const
{
return outputFile;
}
/*
* g e t E r r o r C o u n t
*/
inline int_t 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( FILE* _outputFile )
{
outputFile = _outputFile;
}
/*
* s e t E r r o r C o u n t
*/
inline returnValue MessageHandling::setErrorCount( int_t _errorCount )
{
if ( _errorCount >= -1 )
{
errorCount = _errorCount;
return SUCCESSFUL_RETURN;
}
else
return RET_INVALID_ARGUMENTS;
}
END_NAMESPACE_QPOASES
/*
* end of file
*/

View File

@ -0,0 +1,174 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/Options.hpp
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2007-2017
*
* Declaration of the Options class designed to manage user-specified
* options for solving a QProblem.
*/
#ifndef QPOASES_OPTIONS_HPP
#define QPOASES_OPTIONS_HPP
#include <qpOASES/Utils.hpp>
BEGIN_NAMESPACE_QPOASES
/**
* \brief Manages all user-specified options for solving QPs.
*
* This class manages all user-specified options used for solving
* quadratic programs.
*
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2007-2017
*/
class Options
{
/*
* PUBLIC MEMBER FUNCTIONS
*/
public:
/** Default constructor. */
Options( );
/** Copy constructor (deep copy). */
Options( const Options& rhs /**< Rhs object. */
);
/** Destructor. */
~Options( );
/** Assignment operator (deep copy). */
Options& operator=( const Options& rhs /**< Rhs object. */
);
/** Sets all options to default values.
* \return SUCCESSFUL_RETURN */
returnValue setToDefault( );
/** Sets all options to values resulting in maximum reliabilty.
* \return SUCCESSFUL_RETURN */
returnValue setToReliable( );
/** Sets all options to values resulting in minimum solution time.
* \return SUCCESSFUL_RETURN */
returnValue setToMPC( );
/** Same as setToMPC( ), for ensuring backwards compatibility.
* \return SUCCESSFUL_RETURN */
returnValue setToFast( );
/** Ensures that all options have consistent values by automatically
* adjusting inconsistent ones.
* Note: This routine cannot (and does not try to) ensure that values
* are set to reasonable values that make the QP solution work!
* \return SUCCESSFUL_RETURN \n
* RET_OPTIONS_ADJUSTED */
returnValue ensureConsistency( );
/** Prints values of all options.
* \return SUCCESSFUL_RETURN */
returnValue print( ) const;
/*
* PROTECTED MEMBER FUNCTIONS
*/
protected:
/** Copies all members from given rhs object.
* \return SUCCESSFUL_RETURN */
returnValue copy( const Options& rhs /**< Rhs object. */
);
/*
* PUBLIC MEMBER VARIABLES
*/
public:
PrintLevel printLevel; /**< Print level. */
BooleanType enableRamping; /**< Specifies whether ramping shall be enabled or not. */
BooleanType enableFarBounds; /**< Specifies whether far bounds shall be used or not. */
BooleanType enableFlippingBounds; /**< Specifies whether flipping bounds shall be used or not. */
BooleanType enableRegularisation; /**< Specifies whether Hessian matrix shall be regularised in case semi-definiteness is detected. */
BooleanType enableFullLITests; /**< Specifies whether condition-hardened LI test shall be used or not. */
BooleanType enableNZCTests; /**< Specifies whether nonzero curvature tests shall be used. */
int_t enableDriftCorrection; /**< Specifies the frequency of drift corrections (0 = off). */
int_t enableCholeskyRefactorisation; /**< Specifies the frequency of full refactorisation of proj. Hessian (otherwise updates). */
BooleanType enableEqualities; /**< Specifies whether equalities shall be always treated as active constraints. */
real_t terminationTolerance; /**< Termination tolerance. */
real_t boundTolerance; /**< Lower/upper (constraints') bound tolerance (an inequality constraint whose lower and
upper bounds differ by less is regarded to be an equality constraint). */
real_t boundRelaxation; /**< Offset for relaxing (constraints') bounds at beginning of an initial homotopy. It is also as initial value for far bounds. */
real_t epsNum; /**< Numerator tolerance for ratio tests. */
real_t epsDen; /**< Denominator tolerance for ratio tests. */
real_t maxPrimalJump; /**< Maximum allowed jump in primal variables in nonzero curvature tests. */
real_t maxDualJump; /**< Maximum allowed jump in dual variables in linear independence tests. */
real_t initialRamping; /**< Start value for Ramping Strategy. */
real_t finalRamping; /**< Final value for Ramping Strategy. */
real_t initialFarBounds; /**< Initial size of Far Bounds. */
real_t growFarBounds; /**< Factor to grow Far Bounds. */
SubjectToStatus initialStatusBounds; /**< Initial status of bounds at first iteration. */
real_t epsFlipping; /**< Tolerance of squared Cholesky diagonal factor which triggers flipping bound. */
int_t numRegularisationSteps; /**< Maximum number of successive regularisation steps. */
real_t epsRegularisation; /**< Scaling factor of identity matrix used for Hessian regularisation. */
int_t numRefinementSteps; /**< Maximum number of iterative refinement steps. */
real_t epsIterRef; /**< Early termination tolerance for iterative refinement. */
real_t epsLITests; /**< Tolerance for linear independence tests. */
real_t epsNZCTests; /**< Tolerance for nonzero curvature tests. */
real_t rcondSMin; /**< Minimum reciprocal condition number of S before refactorization is triggered */
BooleanType enableInertiaCorrection; /**< Specifies whether the working set should be repaired when negative curvature is discovered during hotstart. */
BooleanType enableDropInfeasibles; /**< ... */
int_t dropBoundPriority; /**< ... */
int_t dropEqConPriority; /**< ... */
int_t dropIneqConPriority; /**< ... */
};
END_NAMESPACE_QPOASES
#endif /* QPOASES_OPTIONS_HPP */
/*
* end of file
*/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,284 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/QProblem.ipp
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2007-2017
*
* 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.
*/
BEGIN_NAMESPACE_QPOASES
/*****************************************************************************
* P U B L I C *
*****************************************************************************/
/*
* g e t C o n s t r a i n t s
*/
inline returnValue QProblem::getConstraints( Constraints& _constraints ) const
{
int_t nV = getNV( );
if ( nV == 0 )
return THROWERROR( RET_QPOBJECT_NOT_SETUP );
_constraints = constraints;
return SUCCESSFUL_RETURN;
}
/*
* g e t N C
*/
inline int_t QProblem::getNC( ) const
{
return constraints.getNC( );
}
/*
* g e t N E C
*/
inline int_t QProblem::getNEC( ) const
{
return constraints.getNEC( );
}
/*
* g e t N A C
*/
inline int_t QProblem::getNAC( ) const
{
return constraints.getNAC( );
}
/*
* g e t N I A C
*/
inline int_t QProblem::getNIAC( ) const
{
return constraints.getNIAC( );
}
/*****************************************************************************
* P R O T E C T E D *
*****************************************************************************/
/*
* s e t A
*/
inline returnValue QProblem::setA( Matrix *A_new )
{
int_t j;
int_t nV = getNV( );
int_t nC = getNC( );
if ( nV == 0 )
return THROWERROR( RET_QPOBJECT_NOT_SETUP );
if ( A_new == 0 )
return THROWERROR( RET_INVALID_ARGUMENTS );
/* Set constraint matrix AND update member AX. */
if ( ( freeConstraintMatrix == BT_TRUE ) && ( A != 0 ) )
{
delete A;
A = 0;
}
A = A_new;
freeConstraintMatrix = BT_FALSE;
A->times(1, 1.0, x, nV, 0.0, Ax, nC);
A->getRowNorm(tempC);
for( j=0; j<nC; ++j )
{
Ax_u[j] = ubA[j] - Ax[j];
Ax_l[j] = Ax[j] - lbA[j];
// (ckirches) disable constraints with empty rows
if ( isZero( tempC[j] ) == BT_TRUE )
constraints.setType ( j, ST_DISABLED );
}
return SUCCESSFUL_RETURN;
}
/*
* s e t A
*/
inline returnValue QProblem::setA( const real_t* const A_new )
{
int_t j;
int_t nV = getNV( );
int_t nC = getNC( );
DenseMatrix* dA;
if ( nV == 0 )
return THROWERROR( RET_QPOBJECT_NOT_SETUP );
if ( A_new == 0 )
return THROWERROR( RET_INVALID_ARGUMENTS );
/* Set constraint matrix AND update member AX. */
if ( ( freeConstraintMatrix == BT_TRUE ) && ( A != 0 ) )
{
delete A;
A = 0;
}
A = dA = new DenseMatrix(nC, nV, nV, (real_t*) A_new);
freeConstraintMatrix = BT_TRUE;
A->times(1, 1.0, x, nV, 0.0, Ax, nC);
for( j=0; j<nC; ++j )
{
Ax_u[j] = ubA[j] - Ax[j];
Ax_l[j] = Ax[j] - lbA[j];
}
return SUCCESSFUL_RETURN;
}
/*
* s e t L B A
*/
inline returnValue QProblem::setLBA( const real_t* const lbA_new )
{
uint_t i;
uint_t nV = (uint_t)getNV( );
uint_t nC = (uint_t)getNC( );
if ( nV == 0 )
return THROWERROR( RET_QPOBJECT_NOT_SETUP );
if ( lbA_new != 0 )
{
memcpy( lbA,lbA_new,nC*sizeof(real_t) );
}
else
{
/* if no lower constraints' bounds are specified, set them to -infinity */
for( i=0; i<nC; ++i )
lbA[i] = -INFTY;
}
return SUCCESSFUL_RETURN;
}
/*
* s e t L B A
*/
inline returnValue QProblem::setLBA( int_t number, real_t value )
{
int_t nV = getNV( );
int_t nC = getNC( );
if ( nV == 0 )
return THROWERROR( RET_QPOBJECT_NOT_SETUP );
if ( ( number >= 0 ) && ( number < nC ) )
{
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 )
{
uint_t i;
uint_t nV = (uint_t)getNV( );
uint_t nC = (uint_t)getNC( );
if ( nV == 0 )
return THROWERROR( RET_QPOBJECT_NOT_SETUP );
if ( ubA_new != 0 )
{
memcpy( ubA,ubA_new,nC*sizeof(real_t) );
}
else
{
/* if no upper constraints' bounds are specified, set them to infinity */
for( i=0; i<nC; ++i )
ubA[i] = INFTY;
}
return SUCCESSFUL_RETURN;
}
/*
* s e t U B A
*/
inline returnValue QProblem::setUBA( int_t number, real_t value )
{
int_t nV = getNV( );
int_t nC = getNC( );
if ( nV == 0 )
return THROWERROR( RET_QPOBJECT_NOT_SETUP );
if ( ( number >= 0 ) && ( number < nC ) )
{
ubA[number] = value;
return SUCCESSFUL_RETURN;
}
else
return THROWERROR( RET_INDEX_OUT_OF_BOUNDS );
}
END_NAMESPACE_QPOASES
/*
* end of file
*/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,496 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/QProblemB.ipp
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2007-2017
*
* 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.
*/
BEGIN_NAMESPACE_QPOASES
/*****************************************************************************
* P U B L I C *
*****************************************************************************/
/*
* g e t B o u n d s
*/
inline returnValue QProblemB::getBounds( Bounds& _bounds ) const
{
int_t nV = getNV( );
if ( nV == 0 )
return THROWERROR( RET_QPOBJECT_NOT_SETUP );
_bounds = bounds;
return SUCCESSFUL_RETURN;
}
/*
* g e t N V
*/
inline int_t QProblemB::getNV( ) const
{
return bounds.getNV( );
}
/*
* g e t N F R
*/
inline int_t QProblemB::getNFR( ) const
{
return bounds.getNFR( );
}
/*
* g e t N F X
*/
inline int_t QProblemB::getNFX( ) const
{
return bounds.getNFX( );
}
/*
* g e t N F V
*/
inline int_t 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 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;
}
/*
* u s i n g R e g u l a r i s a t i o n
*/
inline BooleanType QProblemB::usingRegularisation( ) const
{
if ( regVal > ZERO )
return BT_TRUE;
else
return BT_FALSE;
}
/*
* g e t O p t i o n s
*/
inline Options QProblemB::getOptions( ) const
{
return options;
}
/*
* s e t O p t i o n s
*/
inline returnValue QProblemB::setOptions( const Options& _options
)
{
options = _options;
options.ensureConsistency( );
setPrintLevel( options.printLevel );
return SUCCESSFUL_RETURN;
}
/*
* g e t P r i n t L e v e l
*/
inline PrintLevel QProblemB::getPrintLevel( ) const
{
return options.printLevel;
}
/*
* g e t C o u n t
*/
inline uint_t QProblemB::getCount( ) const
{
return count;
}
/*
* r e s e t C o u n t e r
*/
inline returnValue QProblemB::resetCounter( )
{
count = 0;
return SUCCESSFUL_RETURN;
}
/*****************************************************************************
* P R O T E C T E D *
*****************************************************************************/
/*
* s e t H
*/
inline returnValue QProblemB::setH( SymmetricMatrix* H_new )
{
if ( ( freeHessian == BT_TRUE ) && ( H != 0 ) )
{
delete H;
H = 0;
}
H = H_new;
freeHessian = BT_FALSE;
return SUCCESSFUL_RETURN;
}
/*
* s e t H
*/
inline returnValue QProblemB::setH( const real_t* const H_new )
{
int_t nV = getNV();
SymDenseMat* dH;
/* if null pointer is passed, Hessian is set to zero matrix
* (or stays identity matrix) */
if ( H_new == 0 )
{
if ( hessianType == HST_IDENTITY )
return SUCCESSFUL_RETURN;
hessianType = HST_ZERO;
if ( ( freeHessian == BT_TRUE ) && ( H != 0 ) )
delete H;
H = 0;
freeHessian = BT_FALSE;
}
else
{
if ( ( freeHessian == BT_TRUE ) && ( H != 0 ) )
delete H;
H = dH = new SymDenseMat( nV, nV, nV, (real_t*) H_new );
freeHessian = BT_TRUE;
}
return SUCCESSFUL_RETURN;
}
/*
* s e t G
*/
inline returnValue QProblemB::setG( const real_t* const g_new )
{
uint_t nV = (uint_t)getNV( );
if ( nV == 0 )
return THROWERROR( RET_QPOBJECT_NOT_SETUP );
if ( g_new == 0 )
return THROWERROR( RET_INVALID_ARGUMENTS );
memcpy( g,g_new,nV*sizeof(real_t) );
return SUCCESSFUL_RETURN;
}
/*
* s e t L B
*/
inline returnValue QProblemB::setLB( const real_t* const lb_new )
{
uint_t i;
uint_t nV = (uint_t)getNV( );
if ( nV == 0 )
return THROWERROR( RET_QPOBJECT_NOT_SETUP );
if ( lb_new != 0 )
{
memcpy( lb,lb_new,nV*sizeof(real_t) );
}
else
{
/* if no lower bounds are specified, set them to -infinity */
for( i=0; i<nV; ++i )
lb[i] = -INFTY;
}
return SUCCESSFUL_RETURN;
}
/*
* s e t L B
*/
inline returnValue QProblemB::setLB( int_t number, real_t value )
{
int_t nV = getNV( );
if ( nV == 0 )
return THROWERROR( RET_QPOBJECT_NOT_SETUP );
if ( ( number >= 0 ) && ( number < nV ) )
{
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 )
{
uint_t i;
uint_t nV = (uint_t)getNV( );
if ( nV == 0 )
return THROWERROR( RET_QPOBJECT_NOT_SETUP );
if ( ub_new != 0 )
{
memcpy( ub,ub_new,nV*sizeof(real_t) );
}
else
{
/* if no upper bounds are specified, set them to infinity */
for( i=0; i<nV; ++i )
ub[i] = INFTY;
}
return SUCCESSFUL_RETURN;
}
/*
* s e t U B
*/
inline returnValue QProblemB::setUB( int_t number, real_t value )
{
int_t nV = getNV( );
if ( nV == 0 )
return THROWERROR( RET_QPOBJECT_NOT_SETUP );
if ( ( number >= 0 ) && ( number < nV ) )
{
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
{
real_t t, mu;
if ( isZero( yold ) == BT_TRUE )
{
c = 1.0;
s = 0.0;
xnew = xold;
ynew = yold;
}
else
{
mu = getAbs( xold );
if ( getAbs( yold ) > mu )
mu = getAbs( yold );
t = mu * getSqrt( (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 nu, real_t xold, real_t yold,
real_t& xnew, real_t& ynew
) const
{
#ifdef __USE_THREE_MULTS_GIVENS__
/* Givens plane rotation requiring only three multiplications,
* cf. Hammarling, S.: A note on modifications to the givens plane rotation.
* J. Inst. Maths Applics, 13:215-218, 1974. */
xnew = xold*c + yold*s;
ynew = (xnew+xold)*nu - yold;
#else
/* Usual Givens plane rotation requiring four multiplications. */
xnew = c*xold + s*yold;
ynew = -s*xold + c*yold;
#endif
return;
}
/*
* i s B l o c k i n g
*/
inline BooleanType QProblemB::isBlocking( real_t num,
real_t den,
real_t epsNum,
real_t epsDen,
real_t& t
) const
{
if ( ( den >= epsDen ) && ( num >= epsNum ) )
{
if ( num < t*den )
return BT_TRUE;
}
return BT_FALSE;
}
END_NAMESPACE_QPOASES
/*
* end of file
*/

View File

@ -0,0 +1,359 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/SQProblem.hpp
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2007-2017
*
* Declaration of the SQProblem class which is able to use the newly
* developed online active set strategy for parametric quadratic programming
* with varying matrices.
*/
#ifndef QPOASES_SQPROBLEM_HPP
#define QPOASES_SQPROBLEM_HPP
#include <qpOASES/QProblem.hpp>
BEGIN_NAMESPACE_QPOASES
/**
* \brief Implements the online active set strategy for QPs with varying matrices.
*
* A class for setting up and solving quadratic programs with varying QP matrices.
* The main feature is the possibily to use the newly developed online active set strategy
* for parametric quadratic programming.
*
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2007-2017
*/
class SQProblem : public QProblem
{
/* allow SolutionAnalysis class to access private members */
friend class SolutionAnalysis;
/*
* PUBLIC MEMBER FUNCTIONS
*/
public:
/** Default constructor. */
SQProblem( );
/** Constructor which takes the QP dimension and Hessian type
* information. If the Hessian is the zero (i.e. HST_ZERO) or the
* identity matrix (i.e. HST_IDENTITY), respectively, no memory
* is allocated for it and a NULL pointer can be passed for it
* to the init() functions. */
SQProblem( int_t _nV, /**< Number of variables. */
int_t _nC, /**< Number of constraints. */
HessianType _hessianType = HST_UNKNOWN, /**< Type of Hessian matrix. */
BooleanType allocDenseMats = BT_TRUE /**< Enable allocation of dense matrices. */
);
/** Copy constructor (deep copy). */
SQProblem( const SQProblem& rhs /**< Rhs object. */
);
/** Destructor. */
virtual ~SQProblem( );
/** Assignment operator (deep copy). */
virtual SQProblem& operator=( const SQProblem& rhs /**< Rhs object. */
);
/** Solves an initialised QP sequence with matrix shift using
* the 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_MATRIX_SHIFT_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_SETUP_AUXILIARYQP_FAILED */
returnValue hotstart( SymmetricMatrix *H_new, /**< Hessian matrix of neighbouring QP to be solved (a shallow copy is made). \n
If Hessian matrix is trivial, a NULL pointer can be passed. */
const real_t* const g_new, /**< Gradient of neighbouring QP to be solved. */
Matrix *A_new, /**< Constraint matrix of neighbouring QP to be solved (a shallow copy is made). \n
If QP sequence does not involve constraints, a NULL pointer can be passed. */
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_t& nWSR, /**< Input: Maximum number of working set recalculations; \n
Output: Number of performed working set recalculations. */
real_t* const cputime = 0, /**< Input: Maximum CPU time allowed for QP solution. \n
Output: CPU time spen for QP solution (or to perform nWSR iterations). */
const Bounds* const guessedBounds = 0, /**< Optimal working set of bounds for solution (xOpt,yOpt). \n
(If a null pointer is passed, the previous working set of bounds is kept!) */
const Constraints* const guessedConstraints = 0 /**< Optimal working set of constraints for solution (xOpt,yOpt). \n
(If a null pointer is passed, the previous working set of constraints is kept!) */
);
/** Solves an initialised QP sequence with matrix shift using
* the 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_MATRIX_SHIFT_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_SETUP_AUXILIARYQP_FAILED */
returnValue hotstart( const real_t* const H_new, /**< Hessian matrix of neighbouring QP to be solved (a shallow copy is made). \n
If Hessian matrix is trivial, a NULL pointer can be passed. */
const real_t* const g_new, /**< Gradient of neighbouring QP to be solved. */
const real_t* const A_new, /**< Constraint matrix of neighbouring QP to be solved (a shallow copy is made). \n
If QP sequence does not involve constraints, a NULL pointer can be passed. */
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_t& nWSR, /**< Input: Maximum number of working set recalculations; \n
Output: Number of performed working set recalculations. */
real_t* const cputime = 0, /**< Input: Maximum CPU time allowed for QP solution. \n
Output: CPU time spent for QP solution (or to perform nWSR iterations). */
const Bounds* const guessedBounds = 0, /**< Optimal working set of bounds for solution (xOpt,yOpt). \n
(If a null pointer is passed, the previous working set of bounds is kept!) */
const Constraints* const guessedConstraints = 0 /**< Optimal working set of constraints for solution (xOpt,yOpt). \n
(If a null pointer is passed, the previous working set of constraints is kept!) */
);
/** Solves an initialised QP sequence with matrix shift using
* the online active set strategy, where QP data is read from files.
* \return SUCCESSFUL_RETURN \n
RET_MAX_NWSR_REACHED \n
RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n
RET_HOTSTART_FAILED \n
RET_MATRIX_SHIFT_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_SETUP_AUXILIARYQP_FAILED \n
RET_UNABLE_TO_READ_FILE \n
RET_INVALID_ARGUMENTS */
returnValue hotstart( const char* const H_file, /**< Name of file where Hessian matrix is stored. \n
If Hessian matrix is trivial, a NULL pointer can be passed. */
const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */
const char* const A_file, /**< Name of file where constraint matrix is stored. \n
If QP sequence does not involve constraints, a NULL pointer can be passed. */
const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n
If no lower bounds exist, a NULL pointer can be passed. */
const char* const ub_file, /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n
If no upper bounds exist, a NULL pointer can be passed. */
const char* const lbA_file, /**< Name of file where lower constraints' bounds, of neighbouring QP to be solved, is stored. \n
If no lower constraints' bounds exist, a NULL pointer can be passed. */
const char* const ubA_file, /**< Name of file where upper constraints' bounds, of neighbouring QP to be solved, is stored. \n
If no upper constraints' bounds exist, a NULL pointer can be passed. */
int_t& nWSR, /**< Input: Maximum number of working set recalculations; \n
Output: Number of performed working set recalculations. */
real_t* const cputime = 0, /**< Input: Maximum CPU time allowed for QP solution. \n
Output: CPU time spent for QP solution (or to perform nWSR iterations). */
const Bounds* const guessedBounds = 0, /**< Optimal working set of bounds for solution (xOpt,yOpt). \n
(If a null pointer is passed, the previous working set of bounds is kept!) */
const Constraints* const guessedConstraints = 0 /**< Optimal working set of constraints for solution (xOpt,yOpt). \n
(If a null pointer is passed, the previous working set of constraints is kept!) */
);
/** Solves an initialised QP sequence (without matrix shift) using
* the online active set strategy.
* By default, QP solution is started from previous solution. If a guess
* for the working set is provided, an initialised homotopy is performed.
*
* Note: This functions just forwards to the corresponding
* QProblem::hotstart member function.
*
* \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 */
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_t& nWSR, /**< Input: Maximum number of working set recalculations; \n
Output: Number of performed working set recalculations. */
real_t* const cputime = 0, /**< Input: Maximum CPU time allowed for QP solution. \n
Output: CPU time spent for QP solution (or to perform nWSR iterations). */
const Bounds* const guessedBounds = 0, /**< Optimal working set of bounds for solution (xOpt,yOpt). \n
(If a null pointer is passed, the previous working set of bounds is kept!) */
const Constraints* const guessedConstraints = 0 /**< Optimal working set of constraints for solution (xOpt,yOpt). \n
(If a null pointer is passed, the previous working set of constraints is kept!) */
);
/** Solves an initialised QP sequence (without matrix shift) using
* the online active set strategy, where QP data is read from files.
* By default, QP solution is started from previous solution. If a guess
* for the working set is provided, an initialised homotopy is performed.
*
* Note: This functions just forwards to the corresponding
* QProblem::hotstart member function.
*
* \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_UNABLE_TO_READ_FILE \n
RET_INVALID_ARGUMENTS */
returnValue hotstart( const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */
const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n
If no lower bounds exist, a NULL pointer can be passed. */
const char* const ub_file, /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n
If no upper bounds exist, a NULL pointer can be passed. */
const char* const lbA_file, /**< Name of file where lower constraints' bounds, of neighbouring QP to be solved, is stored. \n
If no lower constraints' bounds exist, a NULL pointer can be passed. */
const char* const ubA_file, /**< Name of file where upper constraints' bounds, of neighbouring QP to be solved, is stored. \n
If no upper constraints' bounds exist, a NULL pointer can be passed. */
int_t& nWSR, /**< Input: Maximum number of working set recalculations; \n
Output: Number of performed working set recalculations. */
real_t* const cputime = 0, /**< Input: Maximum CPU time allowed for QP solution. \n
Output: CPU time spent for QP solution (or to perform nWSR iterations). */
const Bounds* const guessedBounds = 0, /**< Optimal working set of bounds for solution (xOpt,yOpt). \n
(If a null pointer is passed, the previous working set of bounds is kept!) */
const Constraints* const guessedConstraints = 0 /**< Optimal working set of constraints for solution (xOpt,yOpt). \n
(If a null pointer is passed, the previous working set of constraints is kept!) */
);
#ifdef __MATLAB__
/** Sets pointer of Hessian and constraint matrix to zero.
* QUICK HACK FOR MAKING THE MATLAB INTERFACE RUN! TO BE REMOVED!
* \return SUCCESSFUL_RETURN */
returnValue resetMatrixPointers( );
#endif
/*
* PROTECTED MEMBER FUNCTIONS
*/
protected:
/** Sets new matrices and calculates their factorisations. If the
* current Hessian is trivial (i.e. HST_ZERO or HST_IDENTITY) but a
* non-trivial one is given, memory for Hessian is allocated and
* it is set to the given one. Afterwards, all QP vectors are
* transformed in order to start from an optimal solution.
* \return SUCCESSFUL_RETURN \n
* RET_MATRIX_FACTORISATION_FAILED \n
* RET_NO_HESSIAN_SPECIFIED */
virtual returnValue setupNewAuxiliaryQP( SymmetricMatrix *H_new, /**< New Hessian matrix. \n
If Hessian matrix is trivial, a NULL pointer can be passed. */
Matrix *A_new, /**< New constraint matrix. \n
If QP sequence does not involve constraints, a NULL pointer can be passed. */
const real_t *lb_new, /**< New lower bounds. \n
If no lower bounds exist, a NULL pointer can be passed. */
const real_t *ub_new, /**< New upper bounds. \n
If no lower bounds exist, a NULL pointer can be passed. */
const real_t *lbA_new, /**< New lower constraints' bounds. \n
If no lower constraints' bounds exist, a NULL pointer can be passed. */
const real_t *ubA_new /**< New lower constraints' bounds. \n
If no lower constraints' bounds exist, a NULL pointer can be passed. */
);
/** Sets new matrices and calculates their factorisations. If the
* current Hessian is trivial (i.e. HST_ZERO or HST_IDENTITY) but a
* non-trivial one is given, memory for Hessian is allocated and
* it is set to the given one. Afterwards, all QP vectors are
* transformed in order to start from an optimal solution.
* \return SUCCESSFUL_RETURN \n
* RET_MATRIX_FACTORISATION_FAILED \n
* RET_NO_HESSIAN_SPECIFIED */
virtual returnValue setupNewAuxiliaryQP( const real_t* const H_new, /**< New Hessian matrix. \n
If Hessian matrix is trivial, a NULL pointer can be passed. */
const real_t* const A_new, /**< New constraint matrix. \n
If QP sequence does not involve constraints, a NULL pointer can be passed. */
const real_t *lb_new, /**< New lower bounds. \n
If no lower bounds exist, a NULL pointer can be passed. */
const real_t *ub_new, /**< New upper bounds. \n
If no lower bounds exist, a NULL pointer can be passed. */
const real_t *lbA_new, /**< New lower constraints' bounds. \n
If no lower constraints' bounds exist, a NULL pointer can be passed. */
const real_t *ubA_new /**< New lower constraints' bounds. \n
If no lower constraints' bounds exist, a NULL pointer can be passed. */
);
/*
* PROTECTED MEMBER VARIABLES
*/
protected:
};
END_NAMESPACE_QPOASES
#include <qpOASES/SQProblem.ipp>
#endif /* QPOASES_SQPROBLEM_HPP */
/*
* end of file
*/

View File

@ -0,0 +1,51 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/SQProblem.ipp
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2007-2017
*
* Implementation of inlined member functions of the SQProblem class which
* is able to use the newly developed online active set strategy for
* parametric quadratic programming with varying matrices.
*/
/*****************************************************************************
* P U B L I C *
*****************************************************************************/
BEGIN_NAMESPACE_QPOASES
END_NAMESPACE_QPOASES
/*
* end of file
*/

View File

@ -0,0 +1,425 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2014 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/SQProblemSchur.hpp
* \author Andreas Waechter and Dennis Janka, based on QProblem.hpp by Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2012-2017
*
* Declaration of the SQProblemSchur class which is able to use the newly
* developed online active set strategy for parametric quadratic programming
* with varying matrices and uses a Schur Complement approach to solve
* the linear systems.
*/
#ifndef QPOASES_SQPROBLEMSCHUR_HPP
#define QPOASES_SQPROBLEMSCHUR_HPP
#include <qpOASES/SQProblem.hpp>
#include <qpOASES/SparseSolver.hpp>
BEGIN_NAMESPACE_QPOASES
/**
* \brief Implements the online active set strategy for QPs with varying, sparse matrices.
*
* A class for setting up and solving quadratic programs with varying,
* sparse QP matrices. Here, sparsity is exploited by means of a
* Schur complement approach to solve the linear systems.
*
* \author Andreas Waechter, Dennis Janka
* \version 3.2
* \date 2012-2017
*/
class SQProblemSchur : public SQProblem
{
/* allow SolutionAnalysis class to access private members */
friend class SolutionAnalysis;
/*
* PUBLIC MEMBER FUNCTIONS
*/
public:
/** Default constructor. */
SQProblemSchur( );
/** Constructor which takes the QP dimension and Hessian type
* information. If the Hessian is the zero (i.e. HST_ZERO) or the
* identity matrix (i.e. HST_IDENTITY), respectively, no memory
* is allocated for it and a NULL pointer can be passed for it
* to the init() functions. */
SQProblemSchur( int_t _nV, /**< Number of variables. */
int_t _nC, /**< Number of constraints. */
HessianType _hessianType = HST_UNKNOWN, /**< Type of Hessian matrix. */
int_t maxSchurUpdates = 75 /**< Maximal number of Schur updates */
);
/** Copy constructor (deep copy). */
SQProblemSchur( const SQProblemSchur& rhs /**< Rhs object. */
);
/** Destructor. */
virtual ~SQProblemSchur( );
/** Assignment operator (deep copy). */
virtual SQProblemSchur& operator=( const SQProblemSchur& rhs /**< Rhs object. */
);
/** Clears all data structures of QProblem except for QP data.
* \return SUCCESSFUL_RETURN \n
RET_RESET_FAILED */
virtual returnValue reset( );
/** Resets Schur complement. This sets up the KKT matrix for the
current activities, copies the activities, etc. TODO: Return values */
returnValue resetSchurComplement( BooleanType allowInertiaCorrection );
/** Return the total number of sparse matrix factorizations performed so far. */
inline int_t getNumFactorizations( ) const;
/*
* PROTECTED MEMBER FUNCTIONS
*/
protected:
/** Frees all allocated memory.
* \return SUCCESSFUL_RETURN */
returnValue clear( );
/** Copies all members from given rhs object.
* \return SUCCESSFUL_RETURN */
returnValue copy( const SQProblemSchur& rhs /**< Rhs object. */
);
/** Computes the Cholesky decomposition of the projected Hessian (i.e. R^T*R = Z^T*H*Z).
* For the Schur complement version, this function only returns SUCCESSFUL_RETURN. */
virtual returnValue computeProjectedCholesky( );
/** Computes initial Cholesky decomposition of the projected Hessian making
* use of the function setupCholeskyDecomposition() or setupCholeskyDecompositionProjected().
* For the Schur complement version, this function only returns SUCCESSFUL_RETURN. */
virtual returnValue computeInitialCholesky( );
/** Initialises TQ factorisation of A (i.e. A*Q = [0 T]) if NO constraint is active.
* For the Schur complement version, this function only returns SUCCESSFUL_RETURN. */
virtual returnValue setupTQfactorisation( );
/** This method is overloaded from SQProblem.
* Sets new matrices and calculates their factorisations. If the
* current Hessian is trivial (i.e. HST_ZERO or HST_IDENTITY) but a
* non-trivial one is given, memory for Hessian is allocated and
* it is set to the given one. Afterwards, all QP vectors are
* transformed in order to start from an optimal solution.
* \return SUCCESSFUL_RETURN \n
* RET_MATRIX_FACTORISATION_FAILED \n
* RET_NO_HESSIAN_SPECIFIED */
virtual returnValue setupAuxiliaryQP( SymmetricMatrix *H_new, /**< New Hessian matrix. \n
If Hessian matrix is trivial, a NULL pointer can be passed. */
Matrix *A_new, /**< New constraint matrix. \n
If QP sequence does not involve constraints, a NULL pointer can be passed. */
const real_t *lb_new,
const real_t *ub_new,
const real_t *lbA_new,
const real_t *ubA_new
);
/** Setup bounds and constraints data structures according to auxiliaryBounds/Constraints.
* Calls the sparse solver to obtain the factorization for the initial active set.
* \return SUCCESSFUL_RETURN \n
RET_SETUP_WORKINGSET_FAILED \n
RET_INVALID_ARGUMENTS \n
RET_UNKNOWN_BUG */
virtual returnValue setupAuxiliaryWorkingSet( const Bounds* const auxiliaryBounds,
const Constraints* const auxiliaryConstraints,
BooleanType setupAfresh
);
/** Adds a constraint to active set.
* \return SUCCESSFUL_RETURN \n
RET_ADDCONSTRAINT_FAILED \n
RET_ADDCONSTRAINT_FAILED_INFEASIBILITY \n
RET_ENSURELI_FAILED */
virtual returnValue addConstraint( int_t 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. */
BooleanType ensureLI = BT_TRUE /**< Ensure linear independence by exchange rules by default. */
);
/** 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 */
virtual returnValue addConstraint_checkLI( int_t 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 */
virtual returnValue addConstraint_ensureLI( int_t 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 */
virtual returnValue addBound( int_t 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. */
BooleanType ensureLI = BT_TRUE /**< Ensure linear independence by exchange rules by default. */
);
/** 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 */
virtual returnValue addBound_checkLI( int_t 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 */
virtual returnValue addBound_ensureLI( int_t 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 */
virtual returnValue removeConstraint( int_t number, /**< Number of constraint to be removed from active set. */
BooleanType updateCholesky, /**< Flag indicating if Cholesky decomposition shall be updated. */
BooleanType allowFlipping = BT_FALSE, /**< Flag indicating if flipping bounds are allowed. */
BooleanType ensureNZC = BT_FALSE /**< Flag indicating if non-zero curvature is ensured by exchange rules. */
);
/** Removes a bounds from active set.
* \return SUCCESSFUL_RETURN \n
RET_BOUND_NOT_ACTIVE \n
RET_HESSIAN_NOT_SPD \n
RET_REMOVEBOUND_FAILED */
virtual returnValue removeBound( int_t number, /**< Number of bound to be removed from active set. */
BooleanType updateCholesky, /**< Flag indicating if Cholesky decomposition shall be updated. */
BooleanType allowFlipping = BT_FALSE, /**< Flag indicating if flipping bounds are allowed. */
BooleanType ensureNZC = BT_FALSE /**< Flag indicating if non-zero curvature is ensured by exchange rules. */
);
/** Solves the system Ta = b or T^Ta = b where T is a reverse upper triangular matrix.
* This must not be called for the Schur complement version. */
virtual 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 */
) const;
/** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix.
* This must not be called for the Schur complement version. */
virtual 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 */
) const;
/** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix. \n
* This must not be called for the Schur complement version. */
virtual 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 */
) const;
/** Determines step direction of the homotopy path.
* \return SUCCESSFUL_RETURN \n
RET_STEPDIRECTION_FAILED_TQ \n
RET_STEPDIRECTION_FAILED_CHOLESKY */
virtual returnValue determineStepDirection( 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. */
);
virtual returnValue determineStepDirection2( 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. */
);
/*
* PRIVATE MEMBER FUNCTION
*/
private:
/** Checks if new active bound to be added is linearly dependent from
* from row of the active constraints matrix. This version computes
* the multipliers in the (full) test.
* \return RET_LINEARLY_DEPENDENT \n
RET_LINEARLY_INDEPENDENT */
returnValue addBound_checkLISchur( int_t number, /**< Number of bound to be added to active set. */
real_t* const xiC, /**< Output: Multipliers in linear independence test for active constraints. */
real_t* const xiX /**< Output: Multipliers in linear independence test for fixed variables. */
);
/** Checks if new active bound to be added is linearly dependent from
* from row of the active constraints matrix. This version computes
* the multipliers in the (full) test.
* \return RET_LINEARLY_DEPENDENT \n
RET_LINEARLY_INDEPENDENT */
returnValue addConstraint_checkLISchur( int_t number, /**< Number of bound to be added to active set. */
real_t* const xiC, /**< Output: Multipliers in linear independence test for active constraints. */
real_t* const xiX /**< Output: Multipliers in linear independence test for fixed variables. */
);
/** Compute product of "M" matrix (additional columns in KKT
matrix) with vector. y = alpha * M * x + beta * y */
returnValue computeMTimes( real_t alpha, const real_t* const x, real_t beta, real_t* const y );
/** Compute product of transpose of "M" matrix (additional columns in KKT
matrix) with vector. y = alpha * M^T * x + beta * y */
returnValue computeMTransTimes( real_t alpha, const real_t* const x, real_t beta, real_t* const y );
/** Add a row/column to the Schur complement. */
returnValue addToSchurComplement( int_t number, SchurUpdateType update, int_t numNonzerosM, const sparse_int_t* M_pos, const real_t* const M_vals, int_t numNonzerosN, const sparse_int_t* Npos, const real_t* const Nvals, real_t N_diag );
/** Remove a row/column from the Schur complement. */
returnValue deleteFromSchurComplement( int_t idx, BooleanType allowUndo = BT_FALSE );
/** Undo the last deletion from the Schur complement by moving the nS+1th row/column to position idx. */
returnValue undoDeleteFromSchurComplement( int_t idx );
/** Compute determinant of new nS*nS Schur complement from old factorization */
real_t calcDetSchur( int_t idxDel );
/** Update QR factorization and determinant of Schur complement after a row and column have been added or removed */
returnValue updateSchurQR( int_t idxDel );
/** Compute the solution to QRx = rhs and store it in sol */
returnValue backsolveSchurQR( int_t dimS, const real_t* const rhs, int_t dimRhs, real_t* const sol );
/** If negative curvature is discovered in the reduced Hessian, add bounds until all eigenvalues are positive */
returnValue correctInertia();
/** If the KKT matrix is declared singular during refactorization, remove linearly dependent constraints or add bounds */
returnValue repairSingularWorkingSet( );
returnValue stepCalcRhs( int_t nFR, int_t nFX, int_t nAC, int_t* FR_idx, int_t* FX_idx, int_t* AC_idx, real_t& rhs_max, 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
);
returnValue stepCalcReorder(int_t nFR, int_t nAC, int_t* FR_idx, int_t* AC_idx, int_t nFRStart, int_t nACStart,
int_t* FR_idxStart, int_t* AC_idxStart, int_t* FR_iSort, int_t* FR_iSortStart,
int_t* AC_iSort, int_t* AC_iSortStart, real_t* rhs
);
returnValue stepCalcBacksolveSchur( int_t nFR, int_t nFX, int_t nAC, int_t* FR_idx, int_t* FX_idx, int_t* AC_idx,
int_t dim, real_t* rhs, real_t* sol
);
returnValue stepCalcReorder2( int_t nFR, int_t nAC, int_t* FR_idx, int_t* AC_idx, int_t nFRStart, int_t nACStart,
int_t* FR_idxStart, int_t* AC_idxStart, int_t* FR_iSort, int_t* FR_iSortStart,
int_t* AC_iSort, int_t* AC_iSortStart, real_t* sol, real_t* const delta_xFR, real_t* const delta_yAC
);
returnValue stepCalcResid( int_t nFR, int_t nFX, int_t nAC, int_t* FR_idx, int_t* FX_idx, int_t* AC_idx,
BooleanType Delta_bC_isZero, real_t* const delta_xFX, real_t* const delta_xFR,
real_t* const delta_yAC, const real_t* const delta_g,
const real_t* const delta_lbA, const real_t* const delta_ubA, real_t& rnrm
);
returnValue stepCalcDeltayFx( int_t nFR, int_t nFX, int_t nAC, int_t* FX_idx, const real_t* const delta_g,
real_t* const delta_xFX, real_t* const delta_xFR, real_t* const delta_yAC, real_t* const delta_yFX
);
/*
* PROTECTED MEMBER VARIABLES
*/
protected:
SparseSolver* sparseSolver; /**< Interface to the sparse linear solver. */
real_t* S; /**< Schur complement matrix. (This is actually the negative of the Schur complement!) */
int_t nS; /**< Current size of Schur complement matrix. -1 means that the Schur complement has not yet been initialized. */
int_t nSmax; /**< Maximum size of Schur complement matrix. */
real_t* Q_; /**< QR factorization of S: orthogonal matrix Q */
real_t* R_; /**< QR factorization of S: upper triangular matrix R */
real_t detS; /**< Determinant of Schur complement */
real_t rcondS; /**< Reciprocal of condition number of S (estimate) */
int_t numFactorizations; /**< Total number of factorizations performed */
int_t* schurUpdateIndex; /**< Indices of variables or constraints for each update in Schur complement. */
SchurUpdateType* schurUpdate; /**< Type of update for each update in Schur complement. */
int_t M_physicallength; /**< Allocated size of the M_vals and M_ir arrays. */
real_t* M_vals; /**< Values of the sparse M matrix containing the vectors with the additional rows defining the Schur complement (length). */
sparse_int_t* M_ir; /**< Row indices (length). */
sparse_int_t* M_jc; /**< Indices in M to first entry of columns (nS+1). */
Indexlist boundsFreeStart; /**< Index list for free bounds when major iteration started. */
Indexlist constraintsActiveStart; /**< Index list for active constraints when major iteration started. */
};
END_NAMESPACE_QPOASES
#include <qpOASES/SQProblemSchur.ipp>
#endif /* QPOASES_QPROBLEMSCHUR_HPP */
/*
* end of file
*/

View File

@ -0,0 +1,57 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2013 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/SQProblemSchur.ipp
* \author Andreas Waechter, Dennis Janka
* \version 3.2
* \date 2012-2017
*
* Implementation of inlined member functions of the SQProblemSchur class which
* is able to use the newly developed online active set strategy for
* parametric quadratic programming.
*/
BEGIN_NAMESPACE_QPOASES
/*****************************************************************************
* P U B L I C *
*****************************************************************************/
/*
* g e t N u m F a c t o r i z a t i o n s
*/
inline int_t SQProblemSchur::getNumFactorizations( ) const
{
return numFactorizations;
}
END_NAMESPACE_QPOASES
/*
* end of file
*/

View File

@ -0,0 +1,573 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/SparseSolver.hpp
* \author Andreas Waechter, Dennis Janka
* \version 3.2
* \date 2012-2017
*
* Interfaces to sparse linear solvers that are used in a Schur-complement
* implementation in qpOASES.
*/
#ifndef QPOASES_SPARSESOLVER_HPP
#define QPOASES_SPARSESOLVER_HPP
#include <limits>
#include <sstream>
#include <qpOASES/Utils.hpp>
BEGIN_NAMESPACE_QPOASES
/**
* \brief Base class for linear solvers that are used in a Schur-complement
* implementation in qpOASES.
*
* \author Andreas Waechter, Dennis Janka
* \version 3.2
* \date 2012-2017
*/
class SparseSolver
{
/*
* PUBLIC MEMBER FUNCTIONS
*/
public:
/** Default constructor. */
SparseSolver( );
/** Copy constructor (deep copy). */
SparseSolver( const SparseSolver& rhs /**< Rhs object. */
);
/** Destructor. */
virtual ~SparseSolver( );
/** Assignment operator (deep copy). */
virtual SparseSolver& operator=( const SparseSolver& rhs /**< Rhs object. */
);
/** Set new matrix data. The matrix is to be provided
in the Harwell-Boeing format. Only the lower
triangular part should be set. */
virtual returnValue setMatrixData( int_t dim, /**< Dimension of the linear system. */
int_t numNonzeros, /**< Number of nonzeros in the matrix. */
const int_t* const airn, /**< Row indices for each matrix entry. */
const int_t* const acjn, /**< Column indices for each matrix entry. */
const real_t* const avals /**< Values for each matrix entry. */
) = 0;
/** Compute factorization of current matrix. This method must be called before solve.*/
virtual returnValue factorize( ) = 0;
/** Solve linear system with most recently set matrix data. */
virtual returnValue solve( int_t dim, /**< Dimension of the linear system. */
const real_t* const rhs, /**< Values for the right hand side. */
real_t* const sol /**< Solution of the linear system. */
) = 0;
/** Clears all data structures. */
virtual returnValue reset( );
/** Return the number of negative eigenvalues. */
virtual int_t getNegativeEigenvalues( );
/** Return the rank after a factorization */
virtual int_t getRank( );
/** Returns the zero pivots in case the matrix is rank deficient */
virtual returnValue getZeroPivots( int_t *&zeroPivots );
/*
* PROTECTED MEMBER FUNCTIONS
*/
protected:
/** Frees all allocated memory.
* \return SUCCESSFUL_RETURN */
returnValue clear( );
/** Copies all members from given rhs object.
* \return SUCCESSFUL_RETURN */
returnValue copy( const SparseSolver& rhs /**< Rhs object. */
);
/*
* PROTECTED MEMBER VARIABLES
*/
protected:
};
#ifdef SOLVER_MA27
/**
* \brief Implementation of the linear solver interface using Harwell's MA27.
*
* \author Andreas Waechter, Dennis Janka
* \version 3.2
* \date 2012-2017
*/
class Ma27SparseSolver: public SparseSolver
{
/*
* PUBLIC MEMBER FUNCTIONS
*/
public:
/** Default constructor. */
Ma27SparseSolver( );
/** Copy constructor (deep copy). */
Ma27SparseSolver( const Ma27SparseSolver& rhs /**< Rhs object. */
);
/** Destructor. */
virtual ~Ma27SparseSolver( );
/** Assignment operator (deep copy). */
virtual Ma27SparseSolver& operator=( const SparseSolver& rhs /**< Rhs object. */
);
/** Set new matrix data. The matrix is to be provided
in the Harwell-Boeing format. Only the lower
triangular part should be set. */
virtual returnValue setMatrixData( int_t dim, /**< Dimension of the linear system. */
int_t numNonzeros, /**< Number of nonzeros in the matrix. */
const int_t* const airn, /**< Row indices for each matrix entry. */
const int_t* const acjn, /**< Column indices for each matrix entry. */
const real_t* const avals /**< Values for each matrix entry. */
);
/** Compute factorization of current matrix. This method must be called before solve.*/
virtual returnValue factorize( );
/** Solve linear system with most recently set matrix data. */
virtual returnValue solve( int_t dim, /**< Dimension of the linear system. */
const real_t* const rhs, /**< Values for the right hand side. */
real_t* const sol /**< Solution of the linear system. */
);
/** Clears all data structures. */
virtual returnValue reset( );
/** Return the number of negative eigenvalues. */
virtual int_t getNegativeEigenvalues( );
/** Return the rank after a factorization */
virtual int getRank( );
/*
* PROTECTED MEMBER FUNCTIONS
*/
protected:
/** Frees all allocated memory.
* \return SUCCESSFUL_RETURN */
returnValue clear( );
/** Copies all members from given rhs object.
* \return SUCCESSFUL_RETURN */
returnValue copy( const Ma27SparseSolver& rhs /**< Rhs object. */
);
/*
* PRIVATE MEMBER FUNCTIONS
*/
private:
/*
* PRIVATE MEMBER VARIABLES
*/
private:
fint_t dim; /**< Dimension of the current linear system. */
fint_t numNonzeros; /**< Number of nonzeros in the current linear system. */
fint_t la_ma27; /**< size of a_ma27 (LA in MA27) */
double* a_ma27; /**< matrix/factor for MA27 (A in MA27). If have_factorization is false, it contains the matrix entries (and has length numNonzeros), otherwise the factor (and has length la_ma27). */
fint_t* irn_ma27; /**< Row entries of matrix (IRN in MA27) */
fint_t* jcn_ma27; /**< Column entries of matrix (JCN in MA27) */
fint_t icntl_ma27[30]; /**< integer control values (ICNRL in MA27) */
double cntl_ma27[5]; /**< real control values (CNRL in MA27) */
fint_t liw_ma27; /**< length of integer work space (LIW in MA27) */
fint_t* iw_ma27; /**< integer work space (IW in MA27) */
fint_t* ikeep_ma27; /**< IKEEP in MA27 */
fint_t nsteps_ma27; /**< NSTEPS in MA27 */
fint_t maxfrt_ma27; /**< MAXFRT in MA27 */
bool have_factorization; /**< flag indicating whether factorization for current matrix has already been computed */
fint_t neig; /**< number of negative eigenvalues */
fint_t rank; /**< rank of matrix */
};
#endif /* SOLVER_MA27 */
#ifdef SOLVER_MA57
/**
* \brief Implementation of the linear solver interface using Harwell's MA57.
*
* \author Andreas Waechter, Dennis Janka
* \version 3.2
* \date 2013-2017
*/
class Ma57SparseSolver: public SparseSolver
{
/*
* PUBLIC MEMBER FUNCTIONS
*/
public:
/** Default constructor. */
Ma57SparseSolver( );
/** Copy constructor (deep copy). */
Ma57SparseSolver( const Ma57SparseSolver& rhs /**< Rhs object. */
);
/** Destructor. */
virtual ~Ma57SparseSolver( );
/** Assignment operator (deep copy). */
virtual Ma57SparseSolver& operator=( const SparseSolver& rhs /**< Rhs object. */
);
/** Set new matrix data. The matrix is to be provided
in the Harwell-Boeing format. Only the lower
triangular part should be set. */
virtual returnValue setMatrixData( int_t dim, /**< Dimension of the linear system. */
int_t numNonzeros, /**< Number of nonzeros in the matrix. */
const int_t* const airn, /**< Row indices for each matrix entry. */
const int_t* const acjn, /**< Column indices for each matrix entry. */
const real_t* const avals /**< Values for each matrix entry. */
);
/** Compute factorization of current matrix. This method must be called before solve.*/
virtual returnValue factorize( );
/** Solve linear system with most recently set matrix data. */
virtual returnValue solve( int_t dim, /**< Dimension of the linear system. */
const real_t* const rhs, /**< Values for the right hand side. */
real_t* const sol /**< Solution of the linear system. */
);
/** Clears all data structures. */
virtual returnValue reset( );
/** Return the number of negative eigenvalues. */
virtual int_t getNegativeEigenvalues( );
/** Return the rank after a factorization */
virtual int_t getRank( );
/** Returns the zero pivots in case the matrix is rank deficient */
virtual returnValue getZeroPivots( int_t* &zeroPivots /**< ... */
);
/*
* PROTECTED MEMBER FUNCTIONS
*/
protected:
/** Frees all allocated memory.
* \return SUCCESSFUL_RETURN */
returnValue clear( );
/** Copies all members from given rhs object.
* \return SUCCESSFUL_RETURN */
returnValue copy( const Ma57SparseSolver& rhs /**< Rhs object. */
);
/*
* PRIVATE MEMBER FUNCTIONS
*/
private:
/*
* PRIVATE MEMBER VARIABLES
*/
private:
fint_t dim; /**< Dimension of the current linear system. */
fint_t numNonzeros; /**< Number of nonzeros in the current linear system. */
double* a_ma57; /**< matrix for MA57 (A in MA57) */
fint_t* irn_ma57; /**< Row entries of matrix (IRN in MA57) */
fint_t* jcn_ma57; /**< Column entries of matrix (JCN in MA57) */
fint_t icntl_ma57[30]; /**< integer control values (ICNRL in MA57) */
double cntl_ma57[5]; /**< real control values (CNRL in MA57) */
double* fact_ma57; /**< array for storing the factors */
fint_t lfact_ma57; /**< length of fact_ma57 */
fint_t* ifact_ma57; /**< indexing information about the factors */
fint_t lifact_ma57; /**< length of ifact_ma57 */
bool have_factorization;/**< flag indicating whether factorization for current matrix has already been computed */
fint_t neig; /**< number of negative eigenvalues */
fint_t rank; /**< rank of matrix */
fint_t* pivots; /**< sequence of pivots used in factorization */
};
#endif /* SOLVER_MA57 */
#ifdef SOLVER_MUMPS
/**
* \brief Implementation of the linear solver interface using MUMPS.
*
* \author Andrea Zanelli
* \version 3.2
* \date 2022
*/
class MumpsSparseSolver: public SparseSolver
{
/*
* PUBLIC MEMBER FUNCTIONS
*/
public:
/** Default constructor. */
MumpsSparseSolver( );
/** Copy constructor (deep copy). */
MumpsSparseSolver( const MumpsSparseSolver& rhs /**< Rhs object. */
);
/** Destructor. */
virtual ~MumpsSparseSolver( );
/** Assignment operator (deep copy). */
virtual MumpsSparseSolver& operator=( const SparseSolver& rhs /**< Rhs object. */
);
/** Set new matrix data. The matrix is to be provided
in the Harwell-Boeing format. Only the lower
triangular part should be set. */
virtual returnValue setMatrixData( int_t dim, /**< Dimension of the linear system. */
int_t numNonzeros, /**< Number of nonzeros in the matrix. */
const int_t* const airn, /**< Row indices for each matrix entry. */
const int_t* const acjn, /**< Column indices for each matrix entry. */
const real_t* const avals /**< Values for each matrix entry. */
);
/** Compute factorization of current matrix. This method must be called before solve.*/
virtual returnValue factorize( );
/** Solve linear system with most recently set matrix data. */
virtual returnValue solve( int_t dim, /**< Dimension of the linear system. */
const real_t* const rhs, /**< Values for the right hand side. */
real_t* const sol /**< Solution of the linear system. */
);
/** Clears all data structures. */
virtual returnValue reset( );
/** Return the number of negative eigenvalues. */
virtual int_t getNegativeEigenvalues( );
/** Return the rank after a factorization */
virtual int_t getRank( );
/** Returns the zero pivots in case the matrix is rank deficient */
virtual returnValue getZeroPivots( int_t* &zeroPivots /**< ... */
);
/*
* PROTECTED MEMBER FUNCTIONS
*/
protected:
/** Frees all allocated memory.
* \return SUCCESSFUL_RETURN */
returnValue clear( );
/** Copies all members from given rhs object.
* \return SUCCESSFUL_RETURN */
returnValue copy( const MumpsSparseSolver& rhs /**< Rhs object. */
);
/*
* PRIVATE MEMBER FUNCTIONS
*/
private:
/*
* PRIVATE MEMBER VARIABLES
*/
private:
void* mumps_ptr_; /** Primary MUMPS data structure */
int dim; /**< Dimension of the current linear system. */
int numNonzeros; /**< Number of nonzeros in the current linear system. */
double* a_mumps; /**< matrix for MUMPS (A in MUMPS) */
int* irn_mumps; /**< Row entries of matrix (IRN in MUMPS) */
int* jcn_mumps; /**< Column entries of matrix (JCN in MUMPS) */
bool have_factorization; /**< flag indicating whether factorization for current matrix has already been computed */
int negevals_; /**< number of negative eigenvalues */
int mumps_pivot_order_; /* pivot order*/
bool initialized_;
/** Flag indicating if the matrix has to be refactorized because
* the pivot tolerance has been changed.
*/
bool pivtol_changed_;
/** Flag that is true if we just requested the values of the
* matrix again (SYMSOLVER_CALL_AGAIN) and have to factorize
* again.
*/
bool refactorize_;
///@}
/** @name Solver specific data/options */
///@{
/** Pivot tolerance */
double pivtol_;
/** Maximal pivot tolerance */
double pivtolmax_;
/** Percent increase in memory */
int mem_percent_;
/** Permutation and scaling method in MUMPS */
int mumps_permuting_scaling_;
/** Scaling in MUMPS */
int mumps_scaling_;
/** Threshold in MUMPS to state that a constraint is linearly dependent */
double mumps_dep_tol_;
/** Flag indicating whether the TNLP with identical structure has
* already been solved before.
*/
bool warm_start_same_structure_;
///@}
/** Flag indicating if symbolic factorization has already been called */
bool have_symbolic_factorization_;
};
template<typename T>
inline void ComputeMemIncrease(
T& len, ///< current length on input, new length on output
double recommended, ///< recommended size
T min, ///< minimal size that should ensured
const char* context ///< context from where this function is called - used to setup message for exception
)
{
if( recommended >= std::numeric_limits<T>::max() )
{
// increase len to the maximum possible, if that is still an increase
if( len < std::numeric_limits<T>::max() )
{
len = std::numeric_limits<T>::max();
}
else
{
std::stringstream what;
what << "Cannot allocate more than " << std::numeric_limits<T>::max()*sizeof(T) << " bytes for " << context << " due to limitation on integer type";
throw std::overflow_error(what.str());
}
}
else
{
len = std::max(min, (T) recommended);
}
}
#endif /* SOLVER_MUMPS */
#ifdef SOLVER_NONE
/**
* \brief Implementation of a dummy sparse solver. An error is thrown if a factorization is attempted.
*
* \author Dennis Janka
* \version 3.2
* \date 2015-2017
*/
class DummySparseSolver: public SparseSolver
{
/*
* PUBLIC MEMBER FUNCTIONS
*/
public:
/** Set new matrix data. The matrix is to be provided
in the Harwell-Boeing format. Only the lower
triangular part should be set. */
virtual returnValue setMatrixData( int_t dim, /**< Dimension of the linear system. */
int_t numNonzeros, /**< Number of nonzeros in the matrix. */
const int_t* const airn, /**< Row indices for each matrix entry. */
const int_t* const acjn, /**< Column indices for each matrix entry. */
const real_t* const avals /**< Values for each matrix entry. */
);
/** Compute factorization of current matrix. This method must be called before solve.*/
virtual returnValue factorize( );
/** Solve linear system with most recently set matrix data. */
virtual returnValue solve( int_t dim, /**< Dimension of the linear system. */
const real_t* const rhs, /**< Values for the right hand side. */
real_t* const sol /**< Solution of the linear system. */
);
};
#endif /* SOLVER_NONE */
END_NAMESPACE_QPOASES
#endif /* QPOASES_SPARSESOLVER_HPP */
/*
* end of file
*/

View File

@ -0,0 +1,229 @@
/*
* This file is part of qpOASES.
*
* qpOASES -- An Implementation of the Online Active Set Strategy.
* Copyright (C) 2007-2017 by Hans Joachim Ferreau, Andreas Potschka,
* Christian Kirches 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/qpOASES/SubjectTo.hpp
* \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
* \version 3.2
* \date 2007-2017
*
* 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 <qpOASES/Indexlist.hpp>
BEGIN_NAMESPACE_QPOASES
/**
* \brief Base class for managing working sets of bounds and constraints.
*
* This class manages working sets of bounds and constraints by storing
* index sets and other status information.
*
* \author Hans Joachim Ferreau
* \version 3.2
* \date 2007-2017
*/
class SubjectTo
{
/*
* PUBLIC MEMBER FUNCTIONS
*/
public:
/** Default constructor. */
SubjectTo( );
/** Constructor which takes the number of constraints or bounds. */
SubjectTo( int_t _n /**< Number of constraints or bounds. */
);
/** Copy constructor (deep copy). */
SubjectTo( const SubjectTo& rhs /**< Rhs object. */
);
/** Destructor. */
virtual ~SubjectTo( );
/** Assignment operator (deep copy). */
SubjectTo& operator=( const SubjectTo& rhs /**< Rhs object. */
);
/** Initialises object with given number of constraints or bounds.
* \return SUCCESSFUL_RETURN \n
RET_INVALID_ARGUMENTS */
returnValue init( int_t _n = 0 /**< Number of constraints or bounds. */
);
/** Returns number of constraints/bounds with given SubjectTo type.
* \return Number of constraints/bounds with given type. */
inline int_t getNumberOfType( SubjectToType _type /**< Type of (constraints') bound. */
) const;
/** Returns type of (constraints') bound.
* \return Type of (constraints') bound \n
RET_INDEX_OUT_OF_BOUNDS */
inline SubjectToType getType( int_t i /**< Number of (constraints') bound. */
) const;
/** Returns status of (constraints') bound.
* \return Status of (constraints') bound \n
ST_UNDEFINED */
inline SubjectToStatus getStatus( int_t i /**< Number of (constraints') bound. */
) const;
/** Sets type of (constraints') bound.
* \return SUCCESSFUL_RETURN \n
RET_INDEX_OUT_OF_BOUNDS */
inline returnValue setType( int_t 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_t 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 hasNoLower( ) const;
/** Returns status of upper bounds.
* \return BT_TRUE if there is no upper (constraints') bound on any variable. */
inline BooleanType hasNoUpper( ) const;
/** Shifts forward type and status of all constraints/bounds by a given
* offset. This offset has to lie within the range [0,n/2] and has to
* be an integer divisor of the total number of constraints/bounds n.
* Type and status of the first \<offset\> constraints/bounds is thrown away,
* type and status of the last \<offset\> constraints/bounds is doubled,
* e.g. for offset = 2: \n
* shift( {c/b1,c/b2,c/b3,c/b4,c/b5,c/b6} ) = {c/b3,c/b4,c/b5,c/b6,c/b5,c/b6}
* \return SUCCESSFUL_RETURN \n
RET_INDEX_OUT_OF_BOUNDS \n
RET_INVALID_ARGUMENTS \n
RET_SHIFTING_FAILED */
virtual returnValue shift( int_t offset /**< Shift offset within the range [0,n/2] and integer divisor of n. */
) = 0;
/** Rotates forward type and status of all constraints/bounds by a given
* offset. This offset has to lie within the range [0,n].
* Example for offset = 2: \n
* rotate( {c/b1,c/b2,c/b3,c/b4,c/b5,c/b6} ) = {c/b3,c/b4,c/b5,c/b6,c/b1,c/b2}
* \return SUCCESSFUL_RETURN \n
RET_INDEX_OUT_OF_BOUNDS \n
RET_ROTATING_FAILED */
virtual returnValue rotate( int_t offset /**< Rotation offset within the range [0,n]. */
) = 0;
/*
* PROTECTED MEMBER FUNCTIONS
*/
protected:
/** Frees all allocated memory.
* \return SUCCESSFUL_RETURN */
returnValue clear( );
/** Copies all members from given rhs object.
* \return SUCCESSFUL_RETURN */
returnValue copy( const SubjectTo& rhs /**< Rhs object. */
);
/** Adds the index of a new constraint or bound to index set.
* \return SUCCESSFUL_RETURN \n
RET_ADDINDEX_FAILED \n
RET_INVALID_ARGUMENTS */
returnValue addIndex( Indexlist* const indexlist, /**< Index list to which the new index shall be added. */
int_t 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_REMOVEINDEX_FAILED \n
RET_INVALID_ARGUMENTS */
returnValue removeIndex( Indexlist* const indexlist, /**< Index list from which the new index shall be removed. */
int_t 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 \n
RET_INVALID_ARGUMENTS */
returnValue swapIndex( Indexlist* const indexlist, /**< Index list in which the indices shold be swapped. */
int_t number1, /**< Number of first constraint or bound. */
int_t number2 /**< Number of second constraint or bound. */
);
/*
* PROTECTED MEMBER VARIABLES
*/
protected:
int_t n; /**< Total number of constraints/bounds. */
SubjectToType* type; /**< Type of constraints/bounds. */
SubjectToStatus* status; /**< 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. */
};
END_NAMESPACE_QPOASES
#include <qpOASES/SubjectTo.ipp>
#endif /* QPOASES_SUBJECTTO_HPP */
/*
* end of file
*/

Some files were not shown because too many files have changed in this diff Show More