diff --git a/src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp b/src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp index f744aa11c2..1d36e3d99c 100644 --- a/src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp +++ b/src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp @@ -136,6 +136,7 @@ void AttitudeEstimator::ImuCallback(const sensor_msgs::ImuConstPtr &msg) msg_v_att.pitchspeed = -(float)msg->angular_velocity.y; msg_v_att.yawspeed = -(float)msg->angular_velocity.z; + msg_v_att.timestamp = px4::get_time_micros(); _vehicle_attitude_pub.publish(msg_v_att); }