forked from Archive/PX4-Autopilot
ros att estimator dummy node: publish timestamp
This commit is contained in:
parent
76d2417cc5
commit
6a122ab643
|
@ -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);
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue