pose_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 "pose_sensor.h"
00033 #include <ssf_core/eigen_utils.h>
00034 
00035 #define N_MEAS 7 // measurement size
00036 PoseSensorHandler::PoseSensorHandler(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 PoseSensorHandler::subscribe()
00053 {
00054   ros::NodeHandle nh("ssf_core");
00055   subMeasurement_ = nh.subscribe("pose_measurement", 1, &PoseSensorHandler::measurementCallback, this);
00056 
00057   measurements->ssf_core_.registerCallback(&PoseSensorHandler::noiseConfig, this);
00058 
00059   nh.param("meas_noise1", n_zp_, 0.01); // default position noise is for ethzasl_ptam
00060   nh.param("meas_noise2", n_zq_, 0.02); // default attitude noise is for ethzasl_ptam
00061 }
00062 
00063 void PoseSensorHandler::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   this->n_zq_ = config.meas_noise2;
00069   //    }
00070 }
00071 
00072 void PoseSensorHandler::measurementCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr & 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->pose.pose.position.x, msg->pose.pose.position.y, msg->pose.pose.position.z);
00089   z_q_ = Eigen::Quaternion<double>(msg->pose.pose.orientation.w, msg->pose.pose.orientation.x, msg->pose.pose.orientation.y, msg->pose.pose.orientation.z);
00090 
00091   // take covariance from sensor
00092   R.block<6, 6> (0, 0) = Eigen::Matrix<double, 6, 6>(&msg->pose.covariance[0]);
00093   //clear cross-correlations between q and p
00094   R.block<3, 3> (0, 3) = Eigen::Matrix<double, 3, 3>::Zero();
00095   R.block<3, 3> (3, 0) = Eigen::Matrix<double, 3, 3>::Zero();
00096   R(6, 6) = 1e-6; // q_vw yaw-measurement noise
00097 
00098   /*************************************************************************************/
00099   // use this if your pose sensor is ethzasl_ptam (www.ros.org/wiki/ethzasl_ptam)
00100   // ethzasl_ptam publishes the camera pose as the world seen from the camera
00101   if (!measurement_world_sensor_)
00102   {
00103     Eigen::Matrix<double, 3, 3> C_zq = z_q_.toRotationMatrix();
00104     z_q_ = z_q_.conjugate();
00105     z_p_ = -C_zq.transpose() * z_p_;
00106 
00107     Eigen::Matrix<double, 6, 6> C_cov(Eigen::Matrix<double, 6, 6>::Zero());
00108     C_cov.block<3, 3> (0, 0) = C_zq;
00109     C_cov.block<3, 3> (3, 3) = C_zq;
00110 
00111     R.block<6, 6> (0, 0) = C_cov.transpose() * R.block<6, 6> (0, 0) * C_cov;
00112   }
00113   /*************************************************************************************/
00114 
00115   //  alternatively take fix covariance from reconfigure GUI
00116   if (use_fixed_covariance_)
00117   {
00118     const double s_zp = n_zp_ * n_zp_;
00119     const double s_zq = n_zq_ * n_zq_;
00120     R = (Eigen::Matrix<double, N_MEAS, 1>() << s_zp, s_zp, s_zp, s_zq, s_zq, s_zq, 1e-6).finished().asDiagonal();
00121   }
00122 
00123   // feedback for init case
00124   measurements->p_vc_ = z_p_;
00125   measurements->q_cv_ = z_q_;
00126 
00127   unsigned char idx = measurements->ssf_core_.getClosestState(&state_old, time_old);
00128   if (state_old.time_ == -1)
00129     return; // // early abort // //
00130 
00131   // get rotation matrices
00132   Eigen::Matrix<double, 3, 3> C_wv = state_old.q_wv_.conjugate().toRotationMatrix();
00133   Eigen::Matrix<double, 3, 3> C_q = state_old.q_.conjugate().toRotationMatrix();
00134   Eigen::Matrix<double, 3, 3> C_ci = state_old.q_ci_.conjugate().toRotationMatrix();
00135 
00136   // preprocess for elements in H matrix
00137   Eigen::Matrix<double, 3, 1> vecold;
00138   vecold = (state_old.p_ + C_q.transpose() * state_old.p_ci_) * state_old.L_;
00139   Eigen::Matrix<double, 3, 3> skewold = skew(vecold);
00140 
00141   Eigen::Matrix<double, 3, 3> pci_sk = skew(state_old.p_ci_);
00142 
00143   // construct H matrix using H-blockx :-)
00144   // position:
00145   H_old.block<3, 3> (0, 0) = C_wv.transpose() * state_old.L_; // p
00146   H_old.block<3, 3> (0, 6) = -C_wv.transpose() * C_q.transpose() * pci_sk * state_old.L_; // q
00147   H_old.block<3, 1> (0, 15) = C_wv.transpose() * C_q.transpose() * state_old.p_ci_ + C_wv.transpose() * state_old.p_; // L
00148   H_old.block<3, 3> (0, 16) = -C_wv.transpose() * skewold; // q_wv
00149   H_old.block<3, 3> (0, 22) = C_wv.transpose() * C_q.transpose() * state_old.L_; //p_ci
00150 
00151   // attitude
00152   H_old.block<3, 3> (3, 6) = C_ci; // q
00153   H_old.block<3, 3> (3, 16) = C_ci * C_q; // q_wv
00154   H_old.block<3, 3> (3, 19) = Eigen::Matrix<double, 3, 3>::Identity(); //q_ci
00155   H_old(6, 18) = 1.0; // fix vision world yaw drift because unobservable otherwise (see PhD Thesis)
00156 
00157   // construct residuals
00158   // position
00159   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_;
00160   // attitude
00161   Eigen::Quaternion<double> q_err;
00162   q_err = (state_old.q_wv_ * state_old.q_ * state_old.q_ci_).conjugate() * z_q_;
00163   r_old.block<3, 1> (3, 0) = q_err.vec() / q_err.w() * 2;
00164   // vision world yaw drift
00165   q_err = state_old.q_wv_;
00166   r_old(6, 0) = -2 * (q_err.w() * q_err.z() + q_err.x() * q_err.y()) / (1 - 2 * (q_err.y() * q_err.y() + q_err.z() * q_err.z()));
00167 
00168   // call update step in core class
00169   measurements->ssf_core_.applyMeasurement(idx, H_old, r_old, R);
00170 }


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