raw_data_subscriber.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 
3 #include <geometry_msgs/QuaternionStamped.h>
4 #include <geometry_msgs/Vector3Stamped.h>
5 #include <sensor_msgs/Imu.h>
6 #include <sensor_msgs/MagneticField.h>
7 
12 void imuCallback(const sensor_msgs::Imu::ConstPtr& msg) {
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);
17 }
18 
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);
22 }
23 
24 void angVelCallback(const geometry_msgs::Vector3StampedConstPtr& msg) {
25  ROS_INFO("Ang. vel: %.3f,%.3f,%.3f [deg/sec]",
26  msg->vector.x, msg->vector.y, msg->vector.z);
27 }
28 
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);
32 }
33 
34 void rpyCallback(const geometry_msgs::Vector3StampedConstPtr& msg) {
35  ROS_INFO("RPY: %.3f,%.3f,%.3f",
36  msg->vector.x, msg->vector.y, msg->vector.z);
37 }
38 
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);
42 }
43 
48 int main(int argc, char** argv) {
49  ros::init(argc, argv, "muse_raw_data_subscriber");
51 
52  ros::Subscriber subImu = n.subscribe("/imu/data", 10, imuCallback);
53  ros::Subscriber subAcc = n.subscribe("/imu/linear_acceleration", 10, accCallback);
54  ros::Subscriber subAngVel = n.subscribe("/imu/angular_velocity", 10, angVelCallback);
55  ros::Subscriber subQuaternion = n.subscribe("/imu/quaternion", 10, quatCallback);
56  ros::Subscriber subRPY = n.subscribe("/imu/rpy", 10, rpyCallback);
57  ros::Subscriber subMag = n.subscribe("/zed/zed_node/imu/mag", 10, magCallback);
58 
59  ros::spin();
60 
61  return 0;
62 }
main
int main(int argc, char **argv)
Definition: raw_data_subscriber.cpp:48
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
angVelCallback
void angVelCallback(const geometry_msgs::Vector3StampedConstPtr &msg)
Definition: raw_data_subscriber.cpp:24
ros.h
rpyCallback
void rpyCallback(const geometry_msgs::Vector3StampedConstPtr &msg)
Definition: raw_data_subscriber.cpp:34
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
imuCallback
void imuCallback(const sensor_msgs::Imu::ConstPtr &msg)
Definition: raw_data_subscriber.cpp:12
quatCallback
void quatCallback(const geometry_msgs::QuaternionStampedConstPtr &msg)
Definition: raw_data_subscriber.cpp:29
magCallback
void magCallback(const sensor_msgs::MagneticField::ConstPtr &msg)
Definition: raw_data_subscriber.cpp:39
accCallback
void accCallback(const geometry_msgs::Vector3StampedConstPtr &msg)
Definition: raw_data_subscriber.cpp:19
ros::spin
ROSCPP_DECL void spin()
ROS_INFO
#define ROS_INFO(...)
ros::NodeHandle
ros::Subscriber


muse_v2_driver
Author(s): Elisa Tosello , Roberto Bortoletto
autogenerated on Thu Jan 20 2022 03:24:53