$search
00001 //================================================================================================= 00002 // Copyright (c) 2011, Johannes Meyer, TU Darmstadt 00003 // All rights reserved. 00004 00005 // Redistribution and use in source and binary forms, with or without 00006 // modification, are permitted provided that the following conditions are met: 00007 // * Redistributions of source code must retain the above copyright 00008 // notice, this list of conditions and the following disclaimer. 00009 // * Redistributions in binary form must reproduce the above copyright 00010 // notice, this list of conditions and the following disclaimer in the 00011 // documentation and/or other materials provided with the distribution. 00012 // * Neither the name of the Flight Systems and Automatic Control group, 00013 // TU Darmstadt, nor the names of its contributors may be used to 00014 // endorse or promote products derived from this software without 00015 // specific prior written permission. 00016 00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY 00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00027 //================================================================================================= 00028 00029 #include <hector_pose_estimation/measurement.h> 00030 #include <hector_pose_estimation/pose_estimation.h> 00031 #include <ros/console.h> 00032 00033 namespace hector_pose_estimation { 00034 00035 Measurement::Measurement(const std::string& name) 00036 : name_(name) 00037 , status_flags_(0) 00038 , enabled_(true) 00039 , min_interval_(0.0) 00040 , timeout_(1.0) 00041 , timer_(0.0) 00042 { 00043 parameters().add("enabled", enabled_); 00044 parameters().add("min_interval", min_interval_); 00045 } 00046 00047 Measurement::~Measurement() 00048 { 00049 } 00050 00051 bool Measurement::init() 00052 { 00053 return onInit(); 00054 } 00055 00056 void Measurement::cleanup() 00057 { 00058 onCleanup(); 00059 } 00060 00061 void Measurement::reset() 00062 { 00063 queue().clear(); 00064 timer_ = 0; 00065 onReset(); 00066 } 00067 00068 void Measurement::increase_timer(double dt) { 00069 timer_ += dt; 00070 } 00071 00072 void Measurement::updated() { 00073 timer_ = 0.0; 00074 if (getModel()) status_flags_ = getModel()->getStatusFlags(); 00075 } 00076 00077 bool Measurement::timedout() const { 00078 if (timer_ > timeout_) { 00079 if (status_flags_ > 0) ROS_WARN("Measurement %s timed out.", getName().c_str()); 00080 return true; 00081 } 00082 return false; 00083 } 00084 00085 void Measurement::add(const MeasurementUpdate& update) { 00086 queue().push(update); 00087 } 00088 00089 void Measurement::process(PoseEstimation &estimator) { 00090 while(!(queue().empty())) { 00091 update(estimator, queue().pop()); 00092 } 00093 00094 // check for timeout 00095 if (timedout()) status_flags_ = 0; 00096 } 00097 00098 void Measurement::updateInternal(PoseEstimation &estimator, ColumnVector const& y) { 00099 ROS_DEBUG("Updating with measurement %s", getName().c_str()); 00100 00101 // std::cout << "[" << getName() << "] x_prior = [" << estimator.getState().transpose() << "]" << std::endl; 00102 // std::cout << "[" << getName() << "] P_prior = [" << estimator.getCovariance() << "]" << std::endl; 00103 // std::cout << "[" << getName() << "] update = [" << y.transpose() << "]" << std::endl; 00104 00105 estimator.filter()->Update(getModel(), y); 00106 updated(); 00107 estimator.updated(); 00108 00109 // std::cout << "[" << getName() << "] expected = [" << getModel()->ExpectedValueGet().transpose() << "]" << std::endl; 00110 // std::cout << "[" << getName() << "] R = [" << getModel()->CovarianceGet() << "]" << std::endl; 00111 // std::cout << "[" << getName() << "] H = dy/dx = [" << getModel()->dfGet(0) << "]" << std::endl; 00112 // std::cout << "[" << getName() << "] x_post = [" << estimator.getState().transpose() << "]" << std::endl; 00113 // std::cout << "[" << getName() << "] P_post = [" << estimator.getCovariance() << "]" << std::endl; 00114 } 00115 00116 } // namespace hector_pose_estimation