diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index f180b82387d4..b0220fd9c931 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -2879,7 +2879,7 @@ Mavlink::stream_command(int argc, char *argv[]) if (0 == strcmp(argv[i], "-r") && i < argc - 1) { rate = strtod(argv[i + 1], nullptr); - if (rate < 0.0f) { + if (rate < -2.5f) { err_flag = true; } @@ -2935,10 +2935,6 @@ Mavlink::stream_command(int argc, char *argv[]) return 1; } - if (rate < 0.0f) { - rate = -2.0f; // use default rate - } - if (inst != nullptr) { inst->configure_stream_threadsafe(stream_name, rate); @@ -3054,7 +3050,7 @@ Start mavlink on UDP port 14556 and enable the HIGHRES_IMU message with 50Hz: #endif PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, "", "Select Mavlink instance via Serial Device", true); PRINT_MODULE_USAGE_PARAM_STRING('s', nullptr, nullptr, "Mavlink stream to configure", false); - PRINT_MODULE_USAGE_PARAM_FLOAT('r', -1.0f, 0.0f, 2000.0f, "Rate in Hz (0 = turn off, -1 = set to default)", false); + PRINT_MODULE_USAGE_PARAM_FLOAT('r', -1.0f, 0.0f, 2000.0f, "Rate in Hz (0 = turn off, -1 = default, -2 = unlimited rate)", false); PRINT_MODULE_USAGE_COMMAND_DESCR("boot_complete", "Enable sending of messages. (Must be) called as last step in startup script.");