diff --git a/Tools/px4moduledoc/srcparser.py b/Tools/px4moduledoc/srcparser.py
index 79df90f054ba62235cb1ac3d11dd2541855a3dbe..2e227699e66b5f86bc79a873f85b5677620258f7 100644
--- a/Tools/px4moduledoc/srcparser.py
+++ b/Tools/px4moduledoc/srcparser.py
@@ -92,7 +92,8 @@ class ModuleDocumentation(object):
         description = self._get_string(args[4])
         if self._is_bool_true(args[5]):
             self._usage_string += "     [-%s <val>]  %s\n" % (option_char, description)
-            self._usage_string += "                 default: %i\n" % default_val
+            if default_val != -1:
+                self._usage_string += "                 default: %i\n" % default_val
         else:
             self._usage_string += "     -%s <val>    %s\n" % (option_char, description)
 
@@ -103,7 +104,8 @@ class ModuleDocumentation(object):
         description = self._get_string(args[4])
         if self._is_bool_true(args[5]):
             self._usage_string += "     [-%s <val>]  %s\n" % (option_char, description)
-            self._usage_string += "                 default: %.1f\n" % default_val
+            if not math.isnan(default_val):
+                self._usage_string += "                 default: %.1f\n" % default_val
         else:
             self._usage_string += "     -%s <val>    %s\n" % (option_char, description)
 
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index c0780144c386b0e3843fbadcd4809240f98d2249..e367baff215fc5fd2907240070e419e06291df61 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -3067,7 +3067,7 @@ $ mavlink stream -u 14556 -s HIGHRES_IMU -r 50
 
 	PRINT_MODULE_USAGE_COMMAND_DESCR("stream", "Configure the sending rate of a stream for a running instance");
 #if defined(CONFIG_NET) || defined(__PX4_POSIX)
-	PRINT_MODULE_USAGE_PARAM_INT('u', 0, 0, 65536, "Select Mavlink instance via local Network Port", true);
+	PRINT_MODULE_USAGE_PARAM_INT('u', -1, 0, 65536, "Select Mavlink instance via local Network Port", true);
 #endif
 	PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, "<file:dev>", "Select Mavlink instance via Serial Device", true);
 	PRINT_MODULE_USAGE_PARAM_STRING('s', nullptr, nullptr, "Mavlink stream to configure", false);
diff --git a/src/modules/micrortps_bridge/micrortps_client/microRTPS_client_main.cpp b/src/modules/micrortps_bridge/micrortps_client/microRTPS_client_main.cpp
index bcb211aaab91c72f2dadc4bb2bae826a0f0d946f..a9f8d86fa5d09a051e5643e8df79f8f4543b2a4d 100644
--- a/src/modules/micrortps_bridge/micrortps_client/microRTPS_client_main.cpp
+++ b/src/modules/micrortps_bridge/micrortps_client/microRTPS_client_main.cpp
@@ -76,7 +76,7 @@ static void usage(const char *name)
 	PRINT_MODULE_USAGE_PARAM_STRING('t', "UART", "UART|UDP", "Transport protocol", true);
 	PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/ttyACM0", "<file:dev>", "Select Serial Device", true);
 	PRINT_MODULE_USAGE_PARAM_INT('b', 460800, 9600, 3000000, "Baudrate (can also be p:<param_name>)", true);
