$search
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 <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 nh_private.param("output_frame", output_frame_, std::string("odom_combined")); 00074 nh_private.param("sensor_timeout", timeout_, 1.0); 00075 nh_private.param("odom_used", odom_used_, true); 00076 nh_private.param("imu_used", imu_used_, true); 00077 nh_private.param("vo_used", vo_used_, true); 00078 nh_private.param("debug", debug_, false); 00079 nh_private.param("self_diagnose", self_diagnose_, false); 00080 double freq; 00081 nh_private.param("freq", freq, 30.0); 00082 00083 timer_ = nh_private.createTimer(ros::Duration(1.0/max(freq,1.0)), &OdomEstimationNode::spin, this); 00084 00085 // advertise our estimation 00086 pose_pub_ = nh_private.advertise<geometry_msgs::PoseWithCovarianceStamped>(output_frame_, 10); 00087 00088 // initialize 00089 filter_stamp_ = Time::now(); 00090 00091 // subscribe to odom messages 00092 if (odom_used_){ 00093 ROS_DEBUG("Odom sensor can be used"); 00094 odom_sub_ = nh.subscribe("odom", 10, &OdomEstimationNode::odomCallback, this); 00095 } 00096 else ROS_DEBUG("Odom sensor will NOT be used"); 00097 00098 // subscribe to imu messages 00099 if (imu_used_){ 00100 ROS_DEBUG("Imu sensor can be used"); 00101 imu_sub_ = nh.subscribe("imu_data", 10, &OdomEstimationNode::imuCallback, this); 00102 } 00103 else ROS_DEBUG("Imu sensor will NOT be used"); 00104 00105 // subscribe to vo messages 00106 if (vo_used_){ 00107 ROS_DEBUG("VO sensor can be used"); 00108 vo_sub_ = nh.subscribe("vo", 10, &OdomEstimationNode::voCallback, this); 00109 } 00110 else ROS_DEBUG("VO sensor will NOT be used"); 00111 00112 // publish state service 00113 state_srv_ = nh_private.advertiseService("get_status", &OdomEstimationNode::getStatus, this); 00114 00115 if (debug_){ 00116 // open files for debugging 00117 odom_file_.open("/tmp/odom_file.txt"); 00118 imu_file_.open("/tmp/imu_file.txt"); 00119 vo_file_.open("/tmp/vo_file.txt"); 00120 corr_file_.open("/tmp/corr_file.txt"); 00121 time_file_.open("/tmp/time_file.txt"); 00122 extra_file_.open("/tmp/extra_file.txt"); 00123 } 00124 }; 00125 00126 00127 00128 00129 // destructor 00130 OdomEstimationNode::~OdomEstimationNode(){ 00131 00132 if (debug_){ 00133 // close files for debugging 00134 odom_file_.close(); 00135 imu_file_.close(); 00136 vo_file_.close(); 00137 corr_file_.close(); 00138 time_file_.close(); 00139 extra_file_.close(); 00140 } 00141 }; 00142 00143 00144 00145 00146 00147 // callback function for odom data 00148 void OdomEstimationNode::odomCallback(const OdomConstPtr& odom) 00149 { 00150 odom_callback_counter_++; 00151 00152 ROS_DEBUG("Odom callback at time %f ", ros::Time::now().toSec()); 00153 assert(odom_used_); 00154 00155 // receive data 00156 odom_stamp_ = odom->header.stamp; 00157 odom_time_ = Time::now(); 00158 Quaternion q; 00159 tf::quaternionMsgToTF(odom->pose.pose.orientation, q); 00160 odom_meas_ = Transform(q, Vector3(odom->pose.pose.position.x, odom->pose.pose.position.y, 0)); 00161 for (unsigned int i=0; i<6; i++) 00162 for (unsigned int j=0; j<6; j++) 00163 odom_covariance_(i+1, j+1) = odom->pose.covariance[6*i+j]; 00164 00165 my_filter_.addMeasurement(StampedTransform(odom_meas_.inverse(), odom_stamp_, "base_footprint", "wheelodom"), odom_covariance_); 00166 00167 // activate odom 00168 if (!odom_active_) { 00169 if (!odom_initializing_){ 00170 odom_initializing_ = true; 00171 odom_init_stamp_ = odom_stamp_; 00172 ROS_INFO("Initializing Odom sensor"); 00173 } 00174 if ( filter_stamp_ >= odom_init_stamp_){ 00175 odom_active_ = true; 00176 odom_initializing_ = false; 00177 ROS_INFO("Odom sensor activated"); 00178 } 00179 else ROS_DEBUG("Waiting to activate Odom, because Odom measurements are still %f sec in the future.", 00180 (odom_init_stamp_ - filter_stamp_).toSec()); 00181 } 00182 00183 if (debug_){ 00184 // write to file 00185 double tmp, yaw; 00186 odom_meas_.getBasis().getEulerZYX(yaw, tmp, tmp); 00187 odom_file_ << odom_meas_.getOrigin().x() << " " << odom_meas_.getOrigin().y() << " " << yaw << " " << endl; 00188 } 00189 }; 00190 00191 00192 00193 00194 // callback function for imu data 00195 void OdomEstimationNode::imuCallback(const ImuConstPtr& imu) 00196 { 00197 imu_callback_counter_++; 00198 00199 assert(imu_used_); 00200 00201 // receive data 00202 imu_stamp_ = imu->header.stamp; 00203 btQuaternion orientation; 00204 quaternionMsgToTF(imu->orientation, orientation); 00205 imu_meas_ = btTransform(orientation, btVector3(0,0,0)); 00206 for (unsigned int i=0; i<3; i++) 00207 for (unsigned int j=0; j<3; j++) 00208 imu_covariance_(i+1, j+1) = imu->orientation_covariance[3*i+j]; 00209 00210 // Transforms imu data to base_footprint frame 00211 if (!robot_state_.waitForTransform("base_footprint", imu->header.frame_id, imu_stamp_, ros::Duration(0.5))){ 00212 // warn when imu was already activated, not when imu is not active yet 00213 if (imu_active_) 00214 ROS_ERROR("Could not transform imu message from %s to base_footprint", imu->header.frame_id.c_str()); 00215 else if (my_filter_.isInitialized()) 00216 ROS_WARN("Could not transform imu message from %s to base_footprint. Imu will not be activated yet.", imu->header.frame_id.c_str()); 00217 else 00218 ROS_DEBUG("Could not transform imu message from %s to base_footprint. Imu will not be activated yet.", imu->header.frame_id.c_str()); 00219 return; 00220 } 00221 StampedTransform base_imu_offset; 00222 robot_state_.lookupTransform("base_footprint", imu->header.frame_id, imu_stamp_, base_imu_offset); 00223 imu_meas_ = imu_meas_ * base_imu_offset; 00224 00225 imu_time_ = Time::now(); 00226 00227 // manually set covariance untile imu sends covariance 00228 if (imu_covariance_(1,1) == 0.0){ 00229 SymmetricMatrix measNoiseImu_Cov(3); measNoiseImu_Cov = 0; 00230 measNoiseImu_Cov(1,1) = pow(0.00017,2); // = 0.01 degrees / sec 00231 measNoiseImu_Cov(2,2) = pow(0.00017,2); // = 0.01 degrees / sec 00232 measNoiseImu_Cov(3,3) = pow(0.00017,2); // = 0.01 degrees / sec 00233 imu_covariance_ = measNoiseImu_Cov; 00234 } 00235 00236 my_filter_.addMeasurement(StampedTransform(imu_meas_.inverse(), imu_stamp_, "base_footprint", "imu"), imu_covariance_); 00237 00238 // activate imu 00239 if (!imu_active_) { 00240 if (!imu_initializing_){ 00241 imu_initializing_ = true; 00242 imu_init_stamp_ = imu_stamp_; 00243 ROS_INFO("Initializing Imu sensor"); 00244 } 00245 if ( filter_stamp_ >= imu_init_stamp_){ 00246 imu_active_ = true; 00247 imu_initializing_ = false; 00248 ROS_INFO("Imu sensor activated"); 00249 } 00250 else ROS_DEBUG("Waiting to activate IMU, because IMU measurements are still %f sec in the future.", 00251 (imu_init_stamp_ - filter_stamp_).toSec()); 00252 } 00253 00254 if (debug_){ 00255 // write to file 00256 double tmp, yaw; 00257 imu_meas_.getBasis().getEulerZYX(yaw, tmp, tmp); 00258 imu_file_ << yaw << endl; 00259 } 00260 }; 00261 00262 00263 00264 00265 // callback function for VO data 00266 void OdomEstimationNode::voCallback(const VoConstPtr& vo) 00267 { 00268 vo_callback_counter_++; 00269 00270 assert(vo_used_); 00271 00272 // get data 00273 vo_stamp_ = vo->header.stamp; 00274 vo_time_ = Time::now(); 00275 poseMsgToTF(vo->pose.pose, vo_meas_); 00276 for (unsigned int i=0; i<6; i++) 00277 for (unsigned int j=0; j<6; j++) 00278 vo_covariance_(i+1, j+1) = vo->pose.covariance[6*i+j]; 00279 my_filter_.addMeasurement(StampedTransform(vo_meas_.inverse(), vo_stamp_, "base_footprint", "vo"), vo_covariance_); 00280 00281 // activate vo 00282 if (!vo_active_) { 00283 if (!vo_initializing_){ 00284 vo_initializing_ = true; 00285 vo_init_stamp_ = vo_stamp_; 00286 ROS_INFO("Initializing Vo sensor"); 00287 } 00288 if (filter_stamp_ >= vo_init_stamp_){ 00289 vo_active_ = true; 00290 vo_initializing_ = false; 00291 ROS_INFO("Vo sensor activated"); 00292 } 00293 else ROS_DEBUG("Waiting to activate VO, because VO measurements are still %f sec in the future.", 00294 (vo_init_stamp_ - filter_stamp_).toSec()); 00295 } 00296 00297 if (debug_){ 00298 // write to file 00299 double Rx, Ry, Rz; 00300 vo_meas_.getBasis().getEulerZYX(Rz, Ry, Rx); 00301 vo_file_ << vo_meas_.getOrigin().x() << " " << vo_meas_.getOrigin().y() << " " << vo_meas_.getOrigin().z() << " " 00302 << Rx << " " << Ry << " " << Rz << endl; 00303 } 00304 }; 00305 00306 00307 00308 00309 00310 // filter loop 00311 void OdomEstimationNode::spin(const ros::TimerEvent& e) 00312 { 00313 ROS_DEBUG("Spin function at time %f", ros::Time::now().toSec()); 00314 00315 // check for timing problems 00316 if ( (odom_initializing_ || odom_active_) && (imu_initializing_ || imu_active_) ){ 00317 double diff = fabs( Duration(odom_stamp_ - imu_stamp_).toSec() ); 00318 if (diff > 1.0) ROS_ERROR("Timestamps of odometry and imu are %f seconds apart.", diff); 00319 } 00320 00321 // initial value for filter stamp; keep this stamp when no sensors are active 00322 filter_stamp_ = Time::now(); 00323 00324 // check which sensors are still active 00325 if ((odom_active_ || odom_initializing_) && 00326 (Time::now() - odom_time_).toSec() > timeout_){ 00327 odom_active_ = false; odom_initializing_ = false; 00328 ROS_INFO("Odom sensor not active any more"); 00329 } 00330 if ((imu_active_ || imu_initializing_) && 00331 (Time::now() - imu_time_).toSec() > timeout_){ 00332 imu_active_ = false; imu_initializing_ = false; 00333 ROS_INFO("Imu sensor not active any more"); 00334 } 00335 if ((vo_active_ || vo_initializing_) && 00336 (Time::now() - vo_time_).toSec() > timeout_){ 00337 vo_active_ = false; vo_initializing_ = false; 00338 ROS_INFO("VO sensor not active any more"); 00339 } 00340 00341 // only update filter when one of the sensors is active 00342 if (odom_active_ || imu_active_ || vo_active_){ 00343 00344 // update filter at time where all sensor measurements are available 00345 if (odom_active_) filter_stamp_ = min(filter_stamp_, odom_stamp_); 00346 if (imu_active_) filter_stamp_ = min(filter_stamp_, imu_stamp_); 00347 if (vo_active_) filter_stamp_ = min(filter_stamp_, vo_stamp_); 00348 00349 // update filter 00350 if ( my_filter_.isInitialized() ) { 00351 bool diagnostics = true; 00352 if (my_filter_.update(odom_active_, imu_active_, vo_active_, filter_stamp_, diagnostics)){ 00353 00354 // output most recent estimate and relative covariance 00355 my_filter_.getEstimate(output_); 00356 pose_pub_.publish(output_); 00357 ekf_sent_counter_++; 00358 00359 // broadcast most recent estimate to TransformArray 00360 StampedTransform tmp; 00361 my_filter_.getEstimate(ros::Time(), tmp); 00362 if(!vo_active_) 00363 tmp.getOrigin().setZ(0.0); 00364 odom_broadcaster_.sendTransform(StampedTransform(tmp, tmp.stamp_, output_frame_, "base_footprint")); 00365 00366 if (debug_){ 00367 // write to file 00368 ColumnVector estimate; 00369 my_filter_.getEstimate(estimate); 00370 for (unsigned int i=1; i<=6; i++) 00371 corr_file_ << estimate(i) << " "; 00372 corr_file_ << endl; 00373 } 00374 } 00375 if (self_diagnose_ && !diagnostics) 00376 ROS_WARN("Robot pose ekf diagnostics discovered a potential problem"); 00377 } 00378 // initialize filer with odometry frame 00379 if ( odom_active_ && !my_filter_.isInitialized()){ 00380 my_filter_.initialize(odom_meas_, odom_stamp_); 00381 ROS_INFO("Kalman filter initialized with odom measurement"); 00382 } 00383 else if ( vo_active_ && !my_filter_.isInitialized()){ 00384 my_filter_.initialize(vo_meas_, vo_stamp_); 00385 ROS_INFO("Kalman filter initialized with vo measurement"); 00386 } 00387 } 00388 }; 00389 00390 00391 bool OdomEstimationNode::getStatus(robot_pose_ekf::GetStatus::Request& req, robot_pose_ekf::GetStatus::Response& resp) 00392 { 00393 stringstream ss; 00394 ss << "Input:" << endl; 00395 ss << " * Odometry sensor" << endl; 00396 ss << " - is "; if (!odom_active_) ss << "NOT "; ss << "active" << endl; 00397 ss << " - received " << odom_callback_counter_ << " messages" << endl; 00398 ss << " - listens to topic " << odom_sub_.getTopic() << endl; 00399 ss << " * IMU sensor" << endl; 00400 ss << " - is "; if (!imu_active_) ss << "NOT "; ss << "active" << endl; 00401 ss << " - received " << imu_callback_counter_ << " messages" << endl; 00402 ss << " - listens to topic " << imu_sub_.getTopic() << endl; 00403 ss << " * Visual Odometry sensor" << endl; 00404 ss << " - is "; if (!vo_active_) ss << "NOT "; ss << "active" << endl; 00405 ss << " - received " << vo_callback_counter_ << " messages" << endl; 00406 ss << " - listens to topic " << vo_sub_.getTopic() << endl; 00407 ss << "Output:" << endl; 00408 ss << " * Robot pose ekf filter" << endl; 00409 ss << " - is "; if (!my_filter_.isInitialized()) ss << "NOT "; ss << "active" << endl; 00410 ss << " - sent " << ekf_sent_counter_ << " messages" << endl; 00411 ss << " - pulishes on topics " << pose_pub_.getTopic() << " and /tf" << endl; 00412 resp.status = ss.str(); 00413 return true; 00414 } 00415 00416 }; // namespace 00417 00418 00419 00420 00421 00422 00423 // ---------- 00424 // -- MAIN -- 00425 // ---------- 00426 using namespace estimation; 00427 int main(int argc, char **argv) 00428 { 00429 // Initialize ROS 00430 ros::init(argc, argv, "robot_pose_ekf"); 00431 00432 // create filter class 00433 OdomEstimationNode my_filter_node; 00434 00435 ros::spin(); 00436 00437 return 0; 00438 }