From f31ea943984f173d1ee240758f5b01846b79ede1 Mon Sep 17 00:00:00 2001 From: Nicolas SIMON <51367203+Nicolas-131@users.noreply.github.com> Date: Wed, 30 Oct 2019 14:27:53 +0100 Subject: [PATCH] Fix error of mag topic not publish --- src/main.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main.cpp b/src/main.cpp index cd11309..b251701 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -212,11 +212,11 @@ void publishMsgs(um7::Registers& r, ros::NodeHandle* imu_nh, sensor_msgs::Imu& i static ros::Publisher mag_pub; if (use_magnetic_field_msg) { - ros::Publisher mag_pub = imu_nh->advertise("mag", 1, false); + mag_pub = imu_nh->advertise("mag", 1, false); } else { - ros::Publisher mag_pub = imu_nh->advertise("mag", 1, false); + mag_pub = imu_nh->advertise("mag", 1, false); } static ros::Publisher rpy_pub = imu_nh->advertise("rpy", 1, false); static ros::Publisher temp_pub = imu_nh->advertise("temperature", 1, false);