pose_measurements.h
Go to the documentation of this file.
00001 /*
00002 
00003 Copyright (c) 2010, Stephan Weiss, ASL, ETH Zurich, Switzerland
00004 You can contact the author at <stephan dot weiss at ieee dot org>
00005 
00006 All rights reserved.
00007 
00008 Redistribution and use in source and binary forms, with or without
00009 modification, are permitted provided that the following conditions are met:
00010 * Redistributions of source code must retain the above copyright
00011 notice, this list of conditions and the following disclaimer.
00012 * Redistributions in binary form must reproduce the above copyright
00013 notice, this list of conditions and the following disclaimer in the
00014 documentation and/or other materials provided with the distribution.
00015 * Neither the name of ETHZ-ASL nor the
00016 names of its contributors may be used to endorse or promote products
00017 derived from this software without specific prior written permission.
00018 
00019 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00020 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00021 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00022 DISCLAIMED. IN NO EVENT SHALL ETHZ-ASL BE LIABLE FOR ANY
00023 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00024 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00026 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00027 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00028 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00029 
00030 */
00031 
00032 #ifndef POSE_MEASUREMENTS_H
00033 #define POSE_MEASUREMENTS_H
00034 
00035 #include <ros/ros.h>
00036 #include <ssf_core/measurement.h>
00037 #include "pose_sensor.h"
00038 
00039 class PoseMeasurements : public ssf_core::Measurements
00040 {
00041 public:
00042   PoseMeasurements()
00043   {
00044     addHandler(new PoseSensorHandler(this));
00045 
00046     ros::NodeHandle pnh("~");
00047     pnh.param("init/p_ci/x", p_ci_[0], 0.0);
00048     pnh.param("init/p_ci/y", p_ci_[1], 0.0);
00049     pnh.param("init/p_ci/z", p_ci_[2], 0.0);
00050 
00051     pnh.param("init/q_ci/w", q_ci_.w(), 1.0);
00052     pnh.param("init/q_ci/x", q_ci_.x(), 0.0);
00053     pnh.param("init/q_ci/y", q_ci_.y(), 0.0);
00054     pnh.param("init/q_ci/z", q_ci_.z(), 0.0);
00055     q_ci_.normalize();
00056 
00057     pnh.param("init/q_wv/w", q_wv_.w(), 1.0);
00058     pnh.param("init/q_wv/x", q_wv_.x(), 0.0);
00059     pnh.param("init/q_wv/y", q_wv_.y(), 0.0);
00060     pnh.param("init/q_wv/z", q_wv_.z(), 0.0);
00061     q_wv_.normalize();
00062   }
00063 
00064 private:
00065 
00066   Eigen::Matrix<double, 3, 1> p_ci_; 
00067   Eigen::Quaternion<double> q_ci_; 
00068   Eigen::Quaternion<double> q_wv_; 
00069 
00070   void init(double scale)
00071   {
00072     Eigen::Matrix<double, 3, 1> p, v, b_w, b_a, g, w_m, a_m;
00073     Eigen::Quaternion<double> q;
00074     ssf_core::SSF_Core::ErrorStateCov P;
00075 
00076         // init values
00077         g << 0, 0, 9.81;        
00078         b_w << 0,0,0;           
00079         b_a << 0,0,0;           
00080 
00081         v << 0,0,0;                     
00082         w_m << 0,0,0;           
00083         a_m =g;                         
00084 
00085     P.setZero(); // error state covariance; if zero, a default initialization in ssf_core is used
00086 
00087     // check if we have already input from the measurement sensor
00088     if (p_vc_.norm() == 0)
00089       ROS_WARN_STREAM("No measurements received yet to initialize position - using [0 0 0]");
00090     if ((q_cv_.norm() == 1) & (q_cv_.w() == 1))
00091       ROS_WARN_STREAM("No measurements received yet to initialize attitude - using [1 0 0 0]");
00092 
00093     // calculate initial attitude and position based on sensor measurements
00094     q = (q_ci_ * q_cv_.conjugate() * q_wv_).conjugate();
00095     q.normalize();
00096     p = q_wv_.conjugate().toRotationMatrix() * p_vc_ / scale - q.toRotationMatrix() * p_ci_;
00097 
00098     // call initialization in core
00099     ssf_core_.initialize(p, v, q, b_w, b_a, scale, q_wv_, P, w_m, a_m, g, q_ci_, p_ci_);
00100 
00101     ROS_INFO_STREAM("filter initialized to: \n" <<
00102         "position: [" << p[0] << ", " << p[1] << ", " << p[2] << "]" << std::endl <<
00103         "scale:" << scale << std::endl <<
00104         "attitude (w,x,y,z): [" << q.w() << ", " << q.x() << ", " << q.y() << ", " << q.z() << std::endl <<
00105         "p_ci: [" << p_ci_[0] << ", " << p_ci_[1] << ", " << p_ci_[2] << std::endl <<
00106         "q_ci: (w,x,y,z): [" << q_ci_.w() << ", " << q_ci_.x() << ", " << q_ci_.y() << ", " << q_ci_.z() << "]");
00107   }
00108 };
00109 
00110 #endif /* POSE_MEASUREMENTS_H */


ssf_updates
Author(s): Stephan Weiss, Markus Achtelik
autogenerated on Mon Oct 6 2014 10:27:06