PlatformKalmanFilter.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * Copyright (C) 2011-2017, High Performance Humanoid Technologies (H2T), Karlsruhe Institute of Technology (KIT), all rights reserved.
5  *
6  * ArmarX is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License version 2 as
8  * published by the Free Software Foundation.
9  *
10  * ArmarX is distributed in the hope that it will be useful, but
11  * WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program. If not, see <http://www.gnu.org/licenses/>.
17  *
18  * @package ArmarX
19  * @author Mirko Waechter( mirko.waechter at kit dot edu)
20  * @date 2018
21  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
22  * GNU General Public License
23  */
24 #include "PlatformKalmanFilter.h"
26 namespace memoryx
27 {
28 
29  PlatformKalmanFilter::PlatformKalmanFilter(Eigen::Vector2d initialPosition, double initialRotation,
30  double translationSensorStdDev, double rotationSensorStdDev,
31  double translationVelocitySensorStdDev, double rotationVelocitySensorStdDev)
32  {
33  pose.head(2) = initialPosition;
34  pose(2) = initialRotation;
35  Eigen::Vector4d motionNoiseCov;
36  motionNoiseCov << translationVelocitySensorStdDev* translationVelocitySensorStdDev, translationVelocitySensorStdDev* translationVelocitySensorStdDev,
37  rotationVelocitySensorStdDev* rotationVelocitySensorStdDev, rotationVelocitySensorStdDev* rotationVelocitySensorStdDev;
38  motionNoise = Gaussian(Eigen::Vector4d::Zero(), motionNoiseCov.asDiagonal());
40  motionNoise);
41 
42  Eigen::Vector4d measurementNoiseCov;
43  measurementNoiseCov << translationSensorStdDev* translationSensorStdDev, translationSensorStdDev* translationSensorStdDev,
44  rotationSensorStdDev* rotationSensorStdDev, rotationSensorStdDev* rotationSensorStdDev;
45  Gaussian measurementNoise(Eigen::Vector4d::Zero(), measurementNoiseCov.asDiagonal());
47 
48  Eigen::Vector4d pose2d = transformPose(pose);
49 
50  state = Gaussian(4);
51  state.setMean(pose2d);
52  state.setCovariance(Eigen::Vector4d(translationSensorStdDev * translationSensorStdDev * 10,
53  translationSensorStdDev * translationSensorStdDev * 10,
54  rotationSensorStdDev * rotationSensorStdDev * 10,
55  rotationSensorStdDev * rotationSensorStdDev * 10).asDiagonal());
56  }
57 
58  void PlatformKalmanFilter::predict(double velX, double velY, double velTheta, const IceUtil::Time& deltaT)
59  {
60  Eigen::Matrix2d rotation = Eigen::Rotation2Dd(pose(2)).matrix();
61  Eigen::Vector2d globalV0 = rotation * Eigen::Vector2d(velX, velY);
62  Eigen::Vector4d currentVelocity;
63  currentVelocity << globalV0(0), globalV0(1), -velTheta* sin(pose(2)), velTheta* cos(pose(2));
64 
65 
66  auto posDelta = currentVelocity * deltaT.toSecondsDouble();
67 
68  // scale motion noise with velocity
69  Eigen::MatrixXd adjustedMotionNoiseCov = motionNoise.getCovariance() * Eigen::Vector4d(std::abs(currentVelocity(0)), std::abs(currentVelocity(1)), std::abs(velTheta), std::abs(velTheta)).asDiagonal();
70 
71  Gaussian adjustedMotionNoise(Eigen::Vector4d::Zero(), adjustedMotionNoiseCov);
73  adjustedMotionNoise);
74 
75 
76 
77  state = filter.predict(state, posDelta);
79 
80 
81 
82  }
83 
84  void PlatformKalmanFilter::update(double x, double y, double alpha)
85  {
86  Eigen::Vector4d pose2d = transformPose(Eigen::Vector3d(x, y, alpha));
87 
88 
89  state = filter.update(state, pose2d);
90 
92  }
93 
94  const Eigen::Vector3d& PlatformKalmanFilter::getPose() const
95  {
96  return pose;
97  }
98 
99  Eigen::Vector2d PlatformKalmanFilter::getPosition() const
100  {
101  return pose.head<2>();
102  }
103 
105  {
106  return pose(2);
107  }
108 
109  Eigen::Matrix3d PlatformKalmanFilter::getCovariance() const
110  {
111  Eigen::Matrix3d result;
112  result.block<2, 2>(0, 0) = state.getCovariance().block<2, 2>(0, 0);
113  result(2, 2) = (state.getCovariance()(2, 2) + state.getCovariance()(3, 3)) * 0.5;
114  return result;
115  }
116 
118  {
119  return filter;
120  }
121 
123  {
124  filter = value;
125  }
126 
127 
128  Eigen::Vector4d PlatformKalmanFilter::transformPose(const Eigen::Vector3d& pose) const
129  {
130  Eigen::Vector4d pose2d;
131  // rotation stored for Mean_of_circular_quantities
132  // http://en.wikipedia.org/wiki/Mean_of_circular_quantities
133  pose2d << pose(0), pose(1), cos(pose(2)), sin(pose(2));
134  return pose2d;
135  }
136 
137  Eigen::Vector3d PlatformKalmanFilter::inverseTransformPose(const Eigen::Vector4d& pose) const
138  {
139  Eigen::Matrix3d ori;
140  ori.setIdentity();
141 
142  double angle = atan2(pose(3), pose(2));
143  ori = Eigen::AngleAxisd(angle, Eigen::Vector3d::UnitZ());
144  Eigen::Vector3d result;
145  result[0] = pose(0);
146  result[1] = pose(1);
147  result[2] = angle;
148  return result;
149  }
150 
151 } // namespace memoryx
Gaussian::getCovariance
const covariance_type & getCovariance() const
Definition: Gaussian.h:77
memoryx::PlatformKalmanFilter::state
Gaussian state
Definition: PlatformKalmanFilter.h:94
KalmanFilter::setMotionModel
void setMotionModel(const Eigen::MatrixXd &motion_A, const Eigen::MatrixXd &motion_B, const Gaussian &motion_noise)
Definition: KalmanFilter.cpp:19
memoryx::PlatformKalmanFilter::transformPose
Eigen::Vector4d transformPose(const Eigen::Vector3d &pose) const
Definition: PlatformKalmanFilter.cpp:128
KalmanFilter
Definition: KalmanFilter.h:27
KalmanFilter::setMeasurementModel
void setMeasurementModel(const Eigen::MatrixXd &measurement_C, const Gaussian &measurement_noise)
Definition: KalmanFilter.cpp:29
memoryx
VirtualRobot headers.
Definition: CommonPlacesTester.cpp:48
memoryx::PlatformKalmanFilter::filter
KalmanFilter filter
Definition: PlatformKalmanFilter.h:93
memoryx::PlatformKalmanFilter::getOrientation
double getOrientation() const
Definition: PlatformKalmanFilter.cpp:104
memoryx::PlatformKalmanFilter::getCovariance
Eigen::Matrix3d getCovariance() const
Covariance matrix of the current belief of the state.
Definition: PlatformKalmanFilter.cpp:109
PlatformKalmanFilter.h
GfxTL::Identity
void Identity(MatrixXX< N, N, T > *a)
Definition: MatrixXX.h:523
memoryx::PlatformKalmanFilter::getPosition
Eigen::Vector2d getPosition() const
Definition: PlatformKalmanFilter.cpp:99
cxxopts::value
std::shared_ptr< Value > value()
Definition: cxxopts.hpp:926
armarx::abs
std::vector< T > abs(const std::vector< T > &v)
Definition: VectorHelpers.h:253
memoryx::PlatformKalmanFilter::update
void update(double x, double y, double alpha)
Performs the update-step of the Kalman filter.
Definition: PlatformKalmanFilter.cpp:84
Gaussian::setMean
void setMean(const value_type &mean)
Definition: Gaussian.cpp:245
Gaussian::setCovariance
void setCovariance(const covariance_type &cov)
Definition: Gaussian.cpp:261
KalmanFilter::predict
Gaussian predict(const Gaussian &believe, const Eigen::VectorXd &actionU)
Definition: KalmanFilter.cpp:52
armarx::armem::Time
armarx::core::time::DateTime Time
Definition: forward_declarations.h:13
memoryx::PlatformKalmanFilter::getPose
const Eigen::Vector3d & getPose() const
Global pose of the holonomic platform.
Definition: PlatformKalmanFilter.cpp:94
memoryx::PlatformKalmanFilter::PlatformKalmanFilter
PlatformKalmanFilter(Eigen::Vector2d initialPosition, double initialRotation, double translationSensorStdDev=100.0, double rotationSensorStdDev=0.1, double translationVelocitySensorStdDev=1., double rotationVelocitySensorStdDev=1.)
PlatformKalmanFilter.
Definition: PlatformKalmanFilter.cpp:29
memoryx::PlatformKalmanFilter::setFilter
void setFilter(const KalmanFilter &value)
Change the internal Kalman Filter.
Definition: PlatformKalmanFilter.cpp:122
angle
double angle(const Point &a, const Point &b, const Point &c)
Definition: point.hpp:100
memoryx::PlatformKalmanFilter::pose
Eigen::Vector3d pose
Definition: PlatformKalmanFilter.h:96
Logging.h
Gaussian::getMean
const value_type & getMean() const
Definition: Gaussian.h:81
Gaussian
Definition: Gaussian.h:46
memoryx::PlatformKalmanFilter::motionNoise
Gaussian motionNoise
Definition: PlatformKalmanFilter.h:95
memoryx::PlatformKalmanFilter::predict
void predict(double velX, double velY, double velTheta, const IceUtil::Time &deltaT)
Performs the predict-step of the Kalman filter.
Definition: PlatformKalmanFilter.cpp:58
memoryx::PlatformKalmanFilter::getFilter
const KalmanFilter & getFilter() const
Definition: PlatformKalmanFilter.cpp:117
memoryx::PlatformKalmanFilter::inverseTransformPose
Eigen::Vector3d inverseTransformPose(const Eigen::Vector4d &pose) const
Definition: PlatformKalmanFilter.cpp:137
KalmanFilter::update
Gaussian update(const Gaussian &predicted_believe, const Eigen::VectorXd &perceptZ)
Definition: KalmanFilter.cpp:63