mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-02-21 11:54:15 +01:00
OP-1150 UI for thermal calibration: Uncrustify
This commit is contained in:
parent
70e13b461f
commit
0a43971dc1
@ -28,12 +28,13 @@
|
|||||||
|
|
||||||
#include "calibrationutils.h"
|
#include "calibrationutils.h"
|
||||||
using namespace Eigen;
|
using namespace Eigen;
|
||||||
namespace OpenPilot{
|
namespace OpenPilot {
|
||||||
/*
|
/*
|
||||||
* The following ellipsoid calibration code is based on RazorImu calibration samples that can be found here:
|
* The following ellipsoid calibration code is based on RazorImu calibration samples that can be found here:
|
||||||
* https://github.com/ptrbrtz/razor-9dof-ahrs/tree/master/Matlab/magnetometer_calibration
|
* https://github.com/ptrbrtz/razor-9dof-ahrs/tree/master/Matlab/magnetometer_calibration
|
||||||
*/
|
*/
|
||||||
bool CalibrationUtils::EllipsoidCalibration(Eigen::VectorXf samplesX, Eigen::VectorXf samplesY, Eigen::VectorXf samplesZ, float nominalRange, EllipsoidCalibrationResult *result){
|
bool CalibrationUtils::EllipsoidCalibration(Eigen::VectorXf samplesX, Eigen::VectorXf samplesY, Eigen::VectorXf samplesZ, float nominalRange, EllipsoidCalibrationResult *result)
|
||||||
|
{
|
||||||
Eigen::VectorXf radii;
|
Eigen::VectorXf radii;
|
||||||
Eigen::Vector3f center;
|
Eigen::Vector3f center;
|
||||||
Eigen::MatrixXf evecs;
|
Eigen::MatrixXf evecs;
|
||||||
@ -43,13 +44,13 @@ bool CalibrationUtils::EllipsoidCalibration(Eigen::VectorXf samplesX, Eigen::Vec
|
|||||||
result->Scale.setZero();
|
result->Scale.setZero();
|
||||||
|
|
||||||
result->Scale << nominalRange / radii.coeff(0),
|
result->Scale << nominalRange / radii.coeff(0),
|
||||||
nominalRange / radii.coeff(1),
|
nominalRange / radii.coeff(1),
|
||||||
nominalRange / radii.coeff(2);
|
nominalRange / radii.coeff(2);
|
||||||
|
|
||||||
Eigen::Matrix3f tmp;
|
Eigen::Matrix3f tmp;
|
||||||
tmp << result->Scale.coeff(0), 0, 0,
|
tmp << result->Scale.coeff(0), 0, 0,
|
||||||
0, result->Scale.coeff(1), 0,
|
0, result->Scale.coeff(1), 0,
|
||||||
0, 0, result->Scale.coeff(2);
|
0, 0, result->Scale.coeff(2);
|
||||||
|
|
||||||
result->CalibrationMatrix = evecs * tmp * evecs.transpose();
|
result->CalibrationMatrix = evecs * tmp * evecs.transpose();
|
||||||
result->Bias.setZero();
|
result->Bias.setZero();
|
||||||
@ -57,8 +58,8 @@ bool CalibrationUtils::EllipsoidCalibration(Eigen::VectorXf samplesX, Eigen::Vec
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool CalibrationUtils::PolynomialCalibration(Eigen::VectorXf samplesX, Eigen::VectorXf samplesY, int degree, Eigen::Ref<Eigen::VectorXf> result){
|
bool CalibrationUtils::PolynomialCalibration(Eigen::VectorXf samplesX, Eigen::VectorXf samplesY, int degree, Eigen::Ref<Eigen::VectorXf> result)
|
||||||
|
{
|
||||||
int samples = samplesX.rows();
|
int samples = samplesX.rows();
|
||||||
// perform internal calculation using doubles
|
// perform internal calculation using doubles
|
||||||
VectorXd doubleX = samplesX.cast<double>();
|
VectorXd doubleX = samplesX.cast<double>();
|
||||||
@ -67,13 +68,13 @@ bool CalibrationUtils::PolynomialCalibration(Eigen::VectorXf samplesX, Eigen::Ve
|
|||||||
|
|
||||||
x.setOnes(samples, degree + 1);
|
x.setOnes(samples, degree + 1);
|
||||||
|
|
||||||
for(int i = 1; i < degree + 1; i++){
|
for (int i = 1; i < degree + 1; i++) {
|
||||||
Eigen::MatrixXd tmp = Eigen::MatrixXd(x.col(i-1));
|
Eigen::MatrixXd tmp = Eigen::MatrixXd(x.col(i - 1));
|
||||||
Eigen::MatrixXd tmp2 = tmp.cwiseProduct(doubleX);
|
Eigen::MatrixXd tmp2 = tmp.cwiseProduct(doubleX);
|
||||||
|
|
||||||
x.col(i) = tmp2;
|
x.col(i) = tmp2;
|
||||||
}
|
}
|
||||||
Eigen::MatrixXd xt = x.transpose();
|
Eigen::MatrixXd xt = x.transpose();
|
||||||
|
|
||||||
Eigen::MatrixXd xtx = xt * x;
|
Eigen::MatrixXd xtx = xt * x;
|
||||||
|
|
||||||
@ -86,91 +87,91 @@ bool CalibrationUtils::PolynomialCalibration(Eigen::VectorXf samplesX, Eigen::Ve
|
|||||||
/* C++ Implementation of Yury Petrov's ellipsoid fit algorithm
|
/* C++ Implementation of Yury Petrov's ellipsoid fit algorithm
|
||||||
* Following is the origial code and its license from which this implementation is derived
|
* Following is the origial code and its license from which this implementation is derived
|
||||||
*
|
*
|
||||||
Copyright (c) 2009, Yury Petrov
|
Copyright (c) 2009, Yury Petrov
|
||||||
All rights reserved.
|
All rights reserved.
|
||||||
|
|
||||||
Redistribution and use in source and binary forms, with or without
|
Redistribution and use in source and binary forms, with or without
|
||||||
modification, are permitted provided that the following conditions are
|
modification, are permitted provided that the following conditions are
|
||||||
met:
|
met:
|
||||||
|
|
||||||
* Redistributions of source code must retain the above copyright
|
* Redistributions of source code must retain the above copyright
|
||||||
notice, this list of conditions and the following disclaimer.
|
notice, this list of conditions and the following disclaimer.
|
||||||
* Redistributions in binary form must reproduce the above copyright
|
* Redistributions in binary form must reproduce the above copyright
|
||||||
notice, this list of conditions and the following disclaimer in
|
notice, this list of conditions and the following disclaimer in
|
||||||
the documentation and/or other materials provided with the distribution
|
the documentation and/or other materials provided with the distribution
|
||||||
|
|
||||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||||
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||||
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||||
ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
|
ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
|
||||||
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
||||||
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
||||||
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
||||||
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
||||||
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||||
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
POSSIBILITY OF SUCH DAMAGE.
|
POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
|
||||||
|
|
||||||
function [ center, radii, evecs, v ] = ellipsoid_fit( X, flag, equals )
|
function [ center, radii, evecs, v ] = ellipsoid_fit( X, flag, equals )
|
||||||
%
|
%
|
||||||
% Fit an ellispoid/sphere to a set of xyz data points:
|
% Fit an ellispoid/sphere to a set of xyz data points:
|
||||||
%
|
%
|
||||||
% [center, radii, evecs, pars ] = ellipsoid_fit( X )
|
% [center, radii, evecs, pars ] = ellipsoid_fit( X )
|
||||||
% [center, radii, evecs, pars ] = ellipsoid_fit( [x y z] );
|
% [center, radii, evecs, pars ] = ellipsoid_fit( [x y z] );
|
||||||
% [center, radii, evecs, pars ] = ellipsoid_fit( X, 1 );
|
% [center, radii, evecs, pars ] = ellipsoid_fit( X, 1 );
|
||||||
% [center, radii, evecs, pars ] = ellipsoid_fit( X, 2, 'xz' );
|
% [center, radii, evecs, pars ] = ellipsoid_fit( X, 2, 'xz' );
|
||||||
% [center, radii, evecs, pars ] = ellipsoid_fit( X, 3 );
|
% [center, radii, evecs, pars ] = ellipsoid_fit( X, 3 );
|
||||||
%
|
%
|
||||||
% Parameters:
|
% Parameters:
|
||||||
% * X, [x y z] - Cartesian data, n x 3 matrix or three n x 1 vectors
|
% * X, [x y z] - Cartesian data, n x 3 matrix or three n x 1 vectors
|
||||||
% * flag - 0 fits an arbitrary ellipsoid (default),
|
% * flag - 0 fits an arbitrary ellipsoid (default),
|
||||||
% - 1 fits an ellipsoid with its axes along [x y z] axes
|
% - 1 fits an ellipsoid with its axes along [x y z] axes
|
||||||
% - 2 followed by, say, 'xy' fits as 1 but also x_rad = y_rad
|
% - 2 followed by, say, 'xy' fits as 1 but also x_rad = y_rad
|
||||||
% - 3 fits a sphere
|
% - 3 fits a sphere
|
||||||
%
|
%
|
||||||
% Output:
|
% Output:
|
||||||
% * center - ellispoid center coordinates [xc; yc; zc]
|
% * center - ellispoid center coordinates [xc; yc; zc]
|
||||||
% * ax - ellipsoid radii [a; b; c]
|
% * ax - ellipsoid radii [a; b; c]
|
||||||
% * evecs - ellipsoid radii directions as columns of the 3x3 matrix
|
% * evecs - ellipsoid radii directions as columns of the 3x3 matrix
|
||||||
% * v - the 9 parameters describing the ellipsoid algebraically:
|
% * v - the 9 parameters describing the ellipsoid algebraically:
|
||||||
% Ax^2 + By^2 + Cz^2 + 2Dxy + 2Exz + 2Fyz + 2Gx + 2Hy + 2Iz = 1
|
% Ax^2 + By^2 + Cz^2 + 2Dxy + 2Exz + 2Fyz + 2Gx + 2Hy + 2Iz = 1
|
||||||
%
|
%
|
||||||
% Author:
|
% Author:
|
||||||
% Yury Petrov, Northeastern University, Boston, MA
|
% Yury Petrov, Northeastern University, Boston, MA
|
||||||
%
|
%
|
||||||
|
|
||||||
error( nargchk( 1, 3, nargin ) ); % check input arguments
|
error( nargchk( 1, 3, nargin ) ); % check input arguments
|
||||||
if nargin == 1
|
if nargin == 1
|
||||||
flag = 0; % default to a free ellipsoid
|
flag = 0; % default to a free ellipsoid
|
||||||
end
|
end
|
||||||
if flag == 2 && nargin == 2
|
if flag == 2 && nargin == 2
|
||||||
equals = 'xy';
|
equals = 'xy';
|
||||||
end
|
end
|
||||||
|
|
||||||
if size( X, 2 ) ~= 3
|
if size( X, 2 ) ~= 3
|
||||||
error( 'Input data must have three columns!' );
|
error( 'Input data must have three columns!' );
|
||||||
else
|
else
|
||||||
x = X( :, 1 );
|
x = X( :, 1 );
|
||||||
y = X( :, 2 );
|
y = X( :, 2 );
|
||||||
z = X( :, 3 );
|
z = X( :, 3 );
|
||||||
end
|
end
|
||||||
|
|
||||||
% need nine or more data points
|
% need nine or more data points
|
||||||
if length( x ) < 9 && flag == 0
|
if length( x ) < 9 && flag == 0
|
||||||
error( 'Must have at least 9 points to fit a unique ellipsoid' );
|
error( 'Must have at least 9 points to fit a unique ellipsoid' );
|
||||||
end
|
end
|
||||||
if length( x ) < 6 && flag == 1
|
if length( x ) < 6 && flag == 1
|
||||||
error( 'Must have at least 6 points to fit a unique oriented ellipsoid' );
|
error( 'Must have at least 6 points to fit a unique oriented ellipsoid' );
|
||||||
end
|
end
|
||||||
if length( x ) < 5 && flag == 2
|
if length( x ) < 5 && flag == 2
|
||||||
error( 'Must have at least 5 points to fit a unique oriented ellipsoid with two axes equal' );
|
error( 'Must have at least 5 points to fit a unique oriented ellipsoid with two axes equal' );
|
||||||
end
|
end
|
||||||
if length( x ) < 3 && flag == 3
|
if length( x ) < 3 && flag == 3
|
||||||
error( 'Must have at least 4 points to fit a unique sphere' );
|
error( 'Must have at least 4 points to fit a unique sphere' );
|
||||||
end
|
end
|
||||||
|
|
||||||
if flag == 0
|
if flag == 0
|
||||||
% fit ellipsoid in the form Ax^2 + By^2 + Cz^2 + 2Dxy + 2Exz + 2Fyz + 2Gx + 2Hy + 2Iz = 1
|
% fit ellipsoid in the form Ax^2 + By^2 + Cz^2 + 2Dxy + 2Exz + 2Fyz + 2Gx + 2Hy + 2Iz = 1
|
||||||
D = [ x .* x, ...
|
D = [ x .* x, ...
|
||||||
y .* y, ...
|
y .* y, ...
|
||||||
@ -181,7 +182,7 @@ if flag == 0
|
|||||||
2 * x, ...
|
2 * x, ...
|
||||||
2 * y, ...
|
2 * y, ...
|
||||||
2 * z ]; % ndatapoints x 9 ellipsoid parameters
|
2 * z ]; % ndatapoints x 9 ellipsoid parameters
|
||||||
elseif flag == 1
|
elseif flag == 1
|
||||||
% fit ellipsoid in the form Ax^2 + By^2 + Cz^2 + 2Gx + 2Hy + 2Iz = 1
|
% fit ellipsoid in the form Ax^2 + By^2 + Cz^2 + 2Gx + 2Hy + 2Iz = 1
|
||||||
D = [ x .* x, ...
|
D = [ x .* x, ...
|
||||||
y .* y, ...
|
y .* y, ...
|
||||||
@ -189,7 +190,7 @@ elseif flag == 1
|
|||||||
2 * x, ...
|
2 * x, ...
|
||||||
2 * y, ...
|
2 * y, ...
|
||||||
2 * z ]; % ndatapoints x 6 ellipsoid parameters
|
2 * z ]; % ndatapoints x 6 ellipsoid parameters
|
||||||
elseif flag == 2
|
elseif flag == 2
|
||||||
% fit ellipsoid in the form Ax^2 + By^2 + Cz^2 + 2Gx + 2Hy + 2Iz = 1,
|
% fit ellipsoid in the form Ax^2 + By^2 + Cz^2 + 2Gx + 2Hy + 2Iz = 1,
|
||||||
% where A = B or B = C or A = C
|
% where A = B or B = C or A = C
|
||||||
if strcmp( equals, 'yz' ) || strcmp( equals, 'zy' )
|
if strcmp( equals, 'yz' ) || strcmp( equals, 'zy' )
|
||||||
@ -211,19 +212,19 @@ elseif flag == 2
|
|||||||
2 * y, ...
|
2 * y, ...
|
||||||
2 * z ];
|
2 * z ];
|
||||||
end
|
end
|
||||||
else
|
else
|
||||||
% fit sphere in the form A(x^2 + y^2 + z^2) + 2Gx + 2Hy + 2Iz = 1
|
% fit sphere in the form A(x^2 + y^2 + z^2) + 2Gx + 2Hy + 2Iz = 1
|
||||||
D = [ x .* x + y .* y + z .* z, ...
|
D = [ x .* x + y .* y + z .* z, ...
|
||||||
2 * x, ...
|
2 * x, ...
|
||||||
2 * y, ...
|
2 * y, ...
|
||||||
2 * z ]; % ndatapoints x 4 sphere parameters
|
2 * z ]; % ndatapoints x 4 sphere parameters
|
||||||
end
|
end
|
||||||
|
|
||||||
% solve the normal system of equations
|
% solve the normal system of equations
|
||||||
v = ( D' * D ) \ ( D' * ones( size( x, 1 ), 1 ) );
|
v = ( D' * D ) \ ( D' * ones( size( x, 1 ), 1 ) );
|
||||||
|
|
||||||
% find the ellipsoid parameters
|
% find the ellipsoid parameters
|
||||||
if flag == 0
|
if flag == 0
|
||||||
% form the algebraic form of the ellipsoid
|
% form the algebraic form of the ellipsoid
|
||||||
A = [ v(1) v(4) v(5) v(7); ...
|
A = [ v(1) v(4) v(5) v(7); ...
|
||||||
v(4) v(2) v(6) v(8); ...
|
v(4) v(2) v(6) v(8); ...
|
||||||
@ -239,7 +240,7 @@ if flag == 0
|
|||||||
% solve the eigenproblem
|
% solve the eigenproblem
|
||||||
[ evecs evals ] = eig( R( 1:3, 1:3 ) / -R( 4, 4 ) );
|
[ evecs evals ] = eig( R( 1:3, 1:3 ) / -R( 4, 4 ) );
|
||||||
radii = sqrt( 1 ./ diag( evals ) );
|
radii = sqrt( 1 ./ diag( evals ) );
|
||||||
else
|
else
|
||||||
if flag == 1
|
if flag == 1
|
||||||
v = [ v(1) v(2) v(3) 0 0 0 v(4) v(5) v(6) ];
|
v = [ v(1) v(2) v(3) 0 0 0 v(4) v(5) v(6) ];
|
||||||
elseif flag == 2
|
elseif flag == 2
|
||||||
@ -257,18 +258,19 @@ else
|
|||||||
gam = 1 + ( v(7)^2 / v(1) + v(8)^2 / v(2) + v(9)^2 / v(3) );
|
gam = 1 + ( v(7)^2 / v(1) + v(8)^2 / v(2) + v(9)^2 / v(3) );
|
||||||
radii = ( sqrt( gam ./ v( 1:3 ) ) )';
|
radii = ( sqrt( gam ./ v( 1:3 ) ) )';
|
||||||
evecs = eye( 3 );
|
evecs = eye( 3 );
|
||||||
end
|
end
|
||||||
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
void CalibrationUtils::EllipsoidFit(Eigen::VectorXf *samplesX, Eigen::VectorXf *samplesY, Eigen::VectorXf *samplesZ,
|
void CalibrationUtils::EllipsoidFit(Eigen::VectorXf *samplesX, Eigen::VectorXf *samplesY, Eigen::VectorXf *samplesZ,
|
||||||
Eigen::Vector3f *center,
|
Eigen::Vector3f *center,
|
||||||
Eigen::VectorXf *radii,
|
Eigen::VectorXf *radii,
|
||||||
Eigen::MatrixXf *evecs)
|
Eigen::MatrixXf *evecs)
|
||||||
{
|
{
|
||||||
int numSamples = (*samplesX).rows();
|
int numSamples = (*samplesX).rows();
|
||||||
Eigen::MatrixXf D(numSamples,9);
|
Eigen::MatrixXf D(numSamples, 9);
|
||||||
|
|
||||||
D.setZero();
|
D.setZero();
|
||||||
D.col(0) = (*samplesX).cwiseProduct(*samplesX);
|
D.col(0) = (*samplesX).cwiseProduct(*samplesX);
|
||||||
D.col(1) = (*samplesY).cwiseProduct(*samplesY);
|
D.col(1) = (*samplesY).cwiseProduct(*samplesY);
|
||||||
@ -285,7 +287,7 @@ void CalibrationUtils::EllipsoidFit(Eigen::VectorXf *samplesX, Eigen::VectorXf *
|
|||||||
|
|
||||||
Eigen::MatrixXf dt1 = (D.transpose() * D);
|
Eigen::MatrixXf dt1 = (D.transpose() * D);
|
||||||
Eigen::MatrixXf dt2 = (D.transpose() * ones);
|
Eigen::MatrixXf dt2 = (D.transpose() * ones);
|
||||||
Eigen::VectorXf v = dt1.inverse() * dt2;
|
Eigen::VectorXf v = dt1.inverse() * dt2;
|
||||||
|
|
||||||
Eigen::Matrix4f A;
|
Eigen::Matrix4f A;
|
||||||
A << v.coeff(0), v.coeff(3), v.coeff(4), v.coeff(6),
|
A << v.coeff(0), v.coeff(3), v.coeff(4), v.coeff(6),
|
||||||
@ -293,19 +295,19 @@ void CalibrationUtils::EllipsoidFit(Eigen::VectorXf *samplesX, Eigen::VectorXf *
|
|||||||
v.coeff(4), v.coeff(5), v.coeff(2), v.coeff(8),
|
v.coeff(4), v.coeff(5), v.coeff(2), v.coeff(8),
|
||||||
v.coeff(6), v.coeff(7), v.coeff(8), -1;
|
v.coeff(6), v.coeff(7), v.coeff(8), -1;
|
||||||
|
|
||||||
(*center) = -1 * A.block(0,0,3,3).inverse() * v.segment(6,3);
|
(*center) = -1 * A.block(0, 0, 3, 3).inverse() * v.segment(6, 3);
|
||||||
|
|
||||||
Eigen::Matrix4f t = Eigen::Matrix4f::Identity();
|
Eigen::Matrix4f t = Eigen::Matrix4f::Identity();
|
||||||
t.block(3,0,1,3) = center->transpose();
|
t.block(3, 0, 1, 3) = center->transpose();
|
||||||
|
|
||||||
Eigen::Matrix4f r = t * A * t.transpose();
|
Eigen::Matrix4f r = t * A * t.transpose();
|
||||||
|
|
||||||
Eigen::Matrix3f tmp2 = r.block(0,0,3,3) * -1 / r.coeff(3,3);
|
Eigen::Matrix3f tmp2 = r.block(0, 0, 3, 3) * -1 / r.coeff(3, 3);
|
||||||
Eigen::EigenSolver<Eigen::Matrix3f> es(tmp2);
|
Eigen::EigenSolver<Eigen::Matrix3f> es(tmp2);
|
||||||
Eigen::VectorXf evals = es.eigenvalues().real();
|
Eigen::VectorXf evals = es.eigenvalues().real();
|
||||||
(*evecs) = es.eigenvectors().real();
|
(*evecs) = es.eigenvectors().real();
|
||||||
radii->setZero(3);
|
radii->setZero(3);
|
||||||
|
|
||||||
(*radii) = (evals.segment(0,3)).cwiseInverse().cwiseSqrt();
|
(*radii) = (evals.segment(0, 3)).cwiseInverse().cwiseSqrt();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -34,12 +34,10 @@
|
|||||||
#include <Eigen/LU>
|
#include <Eigen/LU>
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
|
||||||
namespace OpenPilot{
|
namespace OpenPilot {
|
||||||
|
class CalibrationUtils {
|
||||||
class CalibrationUtils
|
|
||||||
{
|
|
||||||
public:
|
public:
|
||||||
struct EllipsoidCalibrationResult{
|
struct EllipsoidCalibrationResult {
|
||||||
Eigen::Matrix3f CalibrationMatrix;
|
Eigen::Matrix3f CalibrationMatrix;
|
||||||
Eigen::Vector3f Scale;
|
Eigen::Vector3f Scale;
|
||||||
Eigen::Vector3f Bias;
|
Eigen::Vector3f Bias;
|
||||||
@ -50,11 +48,9 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
static void EllipsoidFit(Eigen::VectorXf *samplesX, Eigen::VectorXf *samplesY, Eigen::VectorXf *samplesZ,
|
static void EllipsoidFit(Eigen::VectorXf *samplesX, Eigen::VectorXf *samplesY, Eigen::VectorXf *samplesZ,
|
||||||
Eigen::Vector3f *center,
|
Eigen::Vector3f *center,
|
||||||
Eigen::VectorXf *radii,
|
Eigen::VectorXf *radii,
|
||||||
Eigen::MatrixXf *evecs);
|
Eigen::MatrixXf *evecs);
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
}
|
}
|
||||||
#endif // CALIBRATIONUTILS_H
|
#endif // CALIBRATIONUTILS_H
|
||||||
|
@ -33,28 +33,29 @@
|
|||||||
|
|
||||||
#include "thermalcalibrationhelper.h"
|
#include "thermalcalibrationhelper.h"
|
||||||
|
|
||||||
class BoardStatusSaveTransition : public QSignalTransition
|
class BoardStatusSaveTransition : public QSignalTransition {
|
||||||
{
|
|
||||||
Q_OBJECT
|
Q_OBJECT
|
||||||
public:
|
public:
|
||||||
BoardStatusSaveTransition(ThermalCalibrationHelper *helper, QState *currentState, QState *targetState)
|
BoardStatusSaveTransition(ThermalCalibrationHelper *helper, QState *currentState, QState *targetState)
|
||||||
: QSignalTransition(helper, SIGNAL(statusSaveCompleted(bool))),
|
: QSignalTransition(helper, SIGNAL(statusSaveCompleted(bool))),
|
||||||
m_helper(helper)
|
m_helper(helper)
|
||||||
{
|
{
|
||||||
QObject::connect(currentState, SIGNAL(entered()), this, SLOT(enterState()));
|
QObject::connect(currentState, SIGNAL(entered()), this, SLOT(enterState()));
|
||||||
|
|
||||||
setTargetState(targetState);
|
setTargetState(targetState);
|
||||||
}
|
}
|
||||||
|
|
||||||
virtual bool eventTest(QEvent *e)
|
virtual bool eventTest(QEvent *e)
|
||||||
{
|
{
|
||||||
qDebug() << "BoardStatusSaveTransition::eventTest";
|
qDebug() << "BoardStatusSaveTransition::eventTest";
|
||||||
if (!QSignalTransition::eventTest(e))
|
if (!QSignalTransition::eventTest(e)) {
|
||||||
return false;
|
return false;
|
||||||
QStateMachine::SignalEvent *se = static_cast<QStateMachine::SignalEvent*>(e);
|
}
|
||||||
|
QStateMachine::SignalEvent *se = static_cast<QStateMachine::SignalEvent *>(e);
|
||||||
|
|
||||||
// check wether status stave was successful and retry if not
|
// check wether status stave was successful and retry if not
|
||||||
qDebug() << "BoardStatusSavedTransition::eventTest - " << se->arguments().at(0).toBool();
|
qDebug() << "BoardStatusSavedTransition::eventTest - " << se->arguments().at(0).toBool();
|
||||||
if(se->arguments().at(0).toBool()){
|
if (se->arguments().at(0).toBool()) {
|
||||||
return true;
|
return true;
|
||||||
} else {
|
} else {
|
||||||
m_helper->statusSave();
|
m_helper->statusSave();
|
||||||
@ -64,11 +65,13 @@ public:
|
|||||||
|
|
||||||
virtual void onTransition(QEvent *e)
|
virtual void onTransition(QEvent *e)
|
||||||
{
|
{
|
||||||
QStateMachine::SignalEvent *se = static_cast<QStateMachine::SignalEvent*>(e);
|
QStateMachine::SignalEvent *se = static_cast<QStateMachine::SignalEvent *>(e);
|
||||||
|
|
||||||
qDebug() << "BoardStatusSaveTransition :" << se->arguments().at(0).toBool();
|
qDebug() << "BoardStatusSaveTransition :" << se->arguments().at(0).toBool();
|
||||||
}
|
}
|
||||||
public slots:
|
public slots:
|
||||||
void enterState(){
|
void enterState()
|
||||||
|
{
|
||||||
m_helper->statusSave();
|
m_helper->statusSave();
|
||||||
}
|
}
|
||||||
private:
|
private:
|
||||||
@ -76,26 +79,27 @@ private:
|
|||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
class BoardStatusRestoreTransition : public QSignalTransition
|
class BoardStatusRestoreTransition : public QSignalTransition {
|
||||||
{
|
|
||||||
Q_OBJECT
|
Q_OBJECT
|
||||||
public:
|
public:
|
||||||
BoardStatusRestoreTransition(ThermalCalibrationHelper *helper, QState *currentState, QState *targetState)
|
BoardStatusRestoreTransition(ThermalCalibrationHelper *helper, QState *currentState, QState *targetState)
|
||||||
: QSignalTransition(helper, SIGNAL(statusRestoreCompleted(bool))),
|
: QSignalTransition(helper, SIGNAL(statusRestoreCompleted(bool))),
|
||||||
m_helper(helper)
|
m_helper(helper)
|
||||||
{
|
{
|
||||||
QObject::connect(currentState, SIGNAL(entered()), this, SLOT(enterState()));
|
QObject::connect(currentState, SIGNAL(entered()), this, SLOT(enterState()));
|
||||||
|
|
||||||
setTargetState(targetState);
|
setTargetState(targetState);
|
||||||
}
|
}
|
||||||
|
|
||||||
virtual bool eventTest(QEvent *e)
|
virtual bool eventTest(QEvent *e)
|
||||||
{
|
{
|
||||||
if (!QSignalTransition::eventTest(e))
|
if (!QSignalTransition::eventTest(e)) {
|
||||||
return false;
|
return false;
|
||||||
QStateMachine::SignalEvent *se = static_cast<QStateMachine::SignalEvent*>(e);
|
}
|
||||||
|
QStateMachine::SignalEvent *se = static_cast<QStateMachine::SignalEvent *>(e);
|
||||||
|
|
||||||
// check wether status stave was successful and retry if not
|
// check wether status stave was successful and retry if not
|
||||||
if(se->arguments().at(0).toBool()){
|
if (se->arguments().at(0).toBool()) {
|
||||||
return true;
|
return true;
|
||||||
} else {
|
} else {
|
||||||
qDebug() << "BoardStatusRestoreTransition::eventTest - statusRestore() ";
|
qDebug() << "BoardStatusRestoreTransition::eventTest - statusRestore() ";
|
||||||
@ -104,7 +108,8 @@ public:
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
public slots:
|
public slots:
|
||||||
void enterState(){
|
void enterState()
|
||||||
|
{
|
||||||
m_helper->statusRestore();
|
m_helper->statusRestore();
|
||||||
}
|
}
|
||||||
private:
|
private:
|
||||||
|
@ -32,14 +32,15 @@ bool ThermalCalibration::BarometerCalibration(Eigen::VectorXf pressure, Eigen::V
|
|||||||
{
|
{
|
||||||
// assume the nearest reading to 20°C as the "zero bias" point
|
// assume the nearest reading to 20°C as the "zero bias" point
|
||||||
int index20deg = searchReferenceValue(20.0f, temperature);
|
int index20deg = searchReferenceValue(20.0f, temperature);
|
||||||
|
|
||||||
qDebug() << "Ref zero is " << index20deg << " T: " << temperature[index20deg] << " P:" << pressure[index20deg];
|
qDebug() << "Ref zero is " << index20deg << " T: " << temperature[index20deg] << " P:" << pressure[index20deg];
|
||||||
float refZero = pressure[index20deg];
|
float refZero = pressure[index20deg];
|
||||||
pressure.array() -= refZero;
|
pressure.array() -= refZero;
|
||||||
qDebug() << "Rebased zero is " << pressure[index20deg];
|
qDebug() << "Rebased zero is " << pressure[index20deg];
|
||||||
|
|
||||||
|
|
||||||
Eigen::VectorXf solution(BARO_PRESSURE_POLY_DEGREE + 1);
|
Eigen::VectorXf solution(BARO_PRESSURE_POLY_DEGREE + 1);
|
||||||
if(!CalibrationUtils::PolynomialCalibration(temperature, pressure, BARO_PRESSURE_POLY_DEGREE, solution)){
|
if (!CalibrationUtils::PolynomialCalibration(temperature, pressure, BARO_PRESSURE_POLY_DEGREE, solution)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -50,19 +51,20 @@ bool ThermalCalibration::BarometerCalibration(Eigen::VectorXf pressure, Eigen::V
|
|||||||
bool ThermalCalibration::AccelerometerCalibration(Eigen::VectorXf samplesX, Eigen::VectorXf samplesY, Eigen::VectorXf samplesZ, Eigen::VectorXf temperature, float *result)
|
bool ThermalCalibration::AccelerometerCalibration(Eigen::VectorXf samplesX, Eigen::VectorXf samplesY, Eigen::VectorXf samplesZ, Eigen::VectorXf temperature, float *result)
|
||||||
{
|
{
|
||||||
Eigen::VectorXf solution(ACCEL_X_POLY_DEGREE + 1);
|
Eigen::VectorXf solution(ACCEL_X_POLY_DEGREE + 1);
|
||||||
if(!CalibrationUtils::PolynomialCalibration(temperature, samplesX, ACCEL_X_POLY_DEGREE, solution)){
|
|
||||||
|
if (!CalibrationUtils::PolynomialCalibration(temperature, samplesX, ACCEL_X_POLY_DEGREE, solution)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
result[0] = solution[1];
|
result[0] = solution[1];
|
||||||
|
|
||||||
solution.resize(ACCEL_Y_POLY_DEGREE + 1);
|
solution.resize(ACCEL_Y_POLY_DEGREE + 1);
|
||||||
if(!CalibrationUtils::PolynomialCalibration(temperature, samplesY, ACCEL_Y_POLY_DEGREE, solution)){
|
if (!CalibrationUtils::PolynomialCalibration(temperature, samplesY, ACCEL_Y_POLY_DEGREE, solution)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
result[1] = solution[1];
|
result[1] = solution[1];
|
||||||
|
|
||||||
solution.resize(ACCEL_Z_POLY_DEGREE + 1);
|
solution.resize(ACCEL_Z_POLY_DEGREE + 1);
|
||||||
if(!CalibrationUtils::PolynomialCalibration(temperature, samplesZ, ACCEL_Z_POLY_DEGREE, solution)){
|
if (!CalibrationUtils::PolynomialCalibration(temperature, samplesZ, ACCEL_Z_POLY_DEGREE, solution)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
result[2] = solution[1];
|
result[2] = solution[1];
|
||||||
@ -73,21 +75,22 @@ bool ThermalCalibration::AccelerometerCalibration(Eigen::VectorXf samplesX, Eige
|
|||||||
bool ThermalCalibration::GyroscopeCalibration(Eigen::VectorXf samplesX, Eigen::VectorXf samplesY, Eigen::VectorXf samplesZ, Eigen::VectorXf temperature, float *result)
|
bool ThermalCalibration::GyroscopeCalibration(Eigen::VectorXf samplesX, Eigen::VectorXf samplesY, Eigen::VectorXf samplesZ, Eigen::VectorXf temperature, float *result)
|
||||||
{
|
{
|
||||||
Eigen::VectorXf solution(GYRO_X_POLY_DEGREE + 1);
|
Eigen::VectorXf solution(GYRO_X_POLY_DEGREE + 1);
|
||||||
if(!CalibrationUtils::PolynomialCalibration(temperature, samplesX, GYRO_X_POLY_DEGREE, solution)){
|
|
||||||
|
if (!CalibrationUtils::PolynomialCalibration(temperature, samplesX, GYRO_X_POLY_DEGREE, solution)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
result[0] = solution[1];
|
result[0] = solution[1];
|
||||||
std::cout << solution << std::endl << std::endl;
|
std::cout << solution << std::endl << std::endl;
|
||||||
|
|
||||||
solution.resize(GYRO_Y_POLY_DEGREE + 1);
|
solution.resize(GYRO_Y_POLY_DEGREE + 1);
|
||||||
if(!CalibrationUtils::PolynomialCalibration(temperature, samplesY, GYRO_Y_POLY_DEGREE, solution)){
|
if (!CalibrationUtils::PolynomialCalibration(temperature, samplesY, GYRO_Y_POLY_DEGREE, solution)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
result[1] = solution[1];
|
result[1] = solution[1];
|
||||||
std::cout << solution << std::endl << std::endl;
|
std::cout << solution << std::endl << std::endl;
|
||||||
|
|
||||||
solution.resize(GYRO_Z_POLY_DEGREE + 1);
|
solution.resize(GYRO_Z_POLY_DEGREE + 1);
|
||||||
if(!CalibrationUtils::PolynomialCalibration(temperature, samplesZ, GYRO_Z_POLY_DEGREE, solution)){
|
if (!CalibrationUtils::PolynomialCalibration(temperature, samplesZ, GYRO_Z_POLY_DEGREE, solution)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
result[2] = solution[1];
|
result[2] = solution[1];
|
||||||
@ -99,14 +102,15 @@ bool ThermalCalibration::GyroscopeCalibration(Eigen::VectorXf samplesX, Eigen::V
|
|||||||
|
|
||||||
void ThermalCalibration::copyToArray(float *result, Eigen::VectorXf solution, int elements)
|
void ThermalCalibration::copyToArray(float *result, Eigen::VectorXf solution, int elements)
|
||||||
{
|
{
|
||||||
for(int i = 0; i < elements; i++){
|
for (int i = 0; i < elements; i++) {
|
||||||
result[i] = solution[i];
|
result[i] = solution[i];
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
int ThermalCalibration::searchReferenceValue(float value, Eigen::VectorXf values){
|
int ThermalCalibration::searchReferenceValue(float value, Eigen::VectorXf values)
|
||||||
for(int i = 0; i < values.size(); i++){
|
{
|
||||||
if(!(values[i] < value)){
|
for (int i = 0; i < values.size(); i++) {
|
||||||
|
if (!(values[i] < value)) {
|
||||||
return i;
|
return i;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -114,5 +118,4 @@ int ThermalCalibration::searchReferenceValue(float value, Eigen::VectorXf values
|
|||||||
}
|
}
|
||||||
|
|
||||||
ThermalCalibration::ThermalCalibration()
|
ThermalCalibration::ThermalCalibration()
|
||||||
{
|
{}
|
||||||
}
|
|
||||||
|
@ -31,10 +31,9 @@
|
|||||||
|
|
||||||
namespace OpenPilot {
|
namespace OpenPilot {
|
||||||
class ThermalCalibration {
|
class ThermalCalibration {
|
||||||
|
static const int GYRO_X_POLY_DEGREE = 1;
|
||||||
static const int GYRO_X_POLY_DEGREE = 1;
|
static const int GYRO_Y_POLY_DEGREE = 1;
|
||||||
static const int GYRO_Y_POLY_DEGREE = 1;
|
static const int GYRO_Z_POLY_DEGREE = 2;
|
||||||
static const int GYRO_Z_POLY_DEGREE = 2;
|
|
||||||
|
|
||||||
static const int ACCEL_X_POLY_DEGREE = 1;
|
static const int ACCEL_X_POLY_DEGREE = 1;
|
||||||
static const int ACCEL_Y_POLY_DEGREE = 1;
|
static const int ACCEL_Y_POLY_DEGREE = 1;
|
||||||
@ -72,7 +71,6 @@ public:
|
|||||||
static bool GyroscopeCalibration(Eigen::VectorXf samplesX, Eigen::VectorXf samplesY, Eigen::VectorXf samplesZ, Eigen::VectorXf temperature, float *result);
|
static bool GyroscopeCalibration(Eigen::VectorXf samplesX, Eigen::VectorXf samplesY, Eigen::VectorXf samplesZ, Eigen::VectorXf temperature, float *result);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
static void copyToArray(float *result, Eigen::VectorXf solution, int elements);
|
static void copyToArray(float *result, Eigen::VectorXf solution, int elements);
|
||||||
ThermalCalibration();
|
ThermalCalibration();
|
||||||
|
@ -38,7 +38,8 @@ ThermalCalibrationHelper::ThermalCalibrationHelper(QObject *parent) :
|
|||||||
* @return
|
* @return
|
||||||
*/
|
*/
|
||||||
|
|
||||||
bool ThermalCalibrationHelper::setupBoardForCalibration(){
|
bool ThermalCalibrationHelper::setupBoardForCalibration()
|
||||||
|
{
|
||||||
qDebug() << "setupBoardForCalibration";
|
qDebug() << "setupBoardForCalibration";
|
||||||
|
|
||||||
UAVObjectManager *objManager = getObjectManager();
|
UAVObjectManager *objManager = getObjectManager();
|
||||||
@ -63,7 +64,7 @@ bool ThermalCalibrationHelper::setupBoardForCalibration(){
|
|||||||
RevoSettings *revoSettings = RevoSettings::GetInstance(objManager);
|
RevoSettings *revoSettings = RevoSettings::GetInstance(objManager);
|
||||||
Q_ASSERT(revoSettings);
|
Q_ASSERT(revoSettings);
|
||||||
RevoSettings::DataFields revoSettingsData = revoSettings->getData();
|
RevoSettings::DataFields revoSettingsData = revoSettings->getData();
|
||||||
for (int i = 0; i < RevoSettings::BAROTEMPCORRECTIONPOLYNOMIAL_NUMELEM; i++){
|
for (int i = 0; i < RevoSettings::BAROTEMPCORRECTIONPOLYNOMIAL_NUMELEM; i++) {
|
||||||
revoSettingsData.BaroTempCorrectionPolynomial[i] = 0.0f;
|
revoSettingsData.BaroTempCorrectionPolynomial[i] = 0.0f;
|
||||||
}
|
}
|
||||||
revoSettings->setData(revoSettingsData);
|
revoSettings->setData(revoSettingsData);
|
||||||
@ -72,19 +73,19 @@ bool ThermalCalibrationHelper::setupBoardForCalibration(){
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Save board status to be later restored using restoreBoardStatus
|
* @brief Save board status to be later restored using restoreBoardStatus
|
||||||
* @return
|
* @return
|
||||||
*/
|
*/
|
||||||
bool ThermalCalibrationHelper::saveBoardInitialSettings(){
|
bool ThermalCalibrationHelper::saveBoardInitialSettings()
|
||||||
|
{
|
||||||
// Store current board status:
|
// Store current board status:
|
||||||
qDebug() << "Save initial settings";
|
qDebug() << "Save initial settings";
|
||||||
|
|
||||||
UAVObjectManager *objManager = getObjectManager();
|
UAVObjectManager *objManager = getObjectManager();
|
||||||
Q_ASSERT(objManager);
|
Q_ASSERT(objManager);
|
||||||
// accelSensor Meta
|
// accelSensor Meta
|
||||||
AccelSensor *accelSensor = AccelSensor::GetInstance(objManager);
|
AccelSensor *accelSensor = AccelSensor::GetInstance(objManager);
|
||||||
Q_ASSERT(accelSensor);
|
Q_ASSERT(accelSensor);
|
||||||
m_boardInitialSettings.accelSensorMeta = accelSensor->getMetadata();
|
m_boardInitialSettings.accelSensorMeta = accelSensor->getMetadata();
|
||||||
// gyroSensor Meta
|
// gyroSensor Meta
|
||||||
@ -106,24 +107,26 @@ bool ThermalCalibrationHelper::saveBoardInitialSettings(){
|
|||||||
/*
|
/*
|
||||||
* Note: for revolution it is not neede but in case of CC we would prevent having
|
* Note: for revolution it is not neede but in case of CC we would prevent having
|
||||||
* a new set of xxxSensor UAVOs beside actual xxxState so it may be needed to reset the following
|
* a new set of xxxSensor UAVOs beside actual xxxState so it may be needed to reset the following
|
||||||
AccelGyroSettings *accelGyroSettings = AccelGyroSettings::GetInstance(objManager);
|
AccelGyroSettings *accelGyroSettings = AccelGyroSettings::GetInstance(objManager);
|
||||||
Q_ASSERT(accelGyroSettings);
|
Q_ASSERT(accelGyroSettings);
|
||||||
m_boardInitialSettings.accelGyroSettings = accelGyroSettings->getData();
|
m_boardInitialSettings.accelGyroSettings = accelGyroSettings->getData();
|
||||||
*/
|
*/
|
||||||
m_boardInitialSettings.statusSaved = true;
|
m_boardInitialSettings.statusSaved = true;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void ThermalCalibrationHelper::setupBoard(){
|
void ThermalCalibrationHelper::setupBoard()
|
||||||
if(setupBoardForCalibration()){
|
{
|
||||||
|
if (setupBoardForCalibration()) {
|
||||||
emit setupBoardCompleted(true);
|
emit setupBoardCompleted(true);
|
||||||
} else {
|
} else {
|
||||||
emit setupBoardCompleted(false);
|
emit setupBoardCompleted(false);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ThermalCalibrationHelper::statusRestore(){
|
void ThermalCalibrationHelper::statusRestore()
|
||||||
if(isBoardInitialSettingsSaved() && restoreInitialSettings()){
|
{
|
||||||
|
if (isBoardInitialSettingsSaved() && restoreInitialSettings()) {
|
||||||
clearBoardInitialSettingsSaved();
|
clearBoardInitialSettingsSaved();
|
||||||
emit statusRestoreCompleted(true);
|
emit statusRestoreCompleted(true);
|
||||||
} else {
|
} else {
|
||||||
@ -131,9 +134,10 @@ void ThermalCalibrationHelper::statusRestore(){
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ThermalCalibrationHelper::statusSave(){
|
void ThermalCalibrationHelper::statusSave()
|
||||||
//prevent saving multiple times
|
{
|
||||||
if(!isBoardInitialSettingsSaved() && saveBoardInitialSettings()){
|
// prevent saving multiple times
|
||||||
|
if (!isBoardInitialSettingsSaved() && saveBoardInitialSettings()) {
|
||||||
emit statusSaveCompleted(true);
|
emit statusSaveCompleted(true);
|
||||||
} else {
|
} else {
|
||||||
emit statusSaveCompleted(false);
|
emit statusSaveCompleted(false);
|
||||||
@ -144,8 +148,9 @@ void ThermalCalibrationHelper::statusSave(){
|
|||||||
* @brief restore board settings from status saved calling saveBoardStatus
|
* @brief restore board settings from status saved calling saveBoardStatus
|
||||||
* @return true if success
|
* @return true if success
|
||||||
*/
|
*/
|
||||||
bool ThermalCalibrationHelper::restoreInitialSettings(){
|
bool ThermalCalibrationHelper::restoreInitialSettings()
|
||||||
if(!m_boardInitialSettings.statusSaved) {
|
{
|
||||||
|
if (!m_boardInitialSettings.statusSaved) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
// restore initial board status
|
// restore initial board status
|
||||||
@ -189,7 +194,8 @@ void ThermalCalibrationHelper::setMetadataForCalibration(UAVDataObject *uavo)
|
|||||||
* Util function to get a pointer to the object manager
|
* Util function to get a pointer to the object manager
|
||||||
* @return pointer to the UAVObjectManager
|
* @return pointer to the UAVObjectManager
|
||||||
*/
|
*/
|
||||||
UAVObjectManager *ThermalCalibrationHelper::getObjectManager(){
|
UAVObjectManager *ThermalCalibrationHelper::getObjectManager()
|
||||||
|
{
|
||||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||||
UAVObjectManager *objMngr = pm->getObject<UAVObjectManager>();
|
UAVObjectManager *objMngr = pm->getObject<UAVObjectManager>();
|
||||||
|
|
||||||
|
@ -50,7 +50,6 @@
|
|||||||
#include <revosettings.h>
|
#include <revosettings.h>
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
// this is not needed for revo, but should for CC/CC3D
|
// this is not needed for revo, but should for CC/CC3D
|
||||||
// AccelGyroSettings::DataFields accelGyroSettings;
|
// AccelGyroSettings::DataFields accelGyroSettings;
|
||||||
@ -61,8 +60,7 @@ typedef struct {
|
|||||||
bool statusSaved = false;
|
bool statusSaved = false;
|
||||||
} thermalCalibrationBoardSettings;
|
} thermalCalibrationBoardSettings;
|
||||||
|
|
||||||
class ThermalCalibrationHelper : public QObject
|
class ThermalCalibrationHelper : public QObject {
|
||||||
{
|
|
||||||
Q_OBJECT
|
Q_OBJECT
|
||||||
public:
|
public:
|
||||||
explicit ThermalCalibrationHelper(QObject *parent = 0);
|
explicit ThermalCalibrationHelper(QObject *parent = 0);
|
||||||
@ -70,12 +68,14 @@ public:
|
|||||||
/* board settings save/restore */
|
/* board settings save/restore */
|
||||||
bool saveBoardInitialSettings();
|
bool saveBoardInitialSettings();
|
||||||
bool restoreInitialSettings();
|
bool restoreInitialSettings();
|
||||||
bool isBoardInitialSettingsSaved(){
|
bool isBoardInitialSettingsSaved()
|
||||||
|
{
|
||||||
return m_boardInitialSettings.statusSaved;
|
return m_boardInitialSettings.statusSaved;
|
||||||
}
|
}
|
||||||
private:
|
private:
|
||||||
void setMetadataForCalibration(UAVDataObject *uavo);
|
void setMetadataForCalibration(UAVDataObject *uavo);
|
||||||
void clearBoardInitialSettingsSaved(){
|
void clearBoardInitialSettingsSaved()
|
||||||
|
{
|
||||||
m_boardInitialSettings.statusSaved = false;
|
m_boardInitialSettings.statusSaved = false;
|
||||||
}
|
}
|
||||||
signals:
|
signals:
|
||||||
|
@ -29,27 +29,27 @@
|
|||||||
#include "thermalcalibrationmodel.h"
|
#include "thermalcalibrationmodel.h"
|
||||||
#include "thermalcalibrationtransitions.h"
|
#include "thermalcalibrationtransitions.h"
|
||||||
#include "settinghandlingtransitions.h"
|
#include "settinghandlingtransitions.h"
|
||||||
#define NEXT_EVENT "next"
|
#define NEXT_EVENT "next"
|
||||||
#define PREVIOUS_EVENT "previous"
|
#define PREVIOUS_EVENT "previous"
|
||||||
#define ABORT_EVENT "abort"
|
#define ABORT_EVENT "abort"
|
||||||
|
|
||||||
ThermalCalibrationModel::ThermalCalibrationModel(QObject *parent) :
|
ThermalCalibrationModel::ThermalCalibrationModel(QObject *parent) :
|
||||||
WizardModel(parent)
|
WizardModel(parent)
|
||||||
{
|
{
|
||||||
m_helper = new ThermalCalibrationHelper();
|
m_helper = new ThermalCalibrationHelper();
|
||||||
m_readyState = new WizardState(tr("Start"), this),
|
m_readyState = new WizardState(tr("Start"), this),
|
||||||
m_workingState = new WizardState("workingState",this);
|
m_workingState = new WizardState("workingState", this);
|
||||||
|
|
||||||
m_saveSettingState = new WizardState(tr("Saving initial settings"), m_workingState);
|
m_saveSettingState = new WizardState(tr("Saving initial settings"), m_workingState);
|
||||||
m_workingState->setInitialState(m_saveSettingState);
|
m_workingState->setInitialState(m_saveSettingState);
|
||||||
|
|
||||||
m_setupState = new WizardState(tr("Setup board for calibration"), m_workingState);
|
m_setupState = new WizardState(tr("Setup board for calibration"), m_workingState);
|
||||||
|
|
||||||
m_acquisitionState = new WizardState(tr("Samples acquisition"),m_workingState);
|
m_acquisitionState = new WizardState(tr("Samples acquisition"), m_workingState);
|
||||||
m_calculateState = new WizardState(tr("Calculate calibration matrix"),m_workingState);
|
m_calculateState = new WizardState(tr("Calculate calibration matrix"), m_workingState);
|
||||||
m_finalizeState = new WizardState(tr("Completed"),m_workingState);
|
m_finalizeState = new WizardState(tr("Completed"), m_workingState);
|
||||||
|
|
||||||
m_abortState = new WizardState("abort", this);
|
m_abortState = new WizardState("abort", this);
|
||||||
|
|
||||||
setTransitions();
|
setTransitions();
|
||||||
|
|
||||||
@ -57,9 +57,9 @@ ThermalCalibrationModel::ThermalCalibrationModel(QObject *parent) :
|
|||||||
m_steps << m_readyState
|
m_steps << m_readyState
|
||||||
<< m_setupState
|
<< m_setupState
|
||||||
<< m_acquisitionState << m_calculateState << m_finalizeState;
|
<< m_acquisitionState << m_calculateState << m_finalizeState;
|
||||||
|
|
||||||
}
|
}
|
||||||
void ThermalCalibrationModel::init(){
|
void ThermalCalibrationModel::init()
|
||||||
|
{
|
||||||
setStartEnabled(true);
|
setStartEnabled(true);
|
||||||
setEndEnabled(false);
|
setEndEnabled(false);
|
||||||
setCancelEnabled(false);
|
setCancelEnabled(false);
|
||||||
@ -69,13 +69,11 @@ void ThermalCalibrationModel::init(){
|
|||||||
emit instructionsChanged(instructions());
|
emit instructionsChanged(instructions());
|
||||||
}
|
}
|
||||||
|
|
||||||
void ThermalCalibrationModel::stepChanged(WizardState *state){
|
void ThermalCalibrationModel::stepChanged(WizardState *state) {}
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
void ThermalCalibrationModel::setTransitions()
|
void ThermalCalibrationModel::setTransitions()
|
||||||
{
|
{
|
||||||
m_readyState->addTransition(this,SIGNAL(next()),m_workingState);
|
m_readyState->addTransition(this, SIGNAL(next()), m_workingState);
|
||||||
// handles board status save
|
// handles board status save
|
||||||
// Ready->WorkingState->saveSettings->setup
|
// Ready->WorkingState->saveSettings->setup
|
||||||
m_saveSettingState->addTransition(new BoardStatusSaveTransition(m_helper, m_saveSettingState, m_setupState));
|
m_saveSettingState->addTransition(new BoardStatusSaveTransition(m_helper, m_saveSettingState, m_setupState));
|
||||||
@ -84,13 +82,13 @@ void ThermalCalibrationModel::setTransitions()
|
|||||||
m_setupState->addTransition(new BoardSetupTransition(m_helper, m_setupState, m_acquisitionState));
|
m_setupState->addTransition(new BoardSetupTransition(m_helper, m_setupState, m_acquisitionState));
|
||||||
|
|
||||||
// acquisition -revertSettings-> calculation
|
// acquisition -revertSettings-> calculation
|
||||||
// m_acquisitionState->addTransition(this,SIGNAL(next()),m_calculateState);
|
// m_acquisitionState->addTransition(this,SIGNAL(next()),m_calculateState);
|
||||||
// revert settings after acquisition is completed
|
// revert settings after acquisition is completed
|
||||||
//m_acquisitionState->addTransition(new BoardStatusRestoreTransition(m_helper, m_acquisitionState, m_calculateState));
|
// m_acquisitionState->addTransition(new BoardStatusRestoreTransition(m_helper, m_acquisitionState, m_calculateState));
|
||||||
m_acquisitionState->addTransition(this,SIGNAL(next()), m_calculateState);
|
m_acquisitionState->addTransition(this, SIGNAL(next()), m_calculateState);
|
||||||
|
|
||||||
m_calculateState->addTransition(new BoardStatusRestoreTransition(m_helper,m_calculateState,m_finalizeState));
|
m_calculateState->addTransition(new BoardStatusRestoreTransition(m_helper, m_calculateState, m_finalizeState));
|
||||||
|
|
||||||
m_finalizeState->addTransition(this,SIGNAL(next()),m_readyState);
|
m_finalizeState->addTransition(this, SIGNAL(next()), m_readyState);
|
||||||
// Ready
|
// Ready
|
||||||
}
|
}
|
||||||
|
@ -38,8 +38,7 @@
|
|||||||
#include "../wizardstate.h"
|
#include "../wizardstate.h"
|
||||||
#include "../wizardmodel.h"
|
#include "../wizardmodel.h"
|
||||||
|
|
||||||
class ThermalCalibrationModel : public WizardModel
|
class ThermalCalibrationModel : public WizardModel {
|
||||||
{
|
|
||||||
Q_PROPERTY(bool startEnable READ startEnabled NOTIFY startEnabledChanged)
|
Q_PROPERTY(bool startEnable READ startEnabled NOTIFY startEnabledChanged)
|
||||||
Q_PROPERTY(bool endEnable READ endEnabled NOTIFY endEnabledChanged)
|
Q_PROPERTY(bool endEnable READ endEnabled NOTIFY endEnabledChanged)
|
||||||
Q_PROPERTY(bool cancelEnable READ cancelEnabled NOTIFY cancelEnabledChanged)
|
Q_PROPERTY(bool cancelEnable READ cancelEnabled NOTIFY cancelEnabledChanged)
|
||||||
@ -51,53 +50,63 @@ class ThermalCalibrationModel : public WizardModel
|
|||||||
public:
|
public:
|
||||||
explicit ThermalCalibrationModel(QObject *parent = 0);
|
explicit ThermalCalibrationModel(QObject *parent = 0);
|
||||||
|
|
||||||
bool startEnabled(){
|
bool startEnabled()
|
||||||
|
{
|
||||||
return m_startEnabled;
|
return m_startEnabled;
|
||||||
}
|
}
|
||||||
bool endEnabled(){
|
bool endEnabled()
|
||||||
|
{
|
||||||
return m_endEnabled;
|
return m_endEnabled;
|
||||||
}
|
}
|
||||||
bool cancelEnabled(){
|
bool cancelEnabled()
|
||||||
|
{
|
||||||
return m_cancelEnabled;
|
return m_cancelEnabled;
|
||||||
}
|
}
|
||||||
|
|
||||||
void setStartEnabled(bool status){
|
void setStartEnabled(bool status)
|
||||||
if(m_startEnabled != status){
|
{
|
||||||
|
if (m_startEnabled != status) {
|
||||||
m_startEnabled = status;
|
m_startEnabled = status;
|
||||||
emit startEnabledChanged(status);
|
emit startEnabledChanged(status);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void setEndEnabled(bool status){
|
void setEndEnabled(bool status)
|
||||||
if(m_endEnabled != status){
|
{
|
||||||
|
if (m_endEnabled != status) {
|
||||||
m_endEnabled = status;
|
m_endEnabled = status;
|
||||||
emit endEnabledChanged(status);
|
emit endEnabledChanged(status);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
void setCancelEnabled(bool status) {
|
void setCancelEnabled(bool status)
|
||||||
if(m_cancelEnabled != status) {
|
{
|
||||||
|
if (m_cancelEnabled != status) {
|
||||||
m_cancelEnabled = status;
|
m_cancelEnabled = status;
|
||||||
emit cancelEnabledChanged(status);
|
emit cancelEnabledChanged(status);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
QString temperature(){
|
QString temperature()
|
||||||
|
{
|
||||||
return m_temperature;
|
return m_temperature;
|
||||||
}
|
}
|
||||||
|
|
||||||
QString temperatureGradient(){
|
QString temperatureGradient()
|
||||||
|
{
|
||||||
return m_temperatureGradient;
|
return m_temperatureGradient;
|
||||||
}
|
}
|
||||||
|
|
||||||
void setTemperature(QString status) {
|
void setTemperature(QString status)
|
||||||
if(m_temperature != status) {
|
{
|
||||||
|
if (m_temperature != status) {
|
||||||
m_temperature = status;
|
m_temperature = status;
|
||||||
emit temperatureChanged(status);
|
emit temperatureChanged(status);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
void setTemperatureGradient(QString status) {
|
void setTemperatureGradient(QString status)
|
||||||
if(m_temperatureGradient != status) {
|
{
|
||||||
|
if (m_temperatureGradient != status) {
|
||||||
m_temperatureGradient = status;
|
m_temperatureGradient = status;
|
||||||
emit temperatureGradientChanged(status);
|
emit temperatureGradientChanged(status);
|
||||||
}
|
}
|
||||||
@ -118,7 +127,7 @@ private:
|
|||||||
// this act as top level container for calibration state
|
// this act as top level container for calibration state
|
||||||
// to share common exit signals to abortState
|
// to share common exit signals to abortState
|
||||||
WizardState *m_workingState;
|
WizardState *m_workingState;
|
||||||
//Save settings
|
// Save settings
|
||||||
WizardState *m_saveSettingState;
|
WizardState *m_saveSettingState;
|
||||||
// Setup board for calibration
|
// Setup board for calibration
|
||||||
WizardState *m_setupState;
|
WizardState *m_setupState;
|
||||||
@ -148,15 +157,18 @@ signals:
|
|||||||
public slots:
|
public slots:
|
||||||
void stepChanged(WizardState *state);
|
void stepChanged(WizardState *state);
|
||||||
void init();
|
void init();
|
||||||
void btnStart() {
|
void btnStart()
|
||||||
|
{
|
||||||
emit next();
|
emit next();
|
||||||
}
|
}
|
||||||
|
|
||||||
void btnEnd() {
|
void btnEnd()
|
||||||
|
{
|
||||||
emit previous();
|
emit previous();
|
||||||
}
|
}
|
||||||
|
|
||||||
void btnAbort(){
|
void btnAbort()
|
||||||
|
{
|
||||||
emit abort();
|
emit abort();
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
@ -34,28 +34,29 @@
|
|||||||
|
|
||||||
#include "thermalcalibrationhelper.h"
|
#include "thermalcalibrationhelper.h"
|
||||||
|
|
||||||
class BoardSetupTransition : public QSignalTransition
|
class BoardSetupTransition : public QSignalTransition {
|
||||||
{
|
|
||||||
Q_OBJECT
|
Q_OBJECT
|
||||||
public:
|
public:
|
||||||
BoardSetupTransition (ThermalCalibrationHelper *helper, QState *currentState, QState *targetState)
|
BoardSetupTransition(ThermalCalibrationHelper *helper, QState *currentState, QState *targetState)
|
||||||
: QSignalTransition(helper, SIGNAL(setupBoardCompleted(bool))),
|
: QSignalTransition(helper, SIGNAL(setupBoardCompleted(bool))),
|
||||||
m_helper(helper)
|
m_helper(helper)
|
||||||
{
|
{
|
||||||
QObject::connect(currentState, SIGNAL(entered()), this, SLOT(enterState()));
|
QObject::connect(currentState, SIGNAL(entered()), this, SLOT(enterState()));
|
||||||
|
|
||||||
setTargetState(targetState);
|
setTargetState(targetState);
|
||||||
}
|
}
|
||||||
|
|
||||||
virtual bool eventTest(QEvent *e)
|
virtual bool eventTest(QEvent *e)
|
||||||
{
|
{
|
||||||
qDebug() << "BoardSetupTransition::eventTest";
|
qDebug() << "BoardSetupTransition::eventTest";
|
||||||
if (!QSignalTransition::eventTest(e))
|
if (!QSignalTransition::eventTest(e)) {
|
||||||
return false;
|
return false;
|
||||||
QStateMachine::SignalEvent *se = static_cast<QStateMachine::SignalEvent*>(e);
|
}
|
||||||
|
QStateMachine::SignalEvent *se = static_cast<QStateMachine::SignalEvent *>(e);
|
||||||
|
|
||||||
// check wether status stave was successful and retry if not
|
// check wether status stave was successful and retry if not
|
||||||
qDebug() << "BoardSetupTransition::eventTest - " << se->arguments().at(0).toBool();
|
qDebug() << "BoardSetupTransition::eventTest - " << se->arguments().at(0).toBool();
|
||||||
if(se->arguments().at(0).toBool()){
|
if (se->arguments().at(0).toBool()) {
|
||||||
return true;
|
return true;
|
||||||
} else {
|
} else {
|
||||||
m_helper->setupBoard();
|
m_helper->setupBoard();
|
||||||
@ -65,11 +66,13 @@ public:
|
|||||||
|
|
||||||
virtual void onTransition(QEvent *e)
|
virtual void onTransition(QEvent *e)
|
||||||
{
|
{
|
||||||
QStateMachine::SignalEvent *se = static_cast<QStateMachine::SignalEvent*>(e);
|
QStateMachine::SignalEvent *se = static_cast<QStateMachine::SignalEvent *>(e);
|
||||||
|
|
||||||
qDebug() << "BoardSetupTransition::onTransition" << se->arguments().at(0).toBool();
|
qDebug() << "BoardSetupTransition::onTransition" << se->arguments().at(0).toBool();
|
||||||
}
|
}
|
||||||
public slots:
|
public slots:
|
||||||
void enterState(){
|
void enterState()
|
||||||
|
{
|
||||||
m_helper->setupBoard();
|
m_helper->setupBoard();
|
||||||
}
|
}
|
||||||
private:
|
private:
|
||||||
@ -77,5 +80,4 @@ private:
|
|||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#endif // THERMALCALIBRATIONTRANSITIONS_H
|
#endif // THERMALCALIBRATIONTRANSITIONS_H
|
||||||
|
@ -29,13 +29,13 @@
|
|||||||
|
|
||||||
WizardModel::WizardModel(QObject *parent) :
|
WizardModel::WizardModel(QObject *parent) :
|
||||||
QStateMachine(parent)
|
QStateMachine(parent)
|
||||||
{
|
{}
|
||||||
}
|
|
||||||
|
|
||||||
WizardState* WizardModel::currentState(){
|
WizardState *WizardModel::currentState()
|
||||||
foreach (QAbstractState *value, this->configuration()){
|
{
|
||||||
if(value->parent() != 0){\
|
foreach(QAbstractState * value, this->configuration()) {
|
||||||
return static_cast<WizardState*>(value);
|
if (value->parent() != 0) { \
|
||||||
|
return static_cast<WizardState *>(value);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return NULL;
|
return NULL;
|
||||||
|
@ -33,37 +33,37 @@
|
|||||||
#include "wizardstate.h"
|
#include "wizardstate.h"
|
||||||
#include <accelsensor.h>
|
#include <accelsensor.h>
|
||||||
|
|
||||||
class WizardModel : public QStateMachine
|
class WizardModel : public QStateMachine {
|
||||||
{
|
Q_OBJECT Q_PROPERTY(QQmlListProperty<QObject> steps READ steps CONSTANT)
|
||||||
Q_OBJECT
|
|
||||||
Q_PROPERTY(QQmlListProperty<QObject> steps READ steps CONSTANT)
|
|
||||||
Q_PROPERTY(QString instructions READ instructions NOTIFY instructionsChanged)
|
Q_PROPERTY(QString instructions READ instructions NOTIFY instructionsChanged)
|
||||||
Q_PROPERTY(WizardState* currentState READ currentState NOTIFY currentStateChanged)
|
Q_PROPERTY(WizardState * currentState READ currentState NOTIFY currentStateChanged)
|
||||||
public:
|
public:
|
||||||
explicit WizardModel(QObject *parent = 0);
|
explicit WizardModel(QObject *parent = 0);
|
||||||
|
|
||||||
QQmlListProperty<QObject> steps() {
|
QQmlListProperty<QObject> steps()
|
||||||
|
{
|
||||||
return QQmlListProperty<QObject>(this, m_steps);
|
return QQmlListProperty<QObject>(this, m_steps);
|
||||||
}
|
}
|
||||||
|
|
||||||
QString instructions(){
|
QString instructions()
|
||||||
|
{
|
||||||
return m_instructions;
|
return m_instructions;
|
||||||
}
|
}
|
||||||
|
|
||||||
void setInstructions(QString instructions){
|
void setInstructions(QString instructions)
|
||||||
|
{
|
||||||
m_instructions = instructions;
|
m_instructions = instructions;
|
||||||
emit instructionsChanged(instructions);
|
emit instructionsChanged(instructions);
|
||||||
}
|
}
|
||||||
WizardState *currentState();
|
WizardState *currentState();
|
||||||
protected:
|
protected:
|
||||||
QList<QObject*> m_steps;
|
QList<QObject *> m_steps;
|
||||||
private:
|
private:
|
||||||
QString m_instructions;
|
QString m_instructions;
|
||||||
signals:
|
signals:
|
||||||
void instructionsChanged(QString status);
|
void instructionsChanged(QString status);
|
||||||
void currentStateChanged(WizardState *status);
|
void currentStateChanged(WizardState *status);
|
||||||
public slots:
|
public slots:
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // WIZARDMODEL_H
|
#endif // WIZARDMODEL_H
|
||||||
|
@ -31,11 +31,12 @@ WizardState::WizardState(QString name, QState *parent) :
|
|||||||
QState(parent)
|
QState(parent)
|
||||||
{
|
{
|
||||||
m_stepName = name;
|
m_stepName = name;
|
||||||
m_done = false;
|
m_done = false;
|
||||||
m_active = false;
|
m_active = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void WizardState::setCompletion(qint8 completion){
|
void WizardState::setCompletion(qint8 completion)
|
||||||
|
{
|
||||||
m_completion = completion;
|
m_completion = completion;
|
||||||
emit completionChanged();
|
emit completionChanged();
|
||||||
}
|
}
|
||||||
|
@ -30,28 +30,30 @@
|
|||||||
|
|
||||||
#include <QState>
|
#include <QState>
|
||||||
|
|
||||||
class WizardState : public QState
|
class WizardState : public QState {
|
||||||
{
|
Q_OBJECT Q_PROPERTY(bool isActive READ isActive NOTIFY isActiveChanged)
|
||||||
Q_OBJECT
|
|
||||||
Q_PROPERTY(bool isActive READ isActive NOTIFY isActiveChanged)
|
|
||||||
Q_PROPERTY(bool isDone READ isDone NOTIFY isDoneChanged)
|
Q_PROPERTY(bool isDone READ isDone NOTIFY isDoneChanged)
|
||||||
Q_PROPERTY(qint8 completion READ completion NOTIFY completionChanged)
|
Q_PROPERTY(qint8 completion READ completion NOTIFY completionChanged)
|
||||||
Q_PROPERTY(QString stepName READ stepName NOTIFY stepNameChanged)
|
Q_PROPERTY(QString stepName READ stepName NOTIFY stepNameChanged)
|
||||||
public:
|
public:
|
||||||
explicit WizardState(QString name, QState *parent = 0);
|
explicit WizardState(QString name, QState *parent = 0);
|
||||||
bool isActive(){
|
bool isActive()
|
||||||
|
{
|
||||||
return m_active;
|
return m_active;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool isDone(){
|
bool isDone()
|
||||||
|
{
|
||||||
return m_done;
|
return m_done;
|
||||||
}
|
}
|
||||||
|
|
||||||
qint8 completion(){
|
qint8 completion()
|
||||||
|
{
|
||||||
return m_completion;
|
return m_completion;
|
||||||
}
|
}
|
||||||
|
|
||||||
QString stepName(){
|
QString stepName()
|
||||||
|
{
|
||||||
return m_stepName;
|
return m_stepName;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -224,17 +224,17 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
|
|||||||
// connect the thermalCalibration model to UI
|
// connect the thermalCalibration model to UI
|
||||||
m_thermalCalibrationModel = new ThermalCalibrationModel(this);
|
m_thermalCalibrationModel = new ThermalCalibrationModel(this);
|
||||||
|
|
||||||
connect(m_ui->ThermalBiasStart, SIGNAL(clicked()),m_thermalCalibrationModel, SLOT(btnStart()));
|
connect(m_ui->ThermalBiasStart, SIGNAL(clicked()), m_thermalCalibrationModel, SLOT(btnStart()));
|
||||||
connect(m_ui->ThermalBiasEnd, SIGNAL(clicked()),m_thermalCalibrationModel, SLOT(btnEnd()));
|
connect(m_ui->ThermalBiasEnd, SIGNAL(clicked()), m_thermalCalibrationModel, SLOT(btnEnd()));
|
||||||
connect(m_ui->ThermalBiasCancel, SIGNAL(clicked()),m_thermalCalibrationModel, SLOT(btnAbort()));
|
connect(m_ui->ThermalBiasCancel, SIGNAL(clicked()), m_thermalCalibrationModel, SLOT(btnAbort()));
|
||||||
|
|
||||||
connect(m_thermalCalibrationModel, SIGNAL(startEnabledChanged(bool)),m_ui->ThermalBiasStart, SLOT(setEnabled(bool)));
|
connect(m_thermalCalibrationModel, SIGNAL(startEnabledChanged(bool)), m_ui->ThermalBiasStart, SLOT(setEnabled(bool)));
|
||||||
connect(m_thermalCalibrationModel, SIGNAL(endEnabledChanged(bool)),m_ui->ThermalBiasEnd, SLOT(setEnabled(bool)));
|
connect(m_thermalCalibrationModel, SIGNAL(endEnabledChanged(bool)), m_ui->ThermalBiasEnd, SLOT(setEnabled(bool)));
|
||||||
connect(m_thermalCalibrationModel, SIGNAL(cancelEnabledChanged(bool)),m_ui->ThermalBiasCancel, SLOT(setEnabled(bool)));
|
connect(m_thermalCalibrationModel, SIGNAL(cancelEnabledChanged(bool)), m_ui->ThermalBiasCancel, SLOT(setEnabled(bool)));
|
||||||
|
|
||||||
connect(m_thermalCalibrationModel, SIGNAL(instructionsChanged(QString)),m_ui->label_thermalDescription, SLOT(setText(QString)));
|
connect(m_thermalCalibrationModel, SIGNAL(instructionsChanged(QString)), m_ui->label_thermalDescription, SLOT(setText(QString)));
|
||||||
connect(m_thermalCalibrationModel, SIGNAL(temperatureChanged(QString)),m_ui->label_thermalGradient, SLOT(setText(QString)));
|
connect(m_thermalCalibrationModel, SIGNAL(temperatureChanged(QString)), m_ui->label_thermalGradient, SLOT(setText(QString)));
|
||||||
connect(m_thermalCalibrationModel, SIGNAL(temperatureGradientChanged(QString)),m_ui->label_thermalGradient1, SLOT(setText(QString)));
|
connect(m_thermalCalibrationModel, SIGNAL(temperatureGradientChanged(QString)), m_ui->label_thermalGradient1, SLOT(setText(QString)));
|
||||||
m_thermalCalibrationModel->init();
|
m_thermalCalibrationModel->init();
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
x
Reference in New Issue
Block a user