From a475d71ca975c3343f56eb91412231486e014604 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sat, 2 Nov 2019 10:58:47 -0400 Subject: [PATCH] astyle shift module documentation to bottom of files - Astyle chokes on the module description strings, so for now we can keep them near the bottom of each file. --- src/drivers/dshot/dshot.cpp | 122 +++++++++--------- src/drivers/pwm_out_sim/PWMSim.cpp | 17 +-- src/drivers/px4fmu/fmu.cpp | 112 ++++++++-------- src/drivers/rc_input/RCInput.cpp | 67 +++++----- src/drivers/safety_button/SafetyButton.cpp | 21 ++- src/drivers/tap_esc/tap_esc.cpp | 4 +- .../frsky_telemetry/frsky_telemetry.cpp | 34 ++--- .../airspeed_selector_main.cpp | 31 ++--- src/modules/commander/Commander.cpp | 121 ++++++++++------- src/modules/ekf2/ekf2_main.cpp | 57 ++++---- src/modules/events/send_event.cpp | 61 ++++----- .../FixedwingAttitudeControl.cpp | 27 ++-- .../FixedwingPositionControl.cpp | 20 ++- src/modules/replay/Replay.cpp | 77 +++++------ .../vtol_att_control_main.cpp | 20 ++- src/systemcmds/dmesg/dmesg.cpp | 44 +++---- 16 files changed, 413 insertions(+), 422 deletions(-) diff --git a/src/drivers/dshot/dshot.cpp b/src/drivers/dshot/dshot.cpp index 8e91cf336315..fc28af3d2a22 100644 --- a/src/drivers/dshot/dshot.cpp +++ b/src/drivers/dshot/dshot.cpp @@ -1531,6 +1531,65 @@ int DShotOutput::custom_command(int argc, char *argv[]) return print_usage("unknown command"); } +int DShotOutput::print_status() +{ + const char *mode_str = nullptr; + + switch (_mode) { + + case MODE_NONE: mode_str = "no outputs"; break; + + case MODE_1PWM: mode_str = "outputs1"; break; + + case MODE_2PWM: mode_str = "outputs2"; break; + + case MODE_2PWM2CAP: mode_str = "outputs2cap2"; break; + + case MODE_3PWM: mode_str = "outputs3"; break; + + case MODE_3PWM1CAP: mode_str = "outputs3cap1"; break; + + case MODE_4PWM: mode_str = "outputs4"; break; + + case MODE_4PWM1CAP: mode_str = "outputs4cap1"; break; + + case MODE_4PWM2CAP: mode_str = "outputs4cap2"; break; + + case MODE_5PWM: mode_str = "outputs5"; break; + + case MODE_5PWM1CAP: mode_str = "outputs5cap1"; break; + + case MODE_6PWM: mode_str = "outputs6"; break; + + case MODE_8PWM: mode_str = "outputs8"; break; + + case MODE_4CAP: mode_str = "cap4"; break; + + case MODE_5CAP: mode_str = "cap5"; break; + + case MODE_6CAP: mode_str = "cap6"; break; + + default: + break; + } + + if (mode_str) { + PX4_INFO("Mode: %s", mode_str); + } + + PX4_INFO("Outputs initialized: %s", _outputs_initialized ? "yes" : "no"); + PX4_INFO("Outputs on: %s", _outputs_on ? "yes" : "no"); + perf_print_counter(_cycle_perf); + _mixing_output.printStatus(); + + if (_telemetry) { + PX4_INFO("telemetry on: %s", _telemetry_device); + _telemetry->handler.printStatus(); + } + + return 0; +} + int DShotOutput::print_usage(const char *reason) { if (reason) { @@ -1614,68 +1673,7 @@ After saving, the reversed direction will be regarded as the normal one. So to r return 0; } -int DShotOutput::print_status() -{ - const char *mode_str = nullptr; - - switch (_mode) { - - case MODE_NONE: mode_str = "no outputs"; break; - - case MODE_1PWM: mode_str = "outputs1"; break; - - case MODE_2PWM: mode_str = "outputs2"; break; - - case MODE_2PWM2CAP: mode_str = "outputs2cap2"; break; - - case MODE_3PWM: mode_str = "outputs3"; break; - - case MODE_3PWM1CAP: mode_str = "outputs3cap1"; break; - - case MODE_4PWM: mode_str = "outputs4"; break; - - case MODE_4PWM1CAP: mode_str = "outputs4cap1"; break; - - case MODE_4PWM2CAP: mode_str = "outputs4cap2"; break; - - case MODE_5PWM: mode_str = "outputs5"; break; - - case MODE_5PWM1CAP: mode_str = "outputs5cap1"; break; - - case MODE_6PWM: mode_str = "outputs6"; break; - - case MODE_8PWM: mode_str = "outputs8"; break; - - case MODE_4CAP: mode_str = "cap4"; break; - - case MODE_5CAP: mode_str = "cap5"; break; - - case MODE_6CAP: mode_str = "cap6"; break; - - default: - break; - } - - if (mode_str) { - PX4_INFO("Mode: %s", mode_str); - } - - PX4_INFO("Outputs initialized: %s", _outputs_initialized ? "yes" : "no"); - PX4_INFO("Outputs on: %s", _outputs_on ? "yes" : "no"); - perf_print_counter(_cycle_perf); - _mixing_output.printStatus(); - if (_telemetry) { - PX4_INFO("telemetry on: %s", _telemetry_device); - _telemetry->handler.printStatus(); - } - - return 0; -} - -extern "C" __EXPORT int dshot_main(int argc, char *argv[]); - -int -dshot_main(int argc, char *argv[]) +extern "C" __EXPORT int dshot_main(int argc, char *argv[]) { return DShotOutput::main(argc, argv); } diff --git a/src/drivers/pwm_out_sim/PWMSim.cpp b/src/drivers/pwm_out_sim/PWMSim.cpp index 2f780597208b..cb9acb84d214 100644 --- a/src/drivers/pwm_out_sim/PWMSim.cpp +++ b/src/drivers/pwm_out_sim/PWMSim.cpp @@ -39,8 +39,6 @@ #include #include -extern "C" __EXPORT int pwm_out_sim_main(int argc, char *argv[]); - PWMSim::PWMSim(bool hil_mode_enabled) : CDev(PWM_OUTPUT0_DEVICE_PATH), OutputModuleInterface(MODULE_NAME, px4::wq_configurations::hp_default) @@ -273,6 +271,12 @@ int PWMSim::custom_command(int argc, char *argv[]) return print_usage("unknown command"); } +int PWMSim::print_status() +{ + _mixing_output.printStatus(); + return 0; +} + int PWMSim::print_usage(const char *reason) { if (reason) { @@ -300,14 +304,7 @@ It is used in SITL and HITL. return 0; } -int PWMSim::print_status() -{ - _mixing_output.printStatus(); - return 0; -} - -int -pwm_out_sim_main(int argc, char *argv[]) +extern "C" __EXPORT int pwm_out_sim_main(int argc, char *argv[]) { return PWMSim::main(argc, argv); } diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp index 94bb6880014c..e025eb30d2c2 100644 --- a/src/drivers/px4fmu/fmu.cpp +++ b/src/drivers/px4fmu/fmu.cpp @@ -2173,6 +2173,59 @@ int PX4FMU::custom_command(int argc, char *argv[]) return print_usage("unknown command"); } +int PX4FMU::print_status() +{ + PX4_INFO("Max update rate: %i Hz", _current_update_rate); + + const char *mode_str = nullptr; + + switch (_mode) { + case MODE_NONE: mode_str = "no pwm"; break; + + case MODE_1PWM: mode_str = "pwm1"; break; + + case MODE_2PWM: mode_str = "pwm2"; break; + + case MODE_2PWM2CAP: mode_str = "pwm2cap2"; break; + + case MODE_3PWM: mode_str = "pwm3"; break; + + case MODE_3PWM1CAP: mode_str = "pwm3cap1"; break; + + case MODE_4PWM: mode_str = "pwm4"; break; + + case MODE_4PWM1CAP: mode_str = "pwm4cap1"; break; + + case MODE_4PWM2CAP: mode_str = "pwm4cap2"; break; + + case MODE_5PWM: mode_str = "pwm5"; break; + + case MODE_5PWM1CAP: mode_str = "pwm5cap1"; break; + + case MODE_6PWM: mode_str = "pwm6"; break; + + case MODE_8PWM: mode_str = "pwm8"; break; + + case MODE_4CAP: mode_str = "cap4"; break; + + case MODE_5CAP: mode_str = "cap5"; break; + + case MODE_6CAP: mode_str = "cap6"; break; + + default: + break; + } + + if (mode_str) { + PX4_INFO("PWM Mode: %s", mode_str); + } + + perf_print_counter(_cycle_perf); + _mixing_output.printStatus(); + + return 0; +} + int PX4FMU::print_usage(const char *reason) { if (reason) { @@ -2252,64 +2305,7 @@ mixer files. return 0; } -int PX4FMU::print_status() -{ - PX4_INFO("Max update rate: %i Hz", _current_update_rate); - - const char *mode_str = nullptr; - - switch (_mode) { - - case MODE_NONE: mode_str = "no pwm"; break; - - case MODE_1PWM: mode_str = "pwm1"; break; - - case MODE_2PWM: mode_str = "pwm2"; break; - - case MODE_2PWM2CAP: mode_str = "pwm2cap2"; break; - - case MODE_3PWM: mode_str = "pwm3"; break; - - case MODE_3PWM1CAP: mode_str = "pwm3cap1"; break; - - case MODE_4PWM: mode_str = "pwm4"; break; - - case MODE_4PWM1CAP: mode_str = "pwm4cap1"; break; - - case MODE_4PWM2CAP: mode_str = "pwm4cap2"; break; - - case MODE_5PWM: mode_str = "pwm5"; break; - - case MODE_5PWM1CAP: mode_str = "pwm5cap1"; break; - - case MODE_6PWM: mode_str = "pwm6"; break; - - case MODE_8PWM: mode_str = "pwm8"; break; - - case MODE_4CAP: mode_str = "cap4"; break; - - case MODE_5CAP: mode_str = "cap5"; break; - - case MODE_6CAP: mode_str = "cap6"; break; - - default: - break; - } - - if (mode_str) { - PX4_INFO("PWM Mode: %s", mode_str); - } - - perf_print_counter(_cycle_perf); - _mixing_output.printStatus(); - - return 0; -} - -extern "C" __EXPORT int fmu_main(int argc, char *argv[]); - -int -fmu_main(int argc, char *argv[]) +extern "C" __EXPORT int fmu_main(int argc, char *argv[]) { return PX4FMU::main(argc, argv); } diff --git a/src/drivers/rc_input/RCInput.cpp b/src/drivers/rc_input/RCInput.cpp index 208d25fd26e7..5821c60cbdee 100644 --- a/src/drivers/rc_input/RCInput.cpp +++ b/src/drivers/rc_input/RCInput.cpp @@ -768,7 +768,38 @@ int RCInput::custom_command(int argc, char *argv[]) return print_usage("unknown command"); } -int RCInput::print_usage(const char *reason) +int RCInput::print_status() +{ + PX4_INFO("Running %s", (_run_as_task ? "as task" : "on work queue")); + + if (!_run_as_task) { + PX4_INFO("Max update rate: %i Hz", 1000000 / _current_update_interval); + } + + if (_device[0] != '\0') { + PX4_INFO("Serial device: %s", _device); + } + + PX4_INFO("RC scan state: %s, locked: %s", RC_SCAN_STRING[_rc_scan_state], _rc_scan_locked ? "yes" : "no"); + PX4_INFO("CRSF Telemetry: %s", _crsf_telemetry ? "yes" : "no"); + PX4_INFO("SBUS frame drops: %u", sbus_dropped_frames()); + +#if ADC_RC_RSSI_CHANNEL + PX4_INFO("vrssi: %dmV", (int)(_analog_rc_rssi_volt * 1000.0f)); +#endif + + perf_print_counter(_cycle_perf); + perf_print_counter(_publish_interval_perf); + + if (hrt_elapsed_time(&_rc_in.timestamp) < 1_s) { + print_message(_rc_in); + } + + return 0; +} + +int +RCInput::print_usage(const char *reason) { if (reason) { PX4_WARN("%s\n", reason); @@ -805,39 +836,7 @@ When running on the work queue, it schedules at a fixed frequency. return 0; } -int RCInput::print_status() -{ - PX4_INFO("Running %s", (_run_as_task ? "as task" : "on work queue")); - - if (!_run_as_task) { - PX4_INFO("Max update rate: %i Hz", 1000000 / _current_update_interval); - } - if (_device[0] != '\0') { - PX4_INFO("Serial device: %s", _device); - } - - PX4_INFO("RC scan state: %s, locked: %s", RC_SCAN_STRING[_rc_scan_state], _rc_scan_locked ? "yes" : "no"); - PX4_INFO("CRSF Telemetry: %s", _crsf_telemetry ? "yes" : "no"); - PX4_INFO("SBUS frame drops: %u", sbus_dropped_frames()); - -#if ADC_RC_RSSI_CHANNEL - PX4_INFO("vrssi: %dmV", (int)(_analog_rc_rssi_volt * 1000.0f)); -#endif - - perf_print_counter(_cycle_perf); - perf_print_counter(_publish_interval_perf); - - if (hrt_elapsed_time(&_rc_in.timestamp) < 1_s) { - print_message(_rc_in); - } - - return 0; -} - -extern "C" __EXPORT int rc_input_main(int argc, char *argv[]); - -int -rc_input_main(int argc, char *argv[]) +extern "C" __EXPORT int rc_input_main(int argc, char *argv[]) { return RCInput::main(argc, argv); } diff --git a/src/drivers/safety_button/SafetyButton.cpp b/src/drivers/safety_button/SafetyButton.cpp index 2d1a2a202ed3..f62970eb7974 100644 --- a/src/drivers/safety_button/SafetyButton.cpp +++ b/src/drivers/safety_button/SafetyButton.cpp @@ -199,6 +199,14 @@ SafetyButton::custom_command(int argc, char *argv[]) return print_usage("unknown command"); } +int +SafetyButton::print_status() +{ + PX4_INFO("Safety State (from button): %s", _safety_btn_off ? "off" : "on"); + + return 0; +} + int SafetyButton::print_usage(const char *reason) { @@ -219,18 +227,7 @@ This module is responsible for the safety button. return 0; } -int -SafetyButton::print_status() -{ - PX4_INFO("Safety State (from button): %s", _safety_btn_off ? "off" : "on"); - - return 0; -} - -extern "C" __EXPORT int safety_button_main(int argc, char *argv[]); - -int -safety_button_main(int argc, char *argv[]) +extern "C" __EXPORT int safety_button_main(int argc, char *argv[]) { return SafetyButton::main(argc, argv); } diff --git a/src/drivers/tap_esc/tap_esc.cpp b/src/drivers/tap_esc/tap_esc.cpp index 20bc73a066ca..fe7fa136f933 100644 --- a/src/drivers/tap_esc/tap_esc.cpp +++ b/src/drivers/tap_esc/tap_esc.cpp @@ -778,9 +778,7 @@ tap_esc start -d /dev/ttyS2 -n <1-8> return PX4_OK; } -extern "C" __EXPORT int tap_esc_main(int argc, char *argv[]); - -int tap_esc_main(int argc, char *argv[]) +extern "C" __EXPORT int tap_esc_main(int argc, char *argv[]) { return TAP_ESC::main(argc, argv); } diff --git a/src/drivers/telemetry/frsky_telemetry/frsky_telemetry.cpp b/src/drivers/telemetry/frsky_telemetry/frsky_telemetry.cpp index 92dcaa6fe752..aa2a6c9275fb 100644 --- a/src/drivers/telemetry/frsky_telemetry/frsky_telemetry.cpp +++ b/src/drivers/telemetry/frsky_telemetry/frsky_telemetry.cpp @@ -207,23 +207,6 @@ static void set_uart_single_wire(int uart, bool single_wire) } } -/** - * Print command usage information - */ -static void usage() -{ - PRINT_MODULE_DESCRIPTION("FrSky Telemetry support. Auto-detects D or S.PORT protocol."); - - PRINT_MODULE_USAGE_NAME("frsky_telemetry", "communication"); - PRINT_MODULE_USAGE_COMMAND("start"); - PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/ttyS6", "", "Select Serial Device", true); - PRINT_MODULE_USAGE_PARAM_INT('t', 0, 0, 60, "Scanning timeout [s] (default: no timeout)", true); - PRINT_MODULE_USAGE_PARAM_STRING('m', "auto", "sport|sport_single|dtype", "Select protocol (default: auto-detect)", - true); - PRINT_MODULE_USAGE_COMMAND("stop"); - PRINT_MODULE_USAGE_COMMAND("status"); -} - /** * The daemon thread. */ @@ -806,3 +789,20 @@ int frsky_telemetry_main(int argc, char *argv[]) usage(); return 0; } + +/** + * Print command usage information + */ +static void usage() +{ + PRINT_MODULE_DESCRIPTION("FrSky Telemetry support. Auto-detects D or S.PORT protocol."); + + PRINT_MODULE_USAGE_NAME("frsky_telemetry", "communication"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/ttyS6", "", "Select Serial Device", true); + PRINT_MODULE_USAGE_PARAM_INT('t', 0, 0, 60, "Scanning timeout [s] (default: no timeout)", true); + PRINT_MODULE_USAGE_PARAM_STRING('m', "auto", "sport|sport_single|dtype", "Select protocol (default: auto-detect)", + true); + PRINT_MODULE_USAGE_COMMAND("stop"); + PRINT_MODULE_USAGE_COMMAND("status"); +} diff --git a/src/modules/airspeed_selector/airspeed_selector_main.cpp b/src/modules/airspeed_selector/airspeed_selector_main.cpp index e92b94193292..80ca4b1a6d0b 100644 --- a/src/modules/airspeed_selector/airspeed_selector_main.cpp +++ b/src/modules/airspeed_selector/airspeed_selector_main.cpp @@ -536,6 +536,19 @@ int AirspeedModule::custom_command(int argc, char *argv[]) return print_usage("unknown command"); } +int AirspeedModule::print_status() +{ + perf_print_counter(_perf_elapsed); + + int instance = 0; + uORB::SubscriptionData est{ORB_ID(airspeed_validated), (uint8_t)instance}; + est.update(); + PX4_INFO("Number of airspeed sensors: %i", _number_of_airspeed_sensors); + print_message(est.get()); + + return 0; +} + int AirspeedModule::print_usage(const char *reason) { if (reason) { @@ -562,23 +575,7 @@ and also publishes those. return 0; } -int AirspeedModule::print_status() -{ - perf_print_counter(_perf_elapsed); - - int instance = 0; - uORB::SubscriptionData est{ORB_ID(airspeed_validated), (uint8_t)instance}; - est.update(); - PX4_INFO("Number of airspeed sensors: %i", _number_of_airspeed_sensors); - print_message(est.get()); - - return 0; -} - -extern "C" __EXPORT int airspeed_selector_main(int argc, char *argv[]); - -int -airspeed_selector_main(int argc, char *argv[]) +extern "C" __EXPORT int airspeed_selector_main(int argc, char *argv[]) { return AirspeedModule::main(argc, argv); } diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 00f5accdf526..7a36d63307d3 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -514,38 +514,6 @@ int commander_main(int argc, char *argv[]) return 1; } -void usage(const char *reason) -{ - if (reason) { - PX4_INFO("%s", reason); - } - - PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -The commander module contains the state machine for mode switching and failsafe behavior. -)DESCR_STR"); - - PRINT_MODULE_USAGE_NAME("commander", "system"); - PRINT_MODULE_USAGE_COMMAND("start"); - PRINT_MODULE_USAGE_PARAM_FLAG('h', "Enable HIL mode", true); - PRINT_MODULE_USAGE_COMMAND_DESCR("calibrate", "Run sensor calibration"); - PRINT_MODULE_USAGE_ARG("mag|accel|gyro|level|esc|airspeed", "Calibration type", false); - PRINT_MODULE_USAGE_COMMAND_DESCR("check", "Run preflight checks"); - PRINT_MODULE_USAGE_COMMAND("arm"); - PRINT_MODULE_USAGE_PARAM_FLAG('f', "Force arming (do not run preflight checks)", true); - PRINT_MODULE_USAGE_COMMAND("disarm"); - PRINT_MODULE_USAGE_COMMAND("takeoff"); - PRINT_MODULE_USAGE_COMMAND("land"); - PRINT_MODULE_USAGE_COMMAND_DESCR("transition", "VTOL transition"); - PRINT_MODULE_USAGE_COMMAND_DESCR("mode", "Change flight mode"); - PRINT_MODULE_USAGE_ARG("manual|acro|offboard|stabilized|rattitude|altctl|posctl|auto:mission|auto:loiter|auto:rtl|auto:takeoff|auto:land|auto:precland", - "Flight mode", false); - PRINT_MODULE_USAGE_COMMAND("lockdown"); - PRINT_MODULE_USAGE_ARG("off", "Turn lockdown off", true); - PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); -} - void print_status() { PX4_INFO("arming: %s", arming_state_names[status.arming_state]); @@ -812,6 +780,7 @@ Commander::handle_command(vehicle_status_s *status_local, const vehicle_command_ if (cmd_arms) { if (armed_local->armed) { mavlink_log_warning(&mavlink_log_pub, "Arming denied! Already armed"); + } else { mavlink_log_critical(&mavlink_log_pub, "Arming denied! Not landed"); } @@ -841,18 +810,18 @@ Commander::handle_command(vehicle_status_s *status_local, const vehicle_command_ const bool throttle_above_center = (sp_man.z > 0.6f); if (cmd_arms && throttle_above_center && - (status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_POSCTL || - status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_ALTCTL)) { + (status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_POSCTL || + status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_ALTCTL)) { mavlink_log_critical(&mavlink_log_pub, "Arming denied! Throttle not centered"); cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_DENIED; break; } if (cmd_arms && throttle_above_low && - (status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_MANUAL || - status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_ACRO || - status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_STAB || - status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_RATTITUDE)) { + (status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_MANUAL || + status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_ACRO || + status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_STAB || + status_local->nav_state == vehicle_status_s::NAVIGATION_STATE_RATTITUDE)) { mavlink_log_critical(&mavlink_log_pub, "Arming denied! Throttle not zero"); cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_DENIED; break; @@ -1090,12 +1059,16 @@ Commander::handle_command(vehicle_status_s *status_local, const vehicle_command_ break; case vehicle_command_s::VEHICLE_CMD_DO_ORBIT: + // Switch to orbit state and let the orbit task handle the command further - if (TRANSITION_DENIED != main_state_transition(*status_local, commander_state_s::MAIN_STATE_ORBIT, status_flags, &internal_state)) { + if (TRANSITION_DENIED != main_state_transition(*status_local, commander_state_s::MAIN_STATE_ORBIT, status_flags, + &internal_state)) { cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED; + } else { cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED; } + break; case vehicle_command_s::VEHICLE_CMD_DO_MOTOR_TEST: @@ -1166,24 +1139,32 @@ Commander::handle_command_motor_test(const vehicle_command_s &cmd) test_motor.timestamp = hrt_absolute_time(); test_motor.motor_number = (int)(cmd.param1 + 0.5f) - 1; int throttle_type = (int)(cmd.param2 + 0.5f); + if (throttle_type != 0) { // 0: MOTOR_TEST_THROTTLE_PERCENT return vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED; } - int motor_count = (int) (cmd.param5 + 0.5); + + int motor_count = (int)(cmd.param5 + 0.5); + if (motor_count > 1) { return vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED; } + test_motor.action = test_motor_s::ACTION_RUN; test_motor.value = math::constrain(cmd.param3 / 100.f, 0.f, 1.f); + if (test_motor.value < FLT_EPSILON) { // the message spec is not clear on whether 0 means stop, but it should be closer to what a user expects test_motor.value = -1.f; } + test_motor.timeout_ms = (int)(cmd.param4 * 1000.f + 0.5f); + // enforce a timeout and a maximum limit if (test_motor.timeout_ms == 0 || test_motor.timeout_ms > 3000) { test_motor.timeout_ms = 3000; } + test_motor.driver_instance = 0; // the mavlink command does not allow to specify the instance, so set to 0 for now _test_motor_pub.publish(test_motor); @@ -1799,6 +1780,7 @@ Commander::run() /* update subsystem info which arrives from outside of commander*/ subsystem_info_s info; + while (subsys_sub.update(&info)) { set_health_flags(info.subsystem_type, info.present, info.enabled, info.ok, status); status_changed = true; @@ -2411,6 +2393,7 @@ Commander::run() /* safety switch is not present, do not go into prearmed */ armed.prearmed = false; } + break; default: @@ -2526,13 +2509,20 @@ Commander::run() void Commander::get_circuit_breaker_params() { - status_flags.circuit_breaker_engaged_power_check = circuit_breaker_enabled_by_val(_param_cbrk_supply_chk.get(), CBRK_SUPPLY_CHK_KEY); - status_flags.circuit_breaker_engaged_usb_check = circuit_breaker_enabled_by_val(_param_cbrk_usb_chk.get(), CBRK_USB_CHK_KEY); - status_flags.circuit_breaker_engaged_airspd_check = circuit_breaker_enabled_by_val(_param_cbrk_airspd_chk.get(), CBRK_AIRSPD_CHK_KEY); - status_flags.circuit_breaker_engaged_enginefailure_check = circuit_breaker_enabled_by_val(_param_cbrk_enginefail.get(), CBRK_ENGINEFAIL_KEY); - status_flags.circuit_breaker_engaged_gpsfailure_check = circuit_breaker_enabled_by_val(_param_cbrk_gpsfail.get(), CBRK_GPSFAIL_KEY); - status_flags.circuit_breaker_flight_termination_disabled = circuit_breaker_enabled_by_val(_param_cbrk_flightterm.get(), CBRK_FLIGHTTERM_KEY); - status_flags.circuit_breaker_engaged_posfailure_check = circuit_breaker_enabled_by_val(_param_cbrk_velposerr.get(), CBRK_VELPOSERR_KEY); + status_flags.circuit_breaker_engaged_power_check = circuit_breaker_enabled_by_val(_param_cbrk_supply_chk.get(), + CBRK_SUPPLY_CHK_KEY); + status_flags.circuit_breaker_engaged_usb_check = circuit_breaker_enabled_by_val(_param_cbrk_usb_chk.get(), + CBRK_USB_CHK_KEY); + status_flags.circuit_breaker_engaged_airspd_check = circuit_breaker_enabled_by_val(_param_cbrk_airspd_chk.get(), + CBRK_AIRSPD_CHK_KEY); + status_flags.circuit_breaker_engaged_enginefailure_check = circuit_breaker_enabled_by_val(_param_cbrk_enginefail.get(), + CBRK_ENGINEFAIL_KEY); + status_flags.circuit_breaker_engaged_gpsfailure_check = circuit_breaker_enabled_by_val(_param_cbrk_gpsfail.get(), + CBRK_GPSFAIL_KEY); + status_flags.circuit_breaker_flight_termination_disabled = circuit_breaker_enabled_by_val(_param_cbrk_flightterm.get(), + CBRK_FLIGHTTERM_KEY); + status_flags.circuit_breaker_engaged_posfailure_check = circuit_breaker_enabled_by_val(_param_cbrk_velposerr.get(), + CBRK_VELPOSERR_KEY); } void @@ -2697,7 +2687,8 @@ Commander::set_main_state(const vehicle_status_s &status_local, bool *changed) transition_result_t Commander::set_main_state_override_on(const vehicle_status_s &status_local, bool *changed) { - const transition_result_t res = main_state_transition(status_local, commander_state_s::MAIN_STATE_MANUAL, status_flags, &internal_state); + const transition_result_t res = main_state_transition(status_local, commander_state_s::MAIN_STATE_MANUAL, status_flags, + &internal_state); *changed = (res == TRANSITION_CHANGED); return res; @@ -3767,7 +3758,7 @@ bool Commander::preflight_check(bool report) const bool checkGNSS = (arm_requirements & ARM_REQ_GPS_BIT); const bool success = Preflight::preflightCheck(&mavlink_log_pub, status, status_flags, checkGNSS, report, false, - hrt_elapsed_time(&commander_boot_timestamp)); + hrt_elapsed_time(&commander_boot_timestamp)); if (success) { status_flags.condition_system_sensors_initialized = true; @@ -4497,3 +4488,35 @@ void Commander::esc_status_check(const esc_status_s &esc_status) status_flags.condition_escs_error = true; } } + +void usage(const char *reason) +{ + if (reason) { + PX4_INFO("%s", reason); + } + + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description +The commander module contains the state machine for mode switching and failsafe behavior. +)DESCR_STR"); + + PRINT_MODULE_USAGE_NAME("commander", "system"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_PARAM_FLAG('h', "Enable HIL mode", true); + PRINT_MODULE_USAGE_COMMAND_DESCR("calibrate", "Run sensor calibration"); + PRINT_MODULE_USAGE_ARG("mag|accel|gyro|level|esc|airspeed", "Calibration type", false); + PRINT_MODULE_USAGE_COMMAND_DESCR("check", "Run preflight checks"); + PRINT_MODULE_USAGE_COMMAND("arm"); + PRINT_MODULE_USAGE_PARAM_FLAG('f', "Force arming (do not run preflight checks)", true); + PRINT_MODULE_USAGE_COMMAND("disarm"); + PRINT_MODULE_USAGE_COMMAND("takeoff"); + PRINT_MODULE_USAGE_COMMAND("land"); + PRINT_MODULE_USAGE_COMMAND_DESCR("transition", "VTOL transition"); + PRINT_MODULE_USAGE_COMMAND_DESCR("mode", "Change flight mode"); + PRINT_MODULE_USAGE_ARG("manual|acro|offboard|stabilized|rattitude|altctl|posctl|auto:mission|auto:loiter|auto:rtl|auto:takeoff|auto:land|auto:precland", + "Flight mode", false); + PRINT_MODULE_USAGE_COMMAND("lockdown"); + PRINT_MODULE_USAGE_ARG("off", "Turn lockdown off", true); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); +} diff --git a/src/modules/ekf2/ekf2_main.cpp b/src/modules/ekf2/ekf2_main.cpp index 7340cffc8279..da3f9ee31976 100644 --- a/src/modules/ekf2/ekf2_main.cpp +++ b/src/modules/ekf2/ekf2_main.cpp @@ -92,8 +92,6 @@ using math::constrain; using namespace time_literals; -extern "C" __EXPORT int ekf2_main(int argc, char *argv[]); - class Ekf2 final : public ModuleBase, public ModuleParams, public px4::WorkItem { public: @@ -2368,35 +2366,10 @@ int Ekf2::custom_command(int argc, char *argv[]) return print_usage("unknown command"); } -int Ekf2::print_usage(const char *reason) -{ - if (reason) { - PX4_WARN("%s\n", reason); - } - - PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Attitude and position estimator using an Extended Kalman Filter. It is used for Multirotors and Fixed-Wing. - -The documentation can be found on the [ECL/EKF Overview & Tuning](https://docs.px4.io/en/advanced_config/tuning_the_ecl_ekf.html) page. - -ekf2 can be started in replay mode (`-r`): in this mode it does not access the system time, but only uses the -timestamps from the sensor topics. - -)DESCR_STR"); - - PRINT_MODULE_USAGE_NAME("ekf2", "estimator"); - PRINT_MODULE_USAGE_COMMAND("start"); - PRINT_MODULE_USAGE_PARAM_FLAG('r', "Enable replay mode", true); - PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); - - return 0; -} - int Ekf2::task_spawn(int argc, char *argv[]) { bool replay_mode = false; + if (argc > 1 && !strcmp(argv[1], "-r")) { PX4_INFO("replay mode enabled"); replay_mode = true; @@ -2423,7 +2396,33 @@ int Ekf2::task_spawn(int argc, char *argv[]) return PX4_ERROR; } -int ekf2_main(int argc, char *argv[]) +int Ekf2::print_usage(const char *reason) +{ + if (reason) { + PX4_WARN("%s\n", reason); + } + + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description +Attitude and position estimator using an Extended Kalman Filter. It is used for Multirotors and Fixed-Wing. + +The documentation can be found on the [ECL/EKF Overview & Tuning](https://docs.px4.io/en/advanced_config/tuning_the_ecl_ekf.html) page. + +ekf2 can be started in replay mode (`-r`): in this mode it does not access the system time, but only uses the +timestamps from the sensor topics. + +)DESCR_STR"); + + PRINT_MODULE_USAGE_NAME("ekf2", "estimator"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_PARAM_FLAG('r', "Enable replay mode", true); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); + + return 0; +} + +extern "C" __EXPORT int ekf2_main(int argc, char *argv[]) { return Ekf2::main(argc, argv); } diff --git a/src/modules/events/send_event.cpp b/src/modules/events/send_event.cpp index 4cd7cdcee268..ae92b5cbf4f7 100644 --- a/src/modules/events/send_event.cpp +++ b/src/modules/events/send_event.cpp @@ -201,32 +201,6 @@ void SendEvent::answer_command(const vehicle_command_s &cmd, unsigned result) command_ack_pub.publish(command_ack); } -int SendEvent::print_usage(const char *reason) -{ - if (reason) { - printf("%s\n\n", reason); - } - - PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Background process running periodically on the LP work queue to perform housekeeping tasks. -It is currently only responsible for temperature calibration and tone alarm on RC Loss. - -The tasks can be started via CLI or uORB topics (vehicle_command from MAVLink, etc.). -)DESCR_STR"); - - PRINT_MODULE_USAGE_NAME("send_event", "system"); - PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start the background task"); - PRINT_MODULE_USAGE_COMMAND_DESCR("temperature_calibration", "Run temperature calibration process"); - PRINT_MODULE_USAGE_PARAM_FLAG('g', "calibrate the gyro", true); - PRINT_MODULE_USAGE_PARAM_FLAG('a', "calibrate the accel", true); - PRINT_MODULE_USAGE_PARAM_FLAG('b', "calibrate the baro (if none of these is given, all will be calibrated)", true); - PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); - - return 0; -} - int SendEvent::custom_command(int argc, char *argv[]) { if (!strcmp(argv[0], "temperature_calibration")) { @@ -267,13 +241,16 @@ int SendEvent::custom_command(int argc, char *argv[]) vehicle_command_s vcmd{}; vcmd.timestamp = hrt_absolute_time(); - vcmd.param1 = (float)((gyro_calib || calib_all) ? vehicle_command_s::PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION : NAN); + vcmd.param1 = (float)((gyro_calib + || calib_all) ? vehicle_command_s::PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION : NAN); vcmd.param2 = NAN; vcmd.param3 = NAN; vcmd.param4 = NAN; - vcmd.param5 = ((accel_calib || calib_all) ? vehicle_command_s::PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION : (double)NAN); + vcmd.param5 = ((accel_calib + || calib_all) ? vehicle_command_s::PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION : (double)NAN); vcmd.param6 = (double)NAN; - vcmd.param7 = (float)((baro_calib || calib_all) ? vehicle_command_s::PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION : NAN); + vcmd.param7 = (float)((baro_calib + || calib_all) ? vehicle_command_s::PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION : NAN); vcmd.command = vehicle_command_s::VEHICLE_CMD_PREFLIGHT_CALIBRATION; uORB::PublicationQueued vcmd_pub{ORB_ID(vehicle_command)}; @@ -286,6 +263,32 @@ int SendEvent::custom_command(int argc, char *argv[]) return 0; } +int SendEvent::print_usage(const char *reason) +{ + if (reason) { + printf("%s\n\n", reason); + } + + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description +Background process running periodically on the LP work queue to perform housekeeping tasks. +It is currently only responsible for temperature calibration and tone alarm on RC Loss. + +The tasks can be started via CLI or uORB topics (vehicle_command from MAVLink, etc.). +)DESCR_STR"); + + PRINT_MODULE_USAGE_NAME("send_event", "system"); + PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start the background task"); + PRINT_MODULE_USAGE_COMMAND_DESCR("temperature_calibration", "Run temperature calibration process"); + PRINT_MODULE_USAGE_PARAM_FLAG('g', "calibrate the gyro", true); + PRINT_MODULE_USAGE_PARAM_FLAG('a', "calibrate the accel", true); + PRINT_MODULE_USAGE_PARAM_FLAG('b', "calibrate the baro (if none of these is given, all will be calibrated)", true); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); + + return 0; +} + int send_event_main(int argc, char *argv[]) { return SendEvent::main(argc, argv); diff --git a/src/modules/fw_att_control/FixedwingAttitudeControl.cpp b/src/modules/fw_att_control/FixedwingAttitudeControl.cpp index c9900687aa43..eea6df7fdab5 100644 --- a/src/modules/fw_att_control/FixedwingAttitudeControl.cpp +++ b/src/modules/fw_att_control/FixedwingAttitudeControl.cpp @@ -40,13 +40,6 @@ using math::constrain; using math::gradual; using math::radians; -/** - * Fixedwing attitude control app start / stop handling function - * - * @ingroup apps - */ -extern "C" __EXPORT int fw_att_control_main(int argc, char *argv[]); - FixedwingAttitudeControl::FixedwingAttitudeControl() : ModuleParams(nullptr), WorkItem(MODULE_NAME, px4::wq_configurations::att_pos_ctrl), @@ -762,6 +755,13 @@ int FixedwingAttitudeControl::custom_command(int argc, char *argv[]) return print_usage("unknown command"); } +int FixedwingAttitudeControl::print_status() +{ + PX4_INFO("Running"); + perf_print_counter(_loop_perf); + return 0; +} + int FixedwingAttitudeControl::print_usage(const char *reason) { if (reason) { @@ -776,24 +776,13 @@ fw_att_control is the fixed wing attitude controller. )DESCR_STR"); PRINT_MODULE_USAGE_COMMAND("start"); - PRINT_MODULE_USAGE_NAME("fw_att_control", "controller"); - PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); return 0; } -int FixedwingAttitudeControl::print_status() -{ - PX4_INFO("Running"); - - perf_print_counter(_loop_perf); - - return 0; -} - -int fw_att_control_main(int argc, char *argv[]) +extern "C" __EXPORT int fw_att_control_main(int argc, char *argv[]) { return FixedwingAttitudeControl::main(argc, argv); } diff --git a/src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp b/src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp index 3fab8715e5d1..a644ca50bfb0 100644 --- a/src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp @@ -33,8 +33,6 @@ #include "FixedwingPositionControl.hpp" -extern "C" __EXPORT int fw_pos_control_l1_main(int argc, char *argv[]); - FixedwingPositionControl::FixedwingPositionControl() : ModuleParams(nullptr), WorkItem(MODULE_NAME, px4::wq_configurations::att_pos_ctrl), @@ -1972,6 +1970,13 @@ int FixedwingPositionControl::custom_command(int argc, char *argv[]) return print_usage("unknown command"); } +int FixedwingPositionControl::print_status() +{ + PX4_INFO("Running"); + perf_print_counter(_loop_perf); + return 0; +} + int FixedwingPositionControl::print_usage(const char *reason) { if (reason) { @@ -1993,16 +1998,7 @@ fw_pos_control_l1 is the fixed wing position controller. return 0; } -int FixedwingPositionControl::print_status() -{ - PX4_INFO("Running"); - - perf_print_counter(_loop_perf); - - return 0; -} - -int fw_pos_control_l1_main(int argc, char *argv[]) +extern "C" __EXPORT int fw_pos_control_l1_main(int argc, char *argv[]) { return FixedwingPositionControl::main(argc, argv); } diff --git a/src/modules/replay/Replay.cpp b/src/modules/replay/Replay.cpp index 0759f6dd230a..3039dc7a4c0c 100644 --- a/src/modules/replay/Replay.cpp +++ b/src/modules/replay/Replay.cpp @@ -953,50 +953,15 @@ Replay::custom_command(int argc, char *argv[]) return print_usage("unknown command"); } -int -Replay::print_usage(const char *reason) -{ - if (reason) { - PX4_WARN("%s\n", reason); - } - - PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This module is used to replay ULog files. - -There are 2 environment variables used for configuration: `replay`, which must be set to an ULog file name - it's -the log file to be replayed. The second is the mode, specified via `replay_mode`: -- `replay_mode=ekf2`: specific EKF2 replay mode. It can only be used with the ekf2 module, but allows the replay - to run as fast as possible. -- Generic otherwise: this can be used to replay any module(s), but the replay will be done with the same speed as the - log was recorded. - -The module is typically used together with uORB publisher rules, to specify which messages should be replayed. -The replay module will just publish all messages that are found in the log. It also applies the parameters from -the log. - -The replay procedure is documented on the [System-wide Replay](https://dev.px4.io/en/debug/system_wide_replay.html) -page. -)DESCR_STR"); - - PRINT_MODULE_USAGE_NAME("replay", "system"); - PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start replay, using log file from ENV variable 'replay'"); - PRINT_MODULE_USAGE_COMMAND_DESCR("trystart", "Same as 'start', but silently exit if no log file given"); - PRINT_MODULE_USAGE_COMMAND_DESCR("tryapplyparams", "Try to apply the parameters from the log file"); - PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); - - return 0; -} - int Replay::task_spawn(int argc, char *argv[]) { // check if a log file was found if (!isSetup()) { - if (argc > 0 && strncmp(argv[0], "try", 3)==0) { + if (argc > 0 && strncmp(argv[0], "try", 3) == 0) { return 0; } + PX4_ERR("no log file given (via env variable %s)", replay::ENV_FILENAME); return -1; } @@ -1023,6 +988,7 @@ Replay::applyParams(bool quiet) if (quiet) { return 0; } + PX4_ERR("no log file given (via env variable %s)", replay::ENV_FILENAME); return -1; } @@ -1053,6 +1019,7 @@ Replay::instantiate(int argc, char *argv[]) const char *replay_mode = getenv(replay::ENV_MODE); Replay *instance = nullptr; + if (replay_mode && strcmp(replay_mode, "ekf2") == 0) { PX4_INFO("Ekf2 replay mode"); instance = new ReplayEkf2(); @@ -1064,4 +1031,40 @@ Replay::instantiate(int argc, char *argv[]) return instance; } +int +Replay::print_usage(const char *reason) +{ + if (reason) { + PX4_WARN("%s\n", reason); + } + + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description +This module is used to replay ULog files. + +There are 2 environment variables used for configuration: `replay`, which must be set to an ULog file name - it's +the log file to be replayed. The second is the mode, specified via `replay_mode`: +- `replay_mode=ekf2`: specific EKF2 replay mode. It can only be used with the ekf2 module, but allows the replay + to run as fast as possible. +- Generic otherwise: this can be used to replay any module(s), but the replay will be done with the same speed as the + log was recorded. + +The module is typically used together with uORB publisher rules, to specify which messages should be replayed. +The replay module will just publish all messages that are found in the log. It also applies the parameters from +the log. + +The replay procedure is documented on the [System-wide Replay](https://dev.px4.io/en/debug/system_wide_replay.html) +page. +)DESCR_STR"); + + PRINT_MODULE_USAGE_NAME("replay", "system"); + PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start replay, using log file from ENV variable 'replay'"); + PRINT_MODULE_USAGE_COMMAND_DESCR("trystart", "Same as 'start', but silently exit if no log file given"); + PRINT_MODULE_USAGE_COMMAND_DESCR("tryapplyparams", "Try to apply the parameters from the log file"); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); + + return 0; +} + } //namespace px4 diff --git a/src/modules/vtol_att_control/vtol_att_control_main.cpp b/src/modules/vtol_att_control/vtol_att_control_main.cpp index 0478e1316841..1ab69de96829 100644 --- a/src/modules/vtol_att_control/vtol_att_control_main.cpp +++ b/src/modules/vtol_att_control/vtol_att_control_main.cpp @@ -477,6 +477,14 @@ VtolAttitudeControl::custom_command(int argc, char *argv[]) return print_usage("unknown command"); } +int +VtolAttitudeControl::print_status() +{ + PX4_INFO("Running"); + perf_print_counter(_loop_perf); + return PX4_OK; +} + int VtolAttitudeControl::print_usage(const char *reason) { @@ -491,24 +499,12 @@ fw_att_control is the fixed wing attitude controller. )DESCR_STR"); PRINT_MODULE_USAGE_COMMAND("start"); - PRINT_MODULE_USAGE_NAME("vtol_att_control", "controller"); - PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); return 0; } -int -VtolAttitudeControl::print_status() -{ - PX4_INFO("Running"); - - perf_print_counter(_loop_perf); - - return PX4_OK; -} - int vtol_att_control_main(int argc, char *argv[]) { return VtolAttitudeControl::main(argc, argv); diff --git a/src/systemcmds/dmesg/dmesg.cpp b/src/systemcmds/dmesg/dmesg.cpp index 89cb51a67b23..44e416f19b14 100644 --- a/src/systemcmds/dmesg/dmesg.cpp +++ b/src/systemcmds/dmesg/dmesg.cpp @@ -46,28 +46,6 @@ extern "C" { __EXPORT int dmesg_main(int argc, char *argv[]); } -static void -usage() -{ - - PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -Command-line tool to show bootup console messages. -Note that output from NuttX's work queues and syslog are not captured. - -### Examples - -Keep printing all messages in the background: -$ dmesg -f & -)DESCR_STR"); - - PRINT_MODULE_USAGE_NAME("dmesg", "system"); - PRINT_MODULE_USAGE_PARAM_FLAG('f', "Follow: wait for new messages", true); - -} - int dmesg_main(int argc, char *argv[]) { @@ -93,3 +71,25 @@ dmesg_main(int argc, char *argv[]) return 0; } + +static void +usage() +{ + + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description + +Command-line tool to show bootup console messages. +Note that output from NuttX's work queues and syslog are not captured. + +### Examples + +Keep printing all messages in the background: +$ dmesg -f & +)DESCR_STR"); + + PRINT_MODULE_USAGE_NAME("dmesg", "system"); + PRINT_MODULE_USAGE_PARAM_FLAG('f', "Follow: wait for new messages", true); + +}