36 #include <Eigen/Geometry>
40 #include <geometry_msgs/Twist.h>
41 #include <nav_msgs/Odometry.h>
42 #include <sensor_msgs/Imu.h>
43 #include <std_msgs/Float32.h>
57 Eigen::Vector3d
toEigen(
const geometry_msgs::Vector3& a)
59 return Eigen::Vector3d(a.x, a.y, a.z);
61 Eigen::Vector3d
toEigen(
const geometry_msgs::Point& a)
63 return Eigen::Vector3d(a.x, a.y, a.z);
65 Eigen::Quaterniond
toEigen(
const geometry_msgs::Quaternion& a)
67 return Eigen::Quaterniond(a.w, a.x, a.y, a.z);
69 geometry_msgs::Point
toPoint(
const Eigen::Vector3d& a)
71 geometry_msgs::Point b;
77 geometry_msgs::Vector3
toVector3(
const Eigen::Vector3d& a)
79 geometry_msgs::Vector3 b;
96 std::shared_ptr<message_filters::Subscriber<nav_msgs::Odometry>>
sub_odom_;
97 std::shared_ptr<message_filters::Subscriber<sensor_msgs::Imu>>
sub_imu_;
98 std::shared_ptr<message_filters::Synchronizer<SyncPolicy>>
sync_;
136 void cbOdomImu(
const nav_msgs::Odometry::ConstPtr& odom_msg,
const sensor_msgs::Imu::ConstPtr& imu_msg)
139 "Synchronized timestamp: odom %0.3f, imu %0.3f",
140 odom_msg->header.stamp.toSec(),
141 imu_msg->header.stamp.toSec());
145 void cbImu(
const sensor_msgs::Imu::ConstPtr& msg)
149 ROS_ERROR(
"base_link id is not specified.");
153 imu_.header = msg->header;
159 geometry_msgs::Vector3Stamped vin, vout;
160 vin.header =
imu_.header;
162 vin.vector = msg->linear_acceleration;
164 imu_.linear_acceleration = vout.vector;
166 vin.header =
imu_.header;
168 vin.vector = msg->angular_velocity;
170 imu_.angular_velocity = vout.vector;
173 geometry_msgs::QuaternionStamped qmin, qmout;
174 qmin.header =
imu_.header;
175 qmin.quaternion = msg->orientation;
178 auto axis = qin.getAxis();
179 auto angle = qin.getAngle();
180 geometry_msgs::Vector3Stamped axis2;
181 geometry_msgs::Vector3Stamped axis1;
193 imu_.orientation = qmout.quaternion;
207 void cbOdom(
const nav_msgs::Odometry::ConstPtr& msg)
209 nav_msgs::Odometry odom = *msg;
212 const double dt = (odom.header.stamp -
odomraw_prev_.header.stamp).toSec();
224 double slip_ratio = 1.0;
226 odom.twist.twist.angular =
imu_.angular_velocity;
227 odom.pose.pose.orientation =
imu_.orientation;
229 double w_imu =
imu_.angular_velocity.z;
230 const double w_odom = msg->twist.twist.angular.z;
239 slip_ratio = w_imu / w_odom;
242 const double slip_ratio_per_angvel =
243 (w_odom - w_imu) / (w_odom * std::abs(w_odom));
244 double slip_ratio_per_angvel_sigma =
247 slip_ratio_per_angvel_sigma = std::numeric_limits<double>::infinity();
249 slip_.
measure(slip_ratio_per_angvel, slip_ratio_per_angvel_sigma);
256 printf(
"%0.3f %0.3f %0.3f %0.3f %0.3f %0.3f %0.3f\n",
257 imu_.angular_velocity.z,
258 msg->twist.twist.angular.z,
261 odom.twist.twist.linear.x,
dist_);
263 dist_ += odom.twist.twist.linear.x * dt;
267 toEigen(odom.pose.pose.orientation) *
toEigen(msg->pose.pose.orientation).inverse() * diff;
280 geometry_msgs::TransformStamped odom_trans;
282 odom_trans.header = odom.header;
284 odom_trans.transform.translation =
toVector3(
toEigen(odom.pose.pose.position));
285 odom_trans.transform.rotation = odom.pose.pose.orientation;
302 bool enable_tcp_no_delay;
303 pnh_.
param(
"enable_tcp_no_delay", enable_tcp_no_delay,
true);
332 pnh_.
param(
"sync_window", sync_window, 50);
342 nh_,
"reset_odometry_z",
352 const double odom_freq = 100.0;
353 if (0.0 < z_filter && z_filter < 1.0)
357 "track_odometry: ~z_filter parameter (exponential filter (1 - alpha) value) is deprecated. "
358 "Use ~z_filter_timeconst (in seconds) instead. "
359 "Treated as z_filter_timeconst=%0.6f. (negative value means disabled)",
392 nav_msgs::Odometry::Ptr odom(
new nav_msgs::Odometry);
396 odom->pose.pose.orientation.w = 1.0;
414 int main(
int argc,
char* argv[])