diff --git a/src/visualizer.cpp b/src/visualizer.cpp
index a3d5896abc558c98adf55e4dee605200dd1334ed..276bc6633f30579f2e31e33a27578c892be681d1 100644
--- a/src/visualizer.cpp
+++ b/src/visualizer.cpp
@@ -11,11 +11,6 @@ Visualizer::Visualizer() :
 
 void Visualizer::initialize(ros::NodeHandle& nh)
 {
-    // init publishers ---------------------------------------------------
-    factors_publisher_      = nh.advertise<visualization_msgs::MarkerArray>("factors", 1);
-    landmarks_publisher_    = nh.advertise<visualization_msgs::MarkerArray>("landmarks", 1);
-    trajectory_publisher_   = nh.advertise<visualization_msgs::MarkerArray>("trajectory", 1);
-
     // Load options ---------------------------------------------------
     nh.param<bool>(         "viz_factors",              viz_factors_,               true);
     nh.param<bool>(         "viz_overlapped_factors",   viz_overlapped_factors_,    false);
@@ -61,6 +56,14 @@ void Visualizer::initialize(ros::NodeHandle& nh)
     nh.param<float>(        "factor_geom_color_b",      factor_geom_color_.b,       1.0);
     nh.param<float>(        "factor_geom_color_a",      factor_geom_color_.a,       1);
 
+    // init publishers ---------------------------------------------------
+    if (viz_factors_)
+        factors_publisher_      = nh.advertise<visualization_msgs::MarkerArray>("factors", 1);
+    if (viz_landmarks_)
+        landmarks_publisher_    = nh.advertise<visualization_msgs::MarkerArray>("landmarks", 1);
+    if (viz_trajectory_)
+        trajectory_publisher_   = nh.advertise<visualization_msgs::MarkerArray>("trajectory", 1);
+
     // init markers ---------------------------------------------------
     // factor markers message
     factor_marker_.type = visualization_msgs::Marker::LINE_LIST;