├── .gitignore ├── gps_imu_fusion_gtsam ├── CMakeLists.txt ├── README.md ├── gen_sim_data.h ├── main.cpp ├── motion_interpolator.h ├── pre_integration_data_preparer.cpp ├── pre_integration_data_preparer.h ├── result │ └── display_path.py └── type.h ├── model_predictive_control ├── CMakeLists.txt ├── images │ ├── 2022-02-06 16-16-58 的屏幕截图.png │ ├── 2022-02-06 16-17-31 的屏幕截图.png │ ├── 2022-02-06 16-18-44 的屏幕截图.png │ ├── 2022-02-06 16-19-25 的屏幕截图.png │ ├── 2022-02-06 16-20-08 的屏幕截图.png │ ├── 2022-02-06 16-20-52 的屏幕截图.png │ ├── 2022-02-06 16-23-31 的屏幕截图.png │ ├── 2022-02-06 16-24-10 的屏幕截图.png │ ├── 2022-02-06 16-26-53 的屏幕截图.png │ ├── 2022-02-06 16-27-39 的屏幕截图.png │ ├── 2022-02-06 16-28-31 的屏幕截图.png │ ├── 2022-02-06 16-29-22 的屏幕截图.png │ ├── 2022-02-06 16-30-06 的屏幕截图.png │ ├── 2022-02-06 16-33-56 的屏幕截图.png │ ├── 2022-02-06 16-34-59 的屏幕截图.png │ ├── 2022-02-06 16-35-41 的屏幕截图.png │ ├── 2022-02-06 16-36-34 的屏幕截图.png │ ├── 2022-02-06 16-39-52 的屏幕截图.png │ ├── 2022-02-06 16-41-09 的屏幕截图.png │ ├── 2022-02-06 16-44-17 的屏幕截图.png │ ├── 2022-02-06 16-44-51 的屏幕截图.png │ └── 2022-02-06 16-45-44 的屏幕截图.png ├── main.cpp ├── matplotlibcpp.h ├── readme.md └── 实验结果.md └── serial_plot_tool ├── README.md ├── Serial_Tool.pro ├── Serial_Tool.pro.user ├── Serial_Tool_zh_CN.ts ├── image └── a.png ├── main.cpp ├── mainwindow.cpp ├── mainwindow.h ├── mainwindow.ui ├── qcustomplot.cpp └── qcustomplot.h /.gitignore: -------------------------------------------------------------------------------- 1 | # Created by .ignore support plugin (hsz.mobi) 2 | ### C++ template 3 | # Prerequisites 4 | *.d 5 | 6 | # Compiled Object files 7 | *.slo 8 | *.lo 9 | *.o 10 | *.obj 11 | 12 | # Precompiled Headers 13 | *.gch 14 | *.pch 15 | 16 | # Compiled Dynamic libraries 17 | *.so 18 | *.dylib 19 | *.dll 20 | 21 | # Fortran module files 22 | *.mod 23 | *.smod 24 | 25 | # Compiled Static libraries 26 | *.lai 27 | *.la 28 | *.a 29 | *.lib 30 | 31 | # Executables 32 | *.exe 33 | *.out 34 | *.app 35 | 36 | **/cmake-build-debug 37 | **/build 38 | **/.idea 39 | /bin 40 | */data 41 | */dataset 42 | .catkin_workspace 43 | devel/ 44 | build/ 45 | -------------------------------------------------------------------------------- /gps_imu_fusion_gtsam/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.10) 2 | project(gps_imu_fusion_gtsam) 3 | 4 | set(CMAKE_CXX_FLAGS "-Wall -O3") 5 | 6 | set(CMAKE_BUILD_TYPE "Release") 7 | set(CMAKE_CXX_STANDARD 14) 8 | 9 | find_package(Eigen3 REQUIRED) 10 | include_directories(${EIGEN3_INCLUDE_DIR}) 11 | 12 | find_package(GTSAM REQUIRED) 13 | include_directories(${GTSAM_INCLUDE_DIR}) 14 | 15 | add_executable(gps_imu_fusion_gtsam main.cpp pre_integration_data_preparer.cpp) 16 | target_link_libraries(gps_imu_fusion_gtsam gtsam) 17 | -------------------------------------------------------------------------------- /gps_imu_fusion_gtsam/README.md: -------------------------------------------------------------------------------- 1 | # GPS IMU Fusion By Gtsam 2 | 3 | ## 1. 介绍 4 | 该仓库主要是基于Gtsam,实现了GPS与IMU的融合。通过使用预积分的方法,实现了IMU积分对前后帧的约束。通过边缘化操作限制了优化窗口中始终只包含前后两帧的数据。主要包含了如下内容: 5 | - IMU预积分因子的使用 6 | - GPS因子的使用 7 | - 边缘化操作 8 | - bias的估计 9 | 10 | ## 2. 编译 11 | ```shell 12 | cd gps_imu_fusion_gtsam 13 | mkdir build 14 | cd build 15 | cmake .. 16 | make -j4 17 | ``` 18 | 19 | ## 3. 运行 20 | ```shell 21 | cd gps_imu_fusion_gtsam/build 22 | ./gps_imu_fusion_gtsam 23 | ``` 24 | 25 | ## 4. 效果可视化 26 | ```shell 27 | cd gps_imu_fusion_gtsam/resule 28 | python display_path.py 29 | ``` 30 | 31 | ## 5. 总结 32 | 在IMU的预积分方式下,实现GPS与IMU的融合,其中对于第一帧数据应当设置先验,包括位姿、速度、bias,如果状态置信度较差,需要将噪声设置大一些。另外如果GPS只有位置观测,那么陀螺仪的bias可能会无法收敛,如果依然想要其bias收敛,需要增大滑动窗口的大小。 33 | 34 | 而对于有旋转的GPS观测,加速度计和陀螺仪的bias均可以实现较好的估计。 35 | -------------------------------------------------------------------------------- /gps_imu_fusion_gtsam/gen_sim_data.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by Zhang Zhimeng on 24-1-23. 3 | // 4 | 5 | #ifndef MATCH_TEST_GEN_SIM_DATA_H 6 | #define MATCH_TEST_GEN_SIM_DATA_H 7 | 8 | #include "type.h" 9 | #include 10 | #include 11 | 12 | class PreIntegrationOptimizationTest { 13 | public: 14 | PreIntegrationOptimizationTest() = default; 15 | 16 | // 生成圆弧运动时的IMU数据和GPS数据 17 | void GenImuData(std::vector &imu_data_vec, std::vector &gps_data_vec, 18 | std::vector &nav_state_gt_data_vec) const { 19 | // 噪声生成器 20 | std::random_device rd; 21 | std::default_random_engine eng(rd()); 22 | std::normal_distribution acc_normal_noise(0.0, imu_acc_noise_std_); 23 | std::normal_distribution gyro_normal_noise(0.0, imu_gyro_noise_std_); 24 | std::normal_distribution gps_posi_normal_noise(0.0, gps_posi_noise_std_); 25 | std::normal_distribution gps_vel_normal_noise(0.0, gps_velocity_noise_std_); 26 | std::normal_distribution gps_ori_normal_noise(0.0, gps_orientation_noise_std_); 27 | 28 | // 真实加速度 29 | double acceleration_true = omega_true_ * velocity_true_; 30 | 31 | imu_data_vec.clear(); 32 | gps_data_vec.clear(); 33 | nav_state_gt_data_vec.clear(); 34 | 35 | // 根据总时间和步进时间计算总仿真数据量 36 | int data_size = static_cast(sum_time_ / imu_dt_); 37 | 38 | nav_state_gt_data_vec.reserve(data_size); 39 | imu_data_vec.reserve(data_size); 40 | gps_data_vec.reserve(data_size); 41 | 42 | NavStateDataMy last_nav_state_data; 43 | last_nav_state_data.P_.setZero(); 44 | last_nav_state_data.V_ << 0.0, velocity_true_, 0.0; 45 | last_nav_state_data.R_.setIdentity(); 46 | 47 | for (int i = 0; i < data_size; i++) { 48 | Eigen::Vector3d acceleration; 49 | acceleration << acceleration_true, 0.0, 0.0; 50 | 51 | Eigen::Vector3d angular_velocity; 52 | angular_velocity << 0.0, 0.0, -omega_true_; 53 | 54 | // 生成IMU的仿真数据量 55 | IMUData imu_data; 56 | imu_data.linear_acceleration_ 57 | << acceleration_true + imu_acc_bias_ + acc_normal_noise(eng), 58 | imu_acc_bias_ + acc_normal_noise(eng), 59 | imu_acc_bias_ + acc_normal_noise(eng); 60 | imu_data.angular_velocity_ 61 | << angular_velocity + Vec3d(imu_gyro_bias_ + gyro_normal_noise(eng), 62 | imu_gyro_bias_ + gyro_normal_noise(eng), 63 | imu_gyro_bias_ + gyro_normal_noise(eng)); 64 | imu_data.timestamp_ = static_cast(i * 0.01 * 1.0e6); 65 | imu_data.orientation_ = last_nav_state_data.R_; 66 | imu_data_vec.emplace_back(std::move(imu_data)); 67 | 68 | // 生成GPS的测量数据 69 | if (i % 10 == 0) { 70 | GPSData gps_data; 71 | 72 | gps_data.local_xyz_true_ = last_nav_state_data.P_; 73 | gps_data.local_orientation_true_ = last_nav_state_data.R_; 74 | gps_data.local_xyz_velocity_true_ = last_nav_state_data.V_; 75 | 76 | gps_data.local_xyz_.x() = last_nav_state_data.P_.x() + gps_posi_normal_noise(eng); 77 | gps_data.local_xyz_.y() = last_nav_state_data.P_.y() + gps_posi_normal_noise(eng); 78 | gps_data.local_xyz_.z() = last_nav_state_data.P_.z() + gps_posi_normal_noise(eng); 79 | gps_data.local_xyz_velocity_.x() = last_nav_state_data.V_.x() + gps_vel_normal_noise(eng); 80 | gps_data.local_xyz_velocity_.y() = last_nav_state_data.V_.y() + gps_vel_normal_noise(eng); 81 | gps_data.local_xyz_velocity_.z() = last_nav_state_data.V_.z() + gps_vel_normal_noise(eng); 82 | 83 | Vec3d ori_noise(gps_ori_normal_noise(eng), 84 | gps_ori_normal_noise(eng), 85 | gps_ori_normal_noise(eng)); 86 | 87 | gps_data.local_orientation = last_nav_state_data.R_ * SO3Exp(ori_noise); 88 | 89 | gps_data.timestamp_ = static_cast(i * imu_dt_ * 1.0e6); 90 | 91 | gps_data_vec.emplace_back(std::move(gps_data)); 92 | } 93 | last_nav_state_data.timestamp_ = static_cast(i * imu_dt_ * 1.0e6); 94 | nav_state_gt_data_vec.push_back(last_nav_state_data); 95 | 96 | // 生成真实运动轨迹 97 | last_nav_state_data.P_ = last_nav_state_data.P_ + last_nav_state_data.V_ * imu_dt_ 98 | + 0.5 * imu_dt_ * imu_dt_ * last_nav_state_data.R_ * acceleration; 99 | last_nav_state_data.V_ = last_nav_state_data.V_ + last_nav_state_data.R_ * acceleration * imu_dt_; 100 | last_nav_state_data.R_ = last_nav_state_data.R_ * SO3Exp(angular_velocity * imu_dt_); 101 | } 102 | } 103 | 104 | public: 105 | double sum_time_ = 60.0; // 总仿真时间 106 | double imu_dt_ = 0.01; // imu采样时间 107 | 108 | double imu_acc_noise_std_ = 0.01; 109 | double imu_acc_bias_ = 0.2; 110 | 111 | double imu_gyro_noise_std_ = 0.01; 112 | double imu_gyro_bias_ = 0.1; 113 | 114 | double imu_bias_rw_noise_std_ = 0.001; // imu bias随机游走的标准差 115 | 116 | double gps_posi_noise_std_ = 1.0; 117 | double gps_velocity_noise_std_ = 0.1; 118 | double gps_orientation_noise_std_ = 1.0 * kDegree2Radian; // degree 119 | 120 | double velocity_true_ = 5.0; // velocity norm 121 | double omega_true_ = 5.0 * kDegree2Radian; 122 | }; 123 | 124 | #endif //MATCH_TEST_GEN_SIM_DATA_H 125 | -------------------------------------------------------------------------------- /gps_imu_fusion_gtsam/main.cpp: -------------------------------------------------------------------------------- 1 | #include "type.h" 2 | #include "gen_sim_data.h" 3 | #include "pre_integration_data_preparer.h" 4 | 5 | #include 6 | #include 7 | #include 8 | #include 9 | 10 | // GTSAM related includes. 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | #include 21 | 22 | #include 23 | 24 | #include 25 | #include 26 | 27 | using namespace gtsam; 28 | using namespace std; 29 | 30 | using symbol_shorthand::B; // Bias (ax,ay,az,gx,gy,gz) 31 | using symbol_shorthand::V; // Vel (xdot,ydot,zdot) 32 | using symbol_shorthand::X; // Pose3 (x,y,z,r,p,y) 33 | 34 | namespace po = boost::program_options; 35 | 36 | std::shared_ptr 37 | ImuParams(const PreIntegrationOptimizationTest &pre_integration_optimization_test) { 38 | // We use the sensor specs to build the noise model for the IMU factor. 39 | double accel_noise_sigma = pre_integration_optimization_test.imu_acc_noise_std_; 40 | double gyro_noise_sigma = pre_integration_optimization_test.imu_gyro_noise_std_; 41 | double accel_bias_rw_sigma = pre_integration_optimization_test.imu_bias_rw_noise_std_; 42 | double gyro_bias_rw_sigma = pre_integration_optimization_test.imu_bias_rw_noise_std_; 43 | Matrix33 measured_acc_cov = I_3x3 * pow(accel_noise_sigma, 2); 44 | Matrix33 measured_omega_cov = I_3x3 * pow(gyro_noise_sigma, 2); 45 | Matrix33 integration_error_cov = I_3x3 * 1e-8; //由于速度积分位置时带来的积分误差 46 | Matrix33 bias_acc_cov = I_3x3 * pow(accel_bias_rw_sigma, 2); 47 | Matrix33 bias_omega_cov = I_3x3 * pow(gyro_bias_rw_sigma, 2); 48 | Matrix66 bias_acc_omega_init = I_6x6 * 1e-5; // error in the bias used for preintegration 49 | 50 | auto p = PreintegratedCombinedMeasurements::Params::MakeSharedD(0.0); 51 | 52 | // PreintegrationBase params: 53 | p->accelerometerCovariance = measured_acc_cov; // acc white noise in continuous 54 | p->integrationCovariance = integration_error_cov; // integration uncertainty continuous 55 | 56 | // should be using 2nd order integration 57 | // PreintegratedRotation params: 58 | p->gyroscopeCovariance = measured_omega_cov; // gyro white noise in continuous 59 | 60 | // PreintegrationCombinedMeasurements params: 61 | p->biasAccCovariance = bias_acc_cov; // acc bias in continuous 62 | p->biasOmegaCovariance = bias_omega_cov; // gyro bias in continuous 63 | p->biasAccOmegaInt = bias_acc_omega_init; 64 | 65 | return p; 66 | } 67 | 68 | int main() { 69 | PreIntegrationOptimizationTest pre_integration_optimization_test; 70 | 71 | std::vector imu_data_vec; 72 | std::vector gps_measures_vec; 73 | std::vector nav_state_gt_data_vec; 74 | pre_integration_optimization_test.GenImuData(imu_data_vec, gps_measures_vec, nav_state_gt_data_vec); 75 | 76 | // 设置运动状态的先验 77 | Rot3 prior_rotation(SO3::FromMatrix(nav_state_gt_data_vec[0].R_)); 78 | Point3 prior_point(nav_state_gt_data_vec[0].P_); 79 | Pose3 prior_pose(prior_rotation, prior_point); 80 | Vector3 prior_velocity(nav_state_gt_data_vec[0].V_); 81 | imuBias::ConstantBias prior_imu_bias; 82 | 83 | // 设置先验状态的置信度噪声标准差 84 | noiseModel::Base::shared_ptr prior_pose_noise_model = noiseModel::Diagonal::Sigmas( 85 | (Vector(6) << 0.00001, 0.00001, 0.00001, 0.0005, 0.0005, 0.0005).finished() 86 | ); 87 | noiseModel::Base::shared_ptr prior_velocity_noise_model = noiseModel::Diagonal::Sigmas( 88 | (Vector(3) << 0.00001, 0.00001, 0.00001).finished() 89 | ); 90 | noiseModel::Base::shared_ptr prior_bias_prior_noise_model = noiseModel::Diagonal::Sigmas( 91 | (Vector(6) << 0.2, 0.2, 0.2, 0.1, 0.1, 0.1).finished() 92 | );; 93 | 94 | // 初始化imu的参数和预积分 95 | auto p = ImuParams(pre_integration_optimization_test); 96 | std::shared_ptr preintegrated 97 | = std::make_shared(p, prior_imu_bias); 98 | 99 | NavState prev_state(prior_pose, prior_velocity); 100 | 101 | double dt = pre_integration_optimization_test.imu_dt_; 102 | 103 | // 生成imu数据准备器,便于根据时间点搜索数据段 104 | PreIntegrationDataPreparer pre_integration_data_preparer; 105 | for (const auto &i: imu_data_vec) { 106 | pre_integration_data_preparer.CacheData(i); 107 | } 108 | 109 | int correction_count = 0; 110 | 111 | std::ofstream gps_measure_file("../result/gps_measure.txt", std::ios::trunc); 112 | std::ofstream fuse_path_file("../result/fuse_path.txt", std::ios::trunc); 113 | std::ofstream gt_path_file("../result/gt_path.txt", std::ios::trunc); 114 | std::ofstream imu_bias_file("../result/imu_bias.txt", std::ios::trunc); 115 | 116 | imu_bias_file << pre_integration_optimization_test.imu_acc_bias_ << " " 117 | << pre_integration_optimization_test.imu_acc_bias_ << " " 118 | << pre_integration_optimization_test.imu_acc_bias_ << " " 119 | << pre_integration_optimization_test.imu_gyro_bias_ << " " 120 | << pre_integration_optimization_test.imu_gyro_bias_ << " " 121 | << pre_integration_optimization_test.imu_gyro_bias_ << std::endl; 122 | 123 | // 保存真值轨迹 124 | for (const auto &nav_state: nav_state_gt_data_vec) { 125 | Eigen::Quaterniond q(nav_state.R_); 126 | gt_path_file << std::setprecision(15) << static_cast(nav_state.timestamp_) / 1.0e6 << " " 127 | << nav_state.P_.x() << " " << nav_state.P_.y() << " " << nav_state.P_.z() << " " 128 | << q.x() << " " << q.y() << " " << q.z() << " " << q.w() << std::endl; 129 | } 130 | 131 | for (const auto &gps_measure: gps_measures_vec) { 132 | Eigen::Quaterniond q(gps_measure.local_orientation); 133 | gps_measure_file << std::setprecision(15) << static_cast(gps_measure.timestamp_) / 1.0e6 << " " 134 | << gps_measure.local_xyz_.x() << " " << gps_measure.local_xyz_.y() << " " 135 | << gps_measure.local_xyz_.z() << " " 136 | << q.x() << " " << q.y() << " " << q.z() << " " << q.w() << std::endl; 137 | } 138 | 139 | for (unsigned int i = 0; i < gps_measures_vec.size() - 1; ++i) { 140 | // 搜索相邻两个时间点内的IMU数据段 141 | const auto imu_data_segment = pre_integration_data_preparer.GetDataSegment(gps_measures_vec[i].timestamp_, 142 | gps_measures_vec[i + 1].timestamp_); 143 | 144 | // 对IMU数据进行预积分 145 | for (unsigned int imu_data_index = 0; imu_data_index < imu_data_segment.size() - 1; ++imu_data_index) { 146 | preintegrated->integrateMeasurement(imu_data_segment[imu_data_index].linear_acceleration_, 147 | imu_data_segment[imu_data_index].angular_velocity_, dt); 148 | } 149 | 150 | auto preint_imu = dynamic_cast(*preintegrated); 151 | 152 | // 设置待求解的随机变量 153 | Values initial_values; 154 | initial_values.insert(X(correction_count), prior_pose); 155 | initial_values.insert(V(correction_count), prior_velocity); 156 | initial_values.insert(B(correction_count), prior_imu_bias); 157 | 158 | // 新建非线性因子图 159 | auto *graph = new NonlinearFactorGraph(); 160 | 161 | // 向因子图中增加随机状态量的先验测量和先验的置信度 162 | graph->addPrior(X(correction_count), prior_pose, prior_pose_noise_model); 163 | graph->addPrior(V(correction_count), prior_velocity, prior_velocity_noise_model); 164 | graph->addPrior(B(correction_count), prior_imu_bias, prior_bias_prior_noise_model); 165 | 166 | correction_count++; 167 | 168 | // IMU因子 169 | ImuFactor imu_factor(X(correction_count - 1), 170 | V(correction_count - 1), 171 | X(correction_count), 172 | V(correction_count), 173 | B(correction_count - 1), 174 | preint_imu); 175 | graph->add(imu_factor); 176 | 177 | // MU bias随机游走的因子 178 | noiseModel::Base::shared_ptr bias_rw_noise_model 179 | = noiseModel::Isotropic::Sigma(6, pre_integration_optimization_test.imu_bias_rw_noise_std_); 180 | imuBias::ConstantBias zero_bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); 181 | graph->add(BetweenFactor( 182 | B(correction_count - 1), B(correction_count), zero_bias, bias_rw_noise_model 183 | )); 184 | 185 | // GPS测量的因子,包括位置和姿态 186 | double gps_posi_noise = pre_integration_optimization_test.gps_posi_noise_std_ / 5.0; 187 | double gps_rot_noise = pre_integration_optimization_test.gps_orientation_noise_std_; 188 | auto gps_measure_noise = noiseModel::Diagonal::Sigmas( 189 | (Vector(6) << gps_rot_noise, gps_rot_noise, gps_rot_noise, 190 | gps_posi_noise, gps_posi_noise, gps_posi_noise).finished()); 191 | Rot3 gps_prior_rotation(SO3::FromMatrix(gps_measures_vec[i].local_orientation)); 192 | Point3 gps_prior_point(gps_measures_vec[i].local_xyz_); 193 | Pose3 gps_prior_pose(gps_prior_rotation, gps_prior_point); 194 | PriorFactor gps_pose(X(correction_count), gps_prior_pose, gps_measure_noise); 195 | graph->add(gps_pose); 196 | 197 | // 使用IMU的预测值作为后一个时刻的状态的初始值 198 | NavState prop_state = preintegrated->predict(prev_state, prior_imu_bias); 199 | initial_values.insert(X(correction_count), prop_state.pose()); 200 | initial_values.insert(V(correction_count), prop_state.v()); 201 | initial_values.insert(B(correction_count), prior_imu_bias); 202 | 203 | // 执行非线性优化 204 | GaussNewtonOptimizer optimizer(*graph, initial_values); 205 | Values result = optimizer.optimize(); 206 | 207 | // 获取优化之后的结果 208 | prior_pose = result.at(X(correction_count)); 209 | prior_velocity = result.at(V(correction_count)); 210 | prior_imu_bias = result.at(B(correction_count)); 211 | preintegrated->resetIntegrationAndSetBias(prior_imu_bias); 212 | 213 | // 对优化状态执行边缘化操作,将当前时刻的状态变成下一次优化的先验 214 | // 通过雅克比矩阵,以及信息矩阵从联合概率中中获得某个状态边缘概率 215 | Marginals marginals(*graph, result); 216 | Matrix curr_pose_cov = marginals.marginalCovariance(X(correction_count)); 217 | Matrix curr_velocity_cov = marginals.marginalCovariance(V(correction_count)); 218 | Matrix curr_bias_cov = marginals.marginalCovariance(B(correction_count)); 219 | 220 | // 更下下一个时刻先验的协方差 221 | prior_pose_noise_model = noiseModel::Gaussian::Covariance(curr_pose_cov); 222 | prior_velocity_noise_model = noiseModel::Gaussian::Covariance(curr_velocity_cov); 223 | prior_bias_prior_noise_model = noiseModel::Gaussian::Covariance(curr_bias_cov); 224 | 225 | prev_state = NavState(result.at(X(correction_count)), 226 | result.at(V(correction_count))); 227 | 228 | Rot3 fusion_rot = prev_state.pose().rotation(); 229 | Eigen::Quaterniond fusion_q = fusion_rot.toQuaternion(); 230 | 231 | Vector3 fusion_position = prev_state.pose().translation(); 232 | Vector3 fusion_velocity = prev_state.velocity(); 233 | Vector3 position_error = fusion_position - gps_measures_vec[i].local_xyz_true_; 234 | Vector3 velocity_error = fusion_velocity - gps_measures_vec[i].local_xyz_velocity_true_; 235 | 236 | Vec3d acc_bias_true(1.0, 1.0, 1.0); 237 | Vec3d gyro_bias_true(1.0, 1.0, 1.0); 238 | acc_bias_true *= pre_integration_optimization_test.imu_acc_bias_; 239 | gyro_bias_true *= pre_integration_optimization_test.imu_gyro_bias_; 240 | 241 | const Vec3d acc_bias_fusion = prior_imu_bias.vector().head(3); 242 | const Vec3d gyro_bias_fusion = prior_imu_bias.vector().tail(3); 243 | 244 | std::cout << "timestamp: " << static_cast(gps_measures_vec[i].timestamp_) / 1.0e6 << std::endl; 245 | std::cout << "Position error:" << position_error.norm() << std::endl; 246 | std::cout << "Velocity error:" << velocity_error.norm() << std::endl; 247 | std::cout << "acc gyro bias: " << prior_imu_bias.vector().transpose() << std::endl; 248 | std::cout << "acc bias error: " << (gyro_bias_fusion - gyro_bias_true).transpose() << std::endl; 249 | std::cout << "gyro bias error: " << (acc_bias_fusion - acc_bias_true).transpose() << std::endl << std::endl; 250 | 251 | fuse_path_file << std::setprecision(15) << static_cast(gps_measures_vec[i].timestamp_) / 1.0e6 << " " 252 | << fusion_position.x() << " " << fusion_position.y() << " " << fusion_position.z() << " " 253 | << fusion_q.x() << " " << fusion_q.y() << " " << fusion_q.z() << " " << fusion_q.w() 254 | << std::endl; 255 | 256 | imu_bias_file << acc_bias_fusion.x() << " " 257 | << acc_bias_fusion.y() << " " 258 | << acc_bias_fusion.z() << " " 259 | << gyro_bias_fusion.x() << " " 260 | << gyro_bias_fusion.y() << " " 261 | << gyro_bias_fusion.z() << std::endl; 262 | } 263 | 264 | return 0; 265 | } -------------------------------------------------------------------------------- /gps_imu_fusion_gtsam/motion_interpolator.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by meng on 24-1-17. 3 | // 4 | 5 | #ifndef GTSAM_TEST_MOTION_INTERPOLATOR_H 6 | #define GTSAM_TEST_MOTION_INTERPOLATOR_H 7 | 8 | #include 9 | 10 | /*! 11 | * 该类用来对旋转和向量进行插值,包含四元数和向量的线性插值和球形插值 12 | * 提示:球形插值精度更高。 13 | * 但是多数情况下的平移运动和旋转运动使用线性插值就够用了 14 | * reference: https://zhuanlan.zhihu.com/p/87418561 15 | */ 16 | class MotionInterpolator { 17 | public: 18 | /*! 19 | * Quaternion Normalized Linear Interpolation 20 | * @param q_0 Quaternion start 21 | * @param q_1 Quaternion end 22 | * @param t ratio 23 | * @return 24 | */ 25 | template 26 | static Eigen::Quaterniond InterpolateQuaternionLerp(const Eigen::QuaternionBase &q_0, 27 | const Eigen::QuaternionBase &q_1, 28 | typename Derived::Scalar t) { 29 | CHECK_LE(t, 1.0); 30 | CHECK_GE(t, 0.0); 31 | 32 | Derived q(q_0.coeffs() * ((typename Derived::Scalar(1.0)) - t) + q_1.coeffs() * t); 33 | return q.normalized(); 34 | } 35 | 36 | /*! 37 | * Quaternion Normalized Linear Interpolation 38 | * @param q_0 Quaternion start 39 | * @param q_1 Quaternion end 40 | * @param t_0 start time 41 | * @param t_1 end time 42 | * @param t interpolated time point 43 | * @return 44 | */ 45 | template 46 | static Eigen::Quaterniond InterpolateQuaternionLerp(const Eigen::QuaternionBase &q_0, 47 | const Eigen::QuaternionBase &q_1, 48 | uint64_t t_0, 49 | uint64_t t_1, 50 | uint64_t t) { 51 | typename Derived::Scalar temp_t = static_cast(t - t_0) 52 | / static_cast(t_1 - t_0); 53 | Derived q(q_0.coeffs() * ((typename Derived::Scalar(1.0)) - temp_t) + q_1.coeffs() * temp_t); 54 | return q.normalized(); 55 | } 56 | 57 | /*! 58 | * Quaternion Spherical Linear Interpolation 59 | * @tparam Derived 60 | * @param q_0 Quaternion start 61 | * @param q_1 Quaternion end 62 | * @param t ratio 63 | * @return 64 | */ 65 | template 66 | static Derived InterpolateQuaternionSlerp(const Eigen::QuaternionBase &q_0, 67 | const Eigen::QuaternionBase &q_1, 68 | typename Derived::Scalar t) { 69 | CHECK_LE(t, 1.0); 70 | CHECK_GE(t, 0.0); 71 | 72 | typename Derived::Scalar one = 73 | typename Derived::Scalar(1) - std::numeric_limits::epsilon(); 74 | typename Derived::Scalar d = q_0.template dot(q_1); 75 | typename Derived::Scalar abs_d = std::abs(d); 76 | 77 | typename Derived::Scalar scale_0; 78 | typename Derived::Scalar scale_1; 79 | 80 | if (abs_d >= one) { 81 | scale_0 = typename Derived::Scalar(1) - t; 82 | scale_1 = t; 83 | } else { 84 | typename Derived::Scalar theta = std::acos(abs_d); 85 | typename Derived::Scalar sin_theta = std::sin(theta); 86 | 87 | scale_0 = std::sin((typename Derived::Scalar(1) - t) * theta) / sin_theta; 88 | scale_1 = std::sin(t * theta) / sin_theta; 89 | } 90 | 91 | if (d < typename Derived::Scalar(0)) { 92 | scale_1 = -scale_1; 93 | } 94 | 95 | Derived q; 96 | q = scale_0 * q_0.coeffs() + scale_1 * q_1.coeffs(); 97 | 98 | return q; 99 | } 100 | 101 | /*! 102 | * @tparam Derived 103 | * @param q_0 Quaternion start 104 | * @param q_1 Quaternion end 105 | * @param t_0 start time 106 | * @param t_1 end time 107 | * @param t interpolated time point 108 | * @return 109 | */ 110 | template 111 | static Derived InterpolateQuaternionSlerp(const Eigen::QuaternionBase &q_0, 112 | const Eigen::QuaternionBase &q_1, 113 | uint64_t t_0, 114 | uint64_t t_1, 115 | uint64_t t) { 116 | typename Derived::Scalar temp_t = static_cast(t - t_0) 117 | / static_cast(t_1 - t_0); 118 | 119 | typename Derived::Scalar one = 120 | typename Derived::Scalar(1) - std::numeric_limits::epsilon(); 121 | typename Derived::Scalar d = q_0.template dot(q_1); 122 | typename Derived::Scalar abs_d = std::abs(d); 123 | 124 | typename Derived::Scalar scale_0; 125 | typename Derived::Scalar scale_1; 126 | 127 | if (abs_d >= one) { 128 | scale_0 = typename Derived::Scalar(1) - temp_t; 129 | scale_1 = temp_t; 130 | } else { 131 | typename Derived::Scalar theta = std::acos(abs_d); 132 | typename Derived::Scalar sin_theta = std::sin(theta); 133 | 134 | scale_0 = std::sin((typename Derived::Scalar(1) - temp_t) * theta) / sin_theta; 135 | scale_1 = std::sin(temp_t * theta) / sin_theta; 136 | } 137 | 138 | if (d < typename Derived::Scalar(0)) { 139 | scale_1 = -scale_1; 140 | } 141 | 142 | Derived q; 143 | q = scale_0 * q_0.coeffs() + scale_1 * q_1.coeffs(); 144 | 145 | return q; 146 | } 147 | 148 | 149 | /*! 150 | * Vector Normalized Linear Interpolation 151 | * @tparam Derived 152 | * @param v_0 vector star 153 | * @param v_1 vector end 154 | * @param t ration 155 | * @return 156 | */ 157 | template 158 | static Derived InterpolateVectorLerp(const Eigen::MatrixBase &v_0, 159 | const Eigen::MatrixBase &v_1, 160 | typename Derived::Scalar t) { 161 | CHECK_LE(t, 1.0); 162 | CHECK_GE(t, 0.0); 163 | 164 | return ((typename Derived::Scalar(1.0)) - t) * v_0 + t * v_1; 165 | } 166 | 167 | /*! 168 | * Vector Normalized Linear Interpolation 169 | * @tparam Derived 170 | * @param v_0 vector start 171 | * @param v_1 vector end 172 | * @param t_0 time start 173 | * @param t_1 time end 174 | * @param t interpolated time point 175 | * @return 176 | */ 177 | template 178 | static Derived InterpolateVectorLerp(const Eigen::MatrixBase &v_0, 179 | const Eigen::MatrixBase &v_1, 180 | uint64_t t_0, 181 | uint64_t t_1, 182 | uint64_t t 183 | ) { 184 | typename Derived::Scalar temp_t = static_cast(t - t_0) 185 | / static_cast(t_1 - t_0); 186 | 187 | return ((typename Derived::Scalar(1.0)) - temp_t) * v_0 + temp_t * v_1; 188 | } 189 | 190 | /*! 191 | * Vector Spherical Linear Interpolation 192 | * @tparam Derived 193 | * @param v_0 vector start 194 | * @param v_1 vector end 195 | * @param t ratio 196 | * @return 197 | */ 198 | template 199 | static Derived InterpolateVectorSlerp(const Eigen::MatrixBase &v_0, 200 | const Eigen::MatrixBase &v_1, 201 | typename Derived::Scalar t) { 202 | CHECK_LE(t, 1.0); 203 | CHECK_GE(t, 0.0); 204 | 205 | typename Derived::Scalar theta = std::acos(v_0.dot(v_1)); 206 | 207 | Derived v; 208 | 209 | v = std::sin(((typename Derived::Scalar(1.0)) - t) * theta) / std::sin(theta) * v_0 210 | + std::sin(t * theta) / std::sin(theta) * v_1; 211 | 212 | return v; 213 | } 214 | 215 | /*! 216 | * Vector Spherical Linear Interpolation 217 | * @tparam Derived 218 | * @param v_0 vector start 219 | * @param v_1 vector end 220 | * @param t_0 time start 221 | * @param t_1 time end 222 | * @param t interpolated time point 223 | * @return 224 | */ 225 | template 226 | static Derived InterpolateVectorSlerp(const Eigen::MatrixBase &v_0, 227 | const Eigen::MatrixBase &v_1, 228 | uint64_t t_0, 229 | uint64_t t_1, 230 | uint64_t t) { 231 | typename Derived::Scalar temp_t = static_cast(t - t_0) 232 | / static_cast(t_1 - t_0); 233 | 234 | typename Derived::Scalar theta = std::acos(v_0.dot(v_1)); 235 | 236 | Derived v; 237 | v = std::sin(((typename Derived::Scalar(1.0)) - temp_t) * theta) / std::sin(theta) * v_0 238 | + std::sin(temp_t * theta) / std::sin(theta) * v_1; 239 | 240 | return v; 241 | } 242 | 243 | MotionInterpolator() = delete; 244 | 245 | MotionInterpolator(MotionInterpolator &) = delete; 246 | 247 | ~MotionInterpolator() = delete; 248 | }; 249 | 250 | #endif //GTSAM_TEST_MOTION_INTERPOLATOR_H 251 | -------------------------------------------------------------------------------- /gps_imu_fusion_gtsam/pre_integration_data_preparer.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Created by meng on 24-1-17. 3 | // 4 | #include "pre_integration_data_preparer.h" 5 | #include "motion_interpolator.h" 6 | 7 | void PreIntegrationDataPreparer::CacheData(IMUData imu_data) { 8 | std::lock_guard lg(mutex_); 9 | imu_data_deque_.emplace_back(std::move(imu_data)); 10 | } 11 | 12 | std::vector PreIntegrationDataPreparer::GetDataSegment(uint64_t timestamp_left, 13 | uint64_t timestamp_right) { 14 | if (timestamp_left >= timestamp_right) { 15 | return {}; 16 | } 17 | 18 | std::lock_guard lg(mutex_); 19 | 20 | if (imu_data_deque_.front().timestamp_ > timestamp_left || 21 | imu_data_deque_.back().timestamp_ < timestamp_right) { 22 | return {}; 23 | } 24 | 25 | std::vector data_segment; 26 | 27 | while (!imu_data_deque_.empty()) { 28 | 29 | if (imu_data_deque_.size() < 2) { 30 | return {}; 31 | } 32 | 33 | auto &first_data = imu_data_deque_.at(0); 34 | auto &second_data = imu_data_deque_.at(1); 35 | 36 | if (first_data.timestamp_ == timestamp_left) { 37 | data_segment.emplace_back(imu_data_deque_.front()); 38 | imu_data_deque_.pop_front(); 39 | break; 40 | } 41 | 42 | if (first_data.timestamp_ < timestamp_left && 43 | second_data.timestamp_ > timestamp_left) { 44 | 45 | IMUData imu_data; 46 | imu_data.linear_acceleration_ = MotionInterpolator::InterpolateVectorLerp(first_data.linear_acceleration_, 47 | second_data.linear_acceleration_, 48 | first_data.timestamp_, 49 | second_data.timestamp_, 50 | timestamp_left); 51 | 52 | imu_data.angular_velocity_ = MotionInterpolator::InterpolateVectorLerp(first_data.angular_velocity_, 53 | second_data.angular_velocity_, 54 | first_data.timestamp_, 55 | second_data.timestamp_, 56 | timestamp_left); 57 | 58 | imu_data.orientation_ = MotionInterpolator::InterpolateQuaternionSlerp(first_data.orientation_, 59 | second_data.orientation_, 60 | first_data.timestamp_, 61 | second_data.timestamp_, 62 | timestamp_left); 63 | 64 | imu_data.timestamp_ = timestamp_left; 65 | 66 | data_segment.emplace_back(std::move(imu_data)); 67 | imu_data_deque_.pop_front(); 68 | break; 69 | } 70 | imu_data_deque_.pop_front(); 71 | } 72 | 73 | while (!imu_data_deque_.empty()) { 74 | 75 | if (imu_data_deque_.size() < 2) { 76 | return {}; 77 | } 78 | 79 | auto &first_data = imu_data_deque_.at(0); 80 | auto &second_data = imu_data_deque_.at(1); 81 | 82 | if (first_data.timestamp_ == timestamp_right) { 83 | data_segment.emplace_back(std::move(imu_data_deque_.front())); 84 | break; 85 | } 86 | 87 | if (first_data.timestamp_ < timestamp_right && 88 | second_data.timestamp_ > timestamp_right) { 89 | 90 | IMUData imu_data; 91 | imu_data.linear_acceleration_ = MotionInterpolator::InterpolateVectorLerp(first_data.linear_acceleration_, 92 | second_data.linear_acceleration_, 93 | first_data.timestamp_, 94 | second_data.timestamp_, 95 | timestamp_right); 96 | 97 | imu_data.angular_velocity_ = MotionInterpolator::InterpolateVectorLerp(first_data.angular_velocity_, 98 | second_data.angular_velocity_, 99 | first_data.timestamp_, 100 | second_data.timestamp_, 101 | timestamp_right); 102 | 103 | imu_data.orientation_ = MotionInterpolator::InterpolateQuaternionSlerp(first_data.orientation_, 104 | second_data.orientation_, 105 | first_data.timestamp_, 106 | second_data.timestamp_, 107 | timestamp_right); 108 | 109 | imu_data.timestamp_ = timestamp_right; 110 | 111 | data_segment.emplace_back(std::move(imu_data)); 112 | break; 113 | } 114 | 115 | data_segment.emplace_back(imu_data_deque_.front()); 116 | imu_data_deque_.pop_front(); 117 | } 118 | 119 | return data_segment; 120 | } -------------------------------------------------------------------------------- /gps_imu_fusion_gtsam/pre_integration_data_preparer.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by meng on 24-1-17. 3 | // 4 | #ifndef GTSAM_TEST_PRE_INTEGRATION_DATA_PREPARER_H 5 | #define GTSAM_TEST_PRE_INTEGRATION_DATA_PREPARER_H 6 | 7 | #include "type.h" 8 | 9 | #include 10 | #include 11 | 12 | /*! 13 | * 用于从队列中去除一个时间段内的数据 14 | */ 15 | class PreIntegrationDataPreparer { 16 | public: 17 | PreIntegrationDataPreparer() = default; 18 | 19 | void CacheData(IMUData imu_data); 20 | 21 | std::vector GetDataSegment(uint64_t timestamp_left, uint64_t timestamp_right); 22 | 23 | private: 24 | std::mutex mutex_; 25 | std::deque imu_data_deque_; 26 | }; 27 | 28 | #endif //GTSAM_TEST_PRE_INTEGRATION_DATA_PREPARER_H 29 | -------------------------------------------------------------------------------- /gps_imu_fusion_gtsam/result/display_path.py: -------------------------------------------------------------------------------- 1 | import numpy as np 2 | import matplotlib.pyplot as plt 3 | 4 | 5 | def load_txt_data(data_path): 6 | try: 7 | return np.loadtxt(data_path) 8 | except FileNotFoundError as err: 9 | print('this is a OSError: ' + str(err)) 10 | 11 | 12 | fuse_path_data = load_txt_data('./fuse_path.txt') 13 | gt_path_data = load_txt_data('./gt_path.txt') 14 | gps_measure_data = load_txt_data('./gps_measure.txt') 15 | imu_bias_data = load_txt_data('./imu_bias.txt') 16 | 17 | plt.figure(0) 18 | plt.plot(fuse_path_data[:, 1], fuse_path_data[:, 2], color='g', linestyle='-', label='fuse_path') 19 | plt.plot(gt_path_data[:, 1], gt_path_data[:, 2], color='r', linestyle='--', label='gt_path') 20 | plt.scatter(gps_measure_data[:, 1], gps_measure_data[:, 2], color='b', label='gps_measure', s=3) 21 | plt.title("path") 22 | plt.legend() 23 | 24 | f, ax = plt.subplots(2, 3) 25 | ax[0, 0].axhline(imu_bias_data[0, 0], color='r', label='acc_bias_x_gt') 26 | ax[0, 0].plot(imu_bias_data[1:-1, 0], color='g', label='acc_bias_x') 27 | ax[0, 0].set_title('acc bias x') 28 | 29 | ax[0, 1].axhline(imu_bias_data[0, 1], color='r', label='acc_bias_y_gt') 30 | ax[0, 1].plot(imu_bias_data[1:-1, 1], color='g', label='acc_bias_y') 31 | ax[0, 1].set_title('acc bias y') 32 | 33 | ax[0, 2].axhline(imu_bias_data[0, 2], color='r', label='acc_bias_z_gt') 34 | ax[0, 2].plot(imu_bias_data[1:-1, 2], color='g', label='acc_bias_z') 35 | ax[0, 2].set_title('acc bias z') 36 | 37 | ax[1, 0].axhline(imu_bias_data[0, 3], color='r', label='gyro_bias_x_gt') 38 | ax[1, 0].plot(imu_bias_data[1:-1, 3], color='g', label='gyro_bias_x') 39 | ax[1, 0].set_title('gyro bias x') 40 | 41 | ax[1, 1].axhline(imu_bias_data[0, 4], color='r', label='gyro_bias_y_gt') 42 | ax[1, 1].plot(imu_bias_data[1:-1, 4], color='g', label='gyro_bias_y') 43 | ax[1, 1].set_title('gyro bias y') 44 | 45 | ax[1, 2].axhline(imu_bias_data[0, 5], color='r', label='gyro_bias_z_gt') 46 | ax[1, 2].plot(imu_bias_data[1:-1, 5], color='g', label='gyro_bias_z') 47 | ax[1, 2].set_title('gyro bias z') 48 | plt.show() 49 | -------------------------------------------------------------------------------- /gps_imu_fusion_gtsam/type.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by meng on 24-1-17. 3 | // 4 | 5 | #ifndef GTSAM_TEST_TYPE_H 6 | #define GTSAM_TEST_TYPE_H 7 | 8 | #include 9 | 10 | #define kDegree2Radian (M_PI / 180.0) 11 | 12 | using Vec3d = Eigen::Vector3d; 13 | using Mat3d = Eigen::Matrix3d; 14 | 15 | template 16 | inline Eigen::Matrix Hat(const Eigen::MatrixBase &v) { 17 | eigen_assert(v.size() == 3u); 18 | 19 | Eigen::Matrix skew_mat; 20 | skew_mat.setZero(); 21 | skew_mat(0, 1) = -v(2); 22 | skew_mat(0, 2) = +v(1); 23 | skew_mat(1, 2) = -v(0); 24 | skew_mat(1, 0) = +v(2); 25 | skew_mat(2, 0) = -v(1); 26 | skew_mat(2, 1) = +v(0); 27 | return skew_mat; 28 | } 29 | 30 | template 31 | inline Eigen::Matrix SO3Exp(const Eigen::MatrixBase &v) { 32 | eigen_assert(v.size() == 3u); 33 | 34 | Eigen::Matrix R = Eigen::Matrix::Identity(); 35 | typename Derived::Scalar theta = v.norm(); 36 | 37 | if (theta * theta > std::numeric_limits::epsilon()) { 38 | Eigen::Matrix v_normalized = v.normalized(); 39 | R = std::cos(theta) * Eigen::Matrix::Identity() 40 | + (typename Derived::Scalar(1.0) - std::cos(theta)) * v_normalized * 41 | v_normalized.transpose() + std::sin(theta) * Hat(v_normalized); 42 | return R; 43 | } else { 44 | return R; 45 | } 46 | } 47 | 48 | struct DataBase { 49 | uint64_t timestamp_ = 0u; // us 50 | }; 51 | 52 | struct NavStateDataMy : public DataBase { 53 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 54 | 55 | Vec3d P_ = Vec3d::Zero(); 56 | Vec3d V_ = Vec3d::Zero(); 57 | Mat3d R_ = Mat3d::Identity(); 58 | 59 | Vec3d bg_ = Vec3d::Zero(); // gyro bias 60 | Vec3d ba_ = Vec3d::Zero(); // accel bias 61 | }; 62 | 63 | struct IMUData : public DataBase { 64 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 65 | 66 | Vec3d angular_velocity_ = Vec3d::Zero(); 67 | Vec3d linear_acceleration_ = Vec3d::Zero(); 68 | Eigen::Quaterniond orientation_ = Eigen::Quaterniond::Identity(); 69 | }; 70 | 71 | struct GPSData : public DataBase { 72 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 73 | 74 | double longitude_{0.0}; 75 | double latitude_{0.0}; 76 | double altitude_{0.0}; 77 | 78 | Vec3d local_xyz_ = Vec3d::Zero(); 79 | Vec3d local_xyz_velocity_ = Vec3d::Zero(); 80 | Mat3d local_orientation = Mat3d::Identity(); 81 | 82 | Vec3d local_xyz_true_ = Vec3d::Zero(); 83 | Vec3d local_xyz_velocity_true_ = Vec3d::Zero(); 84 | Mat3d local_orientation_true_ = Mat3d::Identity(); 85 | }; 86 | 87 | #endif //GTSAM_TEST_TYPE_H 88 | -------------------------------------------------------------------------------- /model_predictive_control/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.10) 2 | project(model_predictive_control) 3 | 4 | include(CheckCXXCompilerFlag) 5 | CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11) 6 | CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X) 7 | 8 | if (COMPILER_SUPPORTS_CXX11) 9 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") 10 | elseif (COMPILER_SUPPORTS_CXX0X) 11 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x") 12 | else () 13 | message(FATAL_ERROR "The compiler ${CMAKE_CXX_FLAGS} doesn't have C++11 support. 14 | Please use a different C++ compiler") 15 | endif () 16 | 17 | set(ADDITIONAL_CXX_FLAG "-Wall -O3 -march=native") 18 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${ADDITIONAL_CXX_FLAG}") 19 | 20 | find_package(Eigen3 REQUIRED) 21 | find_package(PythonLibs 2.7 COMPONENTS Development NumPy) 22 | 23 | include_directories(${EIGEN3_INCLUDE_DIRS}) 24 | 25 | add_executable(model_predictive_control main.cpp) 26 | target_include_directories(model_predictive_control PRIVATE ${PYTHON_INCLUDE_DIRS}) 27 | target_link_libraries(model_predictive_control ${PYTHON_LIBRARIES}) 28 | -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-16-58 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-16-58 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-17-31 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-17-31 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-18-44 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-18-44 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-19-25 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-19-25 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-20-08 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-20-08 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-20-52 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-20-52 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-23-31 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-23-31 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-24-10 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-24-10 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-26-53 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-26-53 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-27-39 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-27-39 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-28-31 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-28-31 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-29-22 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-29-22 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-30-06 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-30-06 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-33-56 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-33-56 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-34-59 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-34-59 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-35-41 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-35-41 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-36-34 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-36-34 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-39-52 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-39-52 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-41-09 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-41-09 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-44-17 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-44-17 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-44-51 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-44-51 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/images/2022-02-06 16-45-44 的屏幕截图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/model_predictive_control/images/2022-02-06 16-45-44 的屏幕截图.png -------------------------------------------------------------------------------- /model_predictive_control/main.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | 4 | #include "matplotlibcpp.h" 5 | 6 | namespace plt = matplotlibcpp; 7 | 8 | #include 9 | 10 | Eigen::VectorXd RunMPC(unsigned int N, Eigen::VectorXd &init_x, Eigen::MatrixXd &A, Eigen::MatrixXd &B, 11 | Eigen::MatrixXd &Q, Eigen::MatrixXd &R, Eigen::MatrixXd &F) { 12 | 13 | unsigned int num_state = init_x.rows(); 14 | unsigned int num_control = B.cols(); 15 | 16 | Eigen::MatrixXd C, M; 17 | C.resize((N + 1) * num_state, num_control * N); 18 | C.setZero(); 19 | M.resize((N + 1) * num_state, num_state); 20 | Eigen::MatrixXd temp; 21 | temp.resize(num_state, num_state); 22 | temp.setIdentity(); 23 | M.block(0, 0, num_state, num_state).setIdentity(); 24 | for (unsigned int i = 1; i <= N; ++i) { 25 | Eigen::MatrixXd temp_c; 26 | temp_c.resize(num_state, (N + 1) * num_control); 27 | temp_c << temp * B, C.block(num_state * (i - 1), 0, num_state, C.cols()); 28 | 29 | C.block(num_state * i, 0, num_state, C.cols()) 30 | = temp_c.block(0, 0, num_state, temp_c.cols() - num_control); 31 | 32 | temp = A * temp; 33 | M.block(num_state * i, 0, num_state, num_state) = temp; 34 | } 35 | 36 | Eigen::MatrixXd Q_bar, R_bar; 37 | 38 | Q_bar.resize(num_state * (N + 1), num_state * (N + 1)); 39 | Q_bar.setZero(); 40 | for (unsigned int i = 0; i < N; ++i) { 41 | Q_bar.block(num_state * i, num_state * i, num_state, num_state) = Q; 42 | } 43 | Q_bar.block(num_state * N, num_state * N, num_state, num_state) = F; 44 | 45 | R_bar.resize(N * num_control, N * num_control); 46 | R_bar.setZero(); 47 | for (unsigned int i = 0; i < N; ++i) { 48 | R_bar.block(i * num_control, i * num_control, num_control, num_control) = R; 49 | } 50 | 51 | Eigen::MatrixXd G = M.transpose() * Q_bar * M; 52 | Eigen::MatrixXd E = C.transpose() * Q_bar * M; 53 | Eigen::MatrixXd H = C.transpose() * Q_bar * C + R_bar; 54 | 55 | return H.inverse() * (-E * init_x); 56 | } 57 | 58 | int main() { 59 | Eigen::MatrixXd A, B; 60 | A.resize(2, 2); 61 | B.resize(2, 1); 62 | A << 1, 0.1, 0, 2; 63 | B << 0, 0.5; 64 | 65 | unsigned int num_state = 2; 66 | Eigen::MatrixXd Q, R, F; 67 | Q.resize(num_state, num_state); 68 | Q << 1, 0, 0, 1; 69 | 70 | R.resize(1, 1); 71 | R << 0.1; 72 | 73 | F.resize(num_state, num_state); 74 | F << 2, 0, 0, 2; 75 | 76 | const unsigned int N = 3; 77 | Eigen::VectorXd init_x; 78 | init_x.resize(2, 1); 79 | init_x << 5.0, 5.0; 80 | 81 | std::vector state_0; 82 | std::vector time; 83 | state_0.emplace_back(init_x.x()); 84 | time.emplace_back(0.0); 85 | 86 | for (unsigned int i = 0; i < 200; ++i) { 87 | std::cout << "error: " << init_x.transpose() << std::endl; 88 | std::chrono::steady_clock::time_point start_time = std::chrono::steady_clock::now(); 89 | Eigen::VectorXd control = RunMPC(N, init_x, A, B, Q, R, F); 90 | std::chrono::steady_clock::time_point end_time = std::chrono::steady_clock::now(); 91 | std::chrono::duration used_time = (end_time - start_time); 92 | std::cout << "Once mpc use time(ms): " << used_time.count() * 1000 << std::endl; 93 | init_x = A * init_x + B * control.x(); 94 | state_0.emplace_back(init_x.x()); 95 | time.emplace_back(0.1 * (i + 1)); 96 | } 97 | 98 | plt::plot(time, state_0, "ro"); 99 | plt::xlim(-0.0, 20.0); 100 | plt::ylim(-0.0, 7.0); 101 | plt::title("MPC"); 102 | plt::show(); 103 | 104 | // std::cout << "closed form u: " << control.transpose() << std::endl; 105 | 106 | return 0; 107 | } 108 | -------------------------------------------------------------------------------- /model_predictive_control/matplotlibcpp.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | // Python headers must be included before any system headers, since 4 | // they define _POSIX_C_SOURCE 5 | #include 6 | 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include // requires c++11 support 15 | #include 16 | #include // std::stod 17 | 18 | #ifndef WITHOUT_NUMPY 19 | # define NPY_NO_DEPRECATED_API NPY_1_7_API_VERSION 20 | # include 21 | 22 | # ifdef WITH_OPENCV 23 | # include 24 | # endif // WITH_OPENCV 25 | 26 | /* 27 | * A bunch of constants were removed in OpenCV 4 in favour of enum classes, so 28 | * define the ones we need here. 29 | */ 30 | # if CV_MAJOR_VERSION > 3 31 | # define CV_BGR2RGB cv::COLOR_BGR2RGB 32 | # define CV_BGRA2RGBA cv::COLOR_BGRA2RGBA 33 | # endif 34 | #endif // WITHOUT_NUMPY 35 | 36 | #if PY_MAJOR_VERSION >= 3 37 | # define PyString_FromString PyUnicode_FromString 38 | # define PyInt_FromLong PyLong_FromLong 39 | # define PyString_FromString PyUnicode_FromString 40 | #endif 41 | 42 | 43 | namespace matplotlibcpp { 44 | namespace detail { 45 | 46 | static std::string s_backend; 47 | 48 | struct _interpreter { 49 | PyObject* s_python_function_arrow; 50 | PyObject *s_python_function_show; 51 | PyObject *s_python_function_close; 52 | PyObject *s_python_function_draw; 53 | PyObject *s_python_function_pause; 54 | PyObject *s_python_function_save; 55 | PyObject *s_python_function_figure; 56 | PyObject *s_python_function_fignum_exists; 57 | PyObject *s_python_function_plot; 58 | PyObject *s_python_function_quiver; 59 | PyObject* s_python_function_contour; 60 | PyObject *s_python_function_semilogx; 61 | PyObject *s_python_function_semilogy; 62 | PyObject *s_python_function_loglog; 63 | PyObject *s_python_function_fill; 64 | PyObject *s_python_function_fill_between; 65 | PyObject *s_python_function_hist; 66 | PyObject *s_python_function_imshow; 67 | PyObject *s_python_function_scatter; 68 | PyObject *s_python_function_boxplot; 69 | PyObject *s_python_function_subplot; 70 | PyObject *s_python_function_subplot2grid; 71 | PyObject *s_python_function_legend; 72 | PyObject *s_python_function_xlim; 73 | PyObject *s_python_function_ion; 74 | PyObject *s_python_function_ginput; 75 | PyObject *s_python_function_ylim; 76 | PyObject *s_python_function_title; 77 | PyObject *s_python_function_axis; 78 | PyObject *s_python_function_axhline; 79 | PyObject *s_python_function_axvline; 80 | PyObject *s_python_function_axvspan; 81 | PyObject *s_python_function_xlabel; 82 | PyObject *s_python_function_ylabel; 83 | PyObject *s_python_function_gca; 84 | PyObject *s_python_function_xticks; 85 | PyObject *s_python_function_yticks; 86 | PyObject* s_python_function_margins; 87 | PyObject *s_python_function_tick_params; 88 | PyObject *s_python_function_grid; 89 | PyObject* s_python_function_cla; 90 | PyObject *s_python_function_clf; 91 | PyObject *s_python_function_errorbar; 92 | PyObject *s_python_function_annotate; 93 | PyObject *s_python_function_tight_layout; 94 | PyObject *s_python_colormap; 95 | PyObject *s_python_empty_tuple; 96 | PyObject *s_python_function_stem; 97 | PyObject *s_python_function_xkcd; 98 | PyObject *s_python_function_text; 99 | PyObject *s_python_function_suptitle; 100 | PyObject *s_python_function_bar; 101 | PyObject *s_python_function_barh; 102 | PyObject *s_python_function_colorbar; 103 | PyObject *s_python_function_subplots_adjust; 104 | PyObject *s_python_function_rcparams; 105 | PyObject *s_python_function_spy; 106 | 107 | /* For now, _interpreter is implemented as a singleton since its currently not possible to have 108 | multiple independent embedded python interpreters without patching the python source code 109 | or starting a separate process for each. [1] 110 | Furthermore, many python objects expect that they are destructed in the same thread as they 111 | were constructed. [2] So for advanced usage, a `kill()` function is provided so that library 112 | users can manually ensure that the interpreter is constructed and destroyed within the 113 | same thread. 114 | 115 | 1: http://bytes.com/topic/python/answers/793370-multiple-independent-python-interpreters-c-c-program 116 | 2: https://github.com/lava/matplotlib-cpp/pull/202#issue-436220256 117 | */ 118 | 119 | static _interpreter& get() { 120 | return interkeeper(false); 121 | } 122 | 123 | static _interpreter& kill() { 124 | return interkeeper(true); 125 | } 126 | 127 | // Stores the actual singleton object referenced by `get()` and `kill()`. 128 | static _interpreter& interkeeper(bool should_kill) { 129 | static _interpreter ctx; 130 | if (should_kill) 131 | ctx.~_interpreter(); 132 | return ctx; 133 | } 134 | 135 | PyObject* safe_import(PyObject* module, std::string fname) { 136 | PyObject* fn = PyObject_GetAttrString(module, fname.c_str()); 137 | 138 | if (!fn) 139 | throw std::runtime_error(std::string("Couldn't find required function: ") + fname); 140 | 141 | if (!PyFunction_Check(fn)) 142 | throw std::runtime_error(fname + std::string(" is unexpectedly not a PyFunction.")); 143 | 144 | return fn; 145 | } 146 | 147 | private: 148 | 149 | #ifndef WITHOUT_NUMPY 150 | # if PY_MAJOR_VERSION >= 3 151 | 152 | void *import_numpy() { 153 | import_array(); // initialize C-API 154 | return NULL; 155 | } 156 | 157 | # else 158 | 159 | void import_numpy() { 160 | import_array(); // initialize C-API 161 | } 162 | 163 | # endif 164 | #endif 165 | 166 | _interpreter() { 167 | 168 | // optional but recommended 169 | #if PY_MAJOR_VERSION >= 3 170 | wchar_t name[] = L"plotting"; 171 | #else 172 | char name[] = "plotting"; 173 | #endif 174 | Py_SetProgramName(name); 175 | Py_Initialize(); 176 | 177 | wchar_t const *dummy_args[] = {L"Python", NULL}; // const is needed because literals must not be modified 178 | wchar_t const **argv = dummy_args; 179 | int argc = sizeof(dummy_args)/sizeof(dummy_args[0])-1; 180 | 181 | #if PY_MAJOR_VERSION >= 3 182 | PySys_SetArgv(argc, const_cast(argv)); 183 | #else 184 | PySys_SetArgv(argc, (char **)(argv)); 185 | #endif 186 | 187 | #ifndef WITHOUT_NUMPY 188 | import_numpy(); // initialize numpy C-API 189 | #endif 190 | 191 | PyObject* matplotlibname = PyString_FromString("matplotlib"); 192 | PyObject* pyplotname = PyString_FromString("matplotlib.pyplot"); 193 | PyObject* cmname = PyString_FromString("matplotlib.cm"); 194 | PyObject* pylabname = PyString_FromString("pylab"); 195 | if (!pyplotname || !pylabname || !matplotlibname || !cmname) { 196 | throw std::runtime_error("couldnt create string"); 197 | } 198 | 199 | PyObject* matplotlib = PyImport_Import(matplotlibname); 200 | 201 | Py_DECREF(matplotlibname); 202 | if (!matplotlib) { 203 | PyErr_Print(); 204 | throw std::runtime_error("Error loading module matplotlib!"); 205 | } 206 | 207 | // matplotlib.use() must be called *before* pylab, matplotlib.pyplot, 208 | // or matplotlib.backends is imported for the first time 209 | if (!s_backend.empty()) { 210 | PyObject_CallMethod(matplotlib, const_cast("use"), const_cast("s"), s_backend.c_str()); 211 | } 212 | 213 | 214 | 215 | PyObject* pymod = PyImport_Import(pyplotname); 216 | Py_DECREF(pyplotname); 217 | if (!pymod) { throw std::runtime_error("Error loading module matplotlib.pyplot!"); } 218 | 219 | s_python_colormap = PyImport_Import(cmname); 220 | Py_DECREF(cmname); 221 | if (!s_python_colormap) { throw std::runtime_error("Error loading module matplotlib.cm!"); } 222 | 223 | PyObject* pylabmod = PyImport_Import(pylabname); 224 | Py_DECREF(pylabname); 225 | if (!pylabmod) { throw std::runtime_error("Error loading module pylab!"); } 226 | 227 | s_python_function_arrow = safe_import(pymod, "arrow"); 228 | s_python_function_show = safe_import(pymod, "show"); 229 | s_python_function_close = safe_import(pymod, "close"); 230 | s_python_function_draw = safe_import(pymod, "draw"); 231 | s_python_function_pause = safe_import(pymod, "pause"); 232 | s_python_function_figure = safe_import(pymod, "figure"); 233 | s_python_function_fignum_exists = safe_import(pymod, "fignum_exists"); 234 | s_python_function_plot = safe_import(pymod, "plot"); 235 | s_python_function_quiver = safe_import(pymod, "quiver"); 236 | s_python_function_contour = safe_import(pymod, "contour"); 237 | s_python_function_semilogx = safe_import(pymod, "semilogx"); 238 | s_python_function_semilogy = safe_import(pymod, "semilogy"); 239 | s_python_function_loglog = safe_import(pymod, "loglog"); 240 | s_python_function_fill = safe_import(pymod, "fill"); 241 | s_python_function_fill_between = safe_import(pymod, "fill_between"); 242 | s_python_function_hist = safe_import(pymod,"hist"); 243 | s_python_function_scatter = safe_import(pymod,"scatter"); 244 | s_python_function_boxplot = safe_import(pymod,"boxplot"); 245 | s_python_function_subplot = safe_import(pymod, "subplot"); 246 | s_python_function_subplot2grid = safe_import(pymod, "subplot2grid"); 247 | s_python_function_legend = safe_import(pymod, "legend"); 248 | s_python_function_xlim = safe_import(pymod, "xlim"); 249 | s_python_function_ylim = safe_import(pymod, "ylim"); 250 | s_python_function_title = safe_import(pymod, "title"); 251 | s_python_function_axis = safe_import(pymod, "axis"); 252 | s_python_function_axhline = safe_import(pymod, "axhline"); 253 | s_python_function_axvline = safe_import(pymod, "axvline"); 254 | s_python_function_axvspan = safe_import(pymod, "axvspan"); 255 | s_python_function_xlabel = safe_import(pymod, "xlabel"); 256 | s_python_function_ylabel = safe_import(pymod, "ylabel"); 257 | s_python_function_gca = safe_import(pymod, "gca"); 258 | s_python_function_xticks = safe_import(pymod, "xticks"); 259 | s_python_function_yticks = safe_import(pymod, "yticks"); 260 | s_python_function_margins = safe_import(pymod, "margins"); 261 | s_python_function_tick_params = safe_import(pymod, "tick_params"); 262 | s_python_function_grid = safe_import(pymod, "grid"); 263 | s_python_function_ion = safe_import(pymod, "ion"); 264 | s_python_function_ginput = safe_import(pymod, "ginput"); 265 | s_python_function_save = safe_import(pylabmod, "savefig"); 266 | s_python_function_annotate = safe_import(pymod,"annotate"); 267 | s_python_function_cla = safe_import(pymod, "cla"); 268 | s_python_function_clf = safe_import(pymod, "clf"); 269 | s_python_function_errorbar = safe_import(pymod, "errorbar"); 270 | s_python_function_tight_layout = safe_import(pymod, "tight_layout"); 271 | s_python_function_stem = safe_import(pymod, "stem"); 272 | s_python_function_xkcd = safe_import(pymod, "xkcd"); 273 | s_python_function_text = safe_import(pymod, "text"); 274 | s_python_function_suptitle = safe_import(pymod, "suptitle"); 275 | s_python_function_bar = safe_import(pymod,"bar"); 276 | s_python_function_barh = safe_import(pymod, "barh"); 277 | s_python_function_colorbar = PyObject_GetAttrString(pymod, "colorbar"); 278 | s_python_function_subplots_adjust = safe_import(pymod,"subplots_adjust"); 279 | s_python_function_rcparams = PyObject_GetAttrString(pymod, "rcParams"); 280 | s_python_function_spy = PyObject_GetAttrString(pymod, "spy"); 281 | #ifndef WITHOUT_NUMPY 282 | s_python_function_imshow = safe_import(pymod, "imshow"); 283 | #endif 284 | s_python_empty_tuple = PyTuple_New(0); 285 | } 286 | 287 | ~_interpreter() { 288 | Py_Finalize(); 289 | } 290 | }; 291 | 292 | } // end namespace detail 293 | 294 | /// Select the backend 295 | /// 296 | /// **NOTE:** This must be called before the first plot command to have 297 | /// any effect. 298 | /// 299 | /// Mainly useful to select the non-interactive 'Agg' backend when running 300 | /// matplotlibcpp in headless mode, for example on a machine with no display. 301 | /// 302 | /// See also: https://matplotlib.org/2.0.2/api/matplotlib_configuration_api.html#matplotlib.use 303 | inline void backend(const std::string& name) 304 | { 305 | detail::s_backend = name; 306 | } 307 | 308 | inline bool annotate(std::string annotation, double x, double y) 309 | { 310 | detail::_interpreter::get(); 311 | 312 | PyObject * xy = PyTuple_New(2); 313 | PyObject * str = PyString_FromString(annotation.c_str()); 314 | 315 | PyTuple_SetItem(xy,0,PyFloat_FromDouble(x)); 316 | PyTuple_SetItem(xy,1,PyFloat_FromDouble(y)); 317 | 318 | PyObject* kwargs = PyDict_New(); 319 | PyDict_SetItemString(kwargs, "xy", xy); 320 | 321 | PyObject* args = PyTuple_New(1); 322 | PyTuple_SetItem(args, 0, str); 323 | 324 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_annotate, args, kwargs); 325 | 326 | Py_DECREF(args); 327 | Py_DECREF(kwargs); 328 | 329 | if(res) Py_DECREF(res); 330 | 331 | return res; 332 | } 333 | 334 | namespace detail { 335 | 336 | #ifndef WITHOUT_NUMPY 337 | // Type selector for numpy array conversion 338 | template struct select_npy_type { const static NPY_TYPES type = NPY_NOTYPE; }; //Default 339 | template <> struct select_npy_type { const static NPY_TYPES type = NPY_DOUBLE; }; 340 | template <> struct select_npy_type { const static NPY_TYPES type = NPY_FLOAT; }; 341 | template <> struct select_npy_type { const static NPY_TYPES type = NPY_BOOL; }; 342 | template <> struct select_npy_type { const static NPY_TYPES type = NPY_INT8; }; 343 | template <> struct select_npy_type { const static NPY_TYPES type = NPY_SHORT; }; 344 | template <> struct select_npy_type { const static NPY_TYPES type = NPY_INT; }; 345 | template <> struct select_npy_type { const static NPY_TYPES type = NPY_INT64; }; 346 | template <> struct select_npy_type { const static NPY_TYPES type = NPY_UINT8; }; 347 | template <> struct select_npy_type { const static NPY_TYPES type = NPY_USHORT; }; 348 | template <> struct select_npy_type { const static NPY_TYPES type = NPY_ULONG; }; 349 | template <> struct select_npy_type { const static NPY_TYPES type = NPY_UINT64; }; 350 | 351 | // Sanity checks; comment them out or change the numpy type below if you're compiling on 352 | // a platform where they don't apply 353 | static_assert(sizeof(long long) == 8); 354 | template <> struct select_npy_type { const static NPY_TYPES type = NPY_INT64; }; 355 | static_assert(sizeof(unsigned long long) == 8); 356 | template <> struct select_npy_type { const static NPY_TYPES type = NPY_UINT64; }; 357 | 358 | template 359 | PyObject* get_array(const std::vector& v) 360 | { 361 | npy_intp vsize = v.size(); 362 | NPY_TYPES type = select_npy_type::type; 363 | if (type == NPY_NOTYPE) { 364 | size_t memsize = v.size()*sizeof(double); 365 | double* dp = static_cast(::malloc(memsize)); 366 | for (size_t i=0; i(varray), NPY_ARRAY_OWNDATA); 370 | return varray; 371 | } 372 | 373 | PyObject* varray = PyArray_SimpleNewFromData(1, &vsize, type, (void*)(v.data())); 374 | return varray; 375 | } 376 | 377 | 378 | template 379 | PyObject* get_2darray(const std::vector<::std::vector>& v) 380 | { 381 | if (v.size() < 1) throw std::runtime_error("get_2d_array v too small"); 382 | 383 | npy_intp vsize[2] = {static_cast(v.size()), 384 | static_cast(v[0].size())}; 385 | 386 | PyArrayObject *varray = 387 | (PyArrayObject *)PyArray_SimpleNew(2, vsize, NPY_DOUBLE); 388 | 389 | double *vd_begin = static_cast(PyArray_DATA(varray)); 390 | 391 | for (const ::std::vector &v_row : v) { 392 | if (v_row.size() != static_cast(vsize[1])) 393 | throw std::runtime_error("Missmatched array size"); 394 | std::copy(v_row.begin(), v_row.end(), vd_begin); 395 | vd_begin += vsize[1]; 396 | } 397 | 398 | return reinterpret_cast(varray); 399 | } 400 | 401 | #else // fallback if we don't have numpy: copy every element of the given vector 402 | 403 | template 404 | PyObject* get_array(const std::vector& v) 405 | { 406 | PyObject* list = PyList_New(v.size()); 407 | for(size_t i = 0; i < v.size(); ++i) { 408 | PyList_SetItem(list, i, PyFloat_FromDouble(v.at(i))); 409 | } 410 | return list; 411 | } 412 | 413 | #endif // WITHOUT_NUMPY 414 | 415 | // sometimes, for labels and such, we need string arrays 416 | inline PyObject * get_array(const std::vector& strings) 417 | { 418 | PyObject* list = PyList_New(strings.size()); 419 | for (std::size_t i = 0; i < strings.size(); ++i) { 420 | PyList_SetItem(list, i, PyString_FromString(strings[i].c_str())); 421 | } 422 | return list; 423 | } 424 | 425 | // not all matplotlib need 2d arrays, some prefer lists of lists 426 | template 427 | PyObject* get_listlist(const std::vector>& ll) 428 | { 429 | PyObject* listlist = PyList_New(ll.size()); 430 | for (std::size_t i = 0; i < ll.size(); ++i) { 431 | PyList_SetItem(listlist, i, get_array(ll[i])); 432 | } 433 | return listlist; 434 | } 435 | 436 | } // namespace detail 437 | 438 | /// Plot a line through the given x and y data points.. 439 | /// 440 | /// See: https://matplotlib.org/3.2.1/api/_as_gen/matplotlib.pyplot.plot.html 441 | template 442 | bool plot(const std::vector &x, const std::vector &y, const std::map& keywords) 443 | { 444 | assert(x.size() == y.size()); 445 | 446 | detail::_interpreter::get(); 447 | 448 | // using numpy arrays 449 | PyObject* xarray = detail::get_array(x); 450 | PyObject* yarray = detail::get_array(y); 451 | 452 | // construct positional args 453 | PyObject* args = PyTuple_New(2); 454 | PyTuple_SetItem(args, 0, xarray); 455 | PyTuple_SetItem(args, 1, yarray); 456 | 457 | // construct keyword args 458 | PyObject* kwargs = PyDict_New(); 459 | for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) 460 | { 461 | PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); 462 | } 463 | 464 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_plot, args, kwargs); 465 | 466 | Py_DECREF(args); 467 | Py_DECREF(kwargs); 468 | if(res) Py_DECREF(res); 469 | 470 | return res; 471 | } 472 | 473 | // TODO - it should be possible to make this work by implementing 474 | // a non-numpy alternative for `detail::get_2darray()`. 475 | #ifndef WITHOUT_NUMPY 476 | template 477 | void plot_surface(const std::vector<::std::vector> &x, 478 | const std::vector<::std::vector> &y, 479 | const std::vector<::std::vector> &z, 480 | const std::map &keywords = 481 | std::map(), 482 | const long fig_number=0) 483 | { 484 | detail::_interpreter::get(); 485 | 486 | // We lazily load the modules here the first time this function is called 487 | // because I'm not sure that we can assume "matplotlib installed" implies 488 | // "mpl_toolkits installed" on all platforms, and we don't want to require 489 | // it for people who don't need 3d plots. 490 | static PyObject *mpl_toolkitsmod = nullptr, *axis3dmod = nullptr; 491 | if (!mpl_toolkitsmod) { 492 | detail::_interpreter::get(); 493 | 494 | PyObject* mpl_toolkits = PyString_FromString("mpl_toolkits"); 495 | PyObject* axis3d = PyString_FromString("mpl_toolkits.mplot3d"); 496 | if (!mpl_toolkits || !axis3d) { throw std::runtime_error("couldnt create string"); } 497 | 498 | mpl_toolkitsmod = PyImport_Import(mpl_toolkits); 499 | Py_DECREF(mpl_toolkits); 500 | if (!mpl_toolkitsmod) { throw std::runtime_error("Error loading module mpl_toolkits!"); } 501 | 502 | axis3dmod = PyImport_Import(axis3d); 503 | Py_DECREF(axis3d); 504 | if (!axis3dmod) { throw std::runtime_error("Error loading module mpl_toolkits.mplot3d!"); } 505 | } 506 | 507 | assert(x.size() == y.size()); 508 | assert(y.size() == z.size()); 509 | 510 | // using numpy arrays 511 | PyObject *xarray = detail::get_2darray(x); 512 | PyObject *yarray = detail::get_2darray(y); 513 | PyObject *zarray = detail::get_2darray(z); 514 | 515 | // construct positional args 516 | PyObject *args = PyTuple_New(3); 517 | PyTuple_SetItem(args, 0, xarray); 518 | PyTuple_SetItem(args, 1, yarray); 519 | PyTuple_SetItem(args, 2, zarray); 520 | 521 | // Build up the kw args. 522 | PyObject *kwargs = PyDict_New(); 523 | PyDict_SetItemString(kwargs, "rstride", PyInt_FromLong(1)); 524 | PyDict_SetItemString(kwargs, "cstride", PyInt_FromLong(1)); 525 | 526 | PyObject *python_colormap_coolwarm = PyObject_GetAttrString( 527 | detail::_interpreter::get().s_python_colormap, "coolwarm"); 528 | 529 | PyDict_SetItemString(kwargs, "cmap", python_colormap_coolwarm); 530 | 531 | for (std::map::const_iterator it = keywords.begin(); 532 | it != keywords.end(); ++it) { 533 | if (it->first == "linewidth" || it->first == "alpha") { 534 | PyDict_SetItemString(kwargs, it->first.c_str(), 535 | PyFloat_FromDouble(std::stod(it->second))); 536 | } else { 537 | PyDict_SetItemString(kwargs, it->first.c_str(), 538 | PyString_FromString(it->second.c_str())); 539 | } 540 | } 541 | 542 | PyObject *fig_args = PyTuple_New(1); 543 | PyObject* fig = nullptr; 544 | PyTuple_SetItem(fig_args, 0, PyLong_FromLong(fig_number)); 545 | PyObject *fig_exists = 546 | PyObject_CallObject( 547 | detail::_interpreter::get().s_python_function_fignum_exists, fig_args); 548 | if (!PyObject_IsTrue(fig_exists)) { 549 | fig = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, 550 | detail::_interpreter::get().s_python_empty_tuple); 551 | } else { 552 | fig = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, 553 | fig_args); 554 | } 555 | Py_DECREF(fig_exists); 556 | if (!fig) throw std::runtime_error("Call to figure() failed."); 557 | 558 | PyObject *gca_kwargs = PyDict_New(); 559 | PyDict_SetItemString(gca_kwargs, "projection", PyString_FromString("3d")); 560 | 561 | PyObject *gca = PyObject_GetAttrString(fig, "gca"); 562 | if (!gca) throw std::runtime_error("No gca"); 563 | Py_INCREF(gca); 564 | PyObject *axis = PyObject_Call( 565 | gca, detail::_interpreter::get().s_python_empty_tuple, gca_kwargs); 566 | 567 | if (!axis) throw std::runtime_error("No axis"); 568 | Py_INCREF(axis); 569 | 570 | Py_DECREF(gca); 571 | Py_DECREF(gca_kwargs); 572 | 573 | PyObject *plot_surface = PyObject_GetAttrString(axis, "plot_surface"); 574 | if (!plot_surface) throw std::runtime_error("No surface"); 575 | Py_INCREF(plot_surface); 576 | PyObject *res = PyObject_Call(plot_surface, args, kwargs); 577 | if (!res) throw std::runtime_error("failed surface"); 578 | Py_DECREF(plot_surface); 579 | 580 | Py_DECREF(axis); 581 | Py_DECREF(args); 582 | Py_DECREF(kwargs); 583 | if (res) Py_DECREF(res); 584 | } 585 | 586 | template 587 | void contour(const std::vector<::std::vector> &x, 588 | const std::vector<::std::vector> &y, 589 | const std::vector<::std::vector> &z, 590 | const std::map &keywords = {}) 591 | { 592 | detail::_interpreter::get(); 593 | 594 | // using numpy arrays 595 | PyObject *xarray = detail::get_2darray(x); 596 | PyObject *yarray = detail::get_2darray(y); 597 | PyObject *zarray = detail::get_2darray(z); 598 | 599 | // construct positional args 600 | PyObject *args = PyTuple_New(3); 601 | PyTuple_SetItem(args, 0, xarray); 602 | PyTuple_SetItem(args, 1, yarray); 603 | PyTuple_SetItem(args, 2, zarray); 604 | 605 | // Build up the kw args. 606 | PyObject *kwargs = PyDict_New(); 607 | 608 | PyObject *python_colormap_coolwarm = PyObject_GetAttrString( 609 | detail::_interpreter::get().s_python_colormap, "coolwarm"); 610 | 611 | PyDict_SetItemString(kwargs, "cmap", python_colormap_coolwarm); 612 | 613 | for (std::map::const_iterator it = keywords.begin(); 614 | it != keywords.end(); ++it) { 615 | PyDict_SetItemString(kwargs, it->first.c_str(), 616 | PyString_FromString(it->second.c_str())); 617 | } 618 | 619 | PyObject *res = PyObject_Call(detail::_interpreter::get().s_python_function_contour, args, kwargs); 620 | if (!res) 621 | throw std::runtime_error("failed contour"); 622 | 623 | Py_DECREF(args); 624 | Py_DECREF(kwargs); 625 | if (res) Py_DECREF(res); 626 | } 627 | 628 | template 629 | void spy(const std::vector<::std::vector> &x, 630 | const double markersize = -1, // -1 for default matplotlib size 631 | const std::map &keywords = {}) 632 | { 633 | detail::_interpreter::get(); 634 | 635 | PyObject *xarray = detail::get_2darray(x); 636 | 637 | PyObject *kwargs = PyDict_New(); 638 | if (markersize != -1) { 639 | PyDict_SetItemString(kwargs, "markersize", PyFloat_FromDouble(markersize)); 640 | } 641 | for (std::map::const_iterator it = keywords.begin(); 642 | it != keywords.end(); ++it) { 643 | PyDict_SetItemString(kwargs, it->first.c_str(), 644 | PyString_FromString(it->second.c_str())); 645 | } 646 | 647 | PyObject *plot_args = PyTuple_New(1); 648 | PyTuple_SetItem(plot_args, 0, xarray); 649 | 650 | PyObject *res = PyObject_Call( 651 | detail::_interpreter::get().s_python_function_spy, plot_args, kwargs); 652 | 653 | Py_DECREF(plot_args); 654 | Py_DECREF(kwargs); 655 | if (res) Py_DECREF(res); 656 | } 657 | #endif // WITHOUT_NUMPY 658 | 659 | template 660 | void plot3(const std::vector &x, 661 | const std::vector &y, 662 | const std::vector &z, 663 | const std::map &keywords = 664 | std::map(), 665 | const long fig_number=0) 666 | { 667 | detail::_interpreter::get(); 668 | 669 | // Same as with plot_surface: We lazily load the modules here the first time 670 | // this function is called because I'm not sure that we can assume "matplotlib 671 | // installed" implies "mpl_toolkits installed" on all platforms, and we don't 672 | // want to require it for people who don't need 3d plots. 673 | static PyObject *mpl_toolkitsmod = nullptr, *axis3dmod = nullptr; 674 | if (!mpl_toolkitsmod) { 675 | detail::_interpreter::get(); 676 | 677 | PyObject* mpl_toolkits = PyString_FromString("mpl_toolkits"); 678 | PyObject* axis3d = PyString_FromString("mpl_toolkits.mplot3d"); 679 | if (!mpl_toolkits || !axis3d) { throw std::runtime_error("couldnt create string"); } 680 | 681 | mpl_toolkitsmod = PyImport_Import(mpl_toolkits); 682 | Py_DECREF(mpl_toolkits); 683 | if (!mpl_toolkitsmod) { throw std::runtime_error("Error loading module mpl_toolkits!"); } 684 | 685 | axis3dmod = PyImport_Import(axis3d); 686 | Py_DECREF(axis3d); 687 | if (!axis3dmod) { throw std::runtime_error("Error loading module mpl_toolkits.mplot3d!"); } 688 | } 689 | 690 | assert(x.size() == y.size()); 691 | assert(y.size() == z.size()); 692 | 693 | PyObject *xarray = detail::get_array(x); 694 | PyObject *yarray = detail::get_array(y); 695 | PyObject *zarray = detail::get_array(z); 696 | 697 | // construct positional args 698 | PyObject *args = PyTuple_New(3); 699 | PyTuple_SetItem(args, 0, xarray); 700 | PyTuple_SetItem(args, 1, yarray); 701 | PyTuple_SetItem(args, 2, zarray); 702 | 703 | // Build up the kw args. 704 | PyObject *kwargs = PyDict_New(); 705 | 706 | for (std::map::const_iterator it = keywords.begin(); 707 | it != keywords.end(); ++it) { 708 | PyDict_SetItemString(kwargs, it->first.c_str(), 709 | PyString_FromString(it->second.c_str())); 710 | } 711 | 712 | PyObject *fig_args = PyTuple_New(1); 713 | PyObject* fig = nullptr; 714 | PyTuple_SetItem(fig_args, 0, PyLong_FromLong(fig_number)); 715 | PyObject *fig_exists = 716 | PyObject_CallObject(detail::_interpreter::get().s_python_function_fignum_exists, fig_args); 717 | if (!PyObject_IsTrue(fig_exists)) { 718 | fig = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, 719 | detail::_interpreter::get().s_python_empty_tuple); 720 | } else { 721 | fig = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, 722 | fig_args); 723 | } 724 | if (!fig) throw std::runtime_error("Call to figure() failed."); 725 | 726 | PyObject *gca_kwargs = PyDict_New(); 727 | PyDict_SetItemString(gca_kwargs, "projection", PyString_FromString("3d")); 728 | 729 | PyObject *gca = PyObject_GetAttrString(fig, "gca"); 730 | if (!gca) throw std::runtime_error("No gca"); 731 | Py_INCREF(gca); 732 | PyObject *axis = PyObject_Call( 733 | gca, detail::_interpreter::get().s_python_empty_tuple, gca_kwargs); 734 | 735 | if (!axis) throw std::runtime_error("No axis"); 736 | Py_INCREF(axis); 737 | 738 | Py_DECREF(gca); 739 | Py_DECREF(gca_kwargs); 740 | 741 | PyObject *plot3 = PyObject_GetAttrString(axis, "plot"); 742 | if (!plot3) throw std::runtime_error("No 3D line plot"); 743 | Py_INCREF(plot3); 744 | PyObject *res = PyObject_Call(plot3, args, kwargs); 745 | if (!res) throw std::runtime_error("Failed 3D line plot"); 746 | Py_DECREF(plot3); 747 | 748 | Py_DECREF(axis); 749 | Py_DECREF(args); 750 | Py_DECREF(kwargs); 751 | if (res) Py_DECREF(res); 752 | } 753 | 754 | template 755 | bool stem(const std::vector &x, const std::vector &y, const std::map& keywords) 756 | { 757 | assert(x.size() == y.size()); 758 | 759 | detail::_interpreter::get(); 760 | 761 | // using numpy arrays 762 | PyObject* xarray = detail::get_array(x); 763 | PyObject* yarray = detail::get_array(y); 764 | 765 | // construct positional args 766 | PyObject* args = PyTuple_New(2); 767 | PyTuple_SetItem(args, 0, xarray); 768 | PyTuple_SetItem(args, 1, yarray); 769 | 770 | // construct keyword args 771 | PyObject* kwargs = PyDict_New(); 772 | for (std::map::const_iterator it = 773 | keywords.begin(); it != keywords.end(); ++it) { 774 | PyDict_SetItemString(kwargs, it->first.c_str(), 775 | PyString_FromString(it->second.c_str())); 776 | } 777 | 778 | PyObject* res = PyObject_Call( 779 | detail::_interpreter::get().s_python_function_stem, args, kwargs); 780 | 781 | Py_DECREF(args); 782 | Py_DECREF(kwargs); 783 | if (res) 784 | Py_DECREF(res); 785 | 786 | return res; 787 | } 788 | 789 | template< typename Numeric > 790 | bool fill(const std::vector& x, const std::vector& y, const std::map& keywords) 791 | { 792 | assert(x.size() == y.size()); 793 | 794 | detail::_interpreter::get(); 795 | 796 | // using numpy arrays 797 | PyObject* xarray = detail::get_array(x); 798 | PyObject* yarray = detail::get_array(y); 799 | 800 | // construct positional args 801 | PyObject* args = PyTuple_New(2); 802 | PyTuple_SetItem(args, 0, xarray); 803 | PyTuple_SetItem(args, 1, yarray); 804 | 805 | // construct keyword args 806 | PyObject* kwargs = PyDict_New(); 807 | for (auto it = keywords.begin(); it != keywords.end(); ++it) { 808 | PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); 809 | } 810 | 811 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_fill, args, kwargs); 812 | 813 | Py_DECREF(args); 814 | Py_DECREF(kwargs); 815 | 816 | if (res) Py_DECREF(res); 817 | 818 | return res; 819 | } 820 | 821 | template< typename Numeric > 822 | bool fill_between(const std::vector& x, const std::vector& y1, const std::vector& y2, const std::map& keywords) 823 | { 824 | assert(x.size() == y1.size()); 825 | assert(x.size() == y2.size()); 826 | 827 | detail::_interpreter::get(); 828 | 829 | // using numpy arrays 830 | PyObject* xarray = detail::get_array(x); 831 | PyObject* y1array = detail::get_array(y1); 832 | PyObject* y2array = detail::get_array(y2); 833 | 834 | // construct positional args 835 | PyObject* args = PyTuple_New(3); 836 | PyTuple_SetItem(args, 0, xarray); 837 | PyTuple_SetItem(args, 1, y1array); 838 | PyTuple_SetItem(args, 2, y2array); 839 | 840 | // construct keyword args 841 | PyObject* kwargs = PyDict_New(); 842 | for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { 843 | PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); 844 | } 845 | 846 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_fill_between, args, kwargs); 847 | 848 | Py_DECREF(args); 849 | Py_DECREF(kwargs); 850 | if(res) Py_DECREF(res); 851 | 852 | return res; 853 | } 854 | 855 | template 856 | bool arrow(Numeric x, Numeric y, Numeric end_x, Numeric end_y, const std::string& fc = "r", 857 | const std::string ec = "k", Numeric head_length = 0.25, Numeric head_width = 0.1625) { 858 | PyObject* obj_x = PyFloat_FromDouble(x); 859 | PyObject* obj_y = PyFloat_FromDouble(y); 860 | PyObject* obj_end_x = PyFloat_FromDouble(end_x); 861 | PyObject* obj_end_y = PyFloat_FromDouble(end_y); 862 | 863 | PyObject* kwargs = PyDict_New(); 864 | PyDict_SetItemString(kwargs, "fc", PyString_FromString(fc.c_str())); 865 | PyDict_SetItemString(kwargs, "ec", PyString_FromString(ec.c_str())); 866 | PyDict_SetItemString(kwargs, "head_width", PyFloat_FromDouble(head_width)); 867 | PyDict_SetItemString(kwargs, "head_length", PyFloat_FromDouble(head_length)); 868 | 869 | PyObject* plot_args = PyTuple_New(4); 870 | PyTuple_SetItem(plot_args, 0, obj_x); 871 | PyTuple_SetItem(plot_args, 1, obj_y); 872 | PyTuple_SetItem(plot_args, 2, obj_end_x); 873 | PyTuple_SetItem(plot_args, 3, obj_end_y); 874 | 875 | PyObject* res = 876 | PyObject_Call(detail::_interpreter::get().s_python_function_arrow, plot_args, kwargs); 877 | 878 | Py_DECREF(plot_args); 879 | Py_DECREF(kwargs); 880 | if (res) 881 | Py_DECREF(res); 882 | 883 | return res; 884 | } 885 | 886 | template< typename Numeric> 887 | bool hist(const std::vector& y, long bins=10,std::string color="b", 888 | double alpha=1.0, bool cumulative=false) 889 | { 890 | detail::_interpreter::get(); 891 | 892 | PyObject* yarray = detail::get_array(y); 893 | 894 | PyObject* kwargs = PyDict_New(); 895 | PyDict_SetItemString(kwargs, "bins", PyLong_FromLong(bins)); 896 | PyDict_SetItemString(kwargs, "color", PyString_FromString(color.c_str())); 897 | PyDict_SetItemString(kwargs, "alpha", PyFloat_FromDouble(alpha)); 898 | PyDict_SetItemString(kwargs, "cumulative", cumulative ? Py_True : Py_False); 899 | 900 | PyObject* plot_args = PyTuple_New(1); 901 | 902 | PyTuple_SetItem(plot_args, 0, yarray); 903 | 904 | 905 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_hist, plot_args, kwargs); 906 | 907 | 908 | Py_DECREF(plot_args); 909 | Py_DECREF(kwargs); 910 | if(res) Py_DECREF(res); 911 | 912 | return res; 913 | } 914 | 915 | #ifndef WITHOUT_NUMPY 916 | namespace detail { 917 | 918 | inline void imshow(void *ptr, const NPY_TYPES type, const int rows, const int columns, const int colors, const std::map &keywords, PyObject** out) 919 | { 920 | assert(type == NPY_UINT8 || type == NPY_FLOAT); 921 | assert(colors == 1 || colors == 3 || colors == 4); 922 | 923 | detail::_interpreter::get(); 924 | 925 | // construct args 926 | npy_intp dims[3] = { rows, columns, colors }; 927 | PyObject *args = PyTuple_New(1); 928 | PyTuple_SetItem(args, 0, PyArray_SimpleNewFromData(colors == 1 ? 2 : 3, dims, type, ptr)); 929 | 930 | // construct keyword args 931 | PyObject* kwargs = PyDict_New(); 932 | for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) 933 | { 934 | PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); 935 | } 936 | 937 | PyObject *res = PyObject_Call(detail::_interpreter::get().s_python_function_imshow, args, kwargs); 938 | Py_DECREF(args); 939 | Py_DECREF(kwargs); 940 | if (!res) 941 | throw std::runtime_error("Call to imshow() failed"); 942 | if (out) 943 | *out = res; 944 | else 945 | Py_DECREF(res); 946 | } 947 | 948 | } // namespace detail 949 | 950 | inline void imshow(const unsigned char *ptr, const int rows, const int columns, const int colors, const std::map &keywords = {}, PyObject** out = nullptr) 951 | { 952 | detail::imshow((void *) ptr, NPY_UINT8, rows, columns, colors, keywords, out); 953 | } 954 | 955 | inline void imshow(const float *ptr, const int rows, const int columns, const int colors, const std::map &keywords = {}, PyObject** out = nullptr) 956 | { 957 | detail::imshow((void *) ptr, NPY_FLOAT, rows, columns, colors, keywords, out); 958 | } 959 | 960 | #ifdef WITH_OPENCV 961 | void imshow(const cv::Mat &image, const std::map &keywords = {}) 962 | { 963 | // Convert underlying type of matrix, if needed 964 | cv::Mat image2; 965 | NPY_TYPES npy_type = NPY_UINT8; 966 | switch (image.type() & CV_MAT_DEPTH_MASK) { 967 | case CV_8U: 968 | image2 = image; 969 | break; 970 | case CV_32F: 971 | image2 = image; 972 | npy_type = NPY_FLOAT; 973 | break; 974 | default: 975 | image.convertTo(image2, CV_MAKETYPE(CV_8U, image.channels())); 976 | } 977 | 978 | // If color image, convert from BGR to RGB 979 | switch (image2.channels()) { 980 | case 3: 981 | cv::cvtColor(image2, image2, CV_BGR2RGB); 982 | break; 983 | case 4: 984 | cv::cvtColor(image2, image2, CV_BGRA2RGBA); 985 | } 986 | 987 | detail::imshow(image2.data, npy_type, image2.rows, image2.cols, image2.channels(), keywords); 988 | } 989 | #endif // WITH_OPENCV 990 | #endif // WITHOUT_NUMPY 991 | 992 | template 993 | bool scatter(const std::vector& x, 994 | const std::vector& y, 995 | const double s=1.0, // The marker size in points**2 996 | const std::map & keywords = {}) 997 | { 998 | detail::_interpreter::get(); 999 | 1000 | assert(x.size() == y.size()); 1001 | 1002 | PyObject* xarray = detail::get_array(x); 1003 | PyObject* yarray = detail::get_array(y); 1004 | 1005 | PyObject* kwargs = PyDict_New(); 1006 | PyDict_SetItemString(kwargs, "s", PyLong_FromLong(s)); 1007 | for (const auto& it : keywords) 1008 | { 1009 | PyDict_SetItemString(kwargs, it.first.c_str(), PyString_FromString(it.second.c_str())); 1010 | } 1011 | 1012 | PyObject* plot_args = PyTuple_New(2); 1013 | PyTuple_SetItem(plot_args, 0, xarray); 1014 | PyTuple_SetItem(plot_args, 1, yarray); 1015 | 1016 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_scatter, plot_args, kwargs); 1017 | 1018 | Py_DECREF(plot_args); 1019 | Py_DECREF(kwargs); 1020 | if(res) Py_DECREF(res); 1021 | 1022 | return res; 1023 | } 1024 | 1025 | template 1026 | bool scatter_colored(const std::vector& x, 1027 | const std::vector& y, 1028 | const std::vector& colors, 1029 | const double s=1.0, // The marker size in points**2 1030 | const std::map & keywords = {}) 1031 | { 1032 | detail::_interpreter::get(); 1033 | 1034 | assert(x.size() == y.size()); 1035 | 1036 | PyObject* xarray = detail::get_array(x); 1037 | PyObject* yarray = detail::get_array(y); 1038 | PyObject* colors_array = detail::get_array(colors); 1039 | 1040 | PyObject* kwargs = PyDict_New(); 1041 | PyDict_SetItemString(kwargs, "s", PyLong_FromLong(s)); 1042 | PyDict_SetItemString(kwargs, "c", colors_array); 1043 | 1044 | for (const auto& it : keywords) 1045 | { 1046 | PyDict_SetItemString(kwargs, it.first.c_str(), PyString_FromString(it.second.c_str())); 1047 | } 1048 | 1049 | PyObject* plot_args = PyTuple_New(2); 1050 | PyTuple_SetItem(plot_args, 0, xarray); 1051 | PyTuple_SetItem(plot_args, 1, yarray); 1052 | 1053 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_scatter, plot_args, kwargs); 1054 | 1055 | Py_DECREF(plot_args); 1056 | Py_DECREF(kwargs); 1057 | if(res) Py_DECREF(res); 1058 | 1059 | return res; 1060 | } 1061 | 1062 | 1063 | template 1064 | bool scatter(const std::vector& x, 1065 | const std::vector& y, 1066 | const std::vector& z, 1067 | const double s=1.0, // The marker size in points**2 1068 | const std::map & keywords = {}, 1069 | const long fig_number=0) { 1070 | detail::_interpreter::get(); 1071 | 1072 | // Same as with plot_surface: We lazily load the modules here the first time 1073 | // this function is called because I'm not sure that we can assume "matplotlib 1074 | // installed" implies "mpl_toolkits installed" on all platforms, and we don't 1075 | // want to require it for people who don't need 3d plots. 1076 | static PyObject *mpl_toolkitsmod = nullptr, *axis3dmod = nullptr; 1077 | if (!mpl_toolkitsmod) { 1078 | detail::_interpreter::get(); 1079 | 1080 | PyObject* mpl_toolkits = PyString_FromString("mpl_toolkits"); 1081 | PyObject* axis3d = PyString_FromString("mpl_toolkits.mplot3d"); 1082 | if (!mpl_toolkits || !axis3d) { throw std::runtime_error("couldnt create string"); } 1083 | 1084 | mpl_toolkitsmod = PyImport_Import(mpl_toolkits); 1085 | Py_DECREF(mpl_toolkits); 1086 | if (!mpl_toolkitsmod) { throw std::runtime_error("Error loading module mpl_toolkits!"); } 1087 | 1088 | axis3dmod = PyImport_Import(axis3d); 1089 | Py_DECREF(axis3d); 1090 | if (!axis3dmod) { throw std::runtime_error("Error loading module mpl_toolkits.mplot3d!"); } 1091 | } 1092 | 1093 | assert(x.size() == y.size()); 1094 | assert(y.size() == z.size()); 1095 | 1096 | PyObject *xarray = detail::get_array(x); 1097 | PyObject *yarray = detail::get_array(y); 1098 | PyObject *zarray = detail::get_array(z); 1099 | 1100 | // construct positional args 1101 | PyObject *args = PyTuple_New(3); 1102 | PyTuple_SetItem(args, 0, xarray); 1103 | PyTuple_SetItem(args, 1, yarray); 1104 | PyTuple_SetItem(args, 2, zarray); 1105 | 1106 | // Build up the kw args. 1107 | PyObject *kwargs = PyDict_New(); 1108 | 1109 | for (std::map::const_iterator it = keywords.begin(); 1110 | it != keywords.end(); ++it) { 1111 | PyDict_SetItemString(kwargs, it->first.c_str(), 1112 | PyString_FromString(it->second.c_str())); 1113 | } 1114 | PyObject *fig_args = PyTuple_New(1); 1115 | PyObject* fig = nullptr; 1116 | PyTuple_SetItem(fig_args, 0, PyLong_FromLong(fig_number)); 1117 | PyObject *fig_exists = 1118 | PyObject_CallObject(detail::_interpreter::get().s_python_function_fignum_exists, fig_args); 1119 | if (!PyObject_IsTrue(fig_exists)) { 1120 | fig = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, 1121 | detail::_interpreter::get().s_python_empty_tuple); 1122 | } else { 1123 | fig = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, 1124 | fig_args); 1125 | } 1126 | Py_DECREF(fig_exists); 1127 | if (!fig) throw std::runtime_error("Call to figure() failed."); 1128 | 1129 | PyObject *gca_kwargs = PyDict_New(); 1130 | PyDict_SetItemString(gca_kwargs, "projection", PyString_FromString("3d")); 1131 | 1132 | PyObject *gca = PyObject_GetAttrString(fig, "gca"); 1133 | if (!gca) throw std::runtime_error("No gca"); 1134 | Py_INCREF(gca); 1135 | PyObject *axis = PyObject_Call( 1136 | gca, detail::_interpreter::get().s_python_empty_tuple, gca_kwargs); 1137 | 1138 | if (!axis) throw std::runtime_error("No axis"); 1139 | Py_INCREF(axis); 1140 | 1141 | Py_DECREF(gca); 1142 | Py_DECREF(gca_kwargs); 1143 | 1144 | PyObject *plot3 = PyObject_GetAttrString(axis, "scatter"); 1145 | if (!plot3) throw std::runtime_error("No 3D line plot"); 1146 | Py_INCREF(plot3); 1147 | PyObject *res = PyObject_Call(plot3, args, kwargs); 1148 | if (!res) throw std::runtime_error("Failed 3D line plot"); 1149 | Py_DECREF(plot3); 1150 | 1151 | Py_DECREF(axis); 1152 | Py_DECREF(args); 1153 | Py_DECREF(kwargs); 1154 | Py_DECREF(fig); 1155 | if (res) Py_DECREF(res); 1156 | return res; 1157 | 1158 | } 1159 | 1160 | template 1161 | bool boxplot(const std::vector>& data, 1162 | const std::vector& labels = {}, 1163 | const std::map & keywords = {}) 1164 | { 1165 | detail::_interpreter::get(); 1166 | 1167 | PyObject* listlist = detail::get_listlist(data); 1168 | PyObject* args = PyTuple_New(1); 1169 | PyTuple_SetItem(args, 0, listlist); 1170 | 1171 | PyObject* kwargs = PyDict_New(); 1172 | 1173 | // kwargs needs the labels, if there are (the correct number of) labels 1174 | if (!labels.empty() && labels.size() == data.size()) { 1175 | PyDict_SetItemString(kwargs, "labels", detail::get_array(labels)); 1176 | } 1177 | 1178 | // take care of the remaining keywords 1179 | for (const auto& it : keywords) 1180 | { 1181 | PyDict_SetItemString(kwargs, it.first.c_str(), PyString_FromString(it.second.c_str())); 1182 | } 1183 | 1184 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_boxplot, args, kwargs); 1185 | 1186 | Py_DECREF(args); 1187 | Py_DECREF(kwargs); 1188 | 1189 | if(res) Py_DECREF(res); 1190 | 1191 | return res; 1192 | } 1193 | 1194 | template 1195 | bool boxplot(const std::vector& data, 1196 | const std::map & keywords = {}) 1197 | { 1198 | detail::_interpreter::get(); 1199 | 1200 | PyObject* vector = detail::get_array(data); 1201 | PyObject* args = PyTuple_New(1); 1202 | PyTuple_SetItem(args, 0, vector); 1203 | 1204 | PyObject* kwargs = PyDict_New(); 1205 | for (const auto& it : keywords) 1206 | { 1207 | PyDict_SetItemString(kwargs, it.first.c_str(), PyString_FromString(it.second.c_str())); 1208 | } 1209 | 1210 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_boxplot, args, kwargs); 1211 | 1212 | Py_DECREF(args); 1213 | Py_DECREF(kwargs); 1214 | 1215 | if(res) Py_DECREF(res); 1216 | 1217 | return res; 1218 | } 1219 | 1220 | template 1221 | bool bar(const std::vector & x, 1222 | const std::vector & y, 1223 | std::string ec = "black", 1224 | std::string ls = "-", 1225 | double lw = 1.0, 1226 | const std::map & keywords = {}) 1227 | { 1228 | detail::_interpreter::get(); 1229 | 1230 | PyObject * xarray = detail::get_array(x); 1231 | PyObject * yarray = detail::get_array(y); 1232 | 1233 | PyObject * kwargs = PyDict_New(); 1234 | 1235 | PyDict_SetItemString(kwargs, "ec", PyString_FromString(ec.c_str())); 1236 | PyDict_SetItemString(kwargs, "ls", PyString_FromString(ls.c_str())); 1237 | PyDict_SetItemString(kwargs, "lw", PyFloat_FromDouble(lw)); 1238 | 1239 | for (std::map::const_iterator it = 1240 | keywords.begin(); 1241 | it != keywords.end(); 1242 | ++it) { 1243 | PyDict_SetItemString( 1244 | kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); 1245 | } 1246 | 1247 | PyObject * plot_args = PyTuple_New(2); 1248 | PyTuple_SetItem(plot_args, 0, xarray); 1249 | PyTuple_SetItem(plot_args, 1, yarray); 1250 | 1251 | PyObject * res = PyObject_Call( 1252 | detail::_interpreter::get().s_python_function_bar, plot_args, kwargs); 1253 | 1254 | Py_DECREF(plot_args); 1255 | Py_DECREF(kwargs); 1256 | if (res) Py_DECREF(res); 1257 | 1258 | return res; 1259 | } 1260 | 1261 | template 1262 | bool bar(const std::vector & y, 1263 | std::string ec = "black", 1264 | std::string ls = "-", 1265 | double lw = 1.0, 1266 | const std::map & keywords = {}) 1267 | { 1268 | using T = typename std::remove_reference::type::value_type; 1269 | 1270 | detail::_interpreter::get(); 1271 | 1272 | std::vector x; 1273 | for (std::size_t i = 0; i < y.size(); i++) { x.push_back(i); } 1274 | 1275 | return bar(x, y, ec, ls, lw, keywords); 1276 | } 1277 | 1278 | 1279 | template 1280 | bool barh(const std::vector &x, const std::vector &y, std::string ec = "black", std::string ls = "-", double lw = 1.0, const std::map &keywords = { }) { 1281 | PyObject *xarray = detail::get_array(x); 1282 | PyObject *yarray = detail::get_array(y); 1283 | 1284 | PyObject *kwargs = PyDict_New(); 1285 | 1286 | PyDict_SetItemString(kwargs, "ec", PyString_FromString(ec.c_str())); 1287 | PyDict_SetItemString(kwargs, "ls", PyString_FromString(ls.c_str())); 1288 | PyDict_SetItemString(kwargs, "lw", PyFloat_FromDouble(lw)); 1289 | 1290 | for (std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) { 1291 | PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); 1292 | } 1293 | 1294 | PyObject *plot_args = PyTuple_New(2); 1295 | PyTuple_SetItem(plot_args, 0, xarray); 1296 | PyTuple_SetItem(plot_args, 1, yarray); 1297 | 1298 | PyObject *res = PyObject_Call(detail::_interpreter::get().s_python_function_barh, plot_args, kwargs); 1299 | 1300 | Py_DECREF(plot_args); 1301 | Py_DECREF(kwargs); 1302 | if (res) Py_DECREF(res); 1303 | 1304 | return res; 1305 | } 1306 | 1307 | 1308 | inline bool subplots_adjust(const std::map& keywords = {}) 1309 | { 1310 | detail::_interpreter::get(); 1311 | 1312 | PyObject* kwargs = PyDict_New(); 1313 | for (std::map::const_iterator it = 1314 | keywords.begin(); it != keywords.end(); ++it) { 1315 | PyDict_SetItemString(kwargs, it->first.c_str(), 1316 | PyFloat_FromDouble(it->second)); 1317 | } 1318 | 1319 | 1320 | PyObject* plot_args = PyTuple_New(0); 1321 | 1322 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_subplots_adjust, plot_args, kwargs); 1323 | 1324 | Py_DECREF(plot_args); 1325 | Py_DECREF(kwargs); 1326 | if(res) Py_DECREF(res); 1327 | 1328 | return res; 1329 | } 1330 | 1331 | template< typename Numeric> 1332 | bool named_hist(std::string label,const std::vector& y, long bins=10, std::string color="b", double alpha=1.0) 1333 | { 1334 | detail::_interpreter::get(); 1335 | 1336 | PyObject* yarray = detail::get_array(y); 1337 | 1338 | PyObject* kwargs = PyDict_New(); 1339 | PyDict_SetItemString(kwargs, "label", PyString_FromString(label.c_str())); 1340 | PyDict_SetItemString(kwargs, "bins", PyLong_FromLong(bins)); 1341 | PyDict_SetItemString(kwargs, "color", PyString_FromString(color.c_str())); 1342 | PyDict_SetItemString(kwargs, "alpha", PyFloat_FromDouble(alpha)); 1343 | 1344 | 1345 | PyObject* plot_args = PyTuple_New(1); 1346 | PyTuple_SetItem(plot_args, 0, yarray); 1347 | 1348 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_hist, plot_args, kwargs); 1349 | 1350 | Py_DECREF(plot_args); 1351 | Py_DECREF(kwargs); 1352 | if(res) Py_DECREF(res); 1353 | 1354 | return res; 1355 | } 1356 | 1357 | template 1358 | bool plot(const std::vector& x, const std::vector& y, const std::string& s = "") 1359 | { 1360 | assert(x.size() == y.size()); 1361 | 1362 | detail::_interpreter::get(); 1363 | 1364 | PyObject* xarray = detail::get_array(x); 1365 | PyObject* yarray = detail::get_array(y); 1366 | 1367 | PyObject* pystring = PyString_FromString(s.c_str()); 1368 | 1369 | PyObject* plot_args = PyTuple_New(3); 1370 | PyTuple_SetItem(plot_args, 0, xarray); 1371 | PyTuple_SetItem(plot_args, 1, yarray); 1372 | PyTuple_SetItem(plot_args, 2, pystring); 1373 | 1374 | PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_plot, plot_args); 1375 | 1376 | Py_DECREF(plot_args); 1377 | if(res) Py_DECREF(res); 1378 | 1379 | return res; 1380 | } 1381 | 1382 | template 1383 | bool contour(const std::vector& x, const std::vector& y, 1384 | const std::vector& z, 1385 | const std::map& keywords = {}) { 1386 | assert(x.size() == y.size() && x.size() == z.size()); 1387 | 1388 | PyObject* xarray = detail::get_array(x); 1389 | PyObject* yarray = detail::get_array(y); 1390 | PyObject* zarray = detail::get_array(z); 1391 | 1392 | PyObject* plot_args = PyTuple_New(3); 1393 | PyTuple_SetItem(plot_args, 0, xarray); 1394 | PyTuple_SetItem(plot_args, 1, yarray); 1395 | PyTuple_SetItem(plot_args, 2, zarray); 1396 | 1397 | // construct keyword args 1398 | PyObject* kwargs = PyDict_New(); 1399 | for (std::map::const_iterator it = keywords.begin(); 1400 | it != keywords.end(); ++it) { 1401 | PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); 1402 | } 1403 | 1404 | PyObject* res = 1405 | PyObject_Call(detail::_interpreter::get().s_python_function_contour, plot_args, kwargs); 1406 | 1407 | Py_DECREF(kwargs); 1408 | Py_DECREF(plot_args); 1409 | if (res) 1410 | Py_DECREF(res); 1411 | 1412 | return res; 1413 | } 1414 | 1415 | template 1416 | bool quiver(const std::vector& x, const std::vector& y, const std::vector& u, const std::vector& w, const std::map& keywords = {}) 1417 | { 1418 | assert(x.size() == y.size() && x.size() == u.size() && u.size() == w.size()); 1419 | 1420 | detail::_interpreter::get(); 1421 | 1422 | PyObject* xarray = detail::get_array(x); 1423 | PyObject* yarray = detail::get_array(y); 1424 | PyObject* uarray = detail::get_array(u); 1425 | PyObject* warray = detail::get_array(w); 1426 | 1427 | PyObject* plot_args = PyTuple_New(4); 1428 | PyTuple_SetItem(plot_args, 0, xarray); 1429 | PyTuple_SetItem(plot_args, 1, yarray); 1430 | PyTuple_SetItem(plot_args, 2, uarray); 1431 | PyTuple_SetItem(plot_args, 3, warray); 1432 | 1433 | // construct keyword args 1434 | PyObject* kwargs = PyDict_New(); 1435 | for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) 1436 | { 1437 | PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); 1438 | } 1439 | 1440 | PyObject* res = PyObject_Call( 1441 | detail::_interpreter::get().s_python_function_quiver, plot_args, kwargs); 1442 | 1443 | Py_DECREF(kwargs); 1444 | Py_DECREF(plot_args); 1445 | if (res) 1446 | Py_DECREF(res); 1447 | 1448 | return res; 1449 | } 1450 | 1451 | template 1452 | bool quiver(const std::vector& x, const std::vector& y, const std::vector& z, const std::vector& u, const std::vector& w, const std::vector& v, const std::map& keywords = {}) 1453 | { 1454 | //set up 3d axes stuff 1455 | static PyObject *mpl_toolkitsmod = nullptr, *axis3dmod = nullptr; 1456 | if (!mpl_toolkitsmod) { 1457 | detail::_interpreter::get(); 1458 | 1459 | PyObject* mpl_toolkits = PyString_FromString("mpl_toolkits"); 1460 | PyObject* axis3d = PyString_FromString("mpl_toolkits.mplot3d"); 1461 | if (!mpl_toolkits || !axis3d) { throw std::runtime_error("couldnt create string"); } 1462 | 1463 | mpl_toolkitsmod = PyImport_Import(mpl_toolkits); 1464 | Py_DECREF(mpl_toolkits); 1465 | if (!mpl_toolkitsmod) { throw std::runtime_error("Error loading module mpl_toolkits!"); } 1466 | 1467 | axis3dmod = PyImport_Import(axis3d); 1468 | Py_DECREF(axis3d); 1469 | if (!axis3dmod) { throw std::runtime_error("Error loading module mpl_toolkits.mplot3d!"); } 1470 | } 1471 | 1472 | //assert sizes match up 1473 | assert(x.size() == y.size() && x.size() == u.size() && u.size() == w.size() && x.size() == z.size() && x.size() == v.size() && u.size() == v.size()); 1474 | 1475 | //set up parameters 1476 | detail::_interpreter::get(); 1477 | 1478 | PyObject* xarray = detail::get_array(x); 1479 | PyObject* yarray = detail::get_array(y); 1480 | PyObject* zarray = detail::get_array(z); 1481 | PyObject* uarray = detail::get_array(u); 1482 | PyObject* warray = detail::get_array(w); 1483 | PyObject* varray = detail::get_array(v); 1484 | 1485 | PyObject* plot_args = PyTuple_New(6); 1486 | PyTuple_SetItem(plot_args, 0, xarray); 1487 | PyTuple_SetItem(plot_args, 1, yarray); 1488 | PyTuple_SetItem(plot_args, 2, zarray); 1489 | PyTuple_SetItem(plot_args, 3, uarray); 1490 | PyTuple_SetItem(plot_args, 4, warray); 1491 | PyTuple_SetItem(plot_args, 5, varray); 1492 | 1493 | // construct keyword args 1494 | PyObject* kwargs = PyDict_New(); 1495 | for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) 1496 | { 1497 | PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); 1498 | } 1499 | 1500 | //get figure gca to enable 3d projection 1501 | PyObject *fig = 1502 | PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, 1503 | detail::_interpreter::get().s_python_empty_tuple); 1504 | if (!fig) throw std::runtime_error("Call to figure() failed."); 1505 | 1506 | PyObject *gca_kwargs = PyDict_New(); 1507 | PyDict_SetItemString(gca_kwargs, "projection", PyString_FromString("3d")); 1508 | 1509 | PyObject *gca = PyObject_GetAttrString(fig, "gca"); 1510 | if (!gca) throw std::runtime_error("No gca"); 1511 | Py_INCREF(gca); 1512 | PyObject *axis = PyObject_Call( 1513 | gca, detail::_interpreter::get().s_python_empty_tuple, gca_kwargs); 1514 | 1515 | if (!axis) throw std::runtime_error("No axis"); 1516 | Py_INCREF(axis); 1517 | Py_DECREF(gca); 1518 | Py_DECREF(gca_kwargs); 1519 | 1520 | //plot our boys bravely, plot them strongly, plot them with a wink and clap 1521 | PyObject *plot3 = PyObject_GetAttrString(axis, "quiver"); 1522 | if (!plot3) throw std::runtime_error("No 3D line plot"); 1523 | Py_INCREF(plot3); 1524 | PyObject* res = PyObject_Call( 1525 | plot3, plot_args, kwargs); 1526 | if (!res) throw std::runtime_error("Failed 3D plot"); 1527 | Py_DECREF(plot3); 1528 | Py_DECREF(axis); 1529 | Py_DECREF(kwargs); 1530 | Py_DECREF(plot_args); 1531 | if (res) 1532 | Py_DECREF(res); 1533 | 1534 | return res; 1535 | } 1536 | 1537 | template 1538 | bool stem(const std::vector& x, const std::vector& y, const std::string& s = "") 1539 | { 1540 | assert(x.size() == y.size()); 1541 | 1542 | detail::_interpreter::get(); 1543 | 1544 | PyObject* xarray = detail::get_array(x); 1545 | PyObject* yarray = detail::get_array(y); 1546 | 1547 | PyObject* pystring = PyString_FromString(s.c_str()); 1548 | 1549 | PyObject* plot_args = PyTuple_New(3); 1550 | PyTuple_SetItem(plot_args, 0, xarray); 1551 | PyTuple_SetItem(plot_args, 1, yarray); 1552 | PyTuple_SetItem(plot_args, 2, pystring); 1553 | 1554 | PyObject* res = PyObject_CallObject( 1555 | detail::_interpreter::get().s_python_function_stem, plot_args); 1556 | 1557 | Py_DECREF(plot_args); 1558 | if (res) 1559 | Py_DECREF(res); 1560 | 1561 | return res; 1562 | } 1563 | 1564 | template 1565 | bool semilogx(const std::vector& x, const std::vector& y, const std::string& s = "") 1566 | { 1567 | assert(x.size() == y.size()); 1568 | 1569 | detail::_interpreter::get(); 1570 | 1571 | PyObject* xarray = detail::get_array(x); 1572 | PyObject* yarray = detail::get_array(y); 1573 | 1574 | PyObject* pystring = PyString_FromString(s.c_str()); 1575 | 1576 | PyObject* plot_args = PyTuple_New(3); 1577 | PyTuple_SetItem(plot_args, 0, xarray); 1578 | PyTuple_SetItem(plot_args, 1, yarray); 1579 | PyTuple_SetItem(plot_args, 2, pystring); 1580 | 1581 | PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_semilogx, plot_args); 1582 | 1583 | Py_DECREF(plot_args); 1584 | if(res) Py_DECREF(res); 1585 | 1586 | return res; 1587 | } 1588 | 1589 | template 1590 | bool semilogy(const std::vector& x, const std::vector& y, const std::string& s = "") 1591 | { 1592 | assert(x.size() == y.size()); 1593 | 1594 | detail::_interpreter::get(); 1595 | 1596 | PyObject* xarray = detail::get_array(x); 1597 | PyObject* yarray = detail::get_array(y); 1598 | 1599 | PyObject* pystring = PyString_FromString(s.c_str()); 1600 | 1601 | PyObject* plot_args = PyTuple_New(3); 1602 | PyTuple_SetItem(plot_args, 0, xarray); 1603 | PyTuple_SetItem(plot_args, 1, yarray); 1604 | PyTuple_SetItem(plot_args, 2, pystring); 1605 | 1606 | PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_semilogy, plot_args); 1607 | 1608 | Py_DECREF(plot_args); 1609 | if(res) Py_DECREF(res); 1610 | 1611 | return res; 1612 | } 1613 | 1614 | template 1615 | bool loglog(const std::vector& x, const std::vector& y, const std::string& s = "") 1616 | { 1617 | assert(x.size() == y.size()); 1618 | 1619 | detail::_interpreter::get(); 1620 | 1621 | PyObject* xarray = detail::get_array(x); 1622 | PyObject* yarray = detail::get_array(y); 1623 | 1624 | PyObject* pystring = PyString_FromString(s.c_str()); 1625 | 1626 | PyObject* plot_args = PyTuple_New(3); 1627 | PyTuple_SetItem(plot_args, 0, xarray); 1628 | PyTuple_SetItem(plot_args, 1, yarray); 1629 | PyTuple_SetItem(plot_args, 2, pystring); 1630 | 1631 | PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_loglog, plot_args); 1632 | 1633 | Py_DECREF(plot_args); 1634 | if(res) Py_DECREF(res); 1635 | 1636 | return res; 1637 | } 1638 | 1639 | template 1640 | bool errorbar(const std::vector &x, const std::vector &y, const std::vector &yerr, const std::map &keywords = {}) 1641 | { 1642 | assert(x.size() == y.size()); 1643 | 1644 | detail::_interpreter::get(); 1645 | 1646 | PyObject* xarray = detail::get_array(x); 1647 | PyObject* yarray = detail::get_array(y); 1648 | PyObject* yerrarray = detail::get_array(yerr); 1649 | 1650 | // construct keyword args 1651 | PyObject* kwargs = PyDict_New(); 1652 | for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) 1653 | { 1654 | PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); 1655 | } 1656 | 1657 | PyDict_SetItemString(kwargs, "yerr", yerrarray); 1658 | 1659 | PyObject *plot_args = PyTuple_New(2); 1660 | PyTuple_SetItem(plot_args, 0, xarray); 1661 | PyTuple_SetItem(plot_args, 1, yarray); 1662 | 1663 | PyObject *res = PyObject_Call(detail::_interpreter::get().s_python_function_errorbar, plot_args, kwargs); 1664 | 1665 | Py_DECREF(kwargs); 1666 | Py_DECREF(plot_args); 1667 | 1668 | if (res) 1669 | Py_DECREF(res); 1670 | else 1671 | throw std::runtime_error("Call to errorbar() failed."); 1672 | 1673 | return res; 1674 | } 1675 | 1676 | template 1677 | bool named_plot(const std::string& name, const std::vector& y, const std::string& format = "") 1678 | { 1679 | detail::_interpreter::get(); 1680 | 1681 | PyObject* kwargs = PyDict_New(); 1682 | PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str())); 1683 | 1684 | PyObject* yarray = detail::get_array(y); 1685 | 1686 | PyObject* pystring = PyString_FromString(format.c_str()); 1687 | 1688 | PyObject* plot_args = PyTuple_New(2); 1689 | 1690 | PyTuple_SetItem(plot_args, 0, yarray); 1691 | PyTuple_SetItem(plot_args, 1, pystring); 1692 | 1693 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_plot, plot_args, kwargs); 1694 | 1695 | Py_DECREF(kwargs); 1696 | Py_DECREF(plot_args); 1697 | if (res) Py_DECREF(res); 1698 | 1699 | return res; 1700 | } 1701 | 1702 | template 1703 | bool named_plot(const std::string& name, const std::vector& x, const std::vector& y, const std::string& format = "") 1704 | { 1705 | detail::_interpreter::get(); 1706 | 1707 | PyObject* kwargs = PyDict_New(); 1708 | PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str())); 1709 | 1710 | PyObject* xarray = detail::get_array(x); 1711 | PyObject* yarray = detail::get_array(y); 1712 | 1713 | PyObject* pystring = PyString_FromString(format.c_str()); 1714 | 1715 | PyObject* plot_args = PyTuple_New(3); 1716 | PyTuple_SetItem(plot_args, 0, xarray); 1717 | PyTuple_SetItem(plot_args, 1, yarray); 1718 | PyTuple_SetItem(plot_args, 2, pystring); 1719 | 1720 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_plot, plot_args, kwargs); 1721 | 1722 | Py_DECREF(kwargs); 1723 | Py_DECREF(plot_args); 1724 | if (res) Py_DECREF(res); 1725 | 1726 | return res; 1727 | } 1728 | 1729 | template 1730 | bool named_semilogx(const std::string& name, const std::vector& x, const std::vector& y, const std::string& format = "") 1731 | { 1732 | detail::_interpreter::get(); 1733 | 1734 | PyObject* kwargs = PyDict_New(); 1735 | PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str())); 1736 | 1737 | PyObject* xarray = detail::get_array(x); 1738 | PyObject* yarray = detail::get_array(y); 1739 | 1740 | PyObject* pystring = PyString_FromString(format.c_str()); 1741 | 1742 | PyObject* plot_args = PyTuple_New(3); 1743 | PyTuple_SetItem(plot_args, 0, xarray); 1744 | PyTuple_SetItem(plot_args, 1, yarray); 1745 | PyTuple_SetItem(plot_args, 2, pystring); 1746 | 1747 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_semilogx, plot_args, kwargs); 1748 | 1749 | Py_DECREF(kwargs); 1750 | Py_DECREF(plot_args); 1751 | if (res) Py_DECREF(res); 1752 | 1753 | return res; 1754 | } 1755 | 1756 | template 1757 | bool named_semilogy(const std::string& name, const std::vector& x, const std::vector& y, const std::string& format = "") 1758 | { 1759 | detail::_interpreter::get(); 1760 | 1761 | PyObject* kwargs = PyDict_New(); 1762 | PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str())); 1763 | 1764 | PyObject* xarray = detail::get_array(x); 1765 | PyObject* yarray = detail::get_array(y); 1766 | 1767 | PyObject* pystring = PyString_FromString(format.c_str()); 1768 | 1769 | PyObject* plot_args = PyTuple_New(3); 1770 | PyTuple_SetItem(plot_args, 0, xarray); 1771 | PyTuple_SetItem(plot_args, 1, yarray); 1772 | PyTuple_SetItem(plot_args, 2, pystring); 1773 | 1774 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_semilogy, plot_args, kwargs); 1775 | 1776 | Py_DECREF(kwargs); 1777 | Py_DECREF(plot_args); 1778 | if (res) Py_DECREF(res); 1779 | 1780 | return res; 1781 | } 1782 | 1783 | template 1784 | bool named_loglog(const std::string& name, const std::vector& x, const std::vector& y, const std::string& format = "") 1785 | { 1786 | detail::_interpreter::get(); 1787 | 1788 | PyObject* kwargs = PyDict_New(); 1789 | PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str())); 1790 | 1791 | PyObject* xarray = detail::get_array(x); 1792 | PyObject* yarray = detail::get_array(y); 1793 | 1794 | PyObject* pystring = PyString_FromString(format.c_str()); 1795 | 1796 | PyObject* plot_args = PyTuple_New(3); 1797 | PyTuple_SetItem(plot_args, 0, xarray); 1798 | PyTuple_SetItem(plot_args, 1, yarray); 1799 | PyTuple_SetItem(plot_args, 2, pystring); 1800 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_loglog, plot_args, kwargs); 1801 | 1802 | Py_DECREF(kwargs); 1803 | Py_DECREF(plot_args); 1804 | if (res) Py_DECREF(res); 1805 | 1806 | return res; 1807 | } 1808 | 1809 | template 1810 | bool plot(const std::vector& y, const std::string& format = "") 1811 | { 1812 | std::vector x(y.size()); 1813 | for(size_t i=0; i 1818 | bool plot(const std::vector& y, const std::map& keywords) 1819 | { 1820 | std::vector x(y.size()); 1821 | for(size_t i=0; i 1826 | bool stem(const std::vector& y, const std::string& format = "") 1827 | { 1828 | std::vector x(y.size()); 1829 | for (size_t i = 0; i < x.size(); ++i) x.at(i) = i; 1830 | return stem(x, y, format); 1831 | } 1832 | 1833 | template 1834 | void text(Numeric x, Numeric y, const std::string& s = "") 1835 | { 1836 | detail::_interpreter::get(); 1837 | 1838 | PyObject* args = PyTuple_New(3); 1839 | PyTuple_SetItem(args, 0, PyFloat_FromDouble(x)); 1840 | PyTuple_SetItem(args, 1, PyFloat_FromDouble(y)); 1841 | PyTuple_SetItem(args, 2, PyString_FromString(s.c_str())); 1842 | 1843 | PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_text, args); 1844 | if(!res) throw std::runtime_error("Call to text() failed."); 1845 | 1846 | Py_DECREF(args); 1847 | Py_DECREF(res); 1848 | } 1849 | 1850 | inline void colorbar(PyObject* mappable = NULL, const std::map& keywords = {}) 1851 | { 1852 | if (mappable == NULL) 1853 | throw std::runtime_error("Must call colorbar with PyObject* returned from an image, contour, surface, etc."); 1854 | 1855 | detail::_interpreter::get(); 1856 | 1857 | PyObject* args = PyTuple_New(1); 1858 | PyTuple_SetItem(args, 0, mappable); 1859 | 1860 | PyObject* kwargs = PyDict_New(); 1861 | for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) 1862 | { 1863 | PyDict_SetItemString(kwargs, it->first.c_str(), PyFloat_FromDouble(it->second)); 1864 | } 1865 | 1866 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_colorbar, args, kwargs); 1867 | if(!res) throw std::runtime_error("Call to colorbar() failed."); 1868 | 1869 | Py_DECREF(args); 1870 | Py_DECREF(kwargs); 1871 | Py_DECREF(res); 1872 | } 1873 | 1874 | 1875 | inline long figure(long number = -1) 1876 | { 1877 | detail::_interpreter::get(); 1878 | 1879 | PyObject *res; 1880 | if (number == -1) 1881 | res = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, detail::_interpreter::get().s_python_empty_tuple); 1882 | else { 1883 | assert(number > 0); 1884 | 1885 | // Make sure interpreter is initialised 1886 | detail::_interpreter::get(); 1887 | 1888 | PyObject *args = PyTuple_New(1); 1889 | PyTuple_SetItem(args, 0, PyLong_FromLong(number)); 1890 | res = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, args); 1891 | Py_DECREF(args); 1892 | } 1893 | 1894 | if(!res) throw std::runtime_error("Call to figure() failed."); 1895 | 1896 | PyObject* num = PyObject_GetAttrString(res, "number"); 1897 | if (!num) throw std::runtime_error("Could not get number attribute of figure object"); 1898 | const long figureNumber = PyLong_AsLong(num); 1899 | 1900 | Py_DECREF(num); 1901 | Py_DECREF(res); 1902 | 1903 | return figureNumber; 1904 | } 1905 | 1906 | inline bool fignum_exists(long number) 1907 | { 1908 | detail::_interpreter::get(); 1909 | 1910 | PyObject *args = PyTuple_New(1); 1911 | PyTuple_SetItem(args, 0, PyLong_FromLong(number)); 1912 | PyObject *res = PyObject_CallObject(detail::_interpreter::get().s_python_function_fignum_exists, args); 1913 | if(!res) throw std::runtime_error("Call to fignum_exists() failed."); 1914 | 1915 | bool ret = PyObject_IsTrue(res); 1916 | Py_DECREF(res); 1917 | Py_DECREF(args); 1918 | 1919 | return ret; 1920 | } 1921 | 1922 | inline void figure_size(size_t w, size_t h) 1923 | { 1924 | detail::_interpreter::get(); 1925 | 1926 | const size_t dpi = 100; 1927 | PyObject* size = PyTuple_New(2); 1928 | PyTuple_SetItem(size, 0, PyFloat_FromDouble((double)w / dpi)); 1929 | PyTuple_SetItem(size, 1, PyFloat_FromDouble((double)h / dpi)); 1930 | 1931 | PyObject* kwargs = PyDict_New(); 1932 | PyDict_SetItemString(kwargs, "figsize", size); 1933 | PyDict_SetItemString(kwargs, "dpi", PyLong_FromSize_t(dpi)); 1934 | 1935 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_figure, 1936 | detail::_interpreter::get().s_python_empty_tuple, kwargs); 1937 | 1938 | Py_DECREF(kwargs); 1939 | 1940 | if(!res) throw std::runtime_error("Call to figure_size() failed."); 1941 | Py_DECREF(res); 1942 | } 1943 | 1944 | inline void legend() 1945 | { 1946 | detail::_interpreter::get(); 1947 | 1948 | PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_legend, detail::_interpreter::get().s_python_empty_tuple); 1949 | if(!res) throw std::runtime_error("Call to legend() failed."); 1950 | 1951 | Py_DECREF(res); 1952 | } 1953 | 1954 | inline void legend(const std::map& keywords) 1955 | { 1956 | detail::_interpreter::get(); 1957 | 1958 | // construct keyword args 1959 | PyObject* kwargs = PyDict_New(); 1960 | for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) 1961 | { 1962 | PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); 1963 | } 1964 | 1965 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_legend, detail::_interpreter::get().s_python_empty_tuple, kwargs); 1966 | if(!res) throw std::runtime_error("Call to legend() failed."); 1967 | 1968 | Py_DECREF(kwargs); 1969 | Py_DECREF(res); 1970 | } 1971 | 1972 | template 1973 | inline void set_aspect(Numeric ratio) 1974 | { 1975 | detail::_interpreter::get(); 1976 | 1977 | PyObject* args = PyTuple_New(1); 1978 | PyTuple_SetItem(args, 0, PyFloat_FromDouble(ratio)); 1979 | PyObject* kwargs = PyDict_New(); 1980 | 1981 | PyObject *ax = 1982 | PyObject_CallObject(detail::_interpreter::get().s_python_function_gca, 1983 | detail::_interpreter::get().s_python_empty_tuple); 1984 | if (!ax) throw std::runtime_error("Call to gca() failed."); 1985 | Py_INCREF(ax); 1986 | 1987 | PyObject *set_aspect = PyObject_GetAttrString(ax, "set_aspect"); 1988 | if (!set_aspect) throw std::runtime_error("Attribute set_aspect not found."); 1989 | Py_INCREF(set_aspect); 1990 | 1991 | PyObject *res = PyObject_Call(set_aspect, args, kwargs); 1992 | if (!res) throw std::runtime_error("Call to set_aspect() failed."); 1993 | Py_DECREF(set_aspect); 1994 | 1995 | Py_DECREF(ax); 1996 | Py_DECREF(args); 1997 | Py_DECREF(kwargs); 1998 | } 1999 | 2000 | inline void set_aspect_equal() 2001 | { 2002 | // expect ratio == "equal". Leaving error handling to matplotlib. 2003 | detail::_interpreter::get(); 2004 | 2005 | PyObject* args = PyTuple_New(1); 2006 | PyTuple_SetItem(args, 0, PyString_FromString("equal")); 2007 | PyObject* kwargs = PyDict_New(); 2008 | 2009 | PyObject *ax = 2010 | PyObject_CallObject(detail::_interpreter::get().s_python_function_gca, 2011 | detail::_interpreter::get().s_python_empty_tuple); 2012 | if (!ax) throw std::runtime_error("Call to gca() failed."); 2013 | Py_INCREF(ax); 2014 | 2015 | PyObject *set_aspect = PyObject_GetAttrString(ax, "set_aspect"); 2016 | if (!set_aspect) throw std::runtime_error("Attribute set_aspect not found."); 2017 | Py_INCREF(set_aspect); 2018 | 2019 | PyObject *res = PyObject_Call(set_aspect, args, kwargs); 2020 | if (!res) throw std::runtime_error("Call to set_aspect() failed."); 2021 | Py_DECREF(set_aspect); 2022 | 2023 | Py_DECREF(ax); 2024 | Py_DECREF(args); 2025 | Py_DECREF(kwargs); 2026 | } 2027 | 2028 | template 2029 | void ylim(Numeric left, Numeric right) 2030 | { 2031 | detail::_interpreter::get(); 2032 | 2033 | PyObject* list = PyList_New(2); 2034 | PyList_SetItem(list, 0, PyFloat_FromDouble(left)); 2035 | PyList_SetItem(list, 1, PyFloat_FromDouble(right)); 2036 | 2037 | PyObject* args = PyTuple_New(1); 2038 | PyTuple_SetItem(args, 0, list); 2039 | 2040 | PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_ylim, args); 2041 | if(!res) throw std::runtime_error("Call to ylim() failed."); 2042 | 2043 | Py_DECREF(args); 2044 | Py_DECREF(res); 2045 | } 2046 | 2047 | template 2048 | void xlim(Numeric left, Numeric right) 2049 | { 2050 | detail::_interpreter::get(); 2051 | 2052 | PyObject* list = PyList_New(2); 2053 | PyList_SetItem(list, 0, PyFloat_FromDouble(left)); 2054 | PyList_SetItem(list, 1, PyFloat_FromDouble(right)); 2055 | 2056 | PyObject* args = PyTuple_New(1); 2057 | PyTuple_SetItem(args, 0, list); 2058 | 2059 | PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_xlim, args); 2060 | if(!res) throw std::runtime_error("Call to xlim() failed."); 2061 | 2062 | Py_DECREF(args); 2063 | Py_DECREF(res); 2064 | } 2065 | 2066 | 2067 | inline std::array xlim() 2068 | { 2069 | PyObject* args = PyTuple_New(0); 2070 | PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_xlim, args); 2071 | 2072 | if(!res) throw std::runtime_error("Call to xlim() failed."); 2073 | 2074 | Py_DECREF(res); 2075 | 2076 | PyObject* left = PyTuple_GetItem(res,0); 2077 | PyObject* right = PyTuple_GetItem(res,1); 2078 | return { PyFloat_AsDouble(left), PyFloat_AsDouble(right) }; 2079 | } 2080 | 2081 | 2082 | inline std::array ylim() 2083 | { 2084 | PyObject* args = PyTuple_New(0); 2085 | PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_ylim, args); 2086 | 2087 | if(!res) throw std::runtime_error("Call to ylim() failed."); 2088 | 2089 | Py_DECREF(res); 2090 | 2091 | PyObject* left = PyTuple_GetItem(res,0); 2092 | PyObject* right = PyTuple_GetItem(res,1); 2093 | return { PyFloat_AsDouble(left), PyFloat_AsDouble(right) }; 2094 | } 2095 | 2096 | template 2097 | inline void xticks(const std::vector &ticks, const std::vector &labels = {}, const std::map& keywords = {}) 2098 | { 2099 | assert(labels.size() == 0 || ticks.size() == labels.size()); 2100 | 2101 | detail::_interpreter::get(); 2102 | 2103 | // using numpy array 2104 | PyObject* ticksarray = detail::get_array(ticks); 2105 | 2106 | PyObject* args; 2107 | if(labels.size() == 0) { 2108 | // construct positional args 2109 | args = PyTuple_New(1); 2110 | PyTuple_SetItem(args, 0, ticksarray); 2111 | } else { 2112 | // make tuple of tick labels 2113 | PyObject* labelstuple = PyTuple_New(labels.size()); 2114 | for (size_t i = 0; i < labels.size(); i++) 2115 | PyTuple_SetItem(labelstuple, i, PyUnicode_FromString(labels[i].c_str())); 2116 | 2117 | // construct positional args 2118 | args = PyTuple_New(2); 2119 | PyTuple_SetItem(args, 0, ticksarray); 2120 | PyTuple_SetItem(args, 1, labelstuple); 2121 | } 2122 | 2123 | // construct keyword args 2124 | PyObject* kwargs = PyDict_New(); 2125 | for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) 2126 | { 2127 | PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); 2128 | } 2129 | 2130 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_xticks, args, kwargs); 2131 | 2132 | Py_DECREF(args); 2133 | Py_DECREF(kwargs); 2134 | if(!res) throw std::runtime_error("Call to xticks() failed"); 2135 | 2136 | Py_DECREF(res); 2137 | } 2138 | 2139 | template 2140 | inline void xticks(const std::vector &ticks, const std::map& keywords) 2141 | { 2142 | xticks(ticks, {}, keywords); 2143 | } 2144 | 2145 | template 2146 | inline void yticks(const std::vector &ticks, const std::vector &labels = {}, const std::map& keywords = {}) 2147 | { 2148 | assert(labels.size() == 0 || ticks.size() == labels.size()); 2149 | 2150 | detail::_interpreter::get(); 2151 | 2152 | // using numpy array 2153 | PyObject* ticksarray = detail::get_array(ticks); 2154 | 2155 | PyObject* args; 2156 | if(labels.size() == 0) { 2157 | // construct positional args 2158 | args = PyTuple_New(1); 2159 | PyTuple_SetItem(args, 0, ticksarray); 2160 | } else { 2161 | // make tuple of tick labels 2162 | PyObject* labelstuple = PyTuple_New(labels.size()); 2163 | for (size_t i = 0; i < labels.size(); i++) 2164 | PyTuple_SetItem(labelstuple, i, PyUnicode_FromString(labels[i].c_str())); 2165 | 2166 | // construct positional args 2167 | args = PyTuple_New(2); 2168 | PyTuple_SetItem(args, 0, ticksarray); 2169 | PyTuple_SetItem(args, 1, labelstuple); 2170 | } 2171 | 2172 | // construct keyword args 2173 | PyObject* kwargs = PyDict_New(); 2174 | for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) 2175 | { 2176 | PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); 2177 | } 2178 | 2179 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_yticks, args, kwargs); 2180 | 2181 | Py_DECREF(args); 2182 | Py_DECREF(kwargs); 2183 | if(!res) throw std::runtime_error("Call to yticks() failed"); 2184 | 2185 | Py_DECREF(res); 2186 | } 2187 | 2188 | template 2189 | inline void yticks(const std::vector &ticks, const std::map& keywords) 2190 | { 2191 | yticks(ticks, {}, keywords); 2192 | } 2193 | 2194 | template inline void margins(Numeric margin) 2195 | { 2196 | // construct positional args 2197 | PyObject* args = PyTuple_New(1); 2198 | PyTuple_SetItem(args, 0, PyFloat_FromDouble(margin)); 2199 | 2200 | PyObject* res = 2201 | PyObject_CallObject(detail::_interpreter::get().s_python_function_margins, args); 2202 | if (!res) 2203 | throw std::runtime_error("Call to margins() failed."); 2204 | 2205 | Py_DECREF(args); 2206 | Py_DECREF(res); 2207 | } 2208 | 2209 | template inline void margins(Numeric margin_x, Numeric margin_y) 2210 | { 2211 | // construct positional args 2212 | PyObject* args = PyTuple_New(2); 2213 | PyTuple_SetItem(args, 0, PyFloat_FromDouble(margin_x)); 2214 | PyTuple_SetItem(args, 1, PyFloat_FromDouble(margin_y)); 2215 | 2216 | PyObject* res = 2217 | PyObject_CallObject(detail::_interpreter::get().s_python_function_margins, args); 2218 | if (!res) 2219 | throw std::runtime_error("Call to margins() failed."); 2220 | 2221 | Py_DECREF(args); 2222 | Py_DECREF(res); 2223 | } 2224 | 2225 | 2226 | inline void tick_params(const std::map& keywords, const std::string axis = "both") 2227 | { 2228 | detail::_interpreter::get(); 2229 | 2230 | // construct positional args 2231 | PyObject* args; 2232 | args = PyTuple_New(1); 2233 | PyTuple_SetItem(args, 0, PyString_FromString(axis.c_str())); 2234 | 2235 | // construct keyword args 2236 | PyObject* kwargs = PyDict_New(); 2237 | for (std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) 2238 | { 2239 | PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); 2240 | } 2241 | 2242 | 2243 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_tick_params, args, kwargs); 2244 | 2245 | Py_DECREF(args); 2246 | Py_DECREF(kwargs); 2247 | if (!res) throw std::runtime_error("Call to tick_params() failed"); 2248 | 2249 | Py_DECREF(res); 2250 | } 2251 | 2252 | inline void subplot(long nrows, long ncols, long plot_number) 2253 | { 2254 | detail::_interpreter::get(); 2255 | 2256 | // construct positional args 2257 | PyObject* args = PyTuple_New(3); 2258 | PyTuple_SetItem(args, 0, PyFloat_FromDouble(nrows)); 2259 | PyTuple_SetItem(args, 1, PyFloat_FromDouble(ncols)); 2260 | PyTuple_SetItem(args, 2, PyFloat_FromDouble(plot_number)); 2261 | 2262 | PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_subplot, args); 2263 | if(!res) throw std::runtime_error("Call to subplot() failed."); 2264 | 2265 | Py_DECREF(args); 2266 | Py_DECREF(res); 2267 | } 2268 | 2269 | inline void subplot2grid(long nrows, long ncols, long rowid=0, long colid=0, long rowspan=1, long colspan=1) 2270 | { 2271 | detail::_interpreter::get(); 2272 | 2273 | PyObject* shape = PyTuple_New(2); 2274 | PyTuple_SetItem(shape, 0, PyLong_FromLong(nrows)); 2275 | PyTuple_SetItem(shape, 1, PyLong_FromLong(ncols)); 2276 | 2277 | PyObject* loc = PyTuple_New(2); 2278 | PyTuple_SetItem(loc, 0, PyLong_FromLong(rowid)); 2279 | PyTuple_SetItem(loc, 1, PyLong_FromLong(colid)); 2280 | 2281 | PyObject* args = PyTuple_New(4); 2282 | PyTuple_SetItem(args, 0, shape); 2283 | PyTuple_SetItem(args, 1, loc); 2284 | PyTuple_SetItem(args, 2, PyLong_FromLong(rowspan)); 2285 | PyTuple_SetItem(args, 3, PyLong_FromLong(colspan)); 2286 | 2287 | PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_subplot2grid, args); 2288 | if(!res) throw std::runtime_error("Call to subplot2grid() failed."); 2289 | 2290 | Py_DECREF(shape); 2291 | Py_DECREF(loc); 2292 | Py_DECREF(args); 2293 | Py_DECREF(res); 2294 | } 2295 | 2296 | inline void title(const std::string &titlestr, const std::map &keywords = {}) 2297 | { 2298 | detail::_interpreter::get(); 2299 | 2300 | PyObject* pytitlestr = PyString_FromString(titlestr.c_str()); 2301 | PyObject* args = PyTuple_New(1); 2302 | PyTuple_SetItem(args, 0, pytitlestr); 2303 | 2304 | PyObject* kwargs = PyDict_New(); 2305 | for (auto it = keywords.begin(); it != keywords.end(); ++it) { 2306 | PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); 2307 | } 2308 | 2309 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_title, args, kwargs); 2310 | if(!res) throw std::runtime_error("Call to title() failed."); 2311 | 2312 | Py_DECREF(args); 2313 | Py_DECREF(kwargs); 2314 | Py_DECREF(res); 2315 | } 2316 | 2317 | inline void suptitle(const std::string &suptitlestr, const std::map &keywords = {}) 2318 | { 2319 | detail::_interpreter::get(); 2320 | 2321 | PyObject* pysuptitlestr = PyString_FromString(suptitlestr.c_str()); 2322 | PyObject* args = PyTuple_New(1); 2323 | PyTuple_SetItem(args, 0, pysuptitlestr); 2324 | 2325 | PyObject* kwargs = PyDict_New(); 2326 | for (auto it = keywords.begin(); it != keywords.end(); ++it) { 2327 | PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); 2328 | } 2329 | 2330 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_suptitle, args, kwargs); 2331 | if(!res) throw std::runtime_error("Call to suptitle() failed."); 2332 | 2333 | Py_DECREF(args); 2334 | Py_DECREF(kwargs); 2335 | Py_DECREF(res); 2336 | } 2337 | 2338 | inline void axis(const std::string &axisstr) 2339 | { 2340 | detail::_interpreter::get(); 2341 | 2342 | PyObject* str = PyString_FromString(axisstr.c_str()); 2343 | PyObject* args = PyTuple_New(1); 2344 | PyTuple_SetItem(args, 0, str); 2345 | 2346 | PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_axis, args); 2347 | if(!res) throw std::runtime_error("Call to title() failed."); 2348 | 2349 | Py_DECREF(args); 2350 | Py_DECREF(res); 2351 | } 2352 | 2353 | inline void axhline(double y, double xmin = 0., double xmax = 1., const std::map& keywords = std::map()) 2354 | { 2355 | detail::_interpreter::get(); 2356 | 2357 | // construct positional args 2358 | PyObject* args = PyTuple_New(3); 2359 | PyTuple_SetItem(args, 0, PyFloat_FromDouble(y)); 2360 | PyTuple_SetItem(args, 1, PyFloat_FromDouble(xmin)); 2361 | PyTuple_SetItem(args, 2, PyFloat_FromDouble(xmax)); 2362 | 2363 | // construct keyword args 2364 | PyObject* kwargs = PyDict_New(); 2365 | for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) 2366 | { 2367 | PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); 2368 | } 2369 | 2370 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_axhline, args, kwargs); 2371 | 2372 | Py_DECREF(args); 2373 | Py_DECREF(kwargs); 2374 | 2375 | if(res) Py_DECREF(res); 2376 | } 2377 | 2378 | inline void axvline(double x, double ymin = 0., double ymax = 1., const std::map& keywords = std::map()) 2379 | { 2380 | detail::_interpreter::get(); 2381 | 2382 | // construct positional args 2383 | PyObject* args = PyTuple_New(3); 2384 | PyTuple_SetItem(args, 0, PyFloat_FromDouble(x)); 2385 | PyTuple_SetItem(args, 1, PyFloat_FromDouble(ymin)); 2386 | PyTuple_SetItem(args, 2, PyFloat_FromDouble(ymax)); 2387 | 2388 | // construct keyword args 2389 | PyObject* kwargs = PyDict_New(); 2390 | for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) 2391 | { 2392 | PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); 2393 | } 2394 | 2395 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_axvline, args, kwargs); 2396 | 2397 | Py_DECREF(args); 2398 | Py_DECREF(kwargs); 2399 | 2400 | if(res) Py_DECREF(res); 2401 | } 2402 | 2403 | inline void axvspan(double xmin, double xmax, double ymin = 0., double ymax = 1., const std::map& keywords = std::map()) 2404 | { 2405 | // construct positional args 2406 | PyObject* args = PyTuple_New(4); 2407 | PyTuple_SetItem(args, 0, PyFloat_FromDouble(xmin)); 2408 | PyTuple_SetItem(args, 1, PyFloat_FromDouble(xmax)); 2409 | PyTuple_SetItem(args, 2, PyFloat_FromDouble(ymin)); 2410 | PyTuple_SetItem(args, 3, PyFloat_FromDouble(ymax)); 2411 | 2412 | // construct keyword args 2413 | PyObject* kwargs = PyDict_New(); 2414 | for (auto it = keywords.begin(); it != keywords.end(); ++it) { 2415 | if (it->first == "linewidth" || it->first == "alpha") { 2416 | PyDict_SetItemString(kwargs, it->first.c_str(), 2417 | PyFloat_FromDouble(std::stod(it->second))); 2418 | } else { 2419 | PyDict_SetItemString(kwargs, it->first.c_str(), 2420 | PyString_FromString(it->second.c_str())); 2421 | } 2422 | } 2423 | 2424 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_axvspan, args, kwargs); 2425 | Py_DECREF(args); 2426 | Py_DECREF(kwargs); 2427 | 2428 | if(res) Py_DECREF(res); 2429 | } 2430 | 2431 | inline void xlabel(const std::string &str, const std::map &keywords = {}) 2432 | { 2433 | detail::_interpreter::get(); 2434 | 2435 | PyObject* pystr = PyString_FromString(str.c_str()); 2436 | PyObject* args = PyTuple_New(1); 2437 | PyTuple_SetItem(args, 0, pystr); 2438 | 2439 | PyObject* kwargs = PyDict_New(); 2440 | for (auto it = keywords.begin(); it != keywords.end(); ++it) { 2441 | PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); 2442 | } 2443 | 2444 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_xlabel, args, kwargs); 2445 | if(!res) throw std::runtime_error("Call to xlabel() failed."); 2446 | 2447 | Py_DECREF(args); 2448 | Py_DECREF(kwargs); 2449 | Py_DECREF(res); 2450 | } 2451 | 2452 | inline void ylabel(const std::string &str, const std::map& keywords = {}) 2453 | { 2454 | detail::_interpreter::get(); 2455 | 2456 | PyObject* pystr = PyString_FromString(str.c_str()); 2457 | PyObject* args = PyTuple_New(1); 2458 | PyTuple_SetItem(args, 0, pystr); 2459 | 2460 | PyObject* kwargs = PyDict_New(); 2461 | for (auto it = keywords.begin(); it != keywords.end(); ++it) { 2462 | PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); 2463 | } 2464 | 2465 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_ylabel, args, kwargs); 2466 | if(!res) throw std::runtime_error("Call to ylabel() failed."); 2467 | 2468 | Py_DECREF(args); 2469 | Py_DECREF(kwargs); 2470 | Py_DECREF(res); 2471 | } 2472 | 2473 | inline void set_zlabel(const std::string &str, const std::map& keywords = {}) 2474 | { 2475 | detail::_interpreter::get(); 2476 | 2477 | // Same as with plot_surface: We lazily load the modules here the first time 2478 | // this function is called because I'm not sure that we can assume "matplotlib 2479 | // installed" implies "mpl_toolkits installed" on all platforms, and we don't 2480 | // want to require it for people who don't need 3d plots. 2481 | static PyObject *mpl_toolkitsmod = nullptr, *axis3dmod = nullptr; 2482 | if (!mpl_toolkitsmod) { 2483 | PyObject* mpl_toolkits = PyString_FromString("mpl_toolkits"); 2484 | PyObject* axis3d = PyString_FromString("mpl_toolkits.mplot3d"); 2485 | if (!mpl_toolkits || !axis3d) { throw std::runtime_error("couldnt create string"); } 2486 | 2487 | mpl_toolkitsmod = PyImport_Import(mpl_toolkits); 2488 | Py_DECREF(mpl_toolkits); 2489 | if (!mpl_toolkitsmod) { throw std::runtime_error("Error loading module mpl_toolkits!"); } 2490 | 2491 | axis3dmod = PyImport_Import(axis3d); 2492 | Py_DECREF(axis3d); 2493 | if (!axis3dmod) { throw std::runtime_error("Error loading module mpl_toolkits.mplot3d!"); } 2494 | } 2495 | 2496 | PyObject* pystr = PyString_FromString(str.c_str()); 2497 | PyObject* args = PyTuple_New(1); 2498 | PyTuple_SetItem(args, 0, pystr); 2499 | 2500 | PyObject* kwargs = PyDict_New(); 2501 | for (auto it = keywords.begin(); it != keywords.end(); ++it) { 2502 | PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); 2503 | } 2504 | 2505 | PyObject *ax = 2506 | PyObject_CallObject(detail::_interpreter::get().s_python_function_gca, 2507 | detail::_interpreter::get().s_python_empty_tuple); 2508 | if (!ax) throw std::runtime_error("Call to gca() failed."); 2509 | Py_INCREF(ax); 2510 | 2511 | PyObject *zlabel = PyObject_GetAttrString(ax, "set_zlabel"); 2512 | if (!zlabel) throw std::runtime_error("Attribute set_zlabel not found."); 2513 | Py_INCREF(zlabel); 2514 | 2515 | PyObject *res = PyObject_Call(zlabel, args, kwargs); 2516 | if (!res) throw std::runtime_error("Call to set_zlabel() failed."); 2517 | Py_DECREF(zlabel); 2518 | 2519 | Py_DECREF(ax); 2520 | Py_DECREF(args); 2521 | Py_DECREF(kwargs); 2522 | if (res) Py_DECREF(res); 2523 | } 2524 | 2525 | inline void grid(bool flag) 2526 | { 2527 | detail::_interpreter::get(); 2528 | 2529 | PyObject* pyflag = flag ? Py_True : Py_False; 2530 | Py_INCREF(pyflag); 2531 | 2532 | PyObject* args = PyTuple_New(1); 2533 | PyTuple_SetItem(args, 0, pyflag); 2534 | 2535 | PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_grid, args); 2536 | if(!res) throw std::runtime_error("Call to grid() failed."); 2537 | 2538 | Py_DECREF(args); 2539 | Py_DECREF(res); 2540 | } 2541 | 2542 | inline void show(const bool block = true) 2543 | { 2544 | detail::_interpreter::get(); 2545 | 2546 | PyObject* res; 2547 | if(block) 2548 | { 2549 | res = PyObject_CallObject( 2550 | detail::_interpreter::get().s_python_function_show, 2551 | detail::_interpreter::get().s_python_empty_tuple); 2552 | } 2553 | else 2554 | { 2555 | PyObject *kwargs = PyDict_New(); 2556 | PyDict_SetItemString(kwargs, "block", Py_False); 2557 | res = PyObject_Call( detail::_interpreter::get().s_python_function_show, detail::_interpreter::get().s_python_empty_tuple, kwargs); 2558 | Py_DECREF(kwargs); 2559 | } 2560 | 2561 | 2562 | if (!res) throw std::runtime_error("Call to show() failed."); 2563 | 2564 | Py_DECREF(res); 2565 | } 2566 | 2567 | inline void close() 2568 | { 2569 | detail::_interpreter::get(); 2570 | 2571 | PyObject* res = PyObject_CallObject( 2572 | detail::_interpreter::get().s_python_function_close, 2573 | detail::_interpreter::get().s_python_empty_tuple); 2574 | 2575 | if (!res) throw std::runtime_error("Call to close() failed."); 2576 | 2577 | Py_DECREF(res); 2578 | } 2579 | 2580 | inline void xkcd() { 2581 | detail::_interpreter::get(); 2582 | 2583 | PyObject* res; 2584 | PyObject *kwargs = PyDict_New(); 2585 | 2586 | res = PyObject_Call(detail::_interpreter::get().s_python_function_xkcd, 2587 | detail::_interpreter::get().s_python_empty_tuple, kwargs); 2588 | 2589 | Py_DECREF(kwargs); 2590 | 2591 | if (!res) 2592 | throw std::runtime_error("Call to show() failed."); 2593 | 2594 | Py_DECREF(res); 2595 | } 2596 | 2597 | inline void draw() 2598 | { 2599 | detail::_interpreter::get(); 2600 | 2601 | PyObject* res = PyObject_CallObject( 2602 | detail::_interpreter::get().s_python_function_draw, 2603 | detail::_interpreter::get().s_python_empty_tuple); 2604 | 2605 | if (!res) throw std::runtime_error("Call to draw() failed."); 2606 | 2607 | Py_DECREF(res); 2608 | } 2609 | 2610 | template 2611 | inline void pause(Numeric interval) 2612 | { 2613 | detail::_interpreter::get(); 2614 | 2615 | PyObject* args = PyTuple_New(1); 2616 | PyTuple_SetItem(args, 0, PyFloat_FromDouble(interval)); 2617 | 2618 | PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_pause, args); 2619 | if(!res) throw std::runtime_error("Call to pause() failed."); 2620 | 2621 | Py_DECREF(args); 2622 | Py_DECREF(res); 2623 | } 2624 | 2625 | inline void save(const std::string& filename, const int dpi=0) 2626 | { 2627 | detail::_interpreter::get(); 2628 | 2629 | PyObject* pyfilename = PyString_FromString(filename.c_str()); 2630 | 2631 | PyObject* args = PyTuple_New(1); 2632 | PyTuple_SetItem(args, 0, pyfilename); 2633 | 2634 | PyObject* kwargs = PyDict_New(); 2635 | 2636 | if(dpi > 0) 2637 | { 2638 | PyDict_SetItemString(kwargs, "dpi", PyLong_FromLong(dpi)); 2639 | } 2640 | 2641 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_save, args, kwargs); 2642 | if (!res) throw std::runtime_error("Call to save() failed."); 2643 | 2644 | Py_DECREF(args); 2645 | Py_DECREF(kwargs); 2646 | Py_DECREF(res); 2647 | } 2648 | 2649 | inline void rcparams(const std::map& keywords = {}) { 2650 | detail::_interpreter::get(); 2651 | PyObject* args = PyTuple_New(0); 2652 | PyObject* kwargs = PyDict_New(); 2653 | for (auto it = keywords.begin(); it != keywords.end(); ++it) { 2654 | if ("text.usetex" == it->first) 2655 | PyDict_SetItemString(kwargs, it->first.c_str(), PyLong_FromLong(std::stoi(it->second.c_str()))); 2656 | else PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str())); 2657 | } 2658 | 2659 | PyObject * update = PyObject_GetAttrString(detail::_interpreter::get().s_python_function_rcparams, "update"); 2660 | PyObject * res = PyObject_Call(update, args, kwargs); 2661 | if(!res) throw std::runtime_error("Call to rcParams.update() failed."); 2662 | Py_DECREF(args); 2663 | Py_DECREF(kwargs); 2664 | Py_DECREF(update); 2665 | Py_DECREF(res); 2666 | } 2667 | 2668 | inline void clf() { 2669 | detail::_interpreter::get(); 2670 | 2671 | PyObject *res = PyObject_CallObject( 2672 | detail::_interpreter::get().s_python_function_clf, 2673 | detail::_interpreter::get().s_python_empty_tuple); 2674 | 2675 | if (!res) throw std::runtime_error("Call to clf() failed."); 2676 | 2677 | Py_DECREF(res); 2678 | } 2679 | 2680 | inline void cla() { 2681 | detail::_interpreter::get(); 2682 | 2683 | PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_cla, 2684 | detail::_interpreter::get().s_python_empty_tuple); 2685 | 2686 | if (!res) 2687 | throw std::runtime_error("Call to cla() failed."); 2688 | 2689 | Py_DECREF(res); 2690 | } 2691 | 2692 | inline void ion() { 2693 | detail::_interpreter::get(); 2694 | 2695 | PyObject *res = PyObject_CallObject( 2696 | detail::_interpreter::get().s_python_function_ion, 2697 | detail::_interpreter::get().s_python_empty_tuple); 2698 | 2699 | if (!res) throw std::runtime_error("Call to ion() failed."); 2700 | 2701 | Py_DECREF(res); 2702 | } 2703 | 2704 | inline std::vector> ginput(const int numClicks = 1, const std::map& keywords = {}) 2705 | { 2706 | detail::_interpreter::get(); 2707 | 2708 | PyObject *args = PyTuple_New(1); 2709 | PyTuple_SetItem(args, 0, PyLong_FromLong(numClicks)); 2710 | 2711 | // construct keyword args 2712 | PyObject* kwargs = PyDict_New(); 2713 | for(std::map::const_iterator it = keywords.begin(); it != keywords.end(); ++it) 2714 | { 2715 | PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str())); 2716 | } 2717 | 2718 | PyObject* res = PyObject_Call( 2719 | detail::_interpreter::get().s_python_function_ginput, args, kwargs); 2720 | 2721 | Py_DECREF(kwargs); 2722 | Py_DECREF(args); 2723 | if (!res) throw std::runtime_error("Call to ginput() failed."); 2724 | 2725 | const size_t len = PyList_Size(res); 2726 | std::vector> out; 2727 | out.reserve(len); 2728 | for (size_t i = 0; i < len; i++) { 2729 | PyObject *current = PyList_GetItem(res, i); 2730 | std::array position; 2731 | position[0] = PyFloat_AsDouble(PyTuple_GetItem(current, 0)); 2732 | position[1] = PyFloat_AsDouble(PyTuple_GetItem(current, 1)); 2733 | out.push_back(position); 2734 | } 2735 | Py_DECREF(res); 2736 | 2737 | return out; 2738 | } 2739 | 2740 | // Actually, is there any reason not to call this automatically for every plot? 2741 | inline void tight_layout() { 2742 | detail::_interpreter::get(); 2743 | 2744 | PyObject *res = PyObject_CallObject( 2745 | detail::_interpreter::get().s_python_function_tight_layout, 2746 | detail::_interpreter::get().s_python_empty_tuple); 2747 | 2748 | if (!res) throw std::runtime_error("Call to tight_layout() failed."); 2749 | 2750 | Py_DECREF(res); 2751 | } 2752 | 2753 | // Support for variadic plot() and initializer lists: 2754 | 2755 | namespace detail { 2756 | 2757 | template 2758 | using is_function = typename std::is_function>>::type; 2759 | 2760 | template 2761 | struct is_callable_impl; 2762 | 2763 | template 2764 | struct is_callable_impl 2765 | { 2766 | typedef is_function type; 2767 | }; // a non-object is callable iff it is a function 2768 | 2769 | template 2770 | struct is_callable_impl 2771 | { 2772 | struct Fallback { void operator()(); }; 2773 | struct Derived : T, Fallback { }; 2774 | 2775 | template struct Check; 2776 | 2777 | template 2778 | static std::true_type test( ... ); // use a variadic function to make sure (1) it accepts everything and (2) its always the worst match 2779 | 2780 | template 2781 | static std::false_type test( Check* ); 2782 | 2783 | public: 2784 | typedef decltype(test(nullptr)) type; 2785 | typedef decltype(&Fallback::operator()) dtype; 2786 | static constexpr bool value = type::value; 2787 | }; // an object is callable iff it defines operator() 2788 | 2789 | template 2790 | struct is_callable 2791 | { 2792 | // dispatch to is_callable_impl or is_callable_impl depending on whether T is of class type or not 2793 | typedef typename is_callable_impl::value, T>::type type; 2794 | }; 2795 | 2796 | template 2797 | struct plot_impl { }; 2798 | 2799 | template<> 2800 | struct plot_impl 2801 | { 2802 | template 2803 | bool operator()(const IterableX& x, const IterableY& y, const std::string& format) 2804 | { 2805 | detail::_interpreter::get(); 2806 | 2807 | // 2-phase lookup for distance, begin, end 2808 | using std::distance; 2809 | using std::begin; 2810 | using std::end; 2811 | 2812 | auto xs = distance(begin(x), end(x)); 2813 | auto ys = distance(begin(y), end(y)); 2814 | assert(xs == ys && "x and y data must have the same number of elements!"); 2815 | 2816 | PyObject* xlist = PyList_New(xs); 2817 | PyObject* ylist = PyList_New(ys); 2818 | PyObject* pystring = PyString_FromString(format.c_str()); 2819 | 2820 | auto itx = begin(x), ity = begin(y); 2821 | for(size_t i = 0; i < xs; ++i) { 2822 | PyList_SetItem(xlist, i, PyFloat_FromDouble(*itx++)); 2823 | PyList_SetItem(ylist, i, PyFloat_FromDouble(*ity++)); 2824 | } 2825 | 2826 | PyObject* plot_args = PyTuple_New(3); 2827 | PyTuple_SetItem(plot_args, 0, xlist); 2828 | PyTuple_SetItem(plot_args, 1, ylist); 2829 | PyTuple_SetItem(plot_args, 2, pystring); 2830 | 2831 | PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_plot, plot_args); 2832 | 2833 | Py_DECREF(plot_args); 2834 | if(res) Py_DECREF(res); 2835 | 2836 | return res; 2837 | } 2838 | }; 2839 | 2840 | template<> 2841 | struct plot_impl 2842 | { 2843 | template 2844 | bool operator()(const Iterable& ticks, const Callable& f, const std::string& format) 2845 | { 2846 | if(begin(ticks) == end(ticks)) return true; 2847 | 2848 | // We could use additional meta-programming to deduce the correct element type of y, 2849 | // but all values have to be convertible to double anyways 2850 | std::vector y; 2851 | for(auto x : ticks) y.push_back(f(x)); 2852 | return plot_impl()(ticks,y,format); 2853 | } 2854 | }; 2855 | 2856 | } // end namespace detail 2857 | 2858 | // recursion stop for the above 2859 | template 2860 | bool plot() { return true; } 2861 | 2862 | template 2863 | bool plot(const A& a, const B& b, const std::string& format, Args... args) 2864 | { 2865 | return detail::plot_impl::type>()(a,b,format) && plot(args...); 2866 | } 2867 | 2868 | /* 2869 | * This group of plot() functions is needed to support initializer lists, i.e. calling 2870 | * plot( {1,2,3,4} ) 2871 | */ 2872 | inline bool plot(const std::vector& x, const std::vector& y, const std::string& format = "") { 2873 | return plot(x,y,format); 2874 | } 2875 | 2876 | inline bool plot(const std::vector& y, const std::string& format = "") { 2877 | return plot(y,format); 2878 | } 2879 | 2880 | inline bool plot(const std::vector& x, const std::vector& y, const std::map& keywords) { 2881 | return plot(x,y,keywords); 2882 | } 2883 | 2884 | /* 2885 | * This class allows dynamic plots, ie changing the plotted data without clearing and re-plotting 2886 | */ 2887 | class Plot 2888 | { 2889 | public: 2890 | // default initialization with plot label, some data and format 2891 | template 2892 | Plot(const std::string& name, const std::vector& x, const std::vector& y, const std::string& format = "") { 2893 | detail::_interpreter::get(); 2894 | 2895 | assert(x.size() == y.size()); 2896 | 2897 | PyObject* kwargs = PyDict_New(); 2898 | if(name != "") 2899 | PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str())); 2900 | 2901 | PyObject* xarray = detail::get_array(x); 2902 | PyObject* yarray = detail::get_array(y); 2903 | 2904 | PyObject* pystring = PyString_FromString(format.c_str()); 2905 | 2906 | PyObject* plot_args = PyTuple_New(3); 2907 | PyTuple_SetItem(plot_args, 0, xarray); 2908 | PyTuple_SetItem(plot_args, 1, yarray); 2909 | PyTuple_SetItem(plot_args, 2, pystring); 2910 | 2911 | PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_plot, plot_args, kwargs); 2912 | 2913 | Py_DECREF(kwargs); 2914 | Py_DECREF(plot_args); 2915 | 2916 | if(res) 2917 | { 2918 | line= PyList_GetItem(res, 0); 2919 | 2920 | if(line) 2921 | set_data_fct = PyObject_GetAttrString(line,"set_data"); 2922 | else 2923 | Py_DECREF(line); 2924 | Py_DECREF(res); 2925 | } 2926 | } 2927 | 2928 | // shorter initialization with name or format only 2929 | // basically calls line, = plot([], []) 2930 | Plot(const std::string& name = "", const std::string& format = "") 2931 | : Plot(name, std::vector(), std::vector(), format) {} 2932 | 2933 | template 2934 | bool update(const std::vector& x, const std::vector& y) { 2935 | assert(x.size() == y.size()); 2936 | if(set_data_fct) 2937 | { 2938 | PyObject* xarray = detail::get_array(x); 2939 | PyObject* yarray = detail::get_array(y); 2940 | 2941 | PyObject* plot_args = PyTuple_New(2); 2942 | PyTuple_SetItem(plot_args, 0, xarray); 2943 | PyTuple_SetItem(plot_args, 1, yarray); 2944 | 2945 | PyObject* res = PyObject_CallObject(set_data_fct, plot_args); 2946 | if (res) Py_DECREF(res); 2947 | return res; 2948 | } 2949 | return false; 2950 | } 2951 | 2952 | // clears the plot but keep it available 2953 | bool clear() { 2954 | return update(std::vector(), std::vector()); 2955 | } 2956 | 2957 | // definitely remove this line 2958 | void remove() { 2959 | if(line) 2960 | { 2961 | auto remove_fct = PyObject_GetAttrString(line,"remove"); 2962 | PyObject* args = PyTuple_New(0); 2963 | PyObject* res = PyObject_CallObject(remove_fct, args); 2964 | if (res) Py_DECREF(res); 2965 | } 2966 | decref(); 2967 | } 2968 | 2969 | ~Plot() { 2970 | decref(); 2971 | } 2972 | private: 2973 | 2974 | void decref() { 2975 | if(line) 2976 | Py_DECREF(line); 2977 | if(set_data_fct) 2978 | Py_DECREF(set_data_fct); 2979 | } 2980 | 2981 | 2982 | PyObject* line = nullptr; 2983 | PyObject* set_data_fct = nullptr; 2984 | }; 2985 | 2986 | } // end namespace matplotlibcpp 2987 | -------------------------------------------------------------------------------- /model_predictive_control/readme.md: -------------------------------------------------------------------------------- 1 | # 模型预测控制(Model Predictive Control) 2 | 3 | ## 1.介绍 4 | 5 | 该仓库主要对MPC算法进行了一个简单地实现, 从而达到学习和理解MPC的目的。 6 | 7 | 对于MPC公式的推导和介绍,可以参考我的博客[《【附C++源代码】模型预测控制(MPC)公式推导以及算法实现,Model Predictive control介绍》](https://blog.csdn.net/u011341856/article/details/122799600) 8 | 9 | 10 | 11 | ## 2. 依赖库 12 | 13 | **Eigen** 14 | 15 | ```shell 16 | sudo apt-get install libeigen3-dev 17 | ``` 18 | 19 | **python** 20 | 21 | ```shell 22 | sudo apt-get install python-matplotlib python-numpy python2.7-dev 23 | ``` 24 | 25 | ## 3. 编译和运行 26 | 27 | ```shell 28 | cd algorithm_learning/model_predictive_control 29 | mkdir build 30 | cd build 31 | cmake .. 32 | make 33 | 34 | # 运行 35 | ./model_predictive_control 36 | ``` 37 | 38 | 39 | 40 | 41 | 42 | -------------------------------------------------------------------------------- /model_predictive_control/实验结果.md: -------------------------------------------------------------------------------- 1 | 2 | 3 | **预测窗口大小的影响** 4 | 5 | | N = 1 | N = 2 | 6 | | :----------------------------------------------------------: | :----------------------------------------------------------: | 7 | | 2022-02-06 16-24-10 的屏幕截图 | 2022-02-06 16-23-31 的屏幕截图 | 8 | | N = 3 | N = 4 | 9 | | 2022-02-06 16-16-58 的屏幕截图 | 2022-02-06 16-17-31 的屏幕截图 | 10 | | N = 5 | N = 6 | 11 | | 2022-02-06 16-18-44 的屏幕截图 | 2022-02-06 16-19-25 的屏幕截图 | 12 | | N = 10 | N = 20 | 13 | | 2022-02-06 16-20-08 的屏幕截图 | 2022-02-06 16-20-52 的屏幕截图 | 14 | 15 | 16 | 17 | **权重矩阵F的影响** 18 | 19 | | F=[1,0; 0,1] | F=[2,0; 0,2] | 20 | | :----------------------------------------------------------: | :----------------------------------------------------------: | 21 | | 2022-02-06 16-26-53 的屏幕截图 | 2022-02-06 16-27-39 的屏幕截图 | 22 | | F=[3,0; 0,3] | F=[5,0; 0,5] | 23 | | 2022-02-06 16-28-31 的屏幕截图 | 2022-02-06 16-29-22 的屏幕截图 | 24 | | F=[10,0; 0,10] | | 25 | | 2022-02-06 16-30-06 的屏幕截图 | | 26 | 27 | 28 | 29 | **权重矩阵Q的影响** 30 | 31 | | Q=[1,0;0,1] | Q=[2,0;0,2] | 32 | | :----------------------------------------------------------: | :----------------------------------------------------------: | 33 | | 2022-02-06 16-33-56 的屏幕截图 | 2022-02-06 16-34-59 的屏幕截图 | 34 | | Q=[3,0;0,3] | Q=[5,0;0,5] | 35 | | 2022-02-06 16-35-41 的屏幕截图 | 2022-02-06 16-36-34 的屏幕截图 | 36 | | Q=[10,0;0,10] | | 37 | | 2022-02-06 16-39-52 的屏幕截图 | | 38 | 39 | 40 | 41 | **权重矩阵R的影响** 42 | 43 | | R =0.1 | R =0.1 | 44 | | :----------------------------------------------------------: | :----------------------------------------------------------: | 45 | | 2022-02-06 16-41-09 的屏幕截图 | 2022-02-06 16-44-17 的屏幕截图 | 46 | | R =0.1 | R =0.1 | 47 | | 2022-02-06 16-44-51 的屏幕截图 | 2022-02-06 16-45-44 的屏幕截图 | 48 | 49 | -------------------------------------------------------------------------------- /serial_plot_tool/README.md: -------------------------------------------------------------------------------- 1 | ## 可视化串口程序 2 | 3 | ![2024-11-22 00-01-40 的屏幕截图](image/a.png) -------------------------------------------------------------------------------- /serial_plot_tool/Serial_Tool.pro: -------------------------------------------------------------------------------- 1 | QT += core gui printsupport serialport 2 | 3 | greaterThan(QT_MAJOR_VERSION, 4): QT += widgets 4 | 5 | CONFIG += c++11 6 | 7 | # The following define makes your compiler emit warnings if you use 8 | # any Qt feature that has been marked deprecated (the exact warnings 9 | # depend on your compiler). Please consult the documentation of the 10 | # deprecated API in order to know how to port your code away from it. 11 | DEFINES += QT_DEPRECATED_WARNINGS 12 | 13 | # You can also make your code fail to compile if it uses deprecated APIs. 14 | # In order to do so, uncomment the following line. 15 | # You can also select to disable deprecated APIs only up to a certain version of Qt. 16 | #DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000 # disables all the APIs deprecated before Qt 6.0.0 17 | 18 | SOURCES += \ 19 | main.cpp \ 20 | mainwindow.cpp \ 21 | qcustomplot.cpp 22 | 23 | HEADERS += \ 24 | mainwindow.h \ 25 | qcustomplot.h 26 | 27 | FORMS += \ 28 | mainwindow.ui 29 | 30 | TRANSLATIONS += \ 31 | Serial_Tool_zh_CN.ts 32 | 33 | # Default rules for deployment. 34 | qnx: target.path = /tmp/$${TARGET}/bin 35 | else: unix:!android: target.path = /opt/$${TARGET}/bin 36 | !isEmpty(target.path): INSTALLS += target 37 | -------------------------------------------------------------------------------- /serial_plot_tool/Serial_Tool.pro.user: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | EnvironmentId 7 | {cb3e8c82-ef90-4bcc-a185-5afcb9f6d9db} 8 | 9 | 10 | ProjectExplorer.Project.ActiveTarget 11 | 0 12 | 13 | 14 | ProjectExplorer.Project.EditorSettings 15 | 16 | true 17 | false 18 | true 19 | 20 | Cpp 21 | 22 | CppGlobal 23 | 24 | 25 | 26 | QmlJS 27 | 28 | QmlJSGlobal 29 | 30 | 31 | 2 32 | UTF-8 33 | false 34 | 4 35 | false 36 | 80 37 | true 38 | true 39 | 1 40 | false 41 | true 42 | false 43 | 0 44 | true 45 | true 46 | 0 47 | 8 48 | true 49 | false 50 | 1 51 | true 52 | true 53 | true 54 | *.md, *.MD, Makefile 55 | false 56 | true 57 | 58 | 59 | 60 | ProjectExplorer.Project.PluginSettings 61 | 62 | 63 | true 64 | false 65 | true 66 | true 67 | true 68 | true 69 | 70 | 71 | 0 72 | true 73 | 74 | true 75 | Builtin.BuildSystem 76 | 77 | true 78 | true 79 | Builtin.DefaultTidyAndClazy 80 | 4 81 | 82 | 83 | 84 | true 85 | 86 | 87 | 88 | 89 | ProjectExplorer.Project.Target.0 90 | 91 | Desktop 92 | 桌面 93 | 桌面 94 | {c6c5e2d8-7328-4d26-8051-20357b525a3e} 95 | 0 96 | 0 97 | 0 98 | 99 | 0 100 | /home/meng/code_my/algorithm_learning/build-Serial_Tool-unknown-Debug 101 | /home/meng/code_my/algorithm_learning/build-Serial_Tool-unknown-Debug 102 | 103 | 104 | true 105 | QtProjectManager.QMakeBuildStep 106 | false 107 | 108 | 109 | 110 | true 111 | Qt4ProjectManager.MakeStep 112 | 113 | 2 114 | Build 115 | Build 116 | ProjectExplorer.BuildSteps.Build 117 | 118 | 119 | 120 | true 121 | Qt4ProjectManager.MakeStep 122 | clean 123 | 124 | 1 125 | Clean 126 | Clean 127 | ProjectExplorer.BuildSteps.Clean 128 | 129 | 2 130 | false 131 | 132 | false 133 | 134 | Debug 135 | Qt4ProjectManager.Qt4BuildConfiguration 136 | 2 137 | 138 | 139 | /home/meng/code_my/algorithm_learning/build-Serial_Tool-unknown-Release 140 | /home/meng/code_my/algorithm_learning/build-Serial_Tool-unknown-Release 141 | 142 | 143 | true 144 | QtProjectManager.QMakeBuildStep 145 | false 146 | 147 | 148 | 149 | true 150 | Qt4ProjectManager.MakeStep 151 | 152 | 2 153 | Build 154 | Build 155 | ProjectExplorer.BuildSteps.Build 156 | 157 | 158 | 159 | true 160 | Qt4ProjectManager.MakeStep 161 | clean 162 | 163 | 1 164 | Clean 165 | Clean 166 | ProjectExplorer.BuildSteps.Clean 167 | 168 | 2 169 | false 170 | 171 | false 172 | 173 | Release 174 | Qt4ProjectManager.Qt4BuildConfiguration 175 | 0 176 | 177 | 178 | 0 179 | /home/meng/code_my/algorithm_learning/build-Serial_Tool-unknown-Profile 180 | /home/meng/code_my/algorithm_learning/build-Serial_Tool-unknown-Profile 181 | 182 | 183 | true 184 | QtProjectManager.QMakeBuildStep 185 | false 186 | 187 | 188 | 189 | true 190 | Qt4ProjectManager.MakeStep 191 | 192 | 2 193 | Build 194 | Build 195 | ProjectExplorer.BuildSteps.Build 196 | 197 | 198 | 199 | true 200 | Qt4ProjectManager.MakeStep 201 | clean 202 | 203 | 1 204 | Clean 205 | Clean 206 | ProjectExplorer.BuildSteps.Clean 207 | 208 | 2 209 | false 210 | 211 | false 212 | 213 | Profile 214 | Qt4ProjectManager.Qt4BuildConfiguration 215 | 0 216 | 0 217 | 218 | 3 219 | 220 | 221 | 0 222 | Deploy 223 | Deploy 224 | ProjectExplorer.BuildSteps.Deploy 225 | 226 | 1 227 | 228 | false 229 | ProjectExplorer.DefaultDeployConfiguration 230 | 231 | 1 232 | 233 | true 234 | true 235 | true 236 | 237 | 2 238 | 239 | Qt4ProjectManager.Qt4RunConfiguration:/home/meng/code_my/algorithm_learning/serial_plot_tool/Serial_Tool.pro 240 | /home/meng/code_my/algorithm_learning/serial_plot_tool/Serial_Tool.pro 241 | false 242 | true 243 | true 244 | false 245 | true 246 | /home/meng/code_my/algorithm_learning/build-Serial_Tool-unknown-Debug 247 | 248 | 1 249 | 250 | 251 | 252 | ProjectExplorer.Project.TargetCount 253 | 1 254 | 255 | 256 | ProjectExplorer.Project.Updater.FileVersion 257 | 22 258 | 259 | 260 | Version 261 | 22 262 | 263 | 264 | -------------------------------------------------------------------------------- /serial_plot_tool/Serial_Tool_zh_CN.ts: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /serial_plot_tool/image/a.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zm0612/algorithm_learning/529fbaaec4bd4f5e54e8e8967983a4850658f042/serial_plot_tool/image/a.png -------------------------------------------------------------------------------- /serial_plot_tool/main.cpp: -------------------------------------------------------------------------------- 1 | #include "mainwindow.h" 2 | 3 | #include 4 | 5 | int main(int argc, char *argv[]) 6 | { 7 | QApplication a(argc, argv); 8 | MainWindow w; 9 | w.show(); 10 | return a.exec(); 11 | } 12 | -------------------------------------------------------------------------------- /serial_plot_tool/mainwindow.cpp: -------------------------------------------------------------------------------- 1 | #include "mainwindow.h" 2 | #include "ui_mainwindow.h" 3 | 4 | #include 5 | 6 | MainWindow::MainWindow(QWidget *parent) 7 | : QMainWindow(parent) 8 | , ui(new Ui::MainWindow) 9 | { 10 | ui->setupUi(this); 11 | 12 | // 设置串口数据显示窗口的历史最大行数 13 | ui->SerialPortDataTextEdit->setMaximumBlockCount(100); 14 | 15 | // 新建串口程序 16 | serial_port_ = new QSerialPort; 17 | 18 | InitCustomPlot(); 19 | 20 | // connect 21 | connect(serial_port_, &QSerialPort::readyRead, this, &MainWindow::ReceiveSerialData); 22 | connect(timer_replot_, &QTimer::timeout, this, &MainWindow::CustomReplot); 23 | 24 | start_timestamp_ = std::chrono::steady_clock::now(); 25 | } 26 | 27 | void MainWindow::InitCustomPlot(){ 28 | // new custom plot graph 29 | position_graph_ = ui->CustomPlot->addGraph(); 30 | velocity_graph_ = ui->CustomPlot->addGraph(); 31 | 32 | QSharedPointer ticker(new QCPAxisTickerFixed); 33 | ticker->setTickStep(1.0); 34 | ui->CustomPlot->xAxis->setTicker(ticker); 35 | 36 | position_graph_->setName("Position"); 37 | velocity_graph_->setName("Velocity"); 38 | 39 | QPen position_pen, velocity_pen; 40 | position_pen.setWidth(position_line_width_); 41 | position_pen.setColor(QColor(255, 0, 0, 255)); 42 | velocity_pen.setWidth(velocity_line_width_); 43 | velocity_pen.setColor(QColor(0, 255, 0, 255)); 44 | 45 | position_graph_->setPen(position_pen); 46 | velocity_graph_->setPen(velocity_pen); 47 | 48 | ui->CustomPlot->legend->setVisible(true); 49 | ui->CustomPlot->setInteractions(QCP::iRangeDrag | QCP::iRangeZoom | QCP::iSelectAxes | 50 | QCP::iSelectLegend | QCP::iSelectPlottables); 51 | 52 | timer_replot_ = new QTimer(this); 53 | timer_replot_->setInterval(time_interval_replot_); 54 | } 55 | 56 | void MainWindow::CustomReplot(){ 57 | if(!is_display_position_ && !is_display_velocity_){ 58 | return; 59 | } 60 | 61 | std::pair::iterator, QVector::iterator> min_max_position; 62 | std::pair::iterator, QVector::iterator> min_max_velocity; 63 | 64 | bool position_data_valid = false; 65 | bool velocity_data_valid = false; 66 | 67 | if(position_data_vec_.empty() && velocity_data_vec_.empty()){ 68 | return; 69 | } 70 | 71 | if(position_data_vec_.size() >= 2 && is_display_position_){ 72 | position_data_valid = true; 73 | } 74 | 75 | if(velocity_data_vec_.size() >= 2 && is_display_velocity_){ 76 | velocity_data_valid = true; 77 | } 78 | 79 | if(position_data_valid){ 80 | min_max_position = std::minmax_element(std::begin(position_data_vec_), std::end(position_data_vec_)); 81 | } 82 | 83 | if(velocity_data_valid){ 84 | min_max_velocity = std::minmax_element(std::begin(velocity_data_vec_), std::end(velocity_data_vec_)); 85 | } 86 | 87 | double min_y = std::numeric_limits::max(); 88 | double max_y = std::numeric_limits::max(); 89 | double max_time_s = std::numeric_limits::max(); 90 | if(position_data_valid && velocity_data_valid){ 91 | min_y = std::min(*min_max_position.first, *min_max_velocity.first); 92 | max_y = std::max(*min_max_position.second, *min_max_velocity.second); 93 | max_time_s = std::max(velocity_time_s_vec_.back(), position_time_s_vec_.back()); 94 | } else if (position_data_valid) { 95 | min_y = *min_max_position.first; 96 | max_y = *min_max_position.second; 97 | max_time_s = position_time_s_vec_.back(); 98 | } else if(velocity_data_valid){ 99 | min_y = *min_max_velocity.first; 100 | max_y = *min_max_velocity.second; 101 | max_time_s = velocity_time_s_vec_.back(); 102 | } else { 103 | return; 104 | } 105 | 106 | if(is_display_position_){ 107 | position_graph_->setData(position_time_s_vec_, position_data_vec_); 108 | } 109 | 110 | if(is_display_velocity_){ 111 | velocity_graph_->setData(velocity_time_s_vec_, velocity_data_vec_); 112 | } 113 | 114 | if(min_y == std::numeric_limits::max() || max_y == std::numeric_limits::max()){ 115 | position_graph_->rescaleAxes();; 116 | velocity_graph_->rescaleAxes(); 117 | } else{ 118 | double delta_y = (max_y - min_y) / 5.0; 119 | ui->CustomPlot->yAxis->setRange(min_y - delta_y, max_y + delta_y); 120 | ui->CustomPlot->xAxis->setRange(std::max(0.0, max_time_s - plot_data_duration_), max_time_s); 121 | } 122 | ui->CustomPlot->replot(); 123 | } 124 | 125 | MainWindow::~MainWindow() 126 | { 127 | delete ui; 128 | } 129 | 130 | void MainWindow::on_OpenSerialPortButton_clicked() 131 | { 132 | QList serial_port_info = QSerialPortInfo::availablePorts(); 133 | 134 | if(serial_port_info.isEmpty()){ 135 | QMessageBox::warning(this, "Warning", "No available serial port found", QMessageBox::Close); 136 | return; 137 | } 138 | 139 | for (const auto& it : serial_port_info) { 140 | ui->SerialPortsComboBox->addItem(it.portName()); 141 | } 142 | } 143 | 144 | void MainWindow::on_BaudRateComboBox_currentTextChanged(const QString &arg1) 145 | { 146 | if(arg1 == "4800"){ 147 | serial_port_baud_rate_ = QSerialPort::Baud4800; 148 | } else if(arg1 == "9600"){ 149 | serial_port_baud_rate_ = QSerialPort::Baud9600; 150 | } else if(arg1 == "19200"){ 151 | serial_port_baud_rate_ = QSerialPort::Baud19200; 152 | } else if (arg1 == "38400") { 153 | serial_port_baud_rate_ = QSerialPort::Baud38400; 154 | } else if (arg1 == "57600") { 155 | serial_port_baud_rate_ = QSerialPort::Baud57600; 156 | } else if(arg1 == "115200"){ 157 | serial_port_baud_rate_ = QSerialPort::Baud115200; 158 | } 159 | } 160 | 161 | void MainWindow::on_DataBitsComboBox_currentTextChanged(const QString &arg1) 162 | { 163 | if(arg1 == "5"){ 164 | serial_port_data_bits_ = QSerialPort::Data5; 165 | } else if(arg1 == "6"){ 166 | serial_port_data_bits_ = QSerialPort::Data6; 167 | } else if(arg1 == "7"){ 168 | serial_port_data_bits_ = QSerialPort::Data7; 169 | } else if(arg1 == "8"){ 170 | serial_port_data_bits_ = QSerialPort::Data8; 171 | } 172 | } 173 | 174 | void MainWindow::on_StopBitsComboBox_currentTextChanged(const QString &arg1) 175 | { 176 | if(arg1 == "1"){ 177 | serial_port_stop_bits_ = QSerialPort::StopBits::OneStop; 178 | } else if(arg1 == "2"){ 179 | serial_port_stop_bits_ = QSerialPort::StopBits::TwoStop; 180 | } else if(arg1 == "1.5"){ 181 | serial_port_stop_bits_ = QSerialPort::StopBits::OneAndHalfStop; 182 | } 183 | } 184 | 185 | 186 | void MainWindow::on_VelocityCheckBox_stateChanged(int arg1) 187 | { 188 | if(arg1 == Qt::Unchecked){ 189 | is_display_velocity_ = false; 190 | } else if (arg1 == Qt::Checked) { 191 | is_display_velocity_ = true; 192 | } 193 | } 194 | 195 | void MainWindow::on_PositionCheckBox_stateChanged(int arg1) 196 | { 197 | if(arg1 == Qt::Unchecked){ 198 | is_display_position_ = false; 199 | } else if (arg1 == Qt::Checked) { 200 | is_display_position_ = true; 201 | } 202 | } 203 | 204 | bool MainWindow::SetSerialPort(){ 205 | if(serial_port_name_.isEmpty()){ 206 | QMessageBox::warning(this, "Warning", "Please connect and select serial port", QMessageBox::Close); 207 | return false; 208 | } 209 | 210 | serial_port_->setPortName(serial_port_name_); 211 | serial_port_->setBaudRate(serial_port_baud_rate_); 212 | serial_port_->setDataBits(serial_port_data_bits_); 213 | serial_port_->setParity(serial_port_parity_); 214 | 215 | if(serial_port_->isOpen()){ 216 | serial_port_->close(); 217 | } 218 | 219 | if(!serial_port_->open(QIODevice::ReadOnly)){ 220 | QMessageBox::warning(this, "Warning", "Open COM: " + serial_port_name_ + " failed", QMessageBox::Close); 221 | return false; 222 | } 223 | 224 | return true; 225 | } 226 | 227 | void MainWindow::on_StartButton_clicked() 228 | { 229 | if(!SetSerialPort()){ 230 | return; 231 | } 232 | 233 | ui->BaudRateComboBox->setEnabled(false); 234 | ui->DataBitsComboBox->setEnabled(false); 235 | ui->SerialPortsComboBox->setEnabled(false); 236 | ui->StopBitsComboBox->setEnabled(false); 237 | ui->SerialParityComboBox->setEnabled(false); 238 | ui->OpenSerialPortButton->setEnabled(false); 239 | 240 | timer_replot_->start(); 241 | 242 | ui->StartButton->setEnabled(false); 243 | ui->StopButton->setEnabled(true); 244 | } 245 | 246 | void MainWindow::on_SerialPortsComboBox_currentTextChanged(const QString &arg1) 247 | { 248 | serial_port_name_ = arg1; 249 | } 250 | 251 | void MainWindow::ReceiveSerialData(){ 252 | static std::vector data_segment; 253 | 254 | if(!serial_port_){ 255 | return; 256 | } 257 | 258 | const QByteArray data_array = serial_port_->readAll(); 259 | 260 | for (const auto data : data_array) { 261 | if(receive_state_ == 0){ 262 | data_segment.clear(); 263 | if(data == 'S'){ 264 | receive_state_ = 1; // have received start char 'D' 265 | } else { 266 | receive_state_ = 0; 267 | } 268 | } else if (receive_state_ == 1) { 269 | if(data == 'T'){ 270 | receive_state_ = 2; // have received start char 'A' 271 | } else { 272 | receive_state_ = 0; 273 | } 274 | } else if (receive_state_ == 2) { 275 | if(data == 'A'){ 276 | receive_state_ = 3; // have received start char 'T' 277 | }else { 278 | receive_state_ = 0; 279 | } 280 | }else if (receive_state_ == 3) { 281 | if(data == 'R'){ 282 | receive_state_ = 4; // have received start char 'A' 283 | }else { 284 | receive_state_ = 0; 285 | } 286 | } else if (receive_state_ == 4) { 287 | if(data == 'T'){ 288 | receive_state_ = 5; // have received start char 'A' 289 | }else { 290 | receive_state_ = 0; 291 | } 292 | } else if (receive_state_ >= 5 && receive_state_ <= 9) { 293 | data_segment.push_back(data); // receive data 294 | receive_state_++; 295 | } else if (receive_state_ == 10){ 296 | if(data == 'E'){ 297 | receive_state_ = 11; // have received stop char 'E' 298 | } else { 299 | data_segment.clear(); 300 | receive_state_ = 0; 301 | } 302 | } else if (receive_state_ == 11) { 303 | if(data == 'N'){ 304 | receive_state_ = 12; // have received stop char 'N' 305 | } else { 306 | data_segment.clear(); 307 | receive_state_ = 0; 308 | } 309 | } else if (receive_state_ == 12) { 310 | if(data == 'D'){ 311 | receive_state_ = 13; // have received stop char 'D' 312 | } else { 313 | data_segment.clear(); 314 | receive_state_ = 0; 315 | } 316 | } 317 | 318 | if(receive_state_ < 13){ 319 | continue; 320 | } 321 | 322 | if(data_segment.size() != 5){ 323 | data_segment.clear(); 324 | continue; 325 | } 326 | 327 | receive_state_ = 0; // reset receive status 328 | 329 | std::pair result{MainWindow::SerialPortDataType::InValid, 0.0f}; 330 | 331 | result = ParseSerialPortData(data_segment); 332 | data_segment.clear(); 333 | 334 | if(result.first == SerialPortDataType::InValid){ 335 | continue; 336 | } 337 | 338 | const auto end = std::chrono::steady_clock::now(); 339 | const auto duration = std::chrono::duration_cast(end - start_timestamp_); 340 | const double duration_s = static_cast(duration.count()) / 1.0e6; 341 | 342 | if(result.first == SerialPortDataType::Position){ 343 | position_time_s_vec_.push_back(duration_s); 344 | position_data_vec_.push_back(result.second); 345 | 346 | while (position_time_s_vec_.back() - position_time_s_vec_.front() > retain_data_duration_) { 347 | position_data_vec_.pop_front(); 348 | position_time_s_vec_.pop_front(); 349 | } 350 | if(is_display_position_){ 351 | ui->SerialPortDataTextEdit->appendPlainText(QString("pos: ") + QString::number(result.second, 'f', 3)); 352 | } 353 | } else if (result.first == SerialPortDataType::Velocity) { 354 | velocity_time_s_vec_.push_back(duration_s); 355 | velocity_data_vec_.push_back(result.second); 356 | 357 | while (velocity_time_s_vec_.back() - velocity_time_s_vec_.front() > retain_data_duration_) { 358 | velocity_data_vec_.pop_front(); 359 | velocity_time_s_vec_.pop_front(); 360 | } 361 | 362 | if(is_display_velocity_){ 363 | ui->SerialPortDataTextEdit->appendPlainText(QString("vel: ") + QString::number(result.second, 'f', 3)); 364 | } 365 | } 366 | } 367 | } 368 | 369 | std::pair MainWindow::ParseSerialPortData(const std::vector& data){ 370 | if(data.size() != 5){ 371 | return {SerialPortDataType::InValid, 0.0}; 372 | } 373 | 374 | float result; 375 | if(data[0] == SerialPortDataType::Position){ 376 | result=*((float *)(&data[1])); 377 | return {SerialPortDataType::Position, result}; 378 | } else if (data[0] == SerialPortDataType::Velocity) { 379 | result=*((float *)(&data[1])); 380 | return {SerialPortDataType::Velocity, result}; 381 | } else { 382 | return {SerialPortDataType::InValid, 0.0}; 383 | } 384 | } 385 | 386 | void MainWindow::on_StopButton_clicked() 387 | { 388 | timer_replot_->stop(); 389 | 390 | if(serial_port_->isOpen()){ 391 | serial_port_->close(); 392 | } 393 | 394 | // 释放串口相关按钮的状态 395 | ui->BaudRateComboBox->setEnabled(true); 396 | ui->DataBitsComboBox->setEnabled(true); 397 | ui->SerialPortsComboBox->setEnabled(true); 398 | ui->StopBitsComboBox->setEnabled(true); 399 | ui->SerialParityComboBox->setEnabled(true); 400 | ui->OpenSerialPortButton->setEnabled(true); 401 | 402 | ui->StartButton->setEnabled(true); 403 | ui->StopButton->setEnabled(false); 404 | } 405 | 406 | void MainWindow::on_ClearSerialPortDataButton_clicked() 407 | { 408 | ui->SerialPortDataTextEdit->clear(); 409 | } 410 | 411 | void MainWindow::on_SerialParityComboBox_currentTextChanged(const QString &arg1) 412 | { 413 | if(arg1 == "No"){ 414 | serial_port_parity_ = QSerialPort::Parity::NoParity; 415 | } else if(arg1 == "Even"){ 416 | serial_port_parity_ = QSerialPort::Parity::EvenParity; 417 | } else if(arg1 == "Odd"){ 418 | serial_port_parity_ = QSerialPort::Parity::OddParity; 419 | } 420 | } 421 | -------------------------------------------------------------------------------- /serial_plot_tool/mainwindow.h: -------------------------------------------------------------------------------- 1 | #ifndef MAINWINDOW_H 2 | #define MAINWINDOW_H 3 | 4 | #include "qcustomplot.h" 5 | 6 | #include 7 | #include 8 | #include 9 | 10 | #include 11 | 12 | QT_BEGIN_NAMESPACE 13 | namespace Ui { class MainWindow; } 14 | QT_END_NAMESPACE 15 | 16 | class MainWindow : public QMainWindow 17 | { 18 | Q_OBJECT 19 | 20 | public: 21 | MainWindow(QWidget *parent = nullptr); 22 | ~MainWindow(); 23 | 24 | private slots: 25 | void InitCustomPlot(); 26 | 27 | void CustomReplot(); 28 | 29 | void on_OpenSerialPortButton_clicked(); 30 | 31 | void on_BaudRateComboBox_currentTextChanged(const QString &arg1); 32 | 33 | void on_DataBitsComboBox_currentTextChanged(const QString &arg1); 34 | 35 | void on_StopBitsComboBox_currentTextChanged(const QString &arg1); 36 | 37 | void on_VelocityCheckBox_stateChanged(int arg1); 38 | 39 | void on_PositionCheckBox_stateChanged(int arg1); 40 | 41 | void on_StartButton_clicked(); 42 | 43 | void on_SerialPortsComboBox_currentTextChanged(const QString &arg1); 44 | 45 | void on_StopButton_clicked(); 46 | 47 | void on_ClearSerialPortDataButton_clicked(); 48 | 49 | void on_SerialParityComboBox_currentTextChanged(const QString &arg1); 50 | 51 | private: 52 | enum SerialPortDataType : int8_t{ 53 | Position = '0', 54 | Velocity = '1', 55 | InValid = -1 56 | }; 57 | 58 | private: 59 | bool SetSerialPort(); 60 | 61 | void ReceiveSerialData(); 62 | 63 | std::pair ParseSerialPortData(const std::vector& data); 64 | 65 | private: 66 | Ui::MainWindow *ui; 67 | 68 | QTimer* timer_replot_{nullptr}; 69 | 70 | QCPGraph* position_graph_{nullptr}; 71 | QCPGraph* velocity_graph_{nullptr}; 72 | 73 | QSerialPort::BaudRate serial_port_baud_rate_ = QSerialPort::Baud115200; 74 | QSerialPort::DataBits serial_port_data_bits_ = QSerialPort::Data8; 75 | QSerialPort::StopBits serial_port_stop_bits_ = QSerialPort::OneStop; 76 | QSerialPort::Parity serial_port_parity_ = QSerialPort::Parity::NoParity; 77 | 78 | QSerialPort* serial_port_{nullptr}; 79 | 80 | QString serial_port_name_; 81 | 82 | QVector position_time_s_vec_; 83 | QVector velocity_time_s_vec_; 84 | QVector position_data_vec_; 85 | QVector velocity_data_vec_; 86 | 87 | bool is_display_position_{false}; 88 | bool is_display_velocity_{false}; 89 | 90 | int time_interval_replot_{20}; 91 | int position_line_width_{2}; 92 | int velocity_line_width_{2}; 93 | double retain_data_duration_{50}; 94 | double plot_data_duration_{15}; 95 | 96 | uint8_t receive_state_ = 0; 97 | 98 | std::chrono::steady_clock::time_point start_timestamp_; 99 | }; 100 | #endif // MAINWINDOW_H 101 | -------------------------------------------------------------------------------- /serial_plot_tool/mainwindow.ui: -------------------------------------------------------------------------------- 1 | 2 | 3 | MainWindow 4 | 5 | 6 | 7 | 0 8 | 0 9 | 844 10 | 624 11 | 12 | 13 | 14 | MainWindow 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | true 24 | 25 | 26 | 27 | 600 28 | 600 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | true 39 | 40 | 41 | 42 | 0 43 | 0 44 | 45 | 46 | 47 | 48 | 211 49 | 0 50 | 51 | 52 | 53 | Serial Port Data 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 0 64 | 0 65 | 66 | 67 | 68 | 69 | 0 70 | 0 71 | 72 | 73 | 74 | 75 | 70 76 | 16777215 77 | 78 | 79 | 80 | Qt::LeftToRight 81 | 82 | 83 | false 84 | 85 | 86 | Clear 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 0 98 | 0 99 | 100 | 101 | 102 | 103 | 211 104 | 261 105 | 106 | 107 | 108 | Configure Serial Port 109 | 110 | 111 | 112 | 113 | 114 | COM 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | Parity 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | No 133 | 134 | 135 | 136 | 137 | Even 138 | 139 | 140 | 141 | 142 | Odd 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | Stop Bits 151 | 152 | 153 | 154 | 155 | 156 | 157 | 158 | 1 159 | 160 | 161 | 162 | 163 | 1.5 164 | 165 | 166 | 167 | 168 | 2 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | Data Bits 177 | 178 | 179 | 180 | 181 | 182 | 183 | 3 184 | 185 | 186 | 187 | 5 188 | 189 | 190 | 191 | 192 | 6 193 | 194 | 195 | 196 | 197 | 7 198 | 199 | 200 | 201 | 202 | 8 203 | 204 | 205 | 206 | 207 | 208 | 209 | 210 | Baud Rate 211 | 212 | 213 | 214 | 215 | 216 | 217 | false 218 | 219 | 220 | 5 221 | 222 | 223 | 224 | 4800 225 | 226 | 227 | 228 | 229 | 9600 230 | 231 | 232 | 233 | 234 | 19200 235 | 236 | 237 | 238 | 239 | 38400 240 | 241 | 242 | 243 | 244 | 57600 245 | 246 | 247 | 248 | 249 | 115200 250 | 251 | 252 | 253 | 254 | 255 | 256 | 257 | Open Serial Port 258 | 259 | 260 | 261 | 262 | 263 | 264 | 265 | 266 | 267 | 268 | 0 269 | 0 270 | 271 | 272 | 273 | 274 | 211 275 | 81 276 | 277 | 278 | 279 | Display Plot 280 | 281 | 282 | 283 | 284 | 285 | Vel 286 | 287 | 288 | 289 | 290 | 291 | 292 | Pos 293 | 294 | 295 | 296 | 297 | 298 | 299 | 300 | 301 | 302 | QLayout::SetFixedSize 303 | 304 | 305 | 306 | 307 | 308 | 0 309 | 0 310 | 311 | 312 | 313 | 314 | 80 315 | 30 316 | 317 | 318 | 319 | Start 320 | 321 | 322 | 323 | 324 | 325 | 326 | false 327 | 328 | 329 | 330 | 0 331 | 0 332 | 333 | 334 | 335 | 336 | 80 337 | 30 338 | 339 | 340 | 341 | Stop 342 | 343 | 344 | 345 | 346 | 347 | 348 | 349 | 350 | 351 | 352 | 353 | 354 | 355 | 356 | 357 | QCustomPlot 358 | QWidget 359 |
qcustomplot.h
360 | 1 361 |
362 |
363 | 364 | 365 |
366 | --------------------------------------------------------------------------------