Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Setting some functions to const #28

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions include/kalman/SquareRootExtendedKalmanFilter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -208,7 +208,7 @@ namespace Kalman {
template<class Type>
bool computePredictedCovarianceSquareRoot( const Jacobian<Type, State>& A, const CovarianceSquareRoot<State>& S,
const Jacobian<Type, Type>& B, const CovarianceSquareRoot<Type>& R,
CovarianceSquareRoot<Type>& S_pred)
CovarianceSquareRoot<Type>& S_pred) const
{
// Compute QR decomposition of (transposed) augmented matrix
Matrix<T, State::RowsAtCompileTime + Type::RowsAtCompileTime, Type::RowsAtCompileTime> tmp;
Expand Down Expand Up @@ -251,7 +251,7 @@ namespace Kalman {
template<class Measurement>
bool computeKalmanGain( const Jacobian<Measurement, State>& H,
const CovarianceSquareRoot<Measurement>& S_y,
KalmanGain<Measurement>& K)
KalmanGain<Measurement>& K) const
{
// Solve using backsubstitution
// AX=B with B = HSS^T and X = K^T and A = S_yS_y^T
Expand Down
4 changes: 2 additions & 2 deletions include/kalman/SquareRootUnscentedKalmanFilter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -221,7 +221,7 @@ namespace Kalman {
*/
template<class Type>
bool computeCovarianceSquareRootFromSigmaPoints(const Type& mean, const SigmaPoints<Type>& sigmaPoints,
const CovarianceSquareRoot<Type>& noiseCov, CovarianceSquareRoot<Type>& cov)
const CovarianceSquareRoot<Type>& noiseCov, CovarianceSquareRoot<Type>& cov) const
{
// Compute QR decomposition of (transposed) augmented matrix
Matrix<T, 2*State::RowsAtCompileTime + Type::RowsAtCompileTime, Type::RowsAtCompileTime> tmp;
Expand Down Expand Up @@ -272,7 +272,7 @@ namespace Kalman {
bool computeKalmanGain( const Measurement& y,
const SigmaPoints<Measurement>& sigmaMeasurementPoints,
const CovarianceSquareRoot<Measurement>& S_y,
KalmanGain<Measurement>& K)
KalmanGain<Measurement>& K) const
{
// Note: The intermediate eval() is needed here (for now) due to a bug in Eigen that occurs
// when Measurement::RowsAtCompileTime == 1 AND State::RowsAtCompileTime >= 8
Expand Down
4 changes: 2 additions & 2 deletions include/kalman/UnscentedKalmanFilter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -218,7 +218,7 @@ namespace Kalman {
*/
template<class Type>
bool computeCovarianceFromSigmaPoints( const Type& mean, const SigmaPoints<Type>& sigmaPoints,
const Covariance<Type>& noiseCov, Covariance<Type>& cov)
const Covariance<Type>& noiseCov, Covariance<Type>& cov) const
{
decltype(sigmaPoints) W = this->sigmaWeights_c.transpose().template replicate<Type::RowsAtCompileTime,1>();
decltype(sigmaPoints) tmp = (sigmaPoints.colwise() - mean);
Expand All @@ -241,7 +241,7 @@ namespace Kalman {
bool computeKalmanGain( const Measurement& y,
const SigmaPoints<Measurement>& sigmaMeasurementPoints,
const Covariance<Measurement>& P_yy,
KalmanGain<Measurement>& K)
KalmanGain<Measurement>& K) const
{
// Note: The intermediate eval() is needed here (for now) due to a bug in Eigen that occurs
// when Measurement::RowsAtCompileTime == 1 AND State::RowsAtCompileTime >= 8
Expand Down
8 changes: 5 additions & 3 deletions include/kalman/UnscentedKalmanFilterBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,8 @@ namespace Kalman {
* @return The predicted measurement
*/
template<class Measurement, template<class> class CovarianceBase>
Measurement computeMeasurementPrediction(const MeasurementModelType<Measurement, CovarianceBase>& m, SigmaPoints<Measurement>& sigmaMeasurementPoints)
Measurement computeMeasurementPrediction(const MeasurementModelType<Measurement, CovarianceBase>& m,
SigmaPoints<Measurement>& sigmaMeasurementPoints) const
{
// Predict measurements for each sigma point
computeSigmaPointMeasurements<Measurement>(m, sigmaMeasurementPoints);
Expand Down Expand Up @@ -204,7 +205,8 @@ namespace Kalman {
* @param [out] sigmaMeasurementPoints The struct of expected sigma measurements to be computed
*/
template<class Measurement, template<class> class CovarianceBase>
void computeSigmaPointMeasurements(const MeasurementModelType<Measurement, CovarianceBase>& m, SigmaPoints<Measurement>& sigmaMeasurementPoints)
void computeSigmaPointMeasurements(const MeasurementModelType<Measurement, CovarianceBase>& m,
SigmaPoints<Measurement>& sigmaMeasurementPoints) const
{
for( int i = 0; i < SigmaPointCount; ++i )
{
Expand All @@ -221,7 +223,7 @@ namespace Kalman {
* @return The prediction
*/
template<class Type>
Type computePredictionFromSigmaPoints(const SigmaPoints<Type>& sigmaPoints)
Type computePredictionFromSigmaPoints(const SigmaPoints<Type>& sigmaPoints) const
{
// Use efficient matrix x vector computation
return sigmaPoints * sigmaWeights_m;
Expand Down