HumanFilter.h
Go to the documentation of this file.
1 /**
2  * This file is part of ArmarX.
3  *
4  * ArmarX is free software; you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License version 2 as
6  * published by the Free Software Foundation.
7  *
8  * ArmarX is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  * GNU General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License
14  * along with this program. If not, see <http://www.gnu.org/licenses/>.
15  *
16  * @author Tobias Gröger ( tobias dot groeger at student dot kit dot edu )
17  * @author Corvin Navarro Ecker ( corvin dot ecker at student dot kit dot edu )
18  * @date 2022
19  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20  * GNU General Public License
21  */
22 
23 #pragma once
24 
26 
29 
31 {
32 
33  /**
34  * @brief The HumanFilter class can be used to track and filter the state of a single human. It
35  * hides implementation detail on how the filtering is done. New information about the human can
36  * be fed by using the update method. The human itself can be obtained using the get method.
37  */
39  {
40 
41  public:
42  struct Parameters
43  {
44  //TODO which values are appropriate?
45  double control_pos_cov = 0.01;
46  double control_rot_cov = 0.01;
47  double obs_pos_cov = 0.01;
48  double obs_rot_cov = 0.01;
49  double initial_state_pos_cov = 0.01;
50  double initial_state_rot_cov = 0.01;
51  double alpha = 0.5;
52 
53  float velocityAlpha = 0.5;
54  };
55 
56  /**
57  * @brief HumanFilter::HumanFilter creates a new filter that filters 2D poses (position and
58  * rotation in a two dimensional plane)
59  * @param pose0 the first known pose of the human
60  * @param detectionTime the point of detection
61  */
62  HumanFilter(const core::Pose2D& pose0, const DateTime& detectionTime, bool useKalmanFilter);
63 
64  /**
65  * @brief HumanFilter::propagation propagate the system model to the given point in time. This
66  * means that the human pose is updated according to the filters prediction for the given point
67  * in time. Should be called at most once between every two calls of HumanFilter::update.
68  * @param detectionTime the point in time for which the pose should be predicted
69  */
70  void propagation(const DateTime& detectionTime);
71  /**
72  * @brief HumanFilter::update update the filter a new detected pose of the tracked human and
73  * the detection time
74  * @param pose the new detected pose of the human
75  * @param detectionTime the detection time
76  */
77  void update(const core::Pose2D& pose, const DateTime& detectionTime);
78  /**
79  * @brief HumanFilter::get returns the human whose pose is filtered containing the most recent
80  * state
81  * @return the human
82  */
83  const Human& get() const;
84 
85  Duration detectionAge(const DateTime& currentTime) const;
86 
87  private:
89 
90  SystemModelT::StateT toUkfState(const core::Pose2D& pose);
91  core::Pose2D fromUkfState(const SystemModelT::StateT& pose);
92  SystemModelT::ControlT toUkfControl(const Eigen::Vector2f& vel);
93  SystemModelT::ObsT toUkfObs(const core::Pose2D& pose);
94 
95  private:
96  Parameters params{};
97  /**
98  * @brief oldHuman stores information about the human at the point in time of the last
99  * HumanFilter::update call
100  */
101  Human lastDetectedHuman{};
102  /**
103  * @brief human stores information about the human at the point in time of the last
104  * HumanFilter::propagation call
105  */
106  Human human{};
107  std::unique_ptr<UnscentedKalmanFilter<SystemModelT>> ukf = nullptr;
108  bool useKalmanFilter;
109  };
110 
111 } // namespace armarx::navigation::human
armarx::navigation::human::HumanFilter::HumanFilter
HumanFilter(const core::Pose2D &pose0, const DateTime &detectionTime, bool useKalmanFilter)
HumanFilter::HumanFilter creates a new filter that filters 2D poses (position and rotation in a two d...
Definition: HumanFilter.cpp:6
armarx::navigation::human::HumanFilter::Parameters::obs_rot_cov
double obs_rot_cov
Definition: HumanFilter.h:48
armarx::navigation::human::Human
Definition: types.h:33
armarx::navigation::human::kalman_filter::SystemModelSE2
Definition: HumanSystemModel.h:93
armarx::navigation::human::HumanFilter::Parameters::initial_state_rot_cov
double initial_state_rot_cov
Definition: HumanFilter.h:50
armarx::navigation::human::HumanFilter::Parameters::control_pos_cov
double control_pos_cov
Definition: HumanFilter.h:45
armarx::navigation::human::HumanFilter::Parameters
Definition: HumanFilter.h:42
types.h
armarx::navigation::human
This file is part of ArmarX.
Definition: aron_conversions.cpp:9
armarx::navigation::human::HumanFilter::update
void update(const core::Pose2D &pose, const DateTime &detectionTime)
HumanFilter::update update the filter a new detected pose of the tracked human and the detection time...
Definition: HumanFilter.cpp:59
armarx::navigation::human::HumanFilter::Parameters::obs_pos_cov
double obs_pos_cov
Definition: HumanFilter.h:47
armarx::navigation::core::Pose2D
Eigen::Isometry2f Pose2D
Definition: basic_types.h:34
armarx::navigation::human::HumanFilter::Parameters::initial_state_pos_cov
double initial_state_pos_cov
Definition: HumanFilter.h:49
armarx::navigation::human::kalman_filter::StateSE2
Definition: HumanSystemModel.h:81
armarx::navigation::human::HumanFilter::detectionAge
Duration detectionAge(const DateTime &currentTime) const
Definition: HumanFilter.cpp:104
armarx::navigation::human::HumanFilter::Parameters::alpha
double alpha
Definition: HumanFilter.h:51
armarx::navigation::human::HumanFilter::Parameters::control_rot_cov
double control_rot_cov
Definition: HumanFilter.h:46
armarx::navigation::human::HumanFilter::get
const Human & get() const
HumanFilter::get returns the human whose pose is filtered containing the most recent state.
Definition: HumanFilter.cpp:98
armarx::navigation::human::HumanFilter::propagation
void propagation(const DateTime &detectionTime)
HumanFilter::propagation propagate the system model to the given point in time.
Definition: HumanFilter.cpp:42
armarx::core::time::DateTime
Represents a point in time.
Definition: DateTime.h:24
armarx::navigation::human::HumanFilter
The HumanFilter class can be used to track and filter the state of a single human.
Definition: HumanFilter.h:38
armarx::navigation::human::HumanFilter::Parameters::velocityAlpha
float velocityAlpha
Definition: HumanFilter.h:53
armarx::core::time::Duration
Represents a duration.
Definition: Duration.h:17
armarx::navigation::human::kalman_filter::ControlSE2
Definition: HumanSystemModel.h:87
Eigen::Matrix
Definition: EigenForwardDeclarations.h:27
UnscentedKalmanFilter.h
HumanSystemModel.h