Program Listing for File filter-base.h

Return to documentation for file (algorithms/localization-fusion/include/localization-fusion/filter-base.h)

/*
 * Based on:
 *
 * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.
 * All rights reserved.
 *
 * Redistribution and use in source and binary forms, with or without
 * modification, are permitted provided that the following conditions
 * are met:
 *
 * 1. Redistributions of source code must retain the above copyright
 * notice, this list of conditions and the following disclaimer.
 * 2. Redistributions in binary form must reproduce the above
 * copyright notice, this list of conditions and the following
 * disclaimer in the documentation and/or other materials provided
 * with the distribution.
 * 3. Neither the name of the copyright holder nor the names of its
 * contributors may be used to endorse or promote products derived
 * from this software without specific prior written permission.
 *
 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
 * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 * POSSIBILITY OF SUCH DAMAGE.
 */

#ifndef LOCALIZATION_FUSION_FILTER_BASE_H_
#define LOCALIZATION_FUSION_FILTER_BASE_H_

#include "localization-fusion/filter-common.h"
#include "localization-fusion/filter-utilities.h"

#include <algorithm>
#include <limits>
#include <map>
#include <ostream>
#include <queue>
#include <set>
#include <string>
#include <vector>

#include <Eigen/Dense>
#include <aslam/common/time.h>

namespace maplab {

struct LocalizationFilterMeasurement {
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW

  // The real-valued time, in nanoseconds, since some epoch
  // (presumably the start of execution, but any will do)
  int64_t time_;

  // The measurement and its associated covariance
  Eigen::VectorXd measurement_;
  Eigen::MatrixXd covariance_;

  LocalizationFilterMeasurement() : time_(aslam::time::getInvalidTime()) {}
};

struct LocalizationFilterPrediction {
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW

  // The real-valued time, in nanoseconds, since some epoch
  // (presumably the start of execution, but any will do)
  int64_t time_;

  // The prediction and its associated covariance
  Eigen::VectorXd predicted_state_;
  Eigen::MatrixXd covariance_;

  LocalizationFilterPrediction() : time_(aslam::time::getInvalidTime()) {}
};

struct FilterState {
  // The time stamp of the most recent measurement for the filter
  int64_t lastMeasurementTime_;

  // The filter state vector
  Eigen::VectorXd state_;

  // The filter error covariance matrix
  Eigen::MatrixXd estimateErrorCovariance_;

  FilterState() : lastMeasurementTime_(aslam::time::getInvalidTime()) {}
};

class FilterBase {
 public:
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  FilterBase();

  virtual ~FilterBase();

  void reset();

  virtual bool correct(
      const LocalizationFilterMeasurement& measurement,
      const std::vector<size_t>& updateVector) = 0;

  const Eigen::MatrixXd& getEstimateErrorCovariance() const;

  bool getInitializedStatus() const;

  int64_t getLastMeasurementTime() const;

  const Eigen::VectorXd& getState() const;

  virtual void predict(
      const LocalizationFilterPrediction& odom_prediction =
          LocalizationFilterPrediction()) = 0;

  virtual bool processMeasurement(
      const LocalizationFilterMeasurement& measurement,
      const LocalizationFilterPrediction& odom_prediction,
      const std::vector<size_t>& updateVector);

  void setEstimateErrorCovariance(
      const Eigen::MatrixXd& estimate_error_covariance);

  void setLastMeasurementTime(const int64_t last_measurement_time);

  void setMahalanobisThreshold(const double mahalanobis_threshold);

  void setState(const Eigen::VectorXd& state);

  void validateDelta(double& delta);  // NOLINT

 protected:
  virtual void wrapStateAngles();

  virtual bool checkMahalanobisThreshold(
      const Eigen::VectorXd& innovation,
      const Eigen::MatrixXd& innovation_covariance, const double n_sigmas);

  bool initialized_;

  int64_t last_measurement_time_ns_;

  Eigen::VectorXd state_;

  Eigen::MatrixXd covariance_epsilon_;

  Eigen::MatrixXd estimate_error_covariance_;

  double mahalanobis_distance_threshold_;
};

}  // namespace maplab

#endif  // LOCALIZATION_FUSION_FILTER_BASE_H_