3 #include <geometry_msgs/QuaternionStamped.h>
4 #include <geometry_msgs/Vector3Stamped.h>
5 #include <sensor_msgs/Imu.h>
6 #include <sensor_msgs/MagneticField.h>
13 ROS_INFO(
"Linear acc: %.3f,%.3f,%.3f [m/s^2] - Ang. vel: %.3f,%.3f,%.3f [deg/sec] - Orient. Quat: %.3f,%.3f,%.3f,%.3f",
14 msg->linear_acceleration.x, msg->linear_acceleration.y, msg->linear_acceleration.z,
15 msg->angular_velocity.x, msg->angular_velocity.y, msg->angular_velocity.z,
16 msg->orientation.x, msg->orientation.y, msg->orientation.z, msg->orientation.w);
19 void accCallback(
const geometry_msgs::Vector3StampedConstPtr& msg) {
20 ROS_INFO(
"Linear acc: %.3f,%.3f,%.3f [m/s^2]",
21 msg->vector.x, msg->vector.y, msg->vector.z);
25 ROS_INFO(
"Ang. vel: %.3f,%.3f,%.3f [deg/sec]",
26 msg->vector.x, msg->vector.y, msg->vector.z);
29 void quatCallback(
const geometry_msgs::QuaternionStampedConstPtr& msg) {
30 ROS_INFO(
"Orient. Quat: %.3f,%.3f,%.3f,%.3f",
31 msg->quaternion.x, msg->quaternion.y, msg->quaternion.z, msg->quaternion.w);
34 void rpyCallback(
const geometry_msgs::Vector3StampedConstPtr& msg) {
36 msg->vector.x, msg->vector.y, msg->vector.z);
39 void magCallback(
const sensor_msgs::MagneticField::ConstPtr& msg) {
40 ROS_INFO(
"Mag. Field: %.3f,%.3f,%.3f [uT]",
41 msg->magnetic_field.x * 1e-6, msg->magnetic_field.y * 1e-6, msg->magnetic_field.z * 1e-6);
48 int main(
int argc,
char** argv) {
49 ros::init(argc, argv,
"muse_raw_data_subscriber");