31 #include <geometry_msgs/Twist.h> 32 #include <nav_msgs/Odometry.h> 33 #include <sensor_msgs/Imu.h> 34 #include <std_msgs/Float32.h> 44 #include <Eigen/Geometry> 50 Eigen::Vector3f
toEigen(
const geometry_msgs::Vector3& a)
52 return Eigen::Vector3f(a.x, a.y, a.z);
54 Eigen::Vector3f
toEigen(
const geometry_msgs::Point& a)
56 return Eigen::Vector3f(a.x, a.y, a.z);
58 Eigen::Quaternionf
toEigen(
const geometry_msgs::Quaternion& a)
60 return Eigen::Quaternionf(a.w, a.x, a.y, a.z);
62 geometry_msgs::Point
toPoint(
const Eigen::Vector3f& a)
64 geometry_msgs::Point b;
70 geometry_msgs::Vector3
toVector3(
const Eigen::Vector3f& a)
72 geometry_msgs::Vector3 b;
120 odom_prev_.pose.pose.position.z = msg->data;
122 void cbImu(
const sensor_msgs::Imu::Ptr& msg)
124 if (base_link_id_.size() == 0)
126 ROS_ERROR(
"base_link id is not specified.");
130 imu_.header = msg->header;
136 geometry_msgs::Vector3Stamped vin, vout;
137 vin.header = imu_.header;
139 vin.vector = msg->linear_acceleration;
141 imu_.linear_acceleration = vout.vector;
143 vin.header = imu_.header;
145 vin.vector = msg->angular_velocity;
147 imu_.angular_velocity = vout.vector;
150 geometry_msgs::QuaternionStamped qmin, qmout;
151 qmin.header = imu_.header;
152 qmin.quaternion = msg->orientation;
155 auto axis = qin.getAxis();
156 auto angle = qin.getAngle();
157 geometry_msgs::Vector3Stamped axis2;
158 geometry_msgs::Vector3Stamped axis1;
170 imu_.orientation = qmout.quaternion;
184 void cbOdom(
const nav_msgs::Odometry::Ptr& msg)
186 nav_msgs::Odometry odom = *msg;
189 const double dt = (odom.header.stamp - odomraw_prev_.header.stamp).toSec();
190 if (base_link_id_overwrite_.size() == 0)
192 base_link_id_ = odom.child_frame_id;
201 float slip_ratio = 1.0;
203 odom.twist.twist.angular = imu_.angular_velocity;
204 odom.pose.pose.orientation = imu_.orientation;
206 float w_imu = imu_.angular_velocity.z;
207 const float w_odom = msg->twist.twist.angular.z;
209 if (w_imu * w_odom < 0 && !negative_slip_)
212 slip_.
predict(-slip_.
x_ * dt * predict_filter_tc_, dt * sigma_predict_);
213 if (fabs(w_odom) > sigma_odom_ * 3)
216 slip_ratio = w_imu / w_odom;
219 const float slip_ratio_per_angvel =
220 (w_odom - w_imu) / (w_odom * fabs(w_odom));
221 float slip_ratio_per_angvel_sigma =
222 sigma_odom_ * fabs(2 * w_odom * sigma_odom_ / powf(w_odom * w_odom - sigma_odom_ * sigma_odom_, 2.0));
223 if (fabs(w_odom) < sigma_odom_)
224 slip_ratio_per_angvel_sigma = std::numeric_limits<float>::infinity();
226 slip_.
measure(slip_ratio_per_angvel, slip_ratio_per_angvel_sigma);
233 printf(
"%0.3f %0.3f %0.3f %0.3f %0.3f %0.3f %0.3f\n",
234 imu_.angular_velocity.z,
235 msg->twist.twist.angular.z,
238 odom.twist.twist.linear.x, dist_);
240 dist_ += odom.twist.twist.linear.x * dt;
242 const Eigen::Vector3f
diff =
toEigen(msg->pose.pose.position) -
toEigen(odomraw_prev_.pose.pose.position);
244 toEigen(odom.pose.pose.orientation) *
toEigen(msg->pose.pose.orientation).inverse() * diff;
250 odom.pose.pose.position =
toPoint(
toEigen(odom_prev_.pose.pose.position) + v);
251 if (z_filter_timeconst_ > 0)
257 geometry_msgs::TransformStamped odom_trans;
259 odom_trans.header = odom.header;
261 odom_trans.transform.translation =
toVector3(
toEigen(odom.pose.pose.position));
262 odom_trans.transform.rotation = odom.pose.pose.orientation;
266 odomraw_prev_ = *msg;
275 , tf_listener_(tf_buffer_)
278 pnh_.
param(
"without_odom", without_odom_,
false);
285 nh_,
"reset_odometry_z",
287 pub_odom_ = nh_.
advertise<nav_msgs::Odometry>(
"odom", 8);
291 pnh_.
param(
"base_link_id", base_link_id_overwrite_, std::string(
""));
295 pnh_.
param(
"base_link_id", base_link_id_, std::string(
"base_link"));
296 pnh_.
param(
"odom_id", odom_id_, std::string(
"odom"));
301 z_filter_timeconst_ = -1.0;
303 if (pnh_.
getParam(
"z_filter", z_filter))
305 const double odom_freq = 100.0;
306 if (0.0 < z_filter && z_filter < 1.0)
307 z_filter_timeconst_ = (1.0 / odom_freq) / (1.0 - z_filter);
310 "track_odometry: ~z_filter parameter (exponential filter (1 - alpha) value) is deprecated. " 311 "Use ~z_filter_timeconst (in seconds) instead. " 312 "Treated as z_filter_timeconst=%0.6f. (negative value means disabled)",
313 z_filter_timeconst_);
317 pnh_.
param(
"z_filter_timeconst", z_filter_timeconst_, -1.0);
319 pnh_.
param(
"tf_tolerance", tf_tolerance_, 0.01);
320 pnh_.
param(
"use_kf", use_kf_,
true);
321 pnh_.
param(
"enable_negative_slip", negative_slip_,
false);
322 pnh_.
param(
"debug", debug_,
false);
323 pnh_.
param(
"publish_tf", publish_tf_,
true);
325 if (base_link_id_overwrite_.size() > 0)
331 pnh_.
param(
"sigma_odom", sigma_odom_, 0.005);
333 pnh_.
param(
"sigma_predict", sigma_predict_, 0.5);
335 pnh_.
param(
"predict_filter_tc", predict_filter_tc_, 1.0);
345 nav_msgs::Odometry::Ptr odom(
new nav_msgs::Odometry);
349 odom->pose.pose.orientation.w = 1.0;
367 int main(
int argc,
char* argv[])
void measure(const float x_in, const float sigma_in)
std::string base_link_id_
void publish(const boost::shared_ptr< M > &message) const
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void set(const float x0=0.0, const float sigma0=std::numeric_limits< float >::infinity())
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
tf2_ros::Buffer tf_buffer_
Eigen::Vector3f toEigen(const geometry_msgs::Vector3 &a)
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(*fp)(M), const ros::TransportHints &transport_hints=ros::TransportHints())
tf2_ros::TransformListener tf_listener_
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
ros::Subscriber sub_reset_z_
ROSCPP_DECL void spin(Spinner &spinner)
tf2_ros::TransformBroadcaster tf_broadcaster_
geometry_msgs::Vector3 toVector3(const Eigen::Vector3f &a)
double z_filter_timeconst_
ros::Subscriber sub_odom_
void cbImu(const sensor_msgs::Imu::Ptr &msg)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
#define ROS_ERROR_THROTTLE(period,...)
void fromMsg(const A &, B &b)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
int main(int argc, char *argv[])
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double predict_filter_tc_
void cbResetZ(const std_msgs::Float32::Ptr &msg)
geometry_msgs::Point toPoint(const Eigen::Vector3f &a)
nav_msgs::Odometry odomraw_prev_
nav_msgs::Odometry odom_prev_
bool getParam(const std::string &key, std::string &s) const
void predict(const float x_plus, const float sigma_plus)
bool hasParam(const std::string &key) const
void setData(const T &input)
void cbOdom(const nav_msgs::Odometry::Ptr &msg)
std::string base_link_id_overwrite_
void cbTimer(const ros::TimerEvent &event)