-	PRINT_MODULE_USAGE_PARAM_INT('p', 1, 1, 1000, "Poll timeout for UART in ms", true);
+	PRINT_MODULE_USAGE_PARAM_INT('p', -1, 1, 1000, "Poll timeout for UART in ms", true);
 	PRINT_MODULE_USAGE_PARAM_INT('u', 0, 0, 10000,
 				     "Interval in ms to limit the update rate of all sent topics (0=unlimited)", true);
 	PRINT_MODULE_USAGE_PARAM_INT('l', 10000, -1, 100000, "Limit number of iterations until the program exits (-1=infinite)",
diff --git a/src/platforms/common/module.cpp b/src/platforms/common/module.cpp
index bb9cf1d762fc13d824b8ff8a11348263e5821a14..31e8b6c7af10867075b99b4048712e8e9bd82994 100644
--- a/src/platforms/common/module.cpp
+++ b/src/platforms/common/module.cpp
@@ -41,6 +41,7 @@
 #endif
 
 #include <px4_module.h>
+#include <px4_defines.h>
 #include <px4_log.h>
 
 pthread_mutex_t px4_modules_mutex = PTHREAD_MUTEX_INITIALIZER;
@@ -88,7 +89,10 @@ void PRINT_MODULE_USAGE_PARAM_INT(char option_char, int default_val, int min_val
 {
 	if (is_optional) {
 		PX4_INFO_RAW("     [-%c <val>]  %s\n", option_char, description);
-		PX4_INFO_RAW("                 default: %i\n", default_val);
+
+		if (default_val != -1) {
+			PX4_INFO_RAW("                 default: %i\n", default_val);
+		}
 
 	} else {
 		PX4_INFO_RAW("     -%c <val>    %s\n", option_char, description);
@@ -100,7 +104,10 @@ void PRINT_MODULE_USAGE_PARAM_FLOAT(char option_char, float default_val, float m
 {
 	if (is_optional) {
 		PX4_INFO_RAW("     [-%c <val>]  %s\n", option_char, description);
-		PX4_INFO_RAW("                 default: %.1f\n", (double)default_val);
+
+		if (PX4_ISFINITE(default_val)) {
+			PX4_INFO_RAW("                 default: %.1f\n", (double)default_val);
+		}
 
 	} else {
 		PX4_INFO_RAW("     -%c <val>    %s\n", option_char, description);
diff --git a/src/platforms/px4_module.h b/src/platforms/px4_module.h
index 9bbc4006e17d7cb9d12af43f3db538ff33f74a6f..c3806da11019b2959bac5a8f03b4348065994aba 100644
--- a/src/platforms/px4_module.h
+++ b/src/platforms/px4_module.h
@@ -499,7 +499,7 @@ __EXPORT void PRINT_MODULE_USAGE_COMMAND_DESCR(const char *name, const char *des
 /**
  * @brief Prints an integer parameter.
  * @param option_char The option character.
- * @param default_val The parameter default value.
+ * @param default_val The parameter default value (set to -1 if not applicable).
  * @param min_val The parameter minimum value.
  * @param max_val The parameter value.
  * @param description Pointer to the usage description.
@@ -511,7 +511,7 @@ __EXPORT void PRINT_MODULE_USAGE_PARAM_INT(char option_char, int default_val, in
 /**
  * @brief Prints a float parameter.
  * @note See PRINT_MODULE_USAGE_PARAM_INT().
- * @param default_val The parameter default value.
+ * @param default_val The parameter default value (set to NaN if not applicable).
  * @param min_val The parameter minimum value.
  * @param max_val The parameter maximum value.
  * @param description Pointer to the usage description. Pointer to the usage description.
diff --git a/src/systemcmds/esc_calib/esc_calib.c b/src/systemcmds/esc_calib/esc_calib.c
index cdb135ac6e1fcdc78d6aa99e59156c1655c56c8c..72e37b6f67bdbe46407d7259cb997935fe283526 100644
--- a/src/systemcmds/esc_calib/esc_calib.c
+++ b/src/systemcmds/esc_calib/esc_calib.c
@@ -84,7 +84,7 @@ usage(const char *reason)
 	PRINT_MODULE_USAGE_PARAM_INT('h', 2000, 0, 3000, "High PWM value in us", true);
 	PRINT_MODULE_USAGE_PARAM_STRING('c', NULL, NULL, "select channels in the form: 1234 (1 digit per channel, 1=first)",
 					true);
-	PRINT_MODULE_USAGE_PARAM_INT('m', 0, 0, 4096, "Select channels via bitmask (eg. 0xF, 3)", true);
+	PRINT_MODULE_USAGE_PARAM_INT('m', -1, 0, 4096, "Select channels via bitmask (eg. 0xF, 3)", true);
 	PRINT_MODULE_USAGE_PARAM_FLAG('a', "Select all channels", true);
 }
 
diff --git a/src/systemcmds/pwm/pwm.cpp b/src/systemcmds/pwm/pwm.cpp
index 50b9fa3a6cb9176bc445a08f8199c1990424022c..f14b0f07e0900a6797ca7b7811c21f41b3491fd8 100644
--- a/src/systemcmds/pwm/pwm.cpp
+++ b/src/systemcmds/pwm/pwm.cpp
@@ -139,14 +139,14 @@ $ pwm test -c 13 -p 1200
 
 
 	PRINT_MODULE_USAGE_PARAM_COMMENT("The commands 'failsafe', 'disarmed', 'min', 'max' and 'test' require a PWM value:");
-	PRINT_MODULE_USAGE_PARAM_INT('p', 0, 0, 4000, "PWM value (eg. 1100)", false);
+	PRINT_MODULE_USAGE_PARAM_INT('p', -1, 0, 4000, "PWM value (eg. 1100)", false);
 
 	PRINT_MODULE_USAGE_PARAM_COMMENT("The commands 'rate', 'oneshot', 'failsafe', 'disarmed', 'min', 'max', 'test' and 'steps' "
 					 "additionally require to specify the channels with one of the following commands:");
 	PRINT_MODULE_USAGE_PARAM_STRING('c', nullptr, nullptr, "select channels in the form: 1234 (1 digit per channel, 1=first)",
 					true);
-	PRINT_MODULE_USAGE_PARAM_INT('m', 0, 0, 4096, "Select channels via bitmask (eg. 0xF, 3)", true);
-	PRINT_MODULE_USAGE_PARAM_INT('g', 0, 0, 10, "Select channels by group (eg. 0, 1, 2. use 'pwm info' to show groups)",
+	PRINT_MODULE_USAGE_PARAM_INT('m', -1, 0, 4096, "Select channels via bitmask (eg. 0xF, 3)", true);
+	PRINT_MODULE_USAGE_PARAM_INT('g', -1, 0, 10, "Select channels by group (eg. 0, 1, 2. use 'pwm info' to show groups)",
 				     true);
 	PRINT_MODULE_USAGE_PARAM_FLAG('a', "Select all channels", true);
 
diff --git a/src/systemcmds/tune_control/tune_control.cpp b/src/systemcmds/tune_control/tune_control.cpp
index b47dc61d7a395095cb66cf2576dd7e421d5003ff..2dd284fa473b6e9d4f48d66a75c0ddc3e5232718 100644
--- a/src/systemcmds/tune_control/tune_control.cpp
+++ b/src/systemcmds/tune_control/tune_control.cpp
@@ -87,9 +87,9 @@ $ tune_control play -t 2
 
 	PRINT_MODULE_USAGE_NAME("tune_control", "system");
 	PRINT_MODULE_USAGE_COMMAND_DESCR("play","Play system tune, tone, or melody");
-        PRINT_MODULE_USAGE_PARAM_INT('t', 1, 1, 21, "Play predefined system tune", true);
-        PRINT_MODULE_USAGE_PARAM_INT('f', 0, 0, 22, "Frequency of tone in Hz (0-22kHz)", true);
-	PRINT_MODULE_USAGE_PARAM_INT('d', 1, 1, 21, "Duration of tone in us", true);
+	PRINT_MODULE_USAGE_PARAM_INT('t', 1, 1, 21, "Play predefined system tune", true);
+	PRINT_MODULE_USAGE_PARAM_INT('f', -1, 0, 22, "Frequency of tone in Hz (0-22kHz)", true);
+	PRINT_MODULE_USAGE_PARAM_INT('d', -1, 1, 21, "Duration of tone in us", true);
 	PRINT_MODULE_USAGE_PARAM_INT('s', 40, 0, 100, "Strength of tone (0-100)", true);
 	PRINT_MODULE_USAGE_PARAM_STRING('m', nullptr,  R"(<string> - e.g. "MFT200e8a8a")",
 					 "Melody in string form", true);