position_sensor.cpp
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 #include "position_sensor.h"
00033 #include <ssf_core/eigen_utils.h>
00034 
00035 #define N_MEAS 9 // measurement size
00036 PositionSensorHandler::PositionSensorHandler(ssf_core::Measurements* meas) :
00037   MeasurementHandler(meas)
00038 {
00039   ros::NodeHandle pnh("~");
00040   pnh.param("measurement_world_sensor", measurement_world_sensor_, true);
00041   pnh.param("use_fixed_covariance", use_fixed_covariance_, false);
00042 
00043   ROS_INFO_COND(measurement_world_sensor_, "interpreting measurement as sensor w.r.t. world");
00044   ROS_INFO_COND(!measurement_world_sensor_, "interpreting measurement as world w.r.t. sensor (e.g. ethzasl_ptam)");
00045 
00046   ROS_INFO_COND(use_fixed_covariance_, "using fixed covariance");
00047   ROS_INFO_COND(!use_fixed_covariance_, "using covariance from sensor");
00048 
00049   subscribe();
00050 }
00051 
00052 void PositionSensorHandler::subscribe()
00053 {
00054         ros::NodeHandle nh("ssf_core");
00055         subMeasurement_ = nh.subscribe("position_measurement", 1, &PositionSensorHandler::measurementCallback, this);
00056 
00057         measurements->ssf_core_.registerCallback(&PositionSensorHandler::noiseConfig, this);
00058 
00059         nh.param("meas_noise1",n_zp_,0.0001);   // default position noise for laser tracker total station
00060 
00061 }
00062 
00063 void PositionSensorHandler::noiseConfig(ssf_core::SSF_CoreConfig& config, uint32_t level)
00064 {
00065         //      if(level & ssf_core::SSF_Core_MISC)
00066         //      {
00067         this->n_zp_ = config.meas_noise1;
00068 
00069         //      }
00070 }
00071 
00072 void PositionSensorHandler::measurementCallback(const ssf_updates::PositionWithCovarianceStampedConstPtr & msg)
00073 {
00074         //      ROS_INFO_STREAM("measurement received \n"
00075         //                                      << "type is: " << typeid(msg).name());
00076 
00077         // init variables
00078         ssf_core::State state_old;
00079         ros::Time time_old = msg->header.stamp;
00080         Eigen::Matrix<double,N_MEAS,N_STATE>H_old;
00081         Eigen::Matrix<double, N_MEAS, 1> r_old;
00082         Eigen::Matrix<double,N_MEAS,N_MEAS> R;
00083 
00084         H_old.setZero();
00085         R.setZero();
00086 
00087         // get measurements
00088         z_p_ = Eigen::Matrix<double,3,1>(msg->position.x, msg->position.y, msg->position.z);
00089 
00090 
00091         if (!use_fixed_covariance_)  // take covariance from sensor
00092         {
00093                 R.block(0,0,3,3) = Eigen::Matrix<double,3,3>(&msg->covariance[0]);
00094                 Eigen::Matrix<double,6,1> buffvec = Eigen::Matrix<double,6,1>::Constant(1e-6);
00095                 R.block(3,3,6,6) = buffvec.asDiagonal(); // measurement noise for q_vw, q_ci
00096         }
00097         else  // alternatively take fix covariance from reconfigure GUI
00098         {
00099                 const double s_zp = n_zp_ * n_zp_;
00100                 R = (Eigen::Matrix<double, N_MEAS, 1>() << s_zp, s_zp, s_zp, 1e-6, 1e-6, 1e-6, 1e-6, 1e-6, 1e-6).finished().asDiagonal();
00101         }
00102 
00103         // feedback for init case
00104         measurements->p_vc_ = z_p_;
00105 
00106         unsigned char idx = measurements->ssf_core_.getClosestState(&state_old,time_old,0);
00107         if (state_old.time_ == -1)
00108                 return; // // early abort // //
00109 
00110         // get rotation matrices
00111         Eigen::Matrix<double,3,3> C_wv = state_old.q_wv_.conjugate().toRotationMatrix();
00112         Eigen::Matrix<double,3,3> C_q = state_old.q_.conjugate().toRotationMatrix();
00113         Eigen::Matrix<double,3,3> C_ci = state_old.q_ci_.conjugate().toRotationMatrix();
00114 
00115         // preprocess for elements in H matrix
00116         Eigen::Matrix<double,3,1> vecold;
00117         vecold = (state_old.p_+C_q.transpose()*state_old.p_ci_)*state_old.L_;
00118         Eigen::Matrix<double,3,3> skewold = skew(vecold);
00119 
00120         Eigen::Matrix<double,3,3> pci_sk = skew(state_old.p_ci_);
00121 
00122         // construct H matrix using H-blockx :-)
00123         // position
00124         H_old.block<3,3>(0,0) = C_wv.transpose()*state_old.L_; // p
00125         H_old.block<3,3>(0,6) = -C_wv.transpose()*C_q.transpose()*pci_sk*state_old.L_; // q
00126         H_old.block<3,1>(0,15) = C_wv.transpose()*C_q.transpose()*state_old.p_ci_ + C_wv.transpose()*state_old.p_; // L
00127         H_old.block<3,3>(0,16) = -C_wv.transpose()*skewold; // q_wv
00128         H_old.block<3,3>(0,22) = C_wv.transpose()*C_q.transpose()*state_old.L_; // use "camera"-IMU distance p_ci state here as position_sensor-IMU distance
00129         H_old.block<3,3>(3,16) = Eigen::Matrix<double,3,3>::Identity(); // fix vision world drift q_wv since it does not exist here
00130         H_old.block<3,3>(6,19) = Eigen::Matrix<double,3,3>::Identity(); // fix "camera"-IMU drift q_ci since it does not exist here
00131 
00132         // construct residuals
00133         // position
00134         r_old.block<3,1>(0,0) = z_p_ - C_wv.transpose()*(state_old.p_ + C_q.transpose()*state_old.p_ci_)*state_old.L_;
00135         // vision world drift q_wv
00136         r_old.block<3,1>(3,0) = -state_old.q_wv_.vec()/state_old.q_wv_.w()*2;
00137         // "camera"-IMU drift q_ci
00138         r_old.block<3,1>(6,0) = -state_old.q_ci_.vec()/state_old.q_ci_.w()*2;
00139 
00140         // call update step in core class
00141         measurements->ssf_core_.applyMeasurement(idx,H_old,r_old,R);
00142 }


ssf_updates
Author(s): Stephan Weiss, Markus Achtelik
autogenerated on Fri Jan 3 2014 11:21:34