odom_estimation_node.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 /* Author: Wim Meeussen */
00036 
00037 #include <iri_robot_pose_ekf/odom_estimation_node.h>
00038 
00039 
00040 using namespace MatrixWrapper;
00041 using namespace std;
00042 using namespace ros;
00043 using namespace tf;
00044 
00045 
00046 static const double EPS = 1e-5;
00047 
00048 
00049 //#define __EKF_DEBUG_FILE__
00050 
00051 namespace estimation
00052 {
00053   // constructor
00054   OdomEstimationNode::OdomEstimationNode()
00055     : odom_active_(false),
00056       imu_active_(false),
00057       vo_active_(false),
00058       odom_initializing_(false),
00059       imu_initializing_(false),
00060       vo_initializing_(false),
00061       odom_covariance_(6),
00062       imu_covariance_(3),
00063       vo_covariance_(6),
00064       odom_callback_counter_(0),
00065       imu_callback_counter_(0),
00066       vo_callback_counter_(0),
00067       ekf_sent_counter_(0)
00068   {
00069     ros::NodeHandle nh_private("~");
00070     ros::NodeHandle nh;
00071 
00072     // paramters
00073     double freq;
00074     nh_private.param("base_frame",      base_frame_, std::string("/base_footprint"));
00075     nh_private.param("odom_frame",      odom_frame_, std::string("/odom"));
00076     nh_private.param("sensor_timeout",  timeout_, 1.0);
00077     nh_private.param("odom_used",       odom_used_, true);
00078     nh_private.param("imu_used",        imu_used_, true);
00079     nh_private.param("vo_used",         vo_used_, true);
00080     nh_private.param("debug",           debug_, false);
00081     nh_private.param("self_diagnose",   self_diagnose_, false);
00082     nh_private.param("freq",            freq, 30.0);
00083 
00084     timer_ = nh_private.createTimer(ros::Duration(1.0/max(freq,1.0)), &OdomEstimationNode::spin, this);
00085 
00086     // advertise our estimation
00087     pose_pub_ = nh_private.advertise<geometry_msgs::PoseWithCovarianceStamped>("pose", 10);
00088 
00089     // initialize
00090     filter_stamp_ = Time::now();
00091 
00092     // subscribe to odom messages
00093     if (odom_used_){
00094       ROS_DEBUG("Odom sensor can be used");
00095       odom_sub_ = nh.subscribe("odom", 10, &OdomEstimationNode::odomCallback, this);
00096     }
00097     else ROS_DEBUG("Odom sensor will NOT be used");
00098 
00099     // subscribe to imu messages
00100     if (imu_used_){
00101       ROS_DEBUG("Imu sensor can be used");
00102       imu_sub_ = nh.subscribe("imu_data", 10,  &OdomEstimationNode::imuCallback, this);
00103     }
00104     else ROS_DEBUG("Imu sensor will NOT be used");
00105 
00106     // subscribe to vo messages
00107     if (vo_used_){
00108       ROS_DEBUG("VO sensor can be used");
00109       vo_sub_ = nh.subscribe("vo", 10, &OdomEstimationNode::voCallback, this);
00110     }
00111     else ROS_DEBUG("VO sensor will NOT be used");
00112 
00113     // publish state service
00114     state_srv_ = nh_private.advertiseService("get_status", &OdomEstimationNode::getStatus, this);
00115 
00116     if (debug_){
00117       // open files for debugging
00118       odom_file_.open("/tmp/odom_file.txt");
00119       imu_file_.open("/tmp/imu_file.txt");
00120       vo_file_.open("/tmp/vo_file.txt");
00121       corr_file_.open("/tmp/corr_file.txt");
00122       time_file_.open("/tmp/time_file.txt");
00123       extra_file_.open("/tmp/extra_file.txt");
00124     }
00125   };
00126 
00127 
00128 
00129 
00130   // destructor
00131   OdomEstimationNode::~OdomEstimationNode(){
00132 
00133     if (debug_){
00134       // close files for debugging
00135       odom_file_.close();
00136       imu_file_.close();
00137       vo_file_.close();
00138       corr_file_.close();
00139       time_file_.close();
00140       extra_file_.close();
00141     }
00142   };
00143 
00144 
00145 
00146 
00147 
00148   // callback function for odom data
00149   void OdomEstimationNode::odomCallback(const OdomConstPtr& odom)
00150   {
00151     odom_callback_counter_++;
00152 
00153     ROS_DEBUG("Odom callback at time %f ", ros::Time::now().toSec());
00154     assert(odom_used_);
00155 
00156     // receive data
00157     odom_stamp_ = odom->header.stamp;
00158     odom_time_  = Time::now();
00159     Quaternion q;
00160     tf::quaternionMsgToTF(odom->pose.pose.orientation, q);
00161     odom_meas_  = Transform(q, Vector3(odom->pose.pose.position.x, odom->pose.pose.position.y, 0));
00162     for (unsigned int i=0; i<6; i++)
00163       for (unsigned int j=0; j<6; j++)
00164         odom_covariance_(i+1, j+1) = odom->pose.covariance[6*i+j];
00165 
00166     my_filter_.addMeasurement(StampedTransform(odom_meas_.inverse(), odom_stamp_, base_frame_, "wheelodom"), odom_covariance_);
00167 
00168     // activate odom
00169     if (!odom_active_) {
00170       if (!odom_initializing_){
00171         odom_initializing_ = true;
00172         odom_init_stamp_ = odom_stamp_;
00173         ROS_INFO("Initializing Odom sensor");
00174       }
00175       if ( filter_stamp_ >= odom_init_stamp_){
00176         odom_active_ = true;
00177         odom_initializing_ = false;
00178         ROS_INFO("Odom sensor activated");
00179       }
00180       else ROS_DEBUG("Waiting to activate Odom, because Odom measurements are still %f sec in the future.",
00181                       (odom_init_stamp_ - filter_stamp_).toSec());
00182     }
00183 
00184     if (debug_){
00185       // write to file
00186       double tmp, yaw;
00187       odom_meas_.getBasis().getEulerZYX(yaw, tmp, tmp);
00188       odom_file_ << odom_meas_.getOrigin().x() << " " << odom_meas_.getOrigin().y() << "  " << yaw << "  " << endl;
00189     }
00190   };
00191 
00192 
00193 
00194 
00195   // callback function for imu data
00196   void OdomEstimationNode::imuCallback(const ImuConstPtr& imu)
00197   {
00198     imu_callback_counter_++;
00199 
00200     assert(imu_used_);
00201 
00202     // receive data
00203     imu_stamp_ = imu->header.stamp;
00204     tf::Quaternion orientation;
00205     quaternionMsgToTF(imu->orientation, orientation);
00206     imu_meas_ = Transform(orientation, btVector3(0,0,0));
00207     for (unsigned int i=0; i<3; i++)
00208       for (unsigned int j=0; j<3; j++)
00209         imu_covariance_(i+1, j+1) = imu->orientation_covariance[3*i+j];
00210 
00211     // Transforms imu data to base_footprint frame
00212     if (!robot_state_.waitForTransform(base_frame_, imu->header.frame_id, imu_stamp_, ros::Duration(0.5))){
00213       // warn when imu was already activated, not when imu is not active yet
00214       if (imu_active_)
00215         ROS_ERROR("Could not transform imu message from %s to %s", imu->header.frame_id.c_str(),base_frame_.c_str());
00216       else if (my_filter_.isInitialized())
00217         ROS_WARN("Could not transform imu message from %s to %s. Imu will not be activated yet.",
00218                  imu->header.frame_id.c_str(),base_frame_.c_str());
00219       else
00220         ROS_DEBUG("Could not transform imu message from %s to %s. Imu will not be activated yet.",
00221                   imu->header.frame_id.c_str(),base_frame_.c_str());
00222       return;
00223     }
00224     StampedTransform base_imu_offset;
00225     robot_state_.lookupTransform(base_frame_, imu->header.frame_id, imu_stamp_, base_imu_offset);
00226     imu_meas_ = imu_meas_ * base_imu_offset;
00227 
00228     imu_time_  = Time::now();
00229 
00230     // manually set covariance untile imu sends covariance
00231     if (imu_covariance_(1,1) == 0.0){
00232       SymmetricMatrix measNoiseImu_Cov(3);  measNoiseImu_Cov = 0;
00233       measNoiseImu_Cov(1,1) = pow(0.00017,2);  // = 0.01 degrees / sec
00234       measNoiseImu_Cov(2,2) = pow(0.00017,2);  // = 0.01 degrees / sec
00235       measNoiseImu_Cov(3,3) = pow(0.00017,2);  // = 0.01 degrees / sec
00236       imu_covariance_ = measNoiseImu_Cov;
00237     }
00238 
00239     my_filter_.addMeasurement(StampedTransform(imu_meas_.inverse(), imu_stamp_, base_frame_, "imu"), imu_covariance_);
00240 
00241     // activate imu
00242     if (!imu_active_) {
00243       if (!imu_initializing_){
00244         imu_initializing_ = true;
00245         imu_init_stamp_ = imu_stamp_;
00246         ROS_INFO("Initializing Imu sensor");
00247       }
00248       if ( filter_stamp_ >= imu_init_stamp_){
00249         imu_active_ = true;
00250         imu_initializing_ = false;
00251         ROS_INFO("Imu sensor activated");
00252       }
00253       else ROS_DEBUG("Waiting to activate IMU, because IMU measurements are still %f sec in the future.",
00254                       (imu_init_stamp_ - filter_stamp_).toSec());
00255     }
00256 
00257     if (debug_){
00258       // write to file
00259       double tmp, yaw;
00260       imu_meas_.getBasis().getEulerZYX(yaw, tmp, tmp);
00261       imu_file_ << yaw << endl;
00262     }
00263   };
00264 
00265 
00266 
00267 
00268   // callback function for VO data
00269   void OdomEstimationNode::voCallback(const VoConstPtr& vo)
00270   {
00271     vo_callback_counter_++;
00272 
00273     assert(vo_used_);
00274 
00275     // get data
00276     vo_stamp_ = vo->header.stamp;
00277     vo_time_  = Time::now();
00278     poseMsgToTF(vo->pose.pose, vo_meas_);
00279     for (unsigned int i=0; i<6; i++)
00280       for (unsigned int j=0; j<6; j++)
00281         vo_covariance_(i+1, j+1) = vo->pose.covariance[6*i+j];
00282     my_filter_.addMeasurement(StampedTransform(vo_meas_.inverse(), vo_stamp_, base_frame_, "vo"), vo_covariance_);
00283 
00284     // activate vo
00285     if (!vo_active_) {
00286       if (!vo_initializing_){
00287         vo_initializing_ = true;
00288         vo_init_stamp_ = vo_stamp_;
00289         ROS_INFO("Initializing Vo sensor");
00290       }
00291       if (filter_stamp_ >= vo_init_stamp_){
00292         vo_active_ = true;
00293         vo_initializing_ = false;
00294         ROS_INFO("Vo sensor activated");
00295       }
00296       else ROS_DEBUG("Waiting to activate VO, because VO measurements are still %f sec in the future.",
00297                      (vo_init_stamp_ - filter_stamp_).toSec());
00298     }
00299 
00300     if (debug_){
00301       // write to file
00302       double Rx, Ry, Rz;
00303       vo_meas_.getBasis().getEulerZYX(Rz, Ry, Rx);
00304       vo_file_ << vo_meas_.getOrigin().x() << " " << vo_meas_.getOrigin().y() << " "
00305                << vo_meas_.getOrigin().z() << " " << Rx << " " << Ry << " " << Rz << endl;
00306     }
00307   };
00308 
00309 
00310 
00311 
00312 
00313   // filter loop
00314   void OdomEstimationNode::spin(const ros::TimerEvent& e)
00315   {
00316     ROS_DEBUG("Spin function at time %f", ros::Time::now().toSec());
00317 
00318     // check for timing problems
00319     if ( (odom_initializing_ || odom_active_) && (imu_initializing_ || imu_active_) ){
00320       double diff = fabs( Duration(odom_stamp_ - imu_stamp_).toSec() );
00321       if (diff > 1.0) ROS_ERROR("Timestamps of odometry and imu are %f seconds apart.", diff);
00322     }
00323 
00324     // initial value for filter stamp; keep this stamp when no sensors are active
00325     filter_stamp_ = Time::now();
00326 
00327     // check which sensors are still active
00328     if ((odom_active_ || odom_initializing_) &&
00329         (Time::now() - odom_time_).toSec() > timeout_){
00330       odom_active_ = false; odom_initializing_ = false;
00331       ROS_INFO("Odom sensor not active any more");
00332     }
00333     if ((imu_active_ || imu_initializing_) &&
00334         (Time::now() - imu_time_).toSec() > timeout_){
00335       imu_active_ = false;  imu_initializing_ = false;
00336       ROS_INFO("Imu sensor not active any more");
00337     }
00338     if ((vo_active_ || vo_initializing_) &&
00339         (Time::now() - vo_time_).toSec() > timeout_){
00340       vo_active_ = false;  vo_initializing_ = false;
00341       ROS_INFO("VO sensor not active any more");
00342     }
00343 
00344     // only update filter when one of the sensors is active
00345     if (odom_active_ || imu_active_ || vo_active_){
00346 
00347       // update filter at time where all sensor measurements are available
00348       if (odom_active_)  filter_stamp_ = min(filter_stamp_, odom_stamp_);
00349       if (imu_active_)   filter_stamp_ = min(filter_stamp_, imu_stamp_);
00350       if (vo_active_)    filter_stamp_ = min(filter_stamp_, vo_stamp_);
00351 
00352       // update filter
00353       if ( my_filter_.isInitialized() )  {
00354         bool diagnostics = true;
00355         if (my_filter_.update(odom_active_, imu_active_, vo_active_,  filter_stamp_, diagnostics)){
00356 
00357           // output most recent estimate and relative covariance
00358           my_filter_.getEstimate(output_);
00359           pose_pub_.publish(output_);
00360           ekf_sent_counter_++;
00361 
00362           // broadcast most recent estimate to TransformArray
00363           StampedTransform tmp;
00364           my_filter_.getEstimate(ros::Time(), tmp);
00365           if(!vo_active_)
00366             tmp.getOrigin().setZ(0.0);
00367           odom_broadcaster_.sendTransform(StampedTransform(tmp, tmp.stamp_, odom_frame_, base_frame_));
00368 
00369           if (debug_){
00370             // write to file
00371             ColumnVector estimate;
00372             my_filter_.getEstimate(estimate);
00373             for (unsigned int i=1; i<=6; i++)
00374               corr_file_ << estimate(i) << " ";
00375             corr_file_ << endl;
00376           }
00377         }
00378         if (self_diagnose_ && !diagnostics)
00379           ROS_WARN("Robot pose ekf diagnostics discovered a potential problem");
00380       }
00381       // initialize filer with odometry frame
00382       if ( odom_active_ && !my_filter_.isInitialized()){
00383         my_filter_.initialize(odom_meas_, odom_stamp_);
00384         ROS_INFO("Kalman filter initialized with odom measurement");
00385       }
00386       else if ( vo_active_ && !my_filter_.isInitialized()){
00387         my_filter_.initialize(vo_meas_, vo_stamp_);
00388         ROS_INFO("Kalman filter initialized with vo measurement");
00389       }
00390     }
00391   };
00392 
00393 
00394 bool OdomEstimationNode::getStatus(iri_robot_pose_ekf::GetStatus::Request& req, iri_robot_pose_ekf::GetStatus::Response& resp)
00395 {
00396   stringstream ss;
00397   ss << "Input:" << endl;
00398   ss << " * Odometry sensor" << endl;
00399   ss << "   - is "; if (!odom_active_) ss << "NOT "; ss << "active" << endl;
00400   ss << "   - received " << odom_callback_counter_ << " messages" << endl;
00401   ss << "   - listens to topic " << odom_sub_.getTopic() << endl;
00402   ss << " * IMU sensor" << endl;
00403   ss << "   - is "; if (!imu_active_) ss << "NOT "; ss << "active" << endl;
00404   ss << "   - received " << imu_callback_counter_ << " messages" << endl;
00405   ss << "   - listens to topic " << imu_sub_.getTopic() << endl;
00406   ss << " * Visual Odometry sensor" << endl;
00407   ss << "   - is "; if (!vo_active_) ss << "NOT "; ss << "active" << endl;
00408   ss << "   - received " << vo_callback_counter_ << " messages" << endl;
00409   ss << "   - listens to topic " << vo_sub_.getTopic() << endl;
00410   ss << "Output:" << endl;
00411   ss << " * Robot pose ekf filter" << endl;
00412   ss << "   - is "; if (!my_filter_.isInitialized()) ss << "NOT "; ss << "active" << endl;
00413   ss << "   - sent " << ekf_sent_counter_ << " messages" << endl;
00414   ss << "   - pulishes on topics " << pose_pub_.getTopic() << " and /tf" << endl;
00415   resp.status = ss.str();
00416   return true;
00417 }
00418 
00419 }; // namespace
00420 
00421 
00422 
00423 
00424 
00425 
00426 // ----------
00427 // -- MAIN --
00428 // ----------
00429 using namespace estimation;
00430 int main(int argc, char **argv)
00431 {
00432   // Initialize ROS
00433   ros::init(argc, argv, "robot_pose_ekf");
00434 
00435   // create filter class
00436   OdomEstimationNode my_filter_node;
00437 
00438   ros::spin();
00439 
00440   return 0;
00441 }


iri_robot_pose_ekf
Author(s): Wim Meeussen
autogenerated on Fri Dec 6 2013 23:49:07