track_odometry.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2014-2017, the neonavigation authors
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the copyright holder nor the names of its 
00014  *       contributors may be used to endorse or promote products derived from 
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <ros/ros.h>
00031 #include <geometry_msgs/Twist.h>
00032 #include <nav_msgs/Odometry.h>
00033 #include <sensor_msgs/Imu.h>
00034 #include <std_msgs/Float32.h>
00035 
00036 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
00037 #include <tf2_ros/transform_broadcaster.h>
00038 #include <tf2_ros/transform_listener.h>
00039 
00040 #include <limits>
00041 #include <string>
00042 
00043 #include <Eigen/Core>
00044 #include <Eigen/Geometry>
00045 
00046 #include <kalman_filter1.h>
00047 
00048 #include <neonavigation_common/compatibility.h>
00049 
00050 Eigen::Vector3f toEigen(const geometry_msgs::Vector3& a)
00051 {
00052   return Eigen::Vector3f(a.x, a.y, a.z);
00053 }
00054 Eigen::Vector3f toEigen(const geometry_msgs::Point& a)
00055 {
00056   return Eigen::Vector3f(a.x, a.y, a.z);
00057 }
00058 Eigen::Quaternionf toEigen(const geometry_msgs::Quaternion& a)
00059 {
00060   return Eigen::Quaternionf(a.w, a.x, a.y, a.z);
00061 }
00062 geometry_msgs::Point toPoint(const Eigen::Vector3f& a)
00063 {
00064   geometry_msgs::Point b;
00065   b.x = a.x();
00066   b.y = a.y();
00067   b.z = a.z();
00068   return b;
00069 }
00070 geometry_msgs::Vector3 toVector3(const Eigen::Vector3f& a)
00071 {
00072   geometry_msgs::Vector3 b;
00073   b.x = a.x();
00074   b.y = a.y();
00075   b.z = a.z();
00076   return b;
00077 }
00078 
00079 class TrackOdometryNode
00080 {
00081 private:
00082   ros::NodeHandle nh_;
00083   ros::NodeHandle pnh_;
00084   ros::Subscriber sub_odom_;
00085   ros::Subscriber sub_imu_;
00086   ros::Subscriber sub_reset_z_;
00087   ros::Publisher pub_odom_;
00088   tf2_ros::Buffer tf_buffer_;
00089   tf2_ros::TransformListener tf_listener_;
00090   tf2_ros::TransformBroadcaster tf_broadcaster_;
00091   nav_msgs::Odometry odom_prev_;
00092   nav_msgs::Odometry odomraw_prev_;
00093 
00094   std::string base_link_id_;
00095   std::string base_link_id_overwrite_;
00096   std::string odom_id_;
00097 
00098   sensor_msgs::Imu imu_;
00099   double gyro_zero_[3];
00100   double z_filter_timeconst_;
00101   double tf_tolerance_;
00102 
00103   bool debug_;
00104   bool use_kf_;
00105   bool negative_slip_;
00106   double sigma_predict_;
00107   double sigma_odom_;
00108   double predict_filter_tc_;
00109   float dist_;
00110   bool without_odom_;
00111 
00112   KalmanFilter1 slip_;
00113 
00114   bool has_imu_;
00115   bool has_odom_;
00116   bool publish_tf_;
00117 
00118   void cbResetZ(const std_msgs::Float32::Ptr& msg)
00119   {
00120     odom_prev_.pose.pose.position.z = msg->data;
00121   }
00122   void cbImu(const sensor_msgs::Imu::Ptr& msg)
00123   {
00124     if (base_link_id_.size() == 0)
00125     {
00126       ROS_ERROR("base_link id is not specified.");
00127       return;
00128     }
00129 
00130     imu_.header = msg->header;
00131     try
00132     {
00133       geometry_msgs::TransformStamped trans = tf_buffer_.lookupTransform(
00134           base_link_id_, msg->header.frame_id, ros::Time(0), ros::Duration(0.1));
00135 
00136       geometry_msgs::Vector3Stamped vin, vout;
00137       vin.header = imu_.header;
00138       vin.header.stamp = ros::Time(0);
00139       vin.vector = msg->linear_acceleration;
00140       tf2::doTransform(vin, vout, trans);
00141       imu_.linear_acceleration = vout.vector;
00142 
00143       vin.header = imu_.header;
00144       vin.header.stamp = ros::Time(0);
00145       vin.vector = msg->angular_velocity;
00146       tf2::doTransform(vin, vout, trans);
00147       imu_.angular_velocity = vout.vector;
00148 
00149       tf2::Stamped<tf2::Quaternion> qin, qout;
00150       geometry_msgs::QuaternionStamped qmin, qmout;
00151       qmin.header = imu_.header;
00152       qmin.quaternion = msg->orientation;
00153       tf2::fromMsg(qmin, qin);
00154 
00155       auto axis = qin.getAxis();
00156       auto angle = qin.getAngle();
00157       geometry_msgs::Vector3Stamped axis2;
00158       geometry_msgs::Vector3Stamped axis1;
00159       axis1.vector = tf2::toMsg(axis);
00160       axis1.header.stamp = ros::Time(0);
00161       axis1.header.frame_id = qin.frame_id_;
00162       tf2::doTransform(axis1, axis2, trans);
00163 
00164       tf2::fromMsg(axis2.vector, axis);
00165       qout.setData(tf2::Quaternion(axis, angle));
00166       qout.stamp_ = qin.stamp_;
00167       qout.frame_id_ = base_link_id_;
00168 
00169       qmout = tf2::toMsg(qout);
00170       imu_.orientation = qmout.quaternion;
00171       // ROS_INFO("%0.3f %s -> %0.3f %s",
00172       //   tf2::getYaw(qmin.quaternion), qmin.header.frame_id.c_str(),
00173       //   tf2::getYaw(qmout.quaternion), qmout.header.frame_id.c_str());
00174 
00175       has_imu_ = true;
00176     }
00177     catch (tf2::TransformException& e)
00178     {
00179       ROS_ERROR("%s", e.what());
00180       has_imu_ = false;
00181       return;
00182     }
00183   }
00184   void cbOdom(const nav_msgs::Odometry::Ptr& msg)
00185   {
00186     nav_msgs::Odometry odom = *msg;
00187     if (has_odom_)
00188     {
00189       const double dt = (odom.header.stamp - odomraw_prev_.header.stamp).toSec();
00190       if (base_link_id_overwrite_.size() == 0)
00191       {
00192         base_link_id_ = odom.child_frame_id;
00193       }
00194 
00195       if (!has_imu_)
00196       {
00197         ROS_ERROR_THROTTLE(1.0, "IMU data not received");
00198         return;
00199       }
00200 
00201       float slip_ratio = 1.0;
00202       odom.header.stamp += ros::Duration(tf_tolerance_);
00203       odom.twist.twist.angular = imu_.angular_velocity;
00204       odom.pose.pose.orientation = imu_.orientation;
00205 
00206       float w_imu = imu_.angular_velocity.z;
00207       const float w_odom = msg->twist.twist.angular.z;
00208 
00209       if (w_imu * w_odom < 0 && !negative_slip_)
00210         w_imu = w_odom;
00211 
00212       slip_.predict(-slip_.x_ * dt * predict_filter_tc_, dt * sigma_predict_);
00213       if (fabs(w_odom) > sigma_odom_ * 3)
00214       {
00215         // non-kf mode: calculate slip_ratio if angular vel < 3*sigma
00216         slip_ratio = w_imu / w_odom;
00217       }
00218 
00219       const float slip_ratio_per_angvel =
00220           (w_odom - w_imu) / (w_odom * fabs(w_odom));
00221       float slip_ratio_per_angvel_sigma =
00222           sigma_odom_ * fabs(2 * w_odom * sigma_odom_ / powf(w_odom * w_odom - sigma_odom_ * sigma_odom_, 2.0));
00223       if (fabs(w_odom) < sigma_odom_)
00224         slip_ratio_per_angvel_sigma = std::numeric_limits<float>::infinity();
00225 
00226       slip_.measure(slip_ratio_per_angvel, slip_ratio_per_angvel_sigma);
00227       // printf("%0.5f %0.5f %0.5f   %0.5f %0.5f  %0.5f\n",
00228       //   slip_ratio_per_angvel, slip_ratio_sigma, slip_ratio_per_angvel_sigma,
00229       //   slip_.x_, slip_.sigma_, msg->twist.twist.angular.z);
00230 
00231       if (debug_)
00232       {
00233         printf("%0.3f %0.3f  %0.3f  %0.3f %0.3f  %0.3f  %0.3f\n",
00234                imu_.angular_velocity.z,
00235                msg->twist.twist.angular.z,
00236                slip_ratio,
00237                slip_.x_, slip_.sigma_,
00238                odom.twist.twist.linear.x, dist_);
00239       }
00240       dist_ += odom.twist.twist.linear.x * dt;
00241 
00242       const Eigen::Vector3f diff = toEigen(msg->pose.pose.position) - toEigen(odomraw_prev_.pose.pose.position);
00243       Eigen::Vector3f v =
00244           toEigen(odom.pose.pose.orientation) * toEigen(msg->pose.pose.orientation).inverse() * diff;
00245       if (use_kf_)
00246         v *= 1.0 - slip_.x_;
00247       else
00248         v *= slip_ratio;
00249 
00250       odom.pose.pose.position = toPoint(toEigen(odom_prev_.pose.pose.position) + v);
00251       if (z_filter_timeconst_ > 0)
00252         odom.pose.pose.position.z *= 1.0 - (dt / z_filter_timeconst_);
00253 
00254       odom.child_frame_id = base_link_id_;
00255       pub_odom_.publish(odom);
00256 
00257       geometry_msgs::TransformStamped odom_trans;
00258 
00259       odom_trans.header = odom.header;
00260       odom_trans.child_frame_id = base_link_id_;
00261       odom_trans.transform.translation = toVector3(toEigen(odom.pose.pose.position));
00262       odom_trans.transform.rotation = odom.pose.pose.orientation;
00263       if (publish_tf_)
00264         tf_broadcaster_.sendTransform(odom_trans);
00265     }
00266     odomraw_prev_ = *msg;
00267     odom_prev_ = odom;
00268     has_odom_ = true;
00269   }
00270 
00271 public:
00272   TrackOdometryNode()
00273     : nh_()
00274     , pnh_("~")
00275     , tf_listener_(tf_buffer_)
00276   {
00277     neonavigation_common::compat::checkCompatMode();
00278     pnh_.param("without_odom", without_odom_, false);
00279     if (!without_odom_)
00280       sub_odom_ = nh_.subscribe("odom_raw", 64, &TrackOdometryNode::cbOdom, this);
00281     sub_imu_ = neonavigation_common::compat::subscribe(
00282         nh_, "imu/data",
00283         nh_, "imu", 64, &TrackOdometryNode::cbImu, this);
00284     sub_reset_z_ = neonavigation_common::compat::subscribe(
00285         nh_, "reset_odometry_z",
00286         pnh_, "reset_z", 1, &TrackOdometryNode::cbResetZ, this);
00287     pub_odom_ = nh_.advertise<nav_msgs::Odometry>("odom", 8);
00288 
00289     if (!without_odom_)
00290     {
00291       pnh_.param("base_link_id", base_link_id_overwrite_, std::string(""));
00292     }
00293     else
00294     {
00295       pnh_.param("base_link_id", base_link_id_, std::string("base_link"));
00296       pnh_.param("odom_id", odom_id_, std::string("odom"));
00297     }
00298 
00299     if (pnh_.hasParam("z_filter"))
00300     {
00301       z_filter_timeconst_ = -1.0;
00302       double z_filter;
00303       if (pnh_.getParam("z_filter", z_filter))
00304       {
00305         const double odom_freq = 100.0;
00306         if (0.0 < z_filter && z_filter < 1.0)
00307           z_filter_timeconst_ = (1.0 / odom_freq) / (1.0 - z_filter);
00308       }
00309       ROS_ERROR(
00310           "track_odometry: ~z_filter parameter (exponential filter (1 - alpha) value) is deprecated. "
00311           "Use ~z_filter_timeconst (in seconds) instead. "
00312           "Treated as z_filter_timeconst=%0.6f. (negative value means disabled)",
00313           z_filter_timeconst_);
00314     }
00315     else
00316     {
00317       pnh_.param("z_filter_timeconst", z_filter_timeconst_, -1.0);
00318     }
00319     pnh_.param("tf_tolerance", tf_tolerance_, 0.01);
00320     pnh_.param("use_kf", use_kf_, true);
00321     pnh_.param("enable_negative_slip", negative_slip_, false);
00322     pnh_.param("debug", debug_, false);
00323     pnh_.param("publish_tf", publish_tf_, true);
00324 
00325     if (base_link_id_overwrite_.size() > 0)
00326     {
00327       base_link_id_ = base_link_id_overwrite_;
00328     }
00329 
00330     // sigma_odom_ [rad/s]: standard deviation of odometry angular vel on straight running
00331     pnh_.param("sigma_odom", sigma_odom_, 0.005);
00332     // sigma_predict_ [sigma/second]: prediction sigma of kalman filter
00333     pnh_.param("sigma_predict", sigma_predict_, 0.5);
00334     // predict_filter_tc_ [sec.]: LPF time-constant to forget estimated slip_ ratio
00335     pnh_.param("predict_filter_tc", predict_filter_tc_, 1.0);
00336 
00337     has_imu_ = false;
00338     has_odom_ = false;
00339 
00340     dist_ = 0;
00341     slip_.set(0.0, 0.1);
00342   }
00343   void cbTimer(const ros::TimerEvent& event)
00344   {
00345     nav_msgs::Odometry::Ptr odom(new nav_msgs::Odometry);
00346     odom->header.stamp = ros::Time::now();
00347     odom->header.frame_id = odom_id_;
00348     odom->child_frame_id = base_link_id_;
00349     odom->pose.pose.orientation.w = 1.0;
00350     cbOdom(odom);
00351   }
00352   void spin()
00353   {
00354     if (!without_odom_)
00355     {
00356       ros::spin();
00357     }
00358     else
00359     {
00360       ros::Timer timer = nh_.createTimer(
00361           ros::Duration(1.0 / 50.0), &TrackOdometryNode::cbTimer, this);
00362       ros::spin();
00363     }
00364   }
00365 };
00366 
00367 int main(int argc, char* argv[])
00368 {
00369   ros::init(argc, argv, "track_odometry");
00370 
00371   TrackOdometryNode odom;
00372 
00373   odom.spin();
00374 
00375   return 0;
00376 }


track_odometry
Author(s): Atsushi Watanabe
autogenerated on Sat Jun 22 2019 20:07:23