measurement.cpp
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2011, Johannes Meyer, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Flight Systems and Automatic Control group,
13 // TU Darmstadt, nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
30 
31 #include <ros/console.h>
32 
33 namespace hector_pose_estimation {
34 
35 Measurement::Measurement(const std::string& name)
36  : name_(name)
37  , status_flags_(0)
38  , enabled_(true)
39  , min_interval_(0.0)
40  , timeout_(0.0)
41  , timer_(0.0)
42 {
43  parameters().add("enabled", enabled_);
44  parameters().add("timeout", timeout_);
45  parameters().add("min_interval", min_interval_);
46  parameters().add("timeout", timeout_);
47 }
48 
50 {
51 }
52 
53 bool Measurement::init(PoseEstimation& estimator, State& state)
54 {
55  if (getModel() && !getModel()->init(estimator, *this, state)) return false;
56  if (!onInit(estimator)) return false;
57  return true;
58 }
59 
61 {
62  if (getModel()) getModel()->cleanup();
63  onCleanup();
64 }
65 
67 {
68  queue().clear();
69  timer_ = 0;
70  status_flags_ = 0;
71 
72  if (getModel()) getModel()->reset(state);
73  onReset();
74 }
75 
76 bool Measurement::active(const State& state) {
77  bool active = enabled() && (getModel() ? getModel()->active(state) : !(state.getSystemStatus() & STATUS_ALIGNMENT));
78  if (!active) status_flags_ = 0;
79  if (min_interval_ > 0.0 && timer_ < min_interval_) return false;
80  return active;
81 }
82 
83 void Measurement::increase_timer(double dt) {
84  timer_ += dt;
85 }
86 
87 bool Measurement::timedout() const {
88  return timeout_ > 0.0 && timer_ > timeout_;
89 }
90 
92  queue().push(update);
93 }
94 
96  bool result = true;
97 
98  while(!(queue().empty())) {
99  result &= update(queue().pop());
100  }
101 
102  // check for timeout
103  if (timedout()) {
104  if (status_flags_ > 0) ROS_WARN("Measurement %s timed out.", getName().c_str());
105  status_flags_ = 0;
106  }
107  return result;
108 }
109 
111 {
112  if (!filter() || !active(filter()->state())) return false;
113 
114  if (!updateImpl(update)) return false;
115  filter()->state().updated();
116 
117  timer_ = 0.0;
119  return true;
120 }
121 
122 } // namespace hector_pose_estimation
virtual void updated()
Definition: state.cpp:110
virtual bool update(const MeasurementUpdate &update)
virtual void cleanup()
Definition: model.h:44
virtual bool active(const State &state)
Definition: measurement.cpp:76
virtual const std::string & getName() const
Definition: measurement.h:50
virtual MeasurementModel * getModel() const
Definition: measurement.h:53
virtual ParameterList & parameters()
Definition: measurement.h:63
virtual bool onInit(PoseEstimation &estimator)
Definition: measurement.h:90
Measurement(const std::string &name)
Definition: measurement.cpp:35
#define ROS_WARN(...)
virtual Filter * filter() const
Definition: measurement.h:56
virtual const State & state() const
Definition: filter.h:50
ParameterList & add(const std::string &key, T &value, const T &default_value)
Definition: parameters.h:148
virtual void reset(State &state)
Definition: measurement.cpp:66
virtual bool updateImpl(const MeasurementUpdate &update)
Definition: measurement.h:88
virtual void reset(State &state)
Definition: model.h:45
virtual bool active(const State &state)
virtual SystemStatus getSystemStatus() const
Definition: state.h:100
virtual bool init(PoseEstimation &estimator, State &state)
Definition: measurement.cpp:53
virtual void push(const MeasurementUpdate &update)=0
virtual void add(const MeasurementUpdate &update)
Definition: measurement.cpp:91


hector_pose_estimation_core
Author(s): Johannes Meyer
autogenerated on Thu Feb 18 2021 03:29:30