Skip to content

Commit

Permalink
Merge pull request #24 from Nicolas-131/indigo-devel
Browse files Browse the repository at this point in the history
Fix error of mag topic not publish
  • Loading branch information
tonybaltovski authored Oct 30, 2019
2 parents a288240 + f31ea94 commit 5a99320
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<sensor_msgs::MagneticField>("mag", 1, false);
mag_pub = imu_nh->advertise<sensor_msgs::MagneticField>("mag", 1, false);
}
else
{
ros::Publisher mag_pub = imu_nh->advertise<geometry_msgs::Vector3Stamped>("mag", 1, false);
mag_pub = imu_nh->advertise<geometry_msgs::Vector3Stamped>("mag", 1, false);
}
static ros::Publisher rpy_pub = imu_nh->advertise<geometry_msgs::Vector3Stamped>("rpy", 1, false);
static ros::Publisher temp_pub = imu_nh->advertise<std_msgs::Float32>("temperature", 1, false);
Expand Down

0 comments on commit 5a99320

Please sign in to comment.