33 #ifndef TWISTPUBLISHER_H
34 #define TWISTPUBLISHER_H
37 #include <geometry_msgs/TwistStamped.h>
47 int pub_queue_size = 5;
49 pub = node.
advertise<geometry_msgs::TwistStamped>(
"filter/twist", pub_queue_size);
55 if (packet.containsVelocity() && packet.containsCalibratedGyroscopeData())
57 geometry_msgs::TwistStamped
msg;
59 msg.header.stamp = timestamp;
64 msg.twist.linear.x = v[0];
65 msg.twist.linear.y = v[1];
66 msg.twist.linear.z = v[2];
68 XsVector gyro = packet.calibratedGyroscopeData();
69 msg.twist.angular.x = gyro[0];
70 msg.twist.angular.y = gyro[1];
71 msg.twist.angular.z = gyro[2];