From 6349ba16401eac01bd7537b4b87a76830de66990 Mon Sep 17 00:00:00 2001 From: bazooka joe Date: Sat, 18 Jan 2025 16:38:19 +0200 Subject: [PATCH] astyle: removed raw string literal from PRINT_MODULE_DESCRIPTION() so astlye will work --- Tools/px4moduledoc/srcparser.py | 3 +- .../emlid/navio2/navio_rgbled/NavioRGBLed.cpp | 7 +- .../src/drivers/ghst_rc/ghst_rc.cpp | 7 +- .../VoxlSaveCalParams.cpp | 7 +- src/drivers/actuators/voxl_esc/voxl_esc.cpp | 84 +-- src/drivers/adc/ads1115/ads1115_main.cpp | 27 +- src/drivers/adc/board_adc/ADC.cpp | 7 +- src/drivers/batt_smbus/batt_smbus.cpp | 90 +-- src/drivers/camera_trigger/camera_trigger.cpp | 68 +-- .../cdcacm_autostart/cdcacm_autostart.cpp | 12 +- .../asp5033/asp5033_main.cpp | 16 +- .../broadcom/afbrs50/AFBRS50.cpp | 22 +- .../leddar_one/leddar_one_main.cpp | 30 +- .../lightware_laser_i2c.cpp | 12 +- .../lightware_laser_serial_main.cpp | 30 +- .../lightware_sf45_serial_main.cpp | 24 +- src/drivers/distance_sensor/ll40ls/ll40ls.cpp | 16 +- .../distance_sensor/ll40ls_pwm/ll40ls.cpp | 22 +- src/drivers/distance_sensor/pga460/pga460.cpp | 64 +- src/drivers/distance_sensor/srf05/SRF05.cpp | 13 +- .../teraranger/teraranger_main.cpp | 16 +- .../distance_sensor/tfmini/tfmini_main.cpp | 40 +- .../ulanding_radar/ulanding_radar_main.cpp | 26 +- src/drivers/dshot/DShot.cpp | 36 +- src/drivers/gnss/septentrio/septentrio.cpp | 571 ++++++++++-------- src/drivers/gps/gps.cpp | 62 +- src/drivers/heater/heater.cpp | 10 +- src/drivers/hygrometer/sht3x/sht3x.cpp | 37 +- src/drivers/ins/vectornav/VectorNav.cpp | 30 +- src/drivers/lights/neopixel/neopixel.cpp | 101 ++-- .../lights/rgbled_lp5562/rgbled_lp5562.cpp | 14 +- src/drivers/linux_pwm_out/linux_pwm_out.cpp | 6 +- .../optical_flow/thoneflow/thoneflow.cpp | 128 ++-- src/drivers/osd/atxxxx/atxxxx.cpp | 10 +- src/drivers/osd/msp_osd/msp_osd.cpp | 21 +- src/drivers/pca9685_pwm_out/main.cpp | 236 ++++---- .../power_monitor/ina220/ina220_main.cpp | 28 +- .../power_monitor/ina226/ina226_main.cpp | 26 +- .../power_monitor/ina228/ina228_main.cpp | 26 +- .../power_monitor/ina238/ina238_main.cpp | 26 +- .../PowerMonitorSelectorAuterion.cpp | 7 +- src/drivers/pps_capture/PPSCapture.cpp | 7 +- src/drivers/pwm_input/pwm_input.cpp | 7 +- src/drivers/pwm_out/PWMOut.cpp | 11 +- src/drivers/px4io/px4io.cpp | 7 +- src/drivers/rc/crsf_rc/CrsfRc.cpp | 7 +- src/drivers/rc/dsm_rc/DsmRc.cpp | 7 +- src/drivers/rc/ghst_rc/GhstRc.cpp | 7 +- src/drivers/rc/sbus_rc/SbusRc.cpp | 7 +- src/drivers/rc_input/RCInput.cpp | 19 +- src/drivers/roboclaw/Roboclaw.cpp | 31 +- src/drivers/safety_button/SafetyButton.cpp | 9 +- src/drivers/smart_battery/batmon/batmon.cpp | 46 +- src/drivers/tap_esc/TAP_ESC.cpp | 34 +- src/drivers/tattu_can/TattuCan.cpp | 7 +- .../telemetry/iridiumsbd/IridiumSBD.cpp | 10 +- src/drivers/tone_alarm/ToneAlarm.cpp | 7 +- .../transponder/sagetech_mxs/SagetechMXS.cpp | 36 +- src/drivers/voxl2_io/voxl2_io.cpp | 16 +- .../ft_technologies/ft7_technologies_main.cpp | 28 +- src/examples/fake_gps/FakeGps.cpp | 5 +- src/examples/fake_imu/FakeImu.cpp | 5 +- .../fake_magnetometer/FakeMagnetometer.cpp | 8 +- src/examples/work_item/WorkItemExample.cpp | 7 +- .../airship_att_control_main.cpp | 21 +- .../airspeed_selector_main.cpp | 19 +- .../attitude_estimator_q_main.cpp | 7 +- src/modules/battery_status/battery_status.cpp | 19 +- .../camera_feedback/CameraFeedback.cpp | 45 +- src/modules/commander/Commander.cpp | 8 +- .../control_allocator/ControlAllocator.cpp | 8 +- src/modules/dataman/dataman.cpp | 37 +- src/modules/ekf2/EKF2.cpp | 27 +- src/modules/esc_battery/EscBattery.cpp | 7 +- src/modules/events/send_event.cpp | 12 +- .../flight_mode_manager/FlightModeManager.cpp | 9 +- .../FixedwingAttitudeControl.cpp | 7 +- .../fw_autotune_attitude_control.cpp | 5 +- .../FixedwingPositionControl.cpp | 7 +- .../fw_rate_control/FixedwingRateControl.cpp | 7 +- src/modules/gimbal/gimbal.cpp | 26 +- .../gyro_calibration/GyroCalibration.cpp | 7 +- src/modules/gyro_fft/GyroFFT.cpp | 5 +- .../land_detector/land_detector_main.cpp | 46 +- src/modules/load_mon/LoadMon.cpp | 14 +- .../BlockLocalPositionEstimator.cpp | 7 +- src/modules/logger/logger.cpp | 66 +- .../mag_bias_estimator/MagBiasEstimator.cpp | 6 +- src/modules/manual_control/ManualControl.cpp | 82 ++- src/modules/mavlink/mavlink_main.cpp | 63 +- .../mc_att_control/mc_att_control_main.cpp | 27 +- .../mc_autotune_attitude_control.cpp | 5 +- .../MulticopterHoverThrustEstimator.cpp | 5 +- .../MulticopterPositionControl.cpp | 16 +- .../MulticopterRateControl.cpp | 13 +- src/modules/navigator/navigator_main.cpp | 25 +- .../payload_deliverer/payload_deliverer.cpp | 9 +- src/modules/rc_update/rc_update.cpp | 17 +- src/modules/replay/Replay.cpp | 34 +- .../rover_ackermann/RoverAckermann.cpp | 6 +- .../rover_differential/RoverDifferential.cpp | 6 +- src/modules/rover_mecanum/RoverMecanum.cpp | 6 +- .../RoverPositionControl.cpp | 37 +- src/modules/sensors/sensors.cpp | 35 +- .../battery_simulator/BatterySimulator.cpp | 6 +- src/modules/simulation/gz_bridge/GZBridge.cpp | 5 +- src/modules/simulation/pwm_out_sim/PWMSim.cpp | 19 +- .../sensor_agp_sim/SensorAgpSim.cpp | 7 +- .../sensor_airspeed_sim/SensorAirspeedSim.cpp | 6 +- .../sensor_baro_sim/SensorBaroSim.cpp | 6 +- .../sensor_gps_sim/SensorGpsSim.cpp | 6 +- .../sensor_mag_sim/SensorMagSim.cpp | 6 +- src/modules/simulation/simulator_sih/sih.cpp | 44 +- .../SystemPowerSimulator.cpp | 6 +- .../TemperatureCompensationModule.cpp | 18 +- src/modules/time_persistor/TimePersistor.cpp | 11 +- .../uuv_att_control/uuv_att_control.cpp | 35 +- .../uuv_pos_control/uuv_pos_control.cpp | 40 +- .../uxrce_dds_client/uxrce_dds_client.cpp | 17 +- .../vtol_att_control_main.cpp | 6 +- .../actuator_test/actuator_test.cpp | 23 +- src/systemcmds/dmesg/dmesg.cpp | 20 +- src/systemcmds/failure/failure.cpp | 29 +- src/systemcmds/gpio/gpio.cpp | 35 +- src/systemcmds/i2c_launcher/i2c_launcher.cpp | 9 +- src/systemcmds/led_control/led_control.cpp | 27 +- src/systemcmds/netman/netman.cpp | 60 +- src/systemcmds/param/param.cpp | 62 +- src/systemcmds/system_time/system_time.cpp | 20 +- .../topic_listener/listener_main.cpp | 8 +- src/systemcmds/tune_control/tune_control.cpp | 30 +- src/systemcmds/uorb/uorb.cpp | 36 +- src/systemcmds/work_queue/work_queue_main.cpp | 9 +- .../template_module/template_module.cpp | 25 +- 134 files changed, 1835 insertions(+), 1950 deletions(-) diff --git a/Tools/px4moduledoc/srcparser.py b/Tools/px4moduledoc/srcparser.py index 4937f67b7ebf..00ccfe6c9c5d 100644 --- a/Tools/px4moduledoc/srcparser.py +++ b/Tools/px4moduledoc/srcparser.py @@ -260,8 +260,7 @@ def documentation(self): # convert '$ cmd' commands into code blocks (e.g. '$ logger start') # use lookahead (?=...) so the multiple consecutive command lines work - doc_string = re.sub(r"\n\$ (.*)(?=\n)", r"\n```\n\1\n```", doc_string) - # now merge consecutive blocks + doc_string = re.sub(r"(?m)^\$ (.*)", r"```\n\1\n```", doc_string) doc_string = re.sub(r"\n```\n```\n", r"\n", doc_string) return doc_string diff --git a/boards/emlid/navio2/navio_rgbled/NavioRGBLed.cpp b/boards/emlid/navio2/navio_rgbled/NavioRGBLed.cpp index 4cc8213537b5..ce84c0fc6c24 100644 --- a/boards/emlid/navio2/navio_rgbled/NavioRGBLed.cpp +++ b/boards/emlid/navio2/navio_rgbled/NavioRGBLed.cpp @@ -155,11 +155,8 @@ int NavioRGBLed::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Emlid Navio2 RGB LED driver. - -)DESCR_STR"); + "### Description\n" + "Emlid Navio2 RGB LED driver."); PRINT_MODULE_USAGE_NAME("navio_rgbled", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/boards/modalai/voxl2-slpi/src/drivers/ghst_rc/ghst_rc.cpp b/boards/modalai/voxl2-slpi/src/drivers/ghst_rc/ghst_rc.cpp index e213179922ad..86fe52e32699 100644 --- a/boards/modalai/voxl2-slpi/src/drivers/ghst_rc/ghst_rc.cpp +++ b/boards/modalai/voxl2-slpi/src/drivers/ghst_rc/ghst_rc.cpp @@ -291,11 +291,8 @@ int GhstRc::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This module parses the GHST RC uplink protocol and can generate GHST downlink telemetry data - -)DESCR_STR"); + "### Description\n" + "This module parses the GHST RC uplink protocol and can generate GHST downlink telemetry data"); PRINT_MODULE_USAGE_NAME("ghst_rc", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/boards/modalai/voxl2/src/modules/voxl_save_cal_params/VoxlSaveCalParams.cpp b/boards/modalai/voxl2/src/modules/voxl_save_cal_params/VoxlSaveCalParams.cpp index 5c8717db267e..ec0f20030e7d 100644 --- a/boards/modalai/voxl2/src/modules/voxl_save_cal_params/VoxlSaveCalParams.cpp +++ b/boards/modalai/voxl2/src/modules/voxl_save_cal_params/VoxlSaveCalParams.cpp @@ -216,11 +216,8 @@ int VoxlSaveCalParams::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This implements autosaving of calibration parameters on VOXL2 platform. - -)DESCR_STR"); + "### Description\n" + "This implements autosaving of calibration parameters on VOXL2 platform."); PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); diff --git a/src/drivers/actuators/voxl_esc/voxl_esc.cpp b/src/drivers/actuators/voxl_esc/voxl_esc.cpp index f5568d7eebc7..53d5b13dae6e 100644 --- a/src/drivers/actuators/voxl_esc/voxl_esc.cpp +++ b/src/drivers/actuators/voxl_esc/voxl_esc.cpp @@ -1469,18 +1469,15 @@ int VoxlEsc::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This module is responsible for... - -### Implementation -By default the module runs on a work queue with a callback on the uORB actuator_controls topic. - -### Examples -It is typically started with: -$ todo - -)DESCR_STR"); + "### Description\n" + "This module is responsible for...\n" + "\n" + "### Implementation\n" + "By default the module runs on a work queue with a callback on the uORB actuator_controls topic.\n" + "\n" + "### Examples\n" + "It is typically started with:\n" + "$ todo"); PRINT_MODULE_USAGE_NAME("voxl_esc", "driver"); PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start the task"); @@ -1497,14 +1494,16 @@ It is typically started with: PRINT_MODULE_USAGE_COMMAND_DESCR("rpm", "Closed-Loop RPM test control request"); PRINT_MODULE_USAGE_PARAM_INT('i', 0, 0, 3, "ESC ID, 0-3", false); PRINT_MODULE_USAGE_PARAM_INT('r', 0, -32768, 32768, "RPM, -32,768 to 32,768", false); - PRINT_MODULE_USAGE_PARAM_INT('n', 100, 0, 1<<31, "Command repeat count, 0 to INT_MAX", false); - PRINT_MODULE_USAGE_PARAM_INT('t', 10000, 0, 1<<31, "Delay between repeated commands (microseconds), 0 to INT_MAX", false); + PRINT_MODULE_USAGE_PARAM_INT('n', 100, 0, 1 << 31, "Command repeat count, 0 to INT_MAX", false); + PRINT_MODULE_USAGE_PARAM_INT('t', 10000, 0, 1 << 31, "Delay between repeated commands (microseconds), 0 to INT_MAX", + false); PRINT_MODULE_USAGE_COMMAND_DESCR("pwm", "Open-Loop PWM test control request"); PRINT_MODULE_USAGE_PARAM_INT('i', 0, 0, 3, "ESC ID, 0-3", false); PRINT_MODULE_USAGE_PARAM_INT('r', 0, 0, 800, "Duty Cycle value, 0 to 800", false); - PRINT_MODULE_USAGE_PARAM_INT('n', 100, 0, 1<<31, "Command repeat count, 0 to INT_MAX", false); - PRINT_MODULE_USAGE_PARAM_INT('t', 10000, 0, 1<<31, "Delay between repeated commands (microseconds), 0 to INT_MAX", false); + PRINT_MODULE_USAGE_PARAM_INT('n', 100, 0, 1 << 31, "Command repeat count, 0 to INT_MAX", false); + PRINT_MODULE_USAGE_PARAM_INT('t', 10000, 0, 1 << 31, "Delay between repeated commands (microseconds), 0 to INT_MAX", + false); PRINT_MODULE_USAGE_COMMAND_DESCR("tone", "Send tone generation request to ESC"); PRINT_MODULE_USAGE_PARAM_INT('i', 0, 0, 3, "ESC ID, 0-3", false); @@ -1513,7 +1512,8 @@ It is typically started with: PRINT_MODULE_USAGE_PARAM_INT('v', 0, 0, 100, "Power (volume) of sound, 0-100", false); PRINT_MODULE_USAGE_COMMAND_DESCR("led", "Send LED control request"); - PRINT_MODULE_USAGE_PARAM_INT('l', 0, 0, 4095, "Bitmask 0x0FFF (12 bits) - ESC0 (RGB) ESC1 (RGB) ESC2 (RGB) ESC3 (RGB)", false); + PRINT_MODULE_USAGE_PARAM_INT('l', 0, 0, 4095, "Bitmask 0x0FFF (12 bits) - ESC0 (RGB) ESC1 (RGB) ESC2 (RGB) ESC3 (RGB)", + false); PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); @@ -1542,12 +1542,12 @@ void VoxlEsc::print_params() PX4_INFO("Params: VOXL_ESC_T_PERC: %" PRId32, _parameters.turtle_motor_percent); PX4_INFO("Params: VOXL_ESC_T_DEAD: %" PRId32, _parameters.turtle_motor_deadband); PX4_INFO("Params: VOXL_ESC_T_EXPO: %" PRId32, _parameters.turtle_motor_expo); - PX4_INFO("Params: VOXL_ESC_T_MINF: %f", (double)_parameters.turtle_stick_minf); - PX4_INFO("Params: VOXL_ESC_T_COSP: %f", (double)_parameters.turtle_cosphi); + PX4_INFO("Params: VOXL_ESC_T_MINF: %f", (double)_parameters.turtle_stick_minf); + PX4_INFO("Params: VOXL_ESC_T_COSP: %f", (double)_parameters.turtle_cosphi); PX4_INFO("Params: VOXL_ESC_VLOG: %" PRId32, _parameters.verbose_logging); PX4_INFO("Params: VOXL_ESC_PUB_BST: %" PRId32, _parameters.publish_battery_status); - + PX4_INFO("Params: VOXL_ESC_T_WARN: %" PRId32, _parameters.esc_warn_temp_threshold); PX4_INFO("Params: VOXL_ESC_T_OVER: %" PRId32, _parameters.esc_over_temp_threshold); } @@ -1563,7 +1563,7 @@ int VoxlEsc::print_status() print_params(); PX4_INFO(""); - for( int i = 0; i < VOXL_ESC_OUTPUT_CHANNELS; i++){ + for (int i = 0; i < VOXL_ESC_OUTPUT_CHANNELS; i++) { PX4_INFO("-- ID: %i", i); PX4_INFO(" Motor: %i", _output_map[i].number); PX4_INFO(" Direction: %i", _output_map[i].direction); @@ -1583,22 +1583,34 @@ int VoxlEsc::print_status() return 0; } -const char * VoxlEsc::board_id_to_name(int board_id) +const char *VoxlEsc::board_id_to_name(int board_id) { - switch(board_id){ - case 31: return "ModalAi 4-in-1 ESC V2 RevB (M0049)"; - case 32: return "Blheli32 4-in-1 ESC Type A (Tmotor F55A PRO F051)"; - case 33: return "Blheli32 4-in-1 ESC Type B (Tmotor F55A PRO G071)"; - case 34: return "ModalAi 4-in-1 ESC (M0117-1)"; - case 35: return "ModalAi I/O Expander (M0065)"; - case 36: return "ModalAi 4-in-1 ESC (M0117-3)"; - case 37: return "ModalAi 4-in-1 ESC (M0134-1)"; - case 38: return "ModalAi 4-in-1 ESC (M0134-3)"; - case 39: return "ModalAi 4-in-1 ESC (M0129-1)"; - case 40: return "ModalAi 4-in-1 ESC (M0129-3)"; - case 41: return "ModalAi 4-in-1 ESC (M0134-6)"; - case 42: return "ModalAi 4-in-1 ESC (M0138-1)"; - default: return "Unknown Board"; + switch (board_id) { + case 31: return "ModalAi 4-in-1 ESC V2 RevB (M0049)"; + + case 32: return "Blheli32 4-in-1 ESC Type A (Tmotor F55A PRO F051)"; + + case 33: return "Blheli32 4-in-1 ESC Type B (Tmotor F55A PRO G071)"; + + case 34: return "ModalAi 4-in-1 ESC (M0117-1)"; + + case 35: return "ModalAi I/O Expander (M0065)"; + + case 36: return "ModalAi 4-in-1 ESC (M0117-3)"; + + case 37: return "ModalAi 4-in-1 ESC (M0134-1)"; + + case 38: return "ModalAi 4-in-1 ESC (M0134-3)"; + + case 39: return "ModalAi 4-in-1 ESC (M0129-1)"; + + case 40: return "ModalAi 4-in-1 ESC (M0129-3)"; + + case 41: return "ModalAi 4-in-1 ESC (M0134-6)"; + + case 42: return "ModalAi 4-in-1 ESC (M0138-1)"; + + default: return "Unknown Board"; } } diff --git a/src/drivers/adc/ads1115/ads1115_main.cpp b/src/drivers/adc/ads1115/ads1115_main.cpp index 2132082c666b..ebfe78092211 100644 --- a/src/drivers/adc/ads1115/ads1115_main.cpp +++ b/src/drivers/adc/ads1115/ads1115_main.cpp @@ -136,22 +136,19 @@ void ADS1115::print_usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description + "### Description\n" + "\n" + "Driver to enable an external [ADS1115](https://www.adafruit.com/product/1085) ADC connected via I2C.\n" + "\n" + "The driver is included by default in firmware for boards that do not have an internal analog to digital converter,\n" + "such as [PilotPi](../flight_controller/raspberry_pi_pilotpi.md) or [CUAV Nora](../flight_controller/cuav_nora.md)\n" + "(search for `CONFIG_DRIVERS_ADC_ADS1115` in board configuration files).\n" + "\n" + "It is enabled/disabled using the\n" + "[ADC_ADS1115_EN](../advanced_config/parameter_reference.md#ADC_ADS1115_EN)\n" + "parameter, and is disabled by default.\n" + "If enabled, internal ADCs are not used."); -Driver to enable an external [ADS1115](https://www.adafruit.com/product/1085) ADC connected via I2C. - -The driver is included by default in firmware for boards that do not have an internal analog to digital converter, -such as [PilotPi](../flight_controller/raspberry_pi_pilotpi.md) or [CUAV Nora](../flight_controller/cuav_nora.md) -(search for `CONFIG_DRIVERS_ADC_ADS1115` in board configuration files). - -It is enabled/disabled using the -[ADC_ADS1115_EN](../advanced_config/parameter_reference.md#ADC_ADS1115_EN) -parameter, and is disabled by default. -If enabled, internal ADCs are not used. - -)DESCR_STR"); - PRINT_MODULE_USAGE_NAME("ads1115", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false); diff --git a/src/drivers/adc/board_adc/ADC.cpp b/src/drivers/adc/board_adc/ADC.cpp index 7bf553f9b418..977780a0a547 100644 --- a/src/drivers/adc/board_adc/ADC.cpp +++ b/src/drivers/adc/board_adc/ADC.cpp @@ -403,11 +403,8 @@ int ADC::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -ADC driver. - -)DESCR_STR"); + "### Description\n" + "ADC driver."); PRINT_MODULE_USAGE_NAME("adc", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/batt_smbus/batt_smbus.cpp b/src/drivers/batt_smbus/batt_smbus.cpp index b9059f5445d6..7503a20fe4ce 100644 --- a/src/drivers/batt_smbus/batt_smbus.cpp +++ b/src/drivers/batt_smbus/batt_smbus.cpp @@ -510,15 +510,12 @@ int BATT_SMBUS::lifetime_read_block_one() void BATT_SMBUS::print_usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Smart battery driver for the BQ40Z50 fuel gauge IC. - -### Examples -To write to flash to set parameters. address, number_of_bytes, byte0, ... , byteN -$ batt_smbus -X write_flash 19069 2 27 0 - -)DESCR_STR"); + "### Description\n" + "Smart battery driver for the BQ40Z50 fuel gauge IC.\n" + "\n" + "### Examples\n" + "To write to flash to set parameters. address, number_of_bytes, byte0, ... , byteN\n" + "$ batt_smbus -X write_flash 19069 2 27 0"); PRINT_MODULE_USAGE_NAME("batt_smbus", "driver"); @@ -532,7 +529,8 @@ To write to flash to set parameters. address, number_of_bytes, byte0, ... , byte PRINT_MODULE_USAGE_COMMAND_DESCR("suspend", "Suspends the driver from rescheduling the cycle."); PRINT_MODULE_USAGE_COMMAND_DESCR("resume", "Resumes the driver from suspension."); - PRINT_MODULE_USAGE_COMMAND_DESCR("write_flash", "Writes to flash. The device must first be unsealed with the unseal command."); + PRINT_MODULE_USAGE_COMMAND_DESCR("write_flash", + "Writes to flash. The device must first be unsealed with the unseal command."); PRINT_MODULE_USAGE_ARG("address", "The address to start writing.", true); PRINT_MODULE_USAGE_ARG("number of bytes", "Number of bytes to send.", true); PRINT_MODULE_USAGE_ARG("data[0]...data[n]", "One byte of data at a time separated by spaces.", true); @@ -542,10 +540,12 @@ To write to flash to set parameters. address, number_of_bytes, byte0, ... , byte I2CSPIDriverBase *BATT_SMBUS::instantiate(const I2CSPIDriverConfig &config, int runtime_instance) { SMBus *interface = new SMBus(DRV_BAT_DEVTYPE_SMBUS, config.bus, config.i2c_address); + if (interface == nullptr) { PX4_ERR("alloc failed"); return nullptr; } + BATT_SMBUS *instance = new BATT_SMBUS(config, interface); if (instance == nullptr) { @@ -568,37 +568,44 @@ I2CSPIDriverBase *BATT_SMBUS::instantiate(const I2CSPIDriverConfig &config, int void BATT_SMBUS::custom_method(const BusCLIArguments &cli) { - switch(cli.custom1) { - case 1: { + switch (cli.custom1) { + case 1: { PX4_INFO("The manufacturer name: %s", _manufacturer_name); PX4_INFO("The manufacturer date: %" PRId16, _manufacture_date); PX4_INFO("The serial number: %d" PRId16, _serial_number); } - break; - case 2: - unseal(); - break; - case 3: - seal(); - break; - case 4: - suspend(); - break; - case 5: - resume(); - break; - case 6: - if (cli.custom_data) { - unsigned address = cli.custom2; - uint8_t *tx_buf = (uint8_t*)cli.custom_data; - unsigned length = tx_buf[0]; - - if (PX4_OK != dataflash_write(address, tx_buf+1, length)) { - PX4_ERR("Dataflash write failed: %u", address); - } - px4_usleep(100_ms); + break; + + case 2: + unseal(); + break; + + case 3: + seal(); + break; + + case 4: + suspend(); + break; + + case 5: + resume(); + break; + + case 6: + if (cli.custom_data) { + unsigned address = cli.custom2; + uint8_t *tx_buf = (uint8_t *)cli.custom_data; + unsigned length = tx_buf[0]; + + if (PX4_OK != dataflash_write(address, tx_buf + 1, length)) { + PX4_ERR("Dataflash write failed: %u", address); } - break; + + px4_usleep(100_ms); + } + + break; } } @@ -610,6 +617,7 @@ extern "C" __EXPORT int batt_smbus_main(int argc, char *argv[]) cli.i2c_address = BATT_SMBUS_ADDR; const char *verb = cli.parseDefaultArguments(argc, argv); + if (!verb) { ThisDriver::print_usage(); return -1; @@ -633,24 +641,30 @@ extern "C" __EXPORT int batt_smbus_main(int argc, char *argv[]) cli.custom1 = 1; return ThisDriver::module_custom_method(cli, iterator, false); } + if (!strcmp(verb, "unseal")) { cli.custom1 = 2; return ThisDriver::module_custom_method(cli, iterator); } + if (!strcmp(verb, "seal")) { cli.custom1 = 3; return ThisDriver::module_custom_method(cli, iterator); } + if (!strcmp(verb, "suspend")) { cli.custom1 = 4; return ThisDriver::module_custom_method(cli, iterator); } + if (!strcmp(verb, "resume")) { cli.custom1 = 5; return ThisDriver::module_custom_method(cli, iterator); } + if (!strcmp(verb, "write_flash")) { cli.custom1 = 6; + if (argc >= 3) { uint16_t address = atoi(argv[1]); unsigned length = atoi(argv[2]); @@ -663,12 +677,14 @@ extern "C" __EXPORT int batt_smbus_main(int argc, char *argv[]) } tx_buf[0] = length; + // Data needs to be fed in 1 byte (0x01) at a time. for (unsigned i = 0; i < length; i++) { if ((unsigned)argc <= 3 + i) { - tx_buf[i+1] = atoi(argv[3 + i]); + tx_buf[i + 1] = atoi(argv[3 + i]); } } + cli.custom2 = address; return ThisDriver::module_custom_method(cli, iterator); } diff --git a/src/drivers/camera_trigger/camera_trigger.cpp b/src/drivers/camera_trigger/camera_trigger.cpp index 33d89f3c0166..cf6ac5c1fe20 100644 --- a/src/drivers/camera_trigger/camera_trigger.cpp +++ b/src/drivers/camera_trigger/camera_trigger.cpp @@ -926,44 +926,42 @@ CameraTrigger::status() static int usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -Camera trigger driver. - -This module triggers cameras that are connected to the flight-controller outputs, -or simple MAVLink cameras that implement the MAVLink trigger protocol. - -The driver responds to the following MAVLink trigger commands being found in missions or recieved over MAVLink: - -- `MAV_CMD_DO_TRIGGER_CONTROL` -- `MAV_CMD_DO_DIGICAM_CONTROL` -- `MAV_CMD_DO_SET_CAM_TRIGG_DIST` -- `MAV_CMD_OBLIQUE_SURVEY` - -The commands cause the driver to trigger camera image capture based on time or distance. -Each time an image capture is triggered, the `CAMERA_TRIGGER` MAVLink message is emitted. - -A "simple MAVLink camera" is one that supports the above command set. -When configured for this kind of camera, all the driver does is emit the `CAMERA_TRIGGER` MAVLink message as expected. -The incoming commands must be forwarded to the MAVLink camera, and are automatically emitted to MAVLink channels -when found in missions. - -The driver is configured using [Camera Trigger parameters](../advanced_config/parameter_reference.md#camera-trigger). -In particular: - -- `TRIG_INTERFACE` - How the camera is connected to flight controller (PWM, GPIO, Seagull, MAVLink) -- `TRIG_MODE` - Distance or time based triggering, with values set by `TRIG_DISTANCE` and `TRIG_INTERVAL`. - -[Setup/usage information](../camera/index.md). -)DESCR_STR"); + "### Description\n" + "\n" + "Camera trigger driver.\n" + "\n" + "This module triggers cameras that are connected to the flight-controller outputs,\n" + "or simple MAVLink cameras that implement the MAVLink trigger protocol.\n" + "\n" + "The driver responds to the following MAVLink trigger commands being found in missions or recieved over MAVLink:\n" + "\n" + "- `MAV_CMD_DO_TRIGGER_CONTROL`\n" + "- `MAV_CMD_DO_DIGICAM_CONTROL`\n" + "- `MAV_CMD_DO_SET_CAM_TRIGG_DIST`\n" + "- `MAV_CMD_OBLIQUE_SURVEY`\n" + "\n" + "The commands cause the driver to trigger camera image capture based on time or distance.\n" + "Each time an image capture is triggered, the `CAMERA_TRIGGER` MAVLink message is emitted.\n" + "\n" + "A 'simple MAVLink camera' is one that supports the above command set.\n" + "When configured for this kind of camera, all the driver does is emit the `CAMERA_TRIGGER` MAVLink message as expected.\n" + "The incoming commands must be forwarded to the MAVLink camera, and are automatically emitted to MAVLink channels\n" + "when found in missions.\n" + "\n" + "The driver is configured using [Camera Trigger parameters](../advanced_config/parameter_reference.md#camera-trigger).\n" + "In particular:\n" + "\n" + "- `TRIG_INTERFACE` - How the camera is connected to flight controller (PWM, GPIO, Seagull, MAVLink)\n" + "- `TRIG_MODE` - Distance or time based triggering, with values set by `TRIG_DISTANCE` and `TRIG_INTERVAL`.\n" + "\n" + "[Setup/usage information](../camera/index.md)."); PRINT_MODULE_USAGE_NAME("camera_trigger", "driver"); PRINT_MODULE_USAGE_SUBCATEGORY("camera"); PRINT_MODULE_USAGE_COMMAND("start"); - PRINT_MODULE_USAGE_COMMAND_DESCR("stop","Stop driver"); - PRINT_MODULE_USAGE_COMMAND_DESCR("status","Print driver status information"); - PRINT_MODULE_USAGE_COMMAND_DESCR("test","Trigger one image (not logged or forwarded to GCS)"); - PRINT_MODULE_USAGE_COMMAND_DESCR("test_power","Toggle power"); + PRINT_MODULE_USAGE_COMMAND_DESCR("stop", "Stop driver"); + PRINT_MODULE_USAGE_COMMAND_DESCR("status", "Print driver status information"); + PRINT_MODULE_USAGE_COMMAND_DESCR("test", "Trigger one image (not logged or forwarded to GCS)"); + PRINT_MODULE_USAGE_COMMAND_DESCR("test_power", "Toggle power"); return 1; } diff --git a/src/drivers/cdcacm_autostart/cdcacm_autostart.cpp b/src/drivers/cdcacm_autostart/cdcacm_autostart.cpp index d86788ff7fa6..1bea7e16c91e 100644 --- a/src/drivers/cdcacm_autostart/cdcacm_autostart.cpp +++ b/src/drivers/cdcacm_autostart/cdcacm_autostart.cpp @@ -640,13 +640,11 @@ int CdcAcmAutostart::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This module listens on USB and auto-configures the protocol depending on the bytes received. -The supported protocols are: MAVLink, nsh, and ublox serial passthrough. If the parameter SYS_USB_AUTO=2 -the module will only try to start mavlink as long as the USB VBUS is detected. Otherwise it will spin -and continue to check for VBUS and start mavlink once it is detected. -)DESCR_STR"); + "### Description\n" + "This module listens on USB and auto-configures the protocol depending on the bytes received.\n" + "The supported protocols are: MAVLink, nsh, and ublox serial passthrough. If the parameter SYS_USB_AUTO=2\n" + "the module will only try to start mavlink as long as the USB VBUS is detected. Otherwise it will spin\n" + "and continue to check for VBUS and start mavlink once it is detected."); PRINT_MODULE_USAGE_NAME("cdcacm_autostart", "system"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/differential_pressure/asp5033/asp5033_main.cpp b/src/drivers/differential_pressure/asp5033/asp5033_main.cpp index f34597ef37fa..3a665f3d0f0d 100644 --- a/src/drivers/differential_pressure/asp5033/asp5033_main.cpp +++ b/src/drivers/differential_pressure/asp5033/asp5033_main.cpp @@ -42,15 +42,13 @@ void ASP5033::print_usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Driver to enable an external [ASP5033] -(https://www.qio-tek.com/index.php/product/qiotek-asp5033-dronecan-airspeed-and-compass-module/) -TE connected via I2C. -This is not included by default in firmware. It can be included with terminal command: "make boardconfig" -or in default.px4board with adding the line: "CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_ASP5033=y" -It can be enabled with the "SENS_EN_ASP5033" parameter set to 1. -)DESCR_STR"); + "### Description\n" + "Driver to enable an external [ASP5033]\n" + "(https://www.qio-tek.com/index.php/product/qiotek-asp5033-dronecan-airspeed-and-compass-module/)\n" + "TE connected via I2C.\n" + "This is not included by default in firmware. It can be included with terminal command: 'make boardconfig'\n" + "or in default.px4board with adding the line: 'CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_ASP5033=y'\n" + "It can be enabled with the 'SENS_EN_ASP5033' parameter set to 1."); PRINT_MODULE_USAGE_NAME("asp5033", "driver"); PRINT_MODULE_USAGE_SUBCATEGORY("airspeed_sensor"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/distance_sensor/broadcom/afbrs50/AFBRS50.cpp b/src/drivers/distance_sensor/broadcom/afbrs50/AFBRS50.cpp index 91e3366d5ec8..bf61d263b7b8 100644 --- a/src/drivers/distance_sensor/broadcom/afbrs50/AFBRS50.cpp +++ b/src/drivers/distance_sensor/broadcom/afbrs50/AFBRS50.cpp @@ -522,18 +522,16 @@ static int test(const uint8_t rotation) static int usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -Driver for the Broadcom AFBRS50. - -### Examples - -Attempt to start driver on a specified serial device. -$ afbrs50 start -Stop driver -$ afbrs50 stop -)DESCR_STR"); + "### Description\n" + "\n" + "Driver for the Broadcom AFBRS50.\n" + "\n" + "### Examples\n" + "\n" + "Attempt to start driver on a specified serial device.\n" + "$ afbrs50 start\n" + "Stop driver\n" + "$ afbrs50 stop"); PRINT_MODULE_USAGE_NAME("afbrs50", "driver"); PRINT_MODULE_USAGE_SUBCATEGORY("distance_sensor"); diff --git a/src/drivers/distance_sensor/leddar_one/leddar_one_main.cpp b/src/drivers/distance_sensor/leddar_one/leddar_one_main.cpp index 6b6c90615a15..dae07c938c46 100644 --- a/src/drivers/distance_sensor/leddar_one/leddar_one_main.cpp +++ b/src/drivers/distance_sensor/leddar_one/leddar_one_main.cpp @@ -96,22 +96,20 @@ static int stop() static int usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -Serial bus driver for the LeddarOne LiDAR. - -Most boards are configured to enable/start the driver on a specified UART using the SENS_LEDDAR1_CFG parameter. - -Setup/usage information: https://docs.px4.io/main/en/sensor/leddar_one.html - -### Examples - -Attempt to start driver on a specified serial device. -$ leddar_one start -d /dev/ttyS1 -Stop driver -$ leddar_one stop -)DESCR_STR"); + "### Description\n" + "\n" + "Serial bus driver for the LeddarOne LiDAR.\n" + "\n" + "Most boards are configured to enable/start the driver on a specified UART using the SENS_LEDDAR1_CFG parameter.\n" + "\n" + "Setup/usage information: https://docs.px4.io/main/en/sensor/leddar_one.html\n" + "\n" + "### Examples\n" + "\n" + "Attempt to start driver on a specified serial device.\n" + "$ leddar_one start -d /dev/ttyS1\n" + "Stop driver\n" + "$ leddar_one stop"); PRINT_MODULE_USAGE_NAME("leddar_one", "driver"); PRINT_MODULE_USAGE_SUBCATEGORY("distance_sensor"); diff --git a/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp b/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp index 614d408a5e30..71bdf947cad7 100644 --- a/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp +++ b/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp @@ -548,13 +548,11 @@ void LightwareLaser::print_status() void LightwareLaser::print_usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20. - -Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html -)DESCR_STR"); + "### Description\n" + "\n" + "I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20.\n" + "\n" + "Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html"); PRINT_MODULE_USAGE_NAME("lightware_laser_i2c", "driver"); PRINT_MODULE_USAGE_SUBCATEGORY("distance_sensor"); diff --git a/src/drivers/distance_sensor/lightware_laser_serial/lightware_laser_serial_main.cpp b/src/drivers/distance_sensor/lightware_laser_serial/lightware_laser_serial_main.cpp index 76c0dc167c2f..7028fa57a573 100644 --- a/src/drivers/distance_sensor/lightware_laser_serial/lightware_laser_serial_main.cpp +++ b/src/drivers/distance_sensor/lightware_laser_serial/lightware_laser_serial_main.cpp @@ -97,22 +97,20 @@ static int status() static int usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -Serial bus driver for the LightWare SF02/F, SF10/a, SF10/b, SF10/c, SF11/c Laser rangefinders. - -Most boards are configured to enable/start the driver on a specified UART using the SENS_SF0X_CFG parameter. - -Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html - -### Examples - -Attempt to start driver on a specified serial device. -$ lightware_laser_serial start -d /dev/ttyS1 -Stop driver -$ lightware_laser_serial stop -)DESCR_STR"); + "### Description\n" + "\n" + "Serial bus driver for the LightWare SF02/F, SF10/a, SF10/b, SF10/c, SF11/c Laser rangefinders.\n" + "\n" + "Most boards are configured to enable/start the driver on a specified UART using the SENS_SF0X_CFG parameter.\n" + "\n" + "Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html\n" + "\n" + "### Examples\n" + "\n" + "Attempt to start driver on a specified serial device.\n" + "$ lightware_laser_serial start -d /dev/ttyS1\n" + "Stop driver\n" + "$ lightware_laser_serial stop"); PRINT_MODULE_USAGE_NAME("lightware_laser_serial", "driver"); PRINT_MODULE_USAGE_SUBCATEGORY("distance_sensor"); diff --git a/src/drivers/distance_sensor/lightware_sf45_serial/lightware_sf45_serial_main.cpp b/src/drivers/distance_sensor/lightware_sf45_serial/lightware_sf45_serial_main.cpp index 4f6c0a814b61..fddc21f6445b 100755 --- a/src/drivers/distance_sensor/lightware_sf45_serial/lightware_sf45_serial_main.cpp +++ b/src/drivers/distance_sensor/lightware_sf45_serial/lightware_sf45_serial_main.cpp @@ -97,19 +97,17 @@ static int status() static int usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -Serial bus driver for the Lightware SF45/b Laser rangefinder. - - -### Examples - -Attempt to start driver on a specified serial device. -$ lightware_sf45_serial start -d /dev/ttyS1 -Stop driver -$ lightware_sf45_serial stop -)DESCR_STR"); + "### Description\n" + "\n" + "Serial bus driver for the Lightware SF45/b Laser rangefinder.\n" + "\n" + "\n" + "### Examples\n" + "\n" + "Attempt to start driver on a specified serial device.\n" + "$ lightware_sf45_serial start -d /dev/ttyS1\n" + "Stop driver\n" + "$ lightware_sf45_serial stop"); PRINT_MODULE_USAGE_NAME("lightware_sf45_serial", "driver"); PRINT_MODULE_USAGE_SUBCATEGORY("distance_sensor"); diff --git a/src/drivers/distance_sensor/ll40ls/ll40ls.cpp b/src/drivers/distance_sensor/ll40ls/ll40ls.cpp index 77252a29fab7..7096f14d74df 100644 --- a/src/drivers/distance_sensor/ll40ls/ll40ls.cpp +++ b/src/drivers/distance_sensor/ll40ls/ll40ls.cpp @@ -50,15 +50,13 @@ void LidarLiteI2C::print_usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -I2C bus driver for LidarLite rangefinders. - -The sensor/driver must be enabled using the parameter SENS_EN_LL40LS. - -Setup/usage information: https://docs.px4.io/main/en/sensor/lidar_lite.html -)DESCR_STR"); + "### Description\n" + "\n" + "I2C bus driver for LidarLite rangefinders.\n" + "\n" + "The sensor/driver must be enabled using the parameter SENS_EN_LL40LS.\n" + "\n" + "Setup/usage information: https://docs.px4.io/main/en/sensor/lidar_lite.html"); PRINT_MODULE_USAGE_NAME("ll40ls", "driver"); PRINT_MODULE_USAGE_SUBCATEGORY("distance_sensor"); diff --git a/src/drivers/distance_sensor/ll40ls_pwm/ll40ls.cpp b/src/drivers/distance_sensor/ll40ls_pwm/ll40ls.cpp index c11df5039f7c..c1966b25ad84 100644 --- a/src/drivers/distance_sensor/ll40ls_pwm/ll40ls.cpp +++ b/src/drivers/distance_sensor/ll40ls_pwm/ll40ls.cpp @@ -140,22 +140,20 @@ int usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -PWM driver for LidarLite rangefinders. - -The sensor/driver must be enabled using the parameter SENS_EN_LL40LS. - -Setup/usage information: https://docs.px4.io/main/en/sensor/lidar_lite.html -)DESCR_STR"); + "### Description\n" + "\n" + "PWM driver for LidarLite rangefinders.\n" + "\n" + "The sensor/driver must be enabled using the parameter SENS_EN_LL40LS.\n" + "\n" + "Setup/usage information: https://docs.px4.io/main/en/sensor/lidar_lite.html"); PRINT_MODULE_USAGE_NAME("ll40ls", "driver"); PRINT_MODULE_USAGE_SUBCATEGORY("distance_sensor"); - PRINT_MODULE_USAGE_COMMAND_DESCR("start","Start driver"); + PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start driver"); PRINT_MODULE_USAGE_PARAM_INT('R', 25, 0, 25, "Sensor rotation - downward facing by default", true); - PRINT_MODULE_USAGE_COMMAND_DESCR("status","Print driver status information"); - PRINT_MODULE_USAGE_COMMAND_DESCR("stop","Stop driver"); + PRINT_MODULE_USAGE_COMMAND_DESCR("status", "Print driver status information"); + PRINT_MODULE_USAGE_COMMAND_DESCR("stop", "Stop driver"); return PX4_OK; } diff --git a/src/drivers/distance_sensor/pga460/pga460.cpp b/src/drivers/distance_sensor/pga460/pga460.cpp index a94f7c5b57f7..a822bab4738d 100644 --- a/src/drivers/distance_sensor/pga460/pga460.cpp +++ b/src/drivers/distance_sensor/pga460/pga460.cpp @@ -480,19 +480,17 @@ int PGA460::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -Ultrasonic range finder driver that handles the communication with the device and publishes the distance via uORB. - -### Implementation - -This driver is implemented as a NuttX task. This Implementation was chosen due to the need for polling on a message -via UART, which is not supported in the work_queue. This driver continuously takes range measurements while it is -running. A simple algorithm to detect false readings is implemented at the driver levelin an attemptto improve -the quality of data that is being published. The driver will not publish data at all if it deems the sensor data -to be invalid or unstable. -)DESCR_STR"); + "### Description\n" + "\n" + "Ultrasonic range finder driver that handles the communication with the device and publishes the distance via uORB.\n" + "\n" + "### Implementation\n" + "\n" + "This driver is implemented as a NuttX task. This Implementation was chosen due to the need for polling on a message\n" + "via UART, which is not supported in the work_queue. This driver continuously takes range measurements while it is\n" + "running. A simple algorithm to detect false readings is implemented at the driver levelin an attemptto improve\n" + "the quality of data that is being published. The driver will not publish data at all if it deems the sensor data\n" + "to be invalid or unstable."); PRINT_MODULE_USAGE_NAME("pga460", "driver"); PRINT_MODULE_USAGE_SUBCATEGORY("distance_sensor"); @@ -510,14 +508,15 @@ int PGA460::read_eeprom() unlock_eeprom(); const int array_size = 43; - uint8_t user_settings[array_size] = - {USER_DATA1, USER_DATA2, USER_DATA3, USER_DATA4, - USER_DATA5, USER_DATA6, USER_DATA7, USER_DATA8, USER_DATA9, USER_DATA10, - USER_DATA11, USER_DATA12, USER_DATA13, USER_DATA14, USER_DATA15, USER_DATA16, - USER_DATA17, USER_DATA18, USER_DATA19, USER_DATA20, - TVGAIN0, TVGAIN1, TVGAIN2, TVGAIN3, TVGAIN4, TVGAIN5, TVGAIN6, INIT_GAIN, FREQUENCY, DEADTIME, - PULSE_P1, PULSE_P2, CURR_LIM_P1, CURR_LIM_P2, REC_LENGTH, FREQ_DIAG, SAT_FDIAG_TH, FVOLT_DEC, DECPL_TEMP, - DSP_SCALE, TEMP_TRIM, P1_GAIN_CTRL, P2_GAIN_CTRL}; + uint8_t user_settings[array_size] = { + USER_DATA1, USER_DATA2, USER_DATA3, USER_DATA4, + USER_DATA5, USER_DATA6, USER_DATA7, USER_DATA8, USER_DATA9, USER_DATA10, + USER_DATA11, USER_DATA12, USER_DATA13, USER_DATA14, USER_DATA15, USER_DATA16, + USER_DATA17, USER_DATA18, USER_DATA19, USER_DATA20, + TVGAIN0, TVGAIN1, TVGAIN2, TVGAIN3, TVGAIN4, TVGAIN5, TVGAIN6, INIT_GAIN, FREQUENCY, DEADTIME, + PULSE_P1, PULSE_P2, CURR_LIM_P1, CURR_LIM_P2, REC_LENGTH, FREQ_DIAG, SAT_FDIAG_TH, FVOLT_DEC, DECPL_TEMP, + DSP_SCALE, TEMP_TRIM, P1_GAIN_CTRL, P2_GAIN_CTRL + }; int ret = -1; @@ -541,7 +540,7 @@ int PGA460::read_eeprom() total_bytes += ret; - if(ret < 0) { + if (ret < 0) { tcflush(_fd, TCIFLUSH); PX4_ERR("read err2: %d", ret); return ret; @@ -559,6 +558,7 @@ int PGA460::read_eeprom() if (mismatched_bytes == 0) { PX4_INFO("EEPROM has settings."); return PX4_OK; + } else { print_diagnostics(buf_rx[0]); PX4_INFO("EEPROM does not have settings."); @@ -579,7 +579,7 @@ uint8_t PGA460::read_register(const uint8_t reg) int ret = ::write(_fd, &buf_tx[0], sizeof(buf_tx)); - if(!ret) { + if (!ret) { return PX4_ERROR; } @@ -594,7 +594,7 @@ uint8_t PGA460::read_register(const uint8_t reg) total_bytes += ret; - if(ret < 0) { + if (ret < 0) { tcflush(_fd, TCIFLUSH); PX4_ERR("read err3: %d", ret); return ret; @@ -627,7 +627,7 @@ int PGA460::read_threshold_registers() int ret = ::write(_fd, &buf_tx[0], sizeof(buf_tx)); - if(!ret) { + if (!ret) { return PX4_ERROR; } @@ -642,7 +642,7 @@ int PGA460::read_threshold_registers() total_bytes += ret; - if(ret < 0) { + if (ret < 0) { tcflush(_fd, TCIFLUSH); PX4_ERR("read err3: %d", ret); return ret; @@ -674,7 +674,7 @@ int PGA460::request_results() int ret = ::write(_fd, &buf_tx[0], sizeof(buf_tx)); px4_usleep(10000); - if(!ret) { + if (!ret) { return PX4_ERROR; } @@ -686,13 +686,14 @@ void PGA460::run() open_serial(); int ret = initialize_device_settings(); - if(ret != PX4_OK) { + if (ret != PX4_OK) { close_serial(); PX4_INFO("Could not initialize device settings. Exiting."); return; } struct distance_sensor_s report = {}; + _distance_sensor_topic = orb_advertise(ORB_ID(distance_sensor), &report); if (_distance_sensor_topic == nullptr) { @@ -744,7 +745,7 @@ int PGA460::take_measurement(const uint8_t mode) int ret = ::write(_fd, &buf_tx[0], sizeof(buf_tx)); - if(!ret) { + if (!ret) { return PX4_ERROR; } @@ -832,7 +833,7 @@ int PGA460::unlock_eeprom() eeprom_write_buf[4] = checksum; int ret = ::write(_fd, &eeprom_write_buf[0], sizeof(eeprom_write_buf)); - if(!ret) { + if (!ret) { return PX4_ERROR; } @@ -855,7 +856,7 @@ int PGA460::write_eeprom() int ret = ::write(_fd, &settings_buf[0], sizeof(settings_buf)); - if(!ret) { + if (!ret) { return PX4_ERROR; } @@ -898,6 +899,7 @@ int PGA460::write_register(const uint8_t reg, const uint8_t val) if (ret != sizeof(buf_tx)) { return PX4_OK; + } else { return PX4_ERROR; } diff --git a/src/drivers/distance_sensor/srf05/SRF05.cpp b/src/drivers/distance_sensor/srf05/SRF05.cpp index 495fa57c7e96..c88be3c76e51 100644 --- a/src/drivers/distance_sensor/srf05/SRF05.cpp +++ b/src/drivers/distance_sensor/srf05/SRF05.cpp @@ -220,14 +220,11 @@ int SRF05::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( - ### Description - - Driver for HY-SRF05 / HC-SR05 and HC-SR04 rangefinders. - - The sensor/driver must be enabled using the parameter SENS_EN_HXSRX0X. - - )DESCR_STR"); + "### Description\n" + "\n" + "Driver for HY-SRF05 / HC-SR05 and HC-SR04 rangefinders.\n" + "\n" + "The sensor/driver must be enabled using the parameter SENS_EN_HXSRX0X."); PRINT_MODULE_USAGE_NAME("srf05", "driver"); PRINT_MODULE_USAGE_SUBCATEGORY("distance_sensor"); diff --git a/src/drivers/distance_sensor/teraranger/teraranger_main.cpp b/src/drivers/distance_sensor/teraranger/teraranger_main.cpp index 0a7faaa9c193..530ab1d6ccd2 100644 --- a/src/drivers/distance_sensor/teraranger/teraranger_main.cpp +++ b/src/drivers/distance_sensor/teraranger/teraranger_main.cpp @@ -40,15 +40,13 @@ void TERARANGER::print_usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -I2C bus driver for TeraRanger rangefinders. - -The sensor/driver must be enabled using the parameter SENS_EN_TRANGER. - -Setup/usage information: https://docs.px4.io/main/en/sensor/rangefinders.html#teraranger-rangefinders -)DESCR_STR"); + "### Description\n" + "\n" + "I2C bus driver for TeraRanger rangefinders.\n" + "\n" + "The sensor/driver must be enabled using the parameter SENS_EN_TRANGER.\n" + "\n" + "Setup/usage information: https://docs.px4.io/main/en/sensor/rangefinders.html#teraranger-rangefinders"); PRINT_MODULE_USAGE_NAME("teraranger", "driver"); PRINT_MODULE_USAGE_SUBCATEGORY("distance_sensor"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/distance_sensor/tfmini/tfmini_main.cpp b/src/drivers/distance_sensor/tfmini/tfmini_main.cpp index 2680378ad781..93cd40646b25 100644 --- a/src/drivers/distance_sensor/tfmini/tfmini_main.cpp +++ b/src/drivers/distance_sensor/tfmini/tfmini_main.cpp @@ -108,32 +108,30 @@ int usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -Serial bus driver for the Benewake TFmini LiDAR. - -Most boards are configured to enable/start the driver on a specified UART using the SENS_TFMINI_CFG parameter. - -Setup/usage information: https://docs.px4.io/main/en/sensor/tfmini.html - -### Examples - -Attempt to start driver on a specified serial device. -$ tfmini start -d /dev/ttyS1 -Stop driver -$ tfmini stop -)DESCR_STR"); + "### Description\n" + "\n" + "Serial bus driver for the Benewake TFmini LiDAR.\n" + "\n" + "Most boards are configured to enable/start the driver on a specified UART using the SENS_TFMINI_CFG parameter.\n" + "\n" + "Setup/usage information: https://docs.px4.io/main/en/sensor/tfmini.html\n" + "\n" + "### Examples\n" + "\n" + "Attempt to start driver on a specified serial device.\n" + "$ tfmini start -d /dev/ttyS1\n" + "Stop driver\n" + "$ tfmini stop"); PRINT_MODULE_USAGE_NAME("tfmini", "driver"); PRINT_MODULE_USAGE_SUBCATEGORY("distance_sensor"); - PRINT_MODULE_USAGE_COMMAND_DESCR("start","Start driver"); + PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start driver"); PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, nullptr, "Serial device", false); PRINT_MODULE_USAGE_PARAM_INT('R', 25, 0, 25, "Sensor rotation - downward facing by default", true); - PRINT_MODULE_USAGE_COMMAND_DESCR("status","Driver status"); - PRINT_MODULE_USAGE_COMMAND_DESCR("stop","Stop driver"); - PRINT_MODULE_USAGE_COMMAND_DESCR("test","Test driver (basic functional tests)"); - PRINT_MODULE_USAGE_COMMAND_DESCR("status","Print driver status"); + PRINT_MODULE_USAGE_COMMAND_DESCR("status", "Driver status"); + PRINT_MODULE_USAGE_COMMAND_DESCR("stop", "Stop driver"); + PRINT_MODULE_USAGE_COMMAND_DESCR("test", "Test driver (basic functional tests)"); + PRINT_MODULE_USAGE_COMMAND_DESCR("status", "Print driver status"); return PX4_OK; } diff --git a/src/drivers/distance_sensor/ulanding_radar/ulanding_radar_main.cpp b/src/drivers/distance_sensor/ulanding_radar/ulanding_radar_main.cpp index d8898fbb68a4..0589f7c0ba24 100644 --- a/src/drivers/distance_sensor/ulanding_radar/ulanding_radar_main.cpp +++ b/src/drivers/distance_sensor/ulanding_radar/ulanding_radar_main.cpp @@ -97,20 +97,18 @@ static int status() static int usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -Serial bus driver for the Aerotenna uLanding radar. - -Setup/usage information: https://docs.px4.io/main/en/sensor/ulanding_radar.html - -### Examples - -Attempt to start driver on a specified serial device. -$ ulanding_radar start -d /dev/ttyS1 -Stop driver -$ ulanding_radar stop -)DESCR_STR"); + "### Description\n" + "\n" + "Serial bus driver for the Aerotenna uLanding radar.\n" + "\n" + "Setup/usage information: https://docs.px4.io/main/en/sensor/ulanding_radar.html\n" + "\n" + "### Examples\n" + "\n" + "Attempt to start driver on a specified serial device.\n" + "$ ulanding_radar start -d /dev/ttyS1\n" + "Stop driver\n" + "$ ulanding_radar stop"); PRINT_MODULE_USAGE_NAME("ulanding_radar", "driver"); PRINT_MODULE_USAGE_SUBCATEGORY("distance_sensor"); diff --git a/src/drivers/dshot/DShot.cpp b/src/drivers/dshot/DShot.cpp index 940019d9bf04..d93dffa8dd67 100644 --- a/src/drivers/dshot/DShot.cpp +++ b/src/drivers/dshot/DShot.cpp @@ -815,25 +815,23 @@ int DShot::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This is the DShot output driver. It is similar to the fmu driver, and can be used as drop-in replacement -to use DShot as ESC communication protocol instead of PWM. - -On startup, the module tries to occupy all available pins for DShot output. -It skips all pins already in use (e.g. by a camera trigger module). - -It supports: -- DShot150, DShot300, DShot600, DShot1200 -- telemetry via separate UART and publishing as esc_status message -- sending DShot commands via CLI - -### Examples -Permanently reverse motor 1: -$ dshot reverse -m 1 -$ dshot save -m 1 -After saving, the reversed direction will be regarded as the normal one. So to reverse again repeat the same commands. -)DESCR_STR"); + "### Description\n" + "This is the DShot output driver. It is similar to the fmu driver, and can be used as drop-in replacement\n" + "to use DShot as ESC communication protocol instead of PWM.\n" + "\n" + "On startup, the module tries to occupy all available pins for DShot output.\n" + "It skips all pins already in use (e.g. by a camera trigger module).\n" + "\n" + "It supports:\n" + "- DShot150, DShot300, DShot600, DShot1200\n" + "- telemetry via separate UART and publishing as esc_status message\n" + "- sending DShot commands via CLI\n" + "\n" + "### Examples\n" + "Permanently reverse motor 1:\n" + "$ dshot reverse -m 1\n" + "$ dshot save -m 1\n" + "After saving, the reversed direction will be regarded as the normal one. So to reverse again repeat the same commands."); PRINT_MODULE_USAGE_NAME("dshot", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/gnss/septentrio/septentrio.cpp b/src/drivers/gnss/septentrio/septentrio.cpp index 9bd5a8bb0557..1b28db6cad26 100644 --- a/src/drivers/gnss/septentrio/septentrio.cpp +++ b/src/drivers/gnss/septentrio/septentrio.cpp @@ -544,26 +544,24 @@ int SeptentrioDriver::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Driver for Septentrio GNSS receivers. -It can automatically configure them and make their output available for the rest of the system. -A secondary receiver is supported for redundancy, logging and dual-receiver heading. -Septentrio receiver baud rates from 57600 to 1500000 are supported. -If others are used, the driver will use 230400 and give a warning. - -### Examples - -Use one receiver on port `/dev/ttyS0` and automatically configure it to use baud rate 230400: -$ septentrio start -d /dev/ttyS0 -b 230400 - -Use two receivers, the primary on port `/dev/ttyS3` and the secondary on `/dev/ttyS4`, -detect baud rate automatically and preserve them: -$ septentrio start -d /dev/ttyS3 -e /dev/ttyS4 - -Perform warm reset of the receivers: -$ gps reset warm -)DESCR_STR"); + "### Description\n" + "Driver for Septentrio GNSS receivers.\n" + "It can automatically configure them and make their output available for the rest of the system.\n" + "A secondary receiver is supported for redundancy, logging and dual-receiver heading.\n" + "Septentrio receiver baud rates from 57600 to 1500000 are supported.\n" + "If others are used, the driver will use 230400 and give a warning.\n" + "\n" + "### Examples\n" + "\n" + "Use one receiver on port `/dev/ttyS0` and automatically configure it to use baud rate 230400:\n" + "$ septentrio start -d /dev/ttyS0 -b 230400\n" + "\n" + "Use two receivers, the primary on port `/dev/ttyS3` and the secondary on `/dev/ttyS4`,\n" + "detect baud rate automatically and preserve them:\n" + "$ septentrio start -d /dev/ttyS3 -e /dev/ttyS4\n" + "\n" + "Perform warm reset of the receivers:\n" + "$ gps reset warm"); PRINT_MODULE_USAGE_NAME("septentrio", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, "", "Primary receiver port", false); @@ -603,6 +601,7 @@ int SeptentrioDriver::reset(ReceiverResetType type) if (res) { return PX4_OK; + } else { return PX4_ERROR; } @@ -610,10 +609,11 @@ int SeptentrioDriver::reset(ReceiverResetType type) int SeptentrioDriver::force_input() { - ssize_t written = write(reinterpret_cast(k_command_force_input), strlen(k_command_force_input)); + ssize_t written = write(reinterpret_cast(k_command_force_input), strlen(k_command_force_input)); if (written < 0) { return PX4_ERROR; + } else { // The receiver can't receive input right after forcing input. From testing, the duration seems to be 1 ms, so wait 10 ms to be sure. px4_usleep(10000); @@ -621,7 +621,7 @@ int SeptentrioDriver::force_input() } } -int SeptentrioDriver::parse_cli_arguments(int argc, char *argv[], ModuleArguments& arguments) +int SeptentrioDriver::parse_cli_arguments(int argc, char *argv[], ModuleArguments &arguments) { int ch{'\0'}; int myoptind{1}; @@ -634,13 +634,17 @@ int SeptentrioDriver::parse_cli_arguments(int argc, char *argv[], ModuleArgument PX4_ERR("Baud rate parsing failed"); return PX4_ERROR; } + break; + case 'g': if (px4_get_parameter_value(myoptarg, arguments.baud_rate_secondary) != 0) { PX4_ERR("Baud rate parsing failed"); return PX4_ERROR; } + break; + case 'd': arguments.device_path_main = myoptarg; break; @@ -684,7 +688,7 @@ int SeptentrioDriver::await_second_instance_shutdown() return PX4_OK; } - SeptentrioDriver* secondary_instance = _secondary_instance.load(); + SeptentrioDriver *secondary_instance = _secondary_instance.load(); if (secondary_instance) { secondary_instance->request_stop(); @@ -699,6 +703,7 @@ int SeptentrioDriver::await_second_instance_shutdown() } return _secondary_instance.load() ? PX4_ERROR : PX4_OK; + } else { return PX4_OK; } @@ -715,7 +720,8 @@ void SeptentrioDriver::schedule_reset(ReceiverResetType reset_type) } } -bool SeptentrioDriver::detect_receiver_baud_rate(const uint32_t &baud_rate, bool forced_input) { +bool SeptentrioDriver::detect_receiver_baud_rate(const uint32_t &baud_rate, bool forced_input) +{ if (set_baudrate(baud_rate) != PX4_OK) { return false; } @@ -735,7 +741,8 @@ bool SeptentrioDriver::detect_receiver_baud_rate(const uint32_t &baud_rate, bool return false; } -int SeptentrioDriver::detect_serial_port(char* const port_name) { +int SeptentrioDriver::detect_serial_port(char *const port_name) +{ // Read buffer to get the COM port char buf[k_read_buffer_size]; size_t buffer_offset = 0; // The offset into the string where the next data should be read to. @@ -749,7 +756,8 @@ int SeptentrioDriver::detect_serial_port(char* const port_name) { do { // Read at most the amount of available bytes in the buffer after the current offset, -1 because we need '\0' at the end for a valid string. - int read_result = read(reinterpret_cast(buf) + buffer_offset, sizeof(buf) - buffer_offset - 1, k_receiver_ack_timeout_fast); + int read_result = read(reinterpret_cast(buf) + buffer_offset, sizeof(buf) - buffer_offset - 1, + k_receiver_ack_timeout_fast); if (read_result < 0) { SEP_WARN("SBF read error"); @@ -768,14 +776,16 @@ int SeptentrioDriver::detect_serial_port(char* const port_name) { // Make sure the current buffer is a valid string. buf[buffer_offset] = '\0'; - char* port_name_address = strstr(buf, ">"); + char *port_name_address = strstr(buf, ">"); // Check if we found a port candidate. if (buffer_offset > 4 && port_name_address != nullptr) { size_t port_name_offset = reinterpret_cast(port_name_address) - reinterpret_cast(buf) - 4; + for (size_t i = 0; i < 4; i++) { port_name[i] = buf[port_name_offset + i]; } + // NOTE: This limits the ports to serial and USB ports only. Otherwise the detection doesn't work correctly. if (strstr(port_name, "COM") != nullptr || strstr(port_name, "USB") != nullptr) { response_detected = true; @@ -788,6 +798,7 @@ int SeptentrioDriver::detect_serial_port(char* const port_name) { for (int i = 0; i < 4; i++) { buf[i] = buf[sizeof(buf) - 4 + i]; } + buffer_offset = 3; } } while (timeout_time > hrt_absolute_time()); @@ -795,6 +806,7 @@ int SeptentrioDriver::detect_serial_port(char* const port_name) { if (!response_detected) { SEP_WARN("No valid serial port detected"); return PX4_ERROR; + } else { SEP_INFO("Serial port found: %s", port_name); return PX4_OK; @@ -854,24 +866,31 @@ SeptentrioDriver::ConfigureResult SeptentrioDriver::configure() // Set up the satellites used in PVT computation. if (_receiver_constellation_usage != static_cast(SatelliteUsage::Default)) { char requested_satellites[40] {}; + if (_receiver_constellation_usage & static_cast(SatelliteUsage::GPS)) { strcat(requested_satellites, "GPS+"); } + if (_receiver_constellation_usage & static_cast(SatelliteUsage::GLONASS)) { strcat(requested_satellites, "GLONASS+"); } + if (_receiver_constellation_usage & static_cast(SatelliteUsage::Galileo)) { strcat(requested_satellites, "GALILEO+"); } + if (_receiver_constellation_usage & static_cast(SatelliteUsage::SBAS)) { strcat(requested_satellites, "SBAS+"); } + if (_receiver_constellation_usage & static_cast(SatelliteUsage::BeiDou)) { strcat(requested_satellites, "BEIDOU+"); } + // Make sure to remove the trailing '+' if any. requested_satellites[math::max(static_cast(strlen(requested_satellites)) - 1, 0)] = '\0'; snprintf(msg, sizeof(msg), k_command_set_satellite_usage, requested_satellites); + // Use a longer timeout as the `setSatelliteUsage` command acknowledges a bit slower on mosaic-H-based receivers. if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout_slow)) { SEP_WARN("CONFIG: Failed to configure constellation usage"); @@ -888,31 +907,40 @@ SeptentrioDriver::ConfigureResult SeptentrioDriver::configure() case ReceiverLogFrequency::Hz0_1: frequency = k_frequency_0_1hz; break; + case ReceiverLogFrequency::Hz0_2: frequency = k_frequency_0_2hz; break; + case ReceiverLogFrequency::Hz0_5: frequency = k_frequency_0_5hz; break; + case ReceiverLogFrequency::Hz1_0: default: frequency = k_frequency_1_0hz; break; + case ReceiverLogFrequency::Hz2_0: frequency = k_frequency_2_0hz; break; + case ReceiverLogFrequency::Hz5_0: frequency = k_frequency_5_0hz; break; + case ReceiverLogFrequency::Hz10_0: frequency = k_frequency_10_0hz; break; + case ReceiverLogFrequency::Hz20_0: frequency = k_frequency_20_0hz; break; + case ReceiverLogFrequency::Hz25_0: frequency = k_frequency_25_0hz; break; + case ReceiverLogFrequency::Hz50_0: frequency = k_frequency_50_0hz; break; @@ -922,22 +950,28 @@ SeptentrioDriver::ConfigureResult SeptentrioDriver::configure() case ReceiverLogLevel::Lite: level = "Comment+ReceiverStatus"; break; + case ReceiverLogLevel::Basic: level = "Comment+ReceiverStatus+PostProcess+Event"; break; + case ReceiverLogLevel::Default: default: level = "Comment+ReceiverStatus+PostProcess+Event+Support"; break; + case ReceiverLogLevel::Full: level = "Comment+ReceiverStatus+PostProcess+Event+Support+BBSamples"; break; } - snprintf(msg, sizeof(msg), k_command_set_sbf_output, _receiver_stream_log, "DSK1", _receiver_logging_overwrite ? "" : "+", level, frequency); + snprintf(msg, sizeof(msg), k_command_set_sbf_output, _receiver_stream_log, "DSK1", + _receiver_logging_overwrite ? "" : "+", level, frequency); + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout_fast)) { result = static_cast(static_cast(result) | static_cast(ConfigureResult::NoLogging)); } + } else if (_receiver_stream_log == _receiver_stream_main) { result = static_cast(static_cast(result) | static_cast(ConfigureResult::NoLogging)); } @@ -950,28 +984,34 @@ SeptentrioDriver::ConfigureResult SeptentrioDriver::configure() } // Specify the offsets that the receiver applies to the computed attitude angles. - snprintf(msg, sizeof(msg), k_command_set_attitude_offset, static_cast(_heading_offset), static_cast(_pitch_offset)); + snprintf(msg, sizeof(msg), k_command_set_attitude_offset, static_cast(_heading_offset), + static_cast(_pitch_offset)); if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout_fast)) { return ConfigureResult::FailedCompletely; } snprintf(msg, sizeof(msg), k_command_set_dynamics, "high"); + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout_fast)) { return ConfigureResult::FailedCompletely; } const char *sbf_frequency {k_frequency_10_0hz}; + switch (_sbf_output_frequency) { case SBFOutputFrequency::Hz5_0: sbf_frequency = k_frequency_5_0hz; break; + case SBFOutputFrequency::Hz10_0: sbf_frequency = k_frequency_10_0hz; break; + case SBFOutputFrequency::Hz20_0: sbf_frequency = k_frequency_20_0hz; break; + case SBFOutputFrequency::Hz25_0: sbf_frequency = k_frequency_25_0hz; break; @@ -979,6 +1019,7 @@ SeptentrioDriver::ConfigureResult SeptentrioDriver::configure() // Output a set of SBF blocks on a given connection at a regular interval. snprintf(msg, sizeof(msg), k_command_sbf_output_pvt, _receiver_stream_main, com_port, sbf_frequency); + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout_fast)) { SEP_WARN("CONFIG: Failed to configure SBF"); return ConfigureResult::FailedCompletely; @@ -987,17 +1028,22 @@ SeptentrioDriver::ConfigureResult SeptentrioDriver::configure() if (_receiver_setup == ReceiverSetup::MovingBase) { if (_instance == Instance::Secondary) { snprintf(msg, sizeof(msg), k_command_set_data_io, com_port, "+RTCMv3"); + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout_fast)) { SEP_WARN("CONFIG: Failed to configure RTCM output"); } + } else { snprintf(msg, sizeof(msg), k_command_set_gnss_attitude, k_gnss_attitude_source_moving_base); + if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout_fast)) { SEP_WARN("CONFIG: Failed to configure attitude source"); } } + } else { snprintf(msg, sizeof(msg), k_command_set_gnss_attitude, k_gnss_attitude_source_multi_antenna); + // This fails on single-antenna receivers, which is fine. Therefore don't check for acknowledgement. if (!send_message(msg)) { SEP_WARN("CONFIG: Failed to configure attitude source"); @@ -1016,27 +1062,35 @@ int SeptentrioDriver::parse_char(const uint8_t byte) case DecodingStatus::Searching: if (_sbf_decoder.add_byte(byte) != sbf::Decoder::State::SearchingSync1) { _active_decoder = DecodingStatus::SBF; + } else if (_rtcm_decoder && _rtcm_decoder->add_byte(byte) != rtcm::Decoder::State::SearchingPreamble) { _active_decoder = DecodingStatus::RTCMv3; } + break; + case DecodingStatus::SBF: if (_sbf_decoder.add_byte(byte) == sbf::Decoder::State::Done) { if (process_message() == PX4_OK) { result = 1; } + _sbf_decoder.reset(); _active_decoder = DecodingStatus::Searching; } + break; + case DecodingStatus::RTCMv3: if (_rtcm_decoder->add_byte(byte) == rtcm::Decoder::State::Done) { if (process_message() == PX4_OK) { result = 1; } + _rtcm_decoder->reset(); _active_decoder = DecodingStatus::Searching; } + break; } @@ -1049,252 +1103,277 @@ int SeptentrioDriver::process_message() switch (_active_decoder) { case DecodingStatus::Searching: { - SEP_ERR("Can't process incomplete message!"); - result = PX4_ERROR; - break; - } - case DecodingStatus::SBF: { - using namespace sbf; - - switch (_sbf_decoder.id()) { - case BlockID::Invalid: { - SEP_TRACE_PARSING("Tried to process invalid SBF message"); + SEP_ERR("Can't process incomplete message!"); + result = PX4_ERROR; break; } - case BlockID::DOP: { - SEP_TRACE_PARSING("Processing DOP SBF message"); - _current_interval_messages.dop = true; - DOP dop; + case DecodingStatus::SBF: { + using namespace sbf; - if (_sbf_decoder.parse(&dop) == PX4_OK) { - _message_gps_state.hdop = dop.h_dop * 0.01f; - _message_gps_state.vdop = dop.v_dop * 0.01f; - result = PX4_OK; - } + switch (_sbf_decoder.id()) { + case BlockID::Invalid: { + SEP_TRACE_PARSING("Tried to process invalid SBF message"); + break; + } - break; - } - case BlockID::PVTGeodetic: { - using ModeType = PVTGeodetic::ModeType; - using Error = PVTGeodetic::Error; + case BlockID::DOP: { + SEP_TRACE_PARSING("Processing DOP SBF message"); + _current_interval_messages.dop = true; - SEP_TRACE_PARSING("Processing PVTGeodetic SBF message"); - _current_interval_messages.pvt_geodetic = true; + DOP dop; - Header header; - PVTGeodetic pvt_geodetic; + if (_sbf_decoder.parse(&dop) == PX4_OK) { + _message_gps_state.hdop = dop.h_dop * 0.01f; + _message_gps_state.vdop = dop.v_dop * 0.01f; + result = PX4_OK; + } - if (_sbf_decoder.parse(&header) == PX4_OK && _sbf_decoder.parse(&pvt_geodetic) == PX4_OK) { - switch (pvt_geodetic.mode_type) { - case ModeType::NoPVT: - _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_NONE; - break; - case ModeType::PVTWithSBAS: - _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_RTCM_CODE_DIFFERENTIAL; - break; - case ModeType::RTKFloat: - case ModeType::MovingBaseRTKFloat: - _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_RTK_FLOAT; - break; - case ModeType::RTKFixed: - case ModeType::MovingBaseRTKFixed: - _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_RTK_FIXED; - break; - default: - _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_3D; break; } - // Check boundaries and invalidate GPS velocities - if (pvt_geodetic.vn <= k_dnu_f4_value || pvt_geodetic.ve <= k_dnu_f4_value || pvt_geodetic.vu <= k_dnu_f4_value) { - _message_gps_state.vel_ned_valid = false; - } + case BlockID::PVTGeodetic: { + using ModeType = PVTGeodetic::ModeType; + using Error = PVTGeodetic::Error; + + SEP_TRACE_PARSING("Processing PVTGeodetic SBF message"); + _current_interval_messages.pvt_geodetic = true; + + Header header; + PVTGeodetic pvt_geodetic; + + if (_sbf_decoder.parse(&header) == PX4_OK && _sbf_decoder.parse(&pvt_geodetic) == PX4_OK) { + switch (pvt_geodetic.mode_type) { + case ModeType::NoPVT: + _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_NONE; + break; + + case ModeType::PVTWithSBAS: + _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_RTCM_CODE_DIFFERENTIAL; + break; + + case ModeType::RTKFloat: + case ModeType::MovingBaseRTKFloat: + _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_RTK_FLOAT; + break; + + case ModeType::RTKFixed: + case ModeType::MovingBaseRTKFixed: + _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_RTK_FIXED; + break; + + default: + _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_3D; + break; + } + + // Check boundaries and invalidate GPS velocities + if (pvt_geodetic.vn <= k_dnu_f4_value || pvt_geodetic.ve <= k_dnu_f4_value || pvt_geodetic.vu <= k_dnu_f4_value) { + _message_gps_state.vel_ned_valid = false; + } + + if (pvt_geodetic.latitude > k_dnu_f8_value && pvt_geodetic.longitude > k_dnu_f8_value + && pvt_geodetic.height > k_dnu_f8_value && pvt_geodetic.undulation > k_dnu_f4_value) { + _message_gps_state.latitude_deg = pvt_geodetic.latitude * M_RAD_TO_DEG; + _message_gps_state.longitude_deg = pvt_geodetic.longitude * M_RAD_TO_DEG; + _message_gps_state.altitude_msl_m = pvt_geodetic.height - static_cast(pvt_geodetic.undulation); + _message_gps_state.altitude_ellipsoid_m = pvt_geodetic.height; + + } else { + _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_NONE; + } + + if (pvt_geodetic.nr_sv != PVTGeodetic::k_dnu_nr_sv) { + _message_gps_state.satellites_used = pvt_geodetic.nr_sv; + + if (_message_satellite_info) { + // Only fill in the satellite count for now (we could use the ChannelStatus message for the + // other data, but it's really large: >800B) + _message_satellite_info->timestamp = hrt_absolute_time(); + _message_satellite_info->count = _message_gps_state.satellites_used; + } + + } else { + _message_gps_state.satellites_used = 0; + } + + /* H and V accuracy are reported in 2DRMS, but based off the u-blox reporting we expect RMS. + * Divide by 100 from cm to m and in addition divide by 2 to get RMS. */ + _message_gps_state.eph = static_cast(pvt_geodetic.h_accuracy) / 200.0f; + _message_gps_state.epv = static_cast(pvt_geodetic.v_accuracy) / 200.0f; + + // Check fix and error code + _message_gps_state.vel_ned_valid = _message_gps_state.fix_type > sensor_gps_s::FIX_TYPE_NONE + && pvt_geodetic.error == Error::None; + _message_gps_state.vel_n_m_s = pvt_geodetic.vn; + _message_gps_state.vel_e_m_s = pvt_geodetic.ve; + _message_gps_state.vel_d_m_s = -1.0f * pvt_geodetic.vu; + _message_gps_state.vel_m_s = sqrtf(_message_gps_state.vel_n_m_s * _message_gps_state.vel_n_m_s + + _message_gps_state.vel_e_m_s * _message_gps_state.vel_e_m_s); + + if (pvt_geodetic.cog > k_dnu_f4_value) { + _message_gps_state.cog_rad = pvt_geodetic.cog * M_DEG_TO_RAD_F; + } + + _message_gps_state.c_variance_rad = M_DEG_TO_RAD_F; + + _message_gps_state.time_utc_usec = 0; +#ifndef __PX4_QURT // NOTE: Functionality isn't available on Snapdragon yet. - if (pvt_geodetic.latitude > k_dnu_f8_value && pvt_geodetic.longitude > k_dnu_f8_value && pvt_geodetic.height > k_dnu_f8_value && pvt_geodetic.undulation > k_dnu_f4_value) { - _message_gps_state.latitude_deg = pvt_geodetic.latitude * M_RAD_TO_DEG; - _message_gps_state.longitude_deg = pvt_geodetic.longitude * M_RAD_TO_DEG; - _message_gps_state.altitude_msl_m = pvt_geodetic.height - static_cast(pvt_geodetic.undulation); - _message_gps_state.altitude_ellipsoid_m = pvt_geodetic.height; - } else { - _message_gps_state.fix_type = sensor_gps_s::FIX_TYPE_NONE; - } + if (_time_synced) { + struct tm timeinfo; + time_t epoch; + + // Convert to unix timestamp + memset(&timeinfo, 0, sizeof(timeinfo)); + + timeinfo.tm_year = 1980 - 1900; + timeinfo.tm_mon = 0; + timeinfo.tm_mday = 6 + header.wnc * 7; + timeinfo.tm_hour = 0; + timeinfo.tm_min = 0; + timeinfo.tm_sec = header.tow / 1000; + + epoch = mktime(&timeinfo); + + if (epoch > k_gps_epoch_secs) { + // FMUv2+ boards have a hardware RTC, but GPS helps us to configure it + // and control its drift. Since we rely on the HRT for our monotonic + // clock, updating it from time to time is safe. - if (pvt_geodetic.nr_sv != PVTGeodetic::k_dnu_nr_sv) { - _message_gps_state.satellites_used = pvt_geodetic.nr_sv; + timespec ts; + memset(&ts, 0, sizeof(ts)); + ts.tv_sec = epoch; + ts.tv_nsec = (header.tow % 1000) * 1000 * 1000; + set_clock(ts); - if (_message_satellite_info) { - // Only fill in the satellite count for now (we could use the ChannelStatus message for the - // other data, but it's really large: >800B) - _message_satellite_info->timestamp = hrt_absolute_time(); - _message_satellite_info->count = _message_gps_state.satellites_used; + _message_gps_state.time_utc_usec = static_cast(epoch) * 1000000ULL; + _message_gps_state.time_utc_usec += (header.tow % 1000) * 1000; + } + } + +#endif + _message_gps_state.timestamp = hrt_absolute_time(); + result = PX4_OK; } - } else { - _message_gps_state.satellites_used = 0; + break; } - /* H and V accuracy are reported in 2DRMS, but based off the u-blox reporting we expect RMS. - * Divide by 100 from cm to m and in addition divide by 2 to get RMS. */ - _message_gps_state.eph = static_cast(pvt_geodetic.h_accuracy) / 200.0f; - _message_gps_state.epv = static_cast(pvt_geodetic.v_accuracy) / 200.0f; - - // Check fix and error code - _message_gps_state.vel_ned_valid = _message_gps_state.fix_type > sensor_gps_s::FIX_TYPE_NONE && pvt_geodetic.error == Error::None; - _message_gps_state.vel_n_m_s = pvt_geodetic.vn; - _message_gps_state.vel_e_m_s = pvt_geodetic.ve; - _message_gps_state.vel_d_m_s = -1.0f * pvt_geodetic.vu; - _message_gps_state.vel_m_s = sqrtf(_message_gps_state.vel_n_m_s * _message_gps_state.vel_n_m_s + - _message_gps_state.vel_e_m_s * _message_gps_state.vel_e_m_s); - - if (pvt_geodetic.cog > k_dnu_f4_value) { - _message_gps_state.cog_rad = pvt_geodetic.cog * M_DEG_TO_RAD_F; - } - _message_gps_state.c_variance_rad = M_DEG_TO_RAD_F; + case BlockID::ReceiverStatus: { + SEP_TRACE_PARSING("Processing ReceiverStatus SBF message"); - _message_gps_state.time_utc_usec = 0; -#ifndef __PX4_QURT // NOTE: Functionality isn't available on Snapdragon yet. - if (_time_synced) { - struct tm timeinfo; - time_t epoch; - - // Convert to unix timestamp - memset(&timeinfo, 0, sizeof(timeinfo)); - - timeinfo.tm_year = 1980 - 1900; - timeinfo.tm_mon = 0; - timeinfo.tm_mday = 6 + header.wnc * 7; - timeinfo.tm_hour = 0; - timeinfo.tm_min = 0; - timeinfo.tm_sec = header.tow / 1000; - - epoch = mktime(&timeinfo); - - if (epoch > k_gps_epoch_secs) { - // FMUv2+ boards have a hardware RTC, but GPS helps us to configure it - // and control its drift. Since we rely on the HRT for our monotonic - // clock, updating it from time to time is safe. - - timespec ts; - memset(&ts, 0, sizeof(ts)); - ts.tv_sec = epoch; - ts.tv_nsec = (header.tow % 1000) * 1000 * 1000; - set_clock(ts); - - _message_gps_state.time_utc_usec = static_cast(epoch) * 1000000ULL; - _message_gps_state.time_utc_usec += (header.tow % 1000) * 1000; + ReceiverStatus receiver_status; + + if (_sbf_decoder.parse(&receiver_status) == PX4_OK) { + _message_gps_state.rtcm_msg_used = receiver_status.rx_state_diff_corr_in ? sensor_gps_s::RTCM_MSG_USED_USED : + sensor_gps_s::RTCM_MSG_USED_NOT_USED; + _time_synced = receiver_status.rx_state_wn_set && receiver_status.rx_state_tow_set; } + + break; } -#endif - _message_gps_state.timestamp = hrt_absolute_time(); - result = PX4_OK; - } + case BlockID::QualityInd: { + SEP_TRACE_PARSING("Processing QualityInd SBF message"); + break; + } - break; - } + case BlockID::RFStatus: { + SEP_TRACE_PARSING("Processing RFStatus SBF message"); + break; + } - case BlockID::ReceiverStatus: { - SEP_TRACE_PARSING("Processing ReceiverStatus SBF message"); + case BlockID::GALAuthStatus: { + SEP_TRACE_PARSING("Processing GALAuthStatus SBF message"); + break; + } - ReceiverStatus receiver_status; + case BlockID::EndOfPVT: { + SEP_TRACE_PARSING("Processing EndOfPVT SBF message"); - if (_sbf_decoder.parse(&receiver_status) == PX4_OK) { - _message_gps_state.rtcm_msg_used = receiver_status.rx_state_diff_corr_in ? sensor_gps_s::RTCM_MSG_USED_USED : sensor_gps_s::RTCM_MSG_USED_NOT_USED; - _time_synced = receiver_status.rx_state_wn_set && receiver_status.rx_state_tow_set; - } + // EndOfPVT guarantees that all PVT blocks for this epoch have been sent, so it's safe to assume the uORB message contains all required data. + publish(); + break; + } - break; - } - case BlockID::QualityInd: { - SEP_TRACE_PARSING("Processing QualityInd SBF message"); - break; - } - case BlockID::RFStatus: { - SEP_TRACE_PARSING("Processing RFStatus SBF message"); - break; - } - case BlockID::GALAuthStatus: { - SEP_TRACE_PARSING("Processing GALAuthStatus SBF message"); - break; - } - case BlockID::EndOfPVT: { - SEP_TRACE_PARSING("Processing EndOfPVT SBF message"); + case BlockID::VelCovGeodetic: { + SEP_TRACE_PARSING("Processing VelCovGeodetic SBF message"); + _current_interval_messages.vel_cov_geodetic = true; - // EndOfPVT guarantees that all PVT blocks for this epoch have been sent, so it's safe to assume the uORB message contains all required data. - publish(); - break; - } - case BlockID::VelCovGeodetic: { - SEP_TRACE_PARSING("Processing VelCovGeodetic SBF message"); - _current_interval_messages.vel_cov_geodetic = true; + VelCovGeodetic vel_cov_geodetic; - VelCovGeodetic vel_cov_geodetic; + if (_sbf_decoder.parse(&vel_cov_geodetic) == PX4_OK) { + if (vel_cov_geodetic.cov_ve_ve > k_dnu_f4_value && vel_cov_geodetic.cov_vn_vn > k_dnu_f4_value + && vel_cov_geodetic.cov_vu_vu > k_dnu_f4_value) { + _message_gps_state.s_variance_m_s = math::max(math::max(vel_cov_geodetic.cov_ve_ve, vel_cov_geodetic.cov_vn_vn), + vel_cov_geodetic.cov_vu_vu); + } + } - if (_sbf_decoder.parse(&vel_cov_geodetic) == PX4_OK) { - if (vel_cov_geodetic.cov_ve_ve > k_dnu_f4_value && vel_cov_geodetic.cov_vn_vn > k_dnu_f4_value && vel_cov_geodetic.cov_vu_vu > k_dnu_f4_value) { - _message_gps_state.s_variance_m_s = math::max(math::max(vel_cov_geodetic.cov_ve_ve, vel_cov_geodetic.cov_vn_vn), vel_cov_geodetic.cov_vu_vu); + break; } - } - break; - } - case BlockID::GEOIonoDelay: { - SEP_TRACE_PARSING("Processing GEOIonoDelay SBF message"); - break; - } - case BlockID::AttEuler: { - using Error = AttEuler::Error; + case BlockID::GEOIonoDelay: { + SEP_TRACE_PARSING("Processing GEOIonoDelay SBF message"); + break; + } + + case BlockID::AttEuler: { + using Error = AttEuler::Error; + + SEP_TRACE_PARSING("Processing AttEuler SBF message"); + _current_interval_messages.att_euler = true; - SEP_TRACE_PARSING("Processing AttEuler SBF message"); - _current_interval_messages.att_euler = true; + AttEuler att_euler; - AttEuler att_euler; + if (_sbf_decoder.parse(&att_euler) == PX4_OK && + !att_euler.error_not_requested && + att_euler.error_aux1 == Error::None && + att_euler.error_aux2 == Error::None && + att_euler.heading > k_dnu_f4_value) { + float heading = att_euler.heading * M_PI_F / 180.0f; // Range of degrees to range of radians in [0, 2PI]. - if (_sbf_decoder.parse(&att_euler) == PX4_OK && - !att_euler.error_not_requested && - att_euler.error_aux1 == Error::None && - att_euler.error_aux2 == Error::None && - att_euler.heading > k_dnu_f4_value) { - float heading = att_euler.heading * M_PI_F / 180.0f; // Range of degrees to range of radians in [0, 2PI]. + // Ensure range is in [-PI, PI]. + if (heading > M_PI_F) { + heading -= 2.f * M_PI_F; + } + + _message_gps_state.heading = heading; + } - // Ensure range is in [-PI, PI]. - if (heading > M_PI_F) { - heading -= 2.f * M_PI_F; + break; } - _message_gps_state.heading = heading; - } + case BlockID::AttCovEuler: { + using Error = AttCovEuler::Error; - break; - } - case BlockID::AttCovEuler: { - using Error = AttCovEuler::Error; + SEP_TRACE_PARSING("Processing AttCovEuler SBF message"); + _current_interval_messages.att_cov_euler = true; - SEP_TRACE_PARSING("Processing AttCovEuler SBF message"); - _current_interval_messages.att_cov_euler = true; + AttCovEuler att_cov_euler; - AttCovEuler att_cov_euler; + if (_sbf_decoder.parse(&att_cov_euler) == PX4_OK && + !att_cov_euler.error_not_requested && + att_cov_euler.error_aux1 == Error::None && + att_cov_euler.error_aux2 == Error::None && + att_cov_euler.cov_headhead > k_dnu_f4_value) { + _message_gps_state.heading_accuracy = att_cov_euler.cov_headhead * M_PI_F / + 180.0f; // Convert range of degrees to range of radians in [0, 2PI] + } - if (_sbf_decoder.parse(&att_cov_euler) == PX4_OK && - !att_cov_euler.error_not_requested && - att_cov_euler.error_aux1 == Error::None && - att_cov_euler.error_aux2 == Error::None && - att_cov_euler.cov_headhead > k_dnu_f4_value) { - _message_gps_state.heading_accuracy = att_cov_euler.cov_headhead * M_PI_F / 180.0f; // Convert range of degrees to range of radians in [0, 2PI] + break; + } } break; } - } - break; - } case DecodingStatus::RTCMv3: { - SEP_TRACE_PARSING("Processing RTCMv3 message"); - publish_rtcm_corrections(_rtcm_decoder->message(), _rtcm_decoder->received_bytes()); - break; - } + SEP_TRACE_PARSING("Processing RTCMv3 message"); + publish_rtcm_corrections(_rtcm_decoder->message(), _rtcm_decoder->received_bytes()); + break; + } } return result; @@ -1305,7 +1384,7 @@ bool SeptentrioDriver::send_message(const char *msg) PX4_DEBUG("Send MSG: %s", msg); int length = strlen(msg); - return (write(reinterpret_cast(msg), length) == length); + return (write(reinterpret_cast(msg), length) == length); } bool SeptentrioDriver::send_message_and_wait_for_ack(const char *msg, const int timeout) @@ -1318,7 +1397,7 @@ bool SeptentrioDriver::send_message_and_wait_for_ack(const char *msg, const int // For all valid set -, get - and exe -commands, the first line of the reply is an exact copy // of the command as entered by the user, preceded with "$R: " char buf[k_read_buffer_size]; - char expected_response[k_max_command_size+4]; + char expected_response[k_max_command_size + 4]; snprintf(expected_response, sizeof(expected_response), "$R: %s", msg); uint16_t response_check_character = 0; // Length of the message without the newline but including the preceding response part "$R: " @@ -1326,7 +1405,7 @@ bool SeptentrioDriver::send_message_and_wait_for_ack(const char *msg, const int hrt_abstime timeout_time = hrt_absolute_time() + 1000 * timeout; do { - int read_result = read(reinterpret_cast(buf), sizeof(buf), 50); + int read_result = read(reinterpret_cast(buf), sizeof(buf), 50); if (read_result < 0) { SEP_WARN("SBF read error"); @@ -1337,11 +1416,14 @@ bool SeptentrioDriver::send_message_and_wait_for_ack(const char *msg, const int if (response_check_character == response_len) { // We encountered the complete response return true; + } else if (expected_response[response_check_character] == buf[i]) { ++response_check_character; + } else if (buf[i] == '$') { // Special case makes sure we don't miss start of new response if that happened to be the character we weren't expecting next (e.g., `$R: ge$R: gecm`) response_check_character = 1; + } else { response_check_character = 0; } @@ -1395,6 +1477,7 @@ int SeptentrioDriver::read(uint8_t *buf, size_t buf_length, int timeout) if (num_read > 0) { _current_interval_bytes_read += num_read; + if (should_dump_incoming()) { dump_gps_data(buf, num_read, DataDirection::FromReceiver); } @@ -1410,12 +1493,13 @@ int SeptentrioDriver::poll_or_read(uint8_t *buf, size_t buf_length, int timeout) return _uart.readAtLeast(buf, buf_length, math::min(k_min_receiver_read_bytes, buf_length), read_timeout); } -int SeptentrioDriver::write(const uint8_t* buf, size_t buf_length) +int SeptentrioDriver::write(const uint8_t *buf, size_t buf_length) { ssize_t write_result = _uart.write(buf, buf_length); if (write_result >= 0) { _current_interval_bytes_written += write_result; + if (should_dump_outgoing()) { dump_gps_data(buf, write_result, DataDirection::ToReceiver); } @@ -1436,6 +1520,7 @@ int SeptentrioDriver::initialize_communication_dump(DumpMode mode) memset(_message_data_from_receiver, 0, sizeof(*_message_data_from_receiver)); } + if (mode == DumpMode::ToReceiver || mode == DumpMode::Both) { _message_data_to_receiver = new gps_dump_s(); @@ -1464,6 +1549,7 @@ void SeptentrioDriver::reset_if_scheduled() if (res == PX4_OK) { SEP_INFO("Reset succeeded."); + } else { SEP_INFO("Reset failed."); } @@ -1475,6 +1561,7 @@ int SeptentrioDriver::set_baudrate(uint32_t baud) if (_uart.setBaudrate(baud)) { SEP_INFO("baud controller: %lu", baud); return PX4_OK; + } else { return PX4_ERROR; } @@ -1520,7 +1607,8 @@ void SeptentrioDriver::handle_inject_data_topic() num_injections++; // Prevent injection of data from self or from ground if moving base and this is rover. - if ((_instance == Instance::Secondary && msg.device_id != get_device_id()) || (_instance == Instance::Main && msg.device_id == get_device_id()) || _receiver_setup != ReceiverSetup::MovingBase) { + if ((_instance == Instance::Secondary && msg.device_id != get_device_id()) || (_instance == Instance::Main + && msg.device_id == get_device_id()) || _receiver_setup != ReceiverSetup::MovingBase) { /* Write the message to the gps device. Note that the message could be fragmented. * But as we don't write anywhere else to the device during operation, we don't * need to assemble the message first. @@ -1558,7 +1646,7 @@ void SeptentrioDriver::publish() if (_message_gps_state.jamming_state > sensor_gps_s::JAMMING_STATE_WARNING) { SEP_WARN("GPS jamming detected! (state: %d) (indicator: %d)", _message_gps_state.jamming_state, - (uint8_t)_message_gps_state.jamming_indicator); + (uint8_t)_message_gps_state.jamming_indicator); } _jamming_state = _message_gps_state.jamming_state; @@ -1613,7 +1701,8 @@ void SeptentrioDriver::publish_rtcm_corrections(uint8_t *data, size_t len) void SeptentrioDriver::dump_gps_data(const uint8_t *data, size_t len, DataDirection data_direction) { - gps_dump_s *dump_data = data_direction == DataDirection::FromReceiver ? _message_data_from_receiver : _message_data_to_receiver; + gps_dump_s *dump_data = data_direction == DataDirection::FromReceiver ? _message_data_from_receiver : + _message_data_to_receiver; dump_data->instance = _instance == Instance::Main ? 0 : 1; while (len > 0) { @@ -1681,21 +1770,23 @@ float SeptentrioDriver::rtcm_injection_frequency() const uint32_t SeptentrioDriver::output_data_rate() const { - return static_cast(_last_interval_bytes_written / us_to_s(static_cast(k_update_monitoring_interval_duration))); + return static_cast(_last_interval_bytes_written / us_to_s(static_cast + (k_update_monitoring_interval_duration))); } uint32_t SeptentrioDriver::input_data_rate() const { - return static_cast(_last_interval_bytes_read / us_to_s(static_cast(k_update_monitoring_interval_duration))); + return static_cast(_last_interval_bytes_read / us_to_s(static_cast + (k_update_monitoring_interval_duration))); } bool SeptentrioDriver::receiver_configuration_healthy() const { return _last_interval_messages.dop && - _last_interval_messages.pvt_geodetic && - _last_interval_messages.vel_cov_geodetic && - _last_interval_messages.att_euler && - _last_interval_messages.att_cov_euler; + _last_interval_messages.pvt_geodetic && + _last_interval_messages.vel_cov_geodetic && + _last_interval_messages.att_euler && + _last_interval_messages.att_cov_euler; } float SeptentrioDriver::us_to_s(uint64_t us) diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index aeeba755e30c..5b50bdaf5b3b 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -1317,27 +1317,25 @@ int GPS::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -GPS driver module that handles the communication with the device and publishes the position via uORB. -It supports multiple protocols (device vendors) and by default automatically selects the correct one. - -The module supports a secondary GPS device, specified via `-e` parameter. The position will be published -on the second uORB topic instance, but it's currently not used by the rest of the system (however the -data will be logged, so that it can be used for comparisons). - -### Implementation -There is a thread for each device polling for data. The GPS protocol classes are implemented with callbacks -so that they can be used in other projects as well (eg. QGroundControl uses them too). - -### Examples - -Starting 2 GPS devices (the main GPS on /dev/ttyS3 and the secondary on /dev/ttyS4): -$ gps start -d /dev/ttyS3 -e /dev/ttyS4 - -Initiate warm restart of GPS device -$ gps reset warm -)DESCR_STR"); + "### Description\n" + "GPS driver module that handles the communication with the device and publishes the position via uORB.\n" + "It supports multiple protocols (device vendors) and by default automatically selects the correct one.\n" + "\n" + "The module supports a secondary GPS device, specified via `-e` parameter. The position will be published\n" + "on the second uORB topic instance, but it's currently not used by the rest of the system (however the\n" + "data will be logged, so that it can be used for comparisons).\n" + "\n" + "### Implementation\n" + "There is a thread for each device polling for data. The GPS protocol classes are implemented with callbacks\n" + "so that they can be used in other projects as well (eg. QGroundControl uses them too).\n" + "\n" + "### Examples\n" + "\n" + "Starting 2 GPS devices (the main GPS on /dev/ttyS3 and the secondary on /dev/ttyS4):\n" + "$ gps start -d /dev/ttyS3 -e /dev/ttyS4\n" + "\n" + "Initiate warm restart of GPS device\n" + "$ gps reset warm"); PRINT_MODULE_USAGE_NAME("gps", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); @@ -1365,15 +1363,17 @@ int GPS::task_spawn(int argc, char *argv[]) int GPS::task_spawn(int argc, char *argv[], Instance instance) { px4_main_t entry_point; + if (instance == Instance::Main) { entry_point = (px4_main_t)&run_trampoline; + } else { entry_point = (px4_main_t)&run_trampoline_secondary; } int task_id = px4_task_spawn_cmd("gps", SCHED_DEFAULT, - SCHED_PRIORITY_SLOW_DRIVER, TASK_STACK_SIZE, - entry_point, (char *const *)argv); + SCHED_PRIORITY_SLOW_DRIVER, TASK_STACK_SIZE, + entry_point, (char *const *)argv); if (task_id < 0) { _task_id = -1; @@ -1394,6 +1394,7 @@ int GPS::run_trampoline_secondary(int argc, char *argv[]) argv += 1; GPS *gps = instantiate(argc, argv, Instance::Secondary); + if (gps) { _secondary_instance.store(gps); gps->run(); @@ -1401,6 +1402,7 @@ int GPS::run_trampoline_secondary(int argc, char *argv[]) _secondary_instance.store(nullptr); delete gps; } + return 0; } GPS *GPS::instantiate(int argc, char *argv[]) @@ -1430,12 +1432,15 @@ GPS *GPS::instantiate(int argc, char *argv[], Instance instance) PX4_ERR("baudrate parsing failed"); error_flag = true; } + break; + case 'g': if (px4_get_parameter_value(myoptarg, baudrate_secondary) != 0) { PX4_ERR("baudrate parsing failed"); error_flag = true; } + break; case 'd': @@ -1450,32 +1455,39 @@ GPS *GPS::instantiate(int argc, char *argv[], Instance instance) if (!strcmp(myoptarg, "uart")) { interface = GPSHelper::Interface::UART; #ifdef __PX4_LINUX + } else if (!strcmp(myoptarg, "spi")) { interface = GPSHelper::Interface::SPI; #endif + } else { PX4_ERR("unknown interface: %s", myoptarg); error_flag = true; } + break; case 'j': if (!strcmp(myoptarg, "uart")) { interface_secondary = GPSHelper::Interface::UART; #ifdef __PX4_LINUX + } else if (!strcmp(myoptarg, "spi")) { interface_secondary = GPSHelper::Interface::SPI; #endif + } else { PX4_ERR("unknown interface for secondary: %s", myoptarg); error_flag = true; } + break; case 'p': if (!strcmp(myoptarg, "ubx")) { mode = gps_driver_mode_t::UBX; #ifndef CONSTRAINED_FLASH + } else if (!strcmp(myoptarg, "mtk")) { mode = gps_driver_mode_t::MTK; @@ -1492,10 +1504,12 @@ GPS *GPS::instantiate(int argc, char *argv[], Instance instance) mode = gps_driver_mode_t::NMEA; #endif // CONSTRAINED_FLASH + } else { PX4_ERR("unknown protocol: %s", myoptarg); error_flag = true; } + break; case '?': @@ -1514,6 +1528,7 @@ GPS *GPS::instantiate(int argc, char *argv[], Instance instance) } GPS *gps = nullptr; + if (instance == Instance::Main) { if (Serial::validatePort(device_name)) { gps = new GPS(device_name, mode, interface, instance, baudrate_main); @@ -1537,6 +1552,7 @@ GPS *GPS::instantiate(int argc, char *argv[], Instance instance) PX4_ERR("Timed out while waiting for thread to start"); } } + } else { // secondary instance if (Serial::validatePort(device_name_secondary)) { gps = new GPS(device_name_secondary, mode, interface_secondary, instance, baudrate_secondary); diff --git a/src/drivers/heater/heater.cpp b/src/drivers/heater/heater.cpp index aba6f7066e40..cc993767652b 100644 --- a/src/drivers/heater/heater.cpp +++ b/src/drivers/heater/heater.cpp @@ -321,12 +321,10 @@ int Heater::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Background process running periodically on the LP work queue to regulate IMU temperature at a setpoint. - -This task can be started at boot from the startup scripts by setting SENS_EN_THERMAL or via CLI. -)DESCR_STR"); + "### Description\n" + "Background process running periodically on the LP work queue to regulate IMU temperature at a setpoint.\n" + "\n" + "This task can be started at boot from the startup scripts by setting SENS_EN_THERMAL or via CLI."); PRINT_MODULE_USAGE_NAME("heater", "system"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/hygrometer/sht3x/sht3x.cpp b/src/drivers/hygrometer/sht3x/sht3x.cpp index c029a90d767e..d1b0aa675bf8 100644 --- a/src/drivers/hygrometer/sht3x/sht3x.cpp +++ b/src/drivers/hygrometer/sht3x/sht3x.cpp @@ -289,25 +289,22 @@ void SHT3X::print_status() void SHT3X::print_usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -SHT3x Temperature and Humidity Sensor Driver by Senserion. - -### Examples -CLI usage example: -$ sht3x start -X - Start the sensor driver on the external bus - -$ sht3x status - Print driver status - -$ sht3x values - Print last measured values - -$ sht3x reset - Reinitialize senzor, reset flags - -)DESCR_STR"); + "### Description\n" + "SHT3x Temperature and Humidity Sensor Driver by Senserion.\n" + "\n" + "### Examples\n" + "CLI usage example:\n" + "$ sht3x start -X\n" + "Start the sensor driver on the external bus\n" + "\n" + "$ sht3x status\n" + "Print driver status\n" + "\n" + "$ sht3x values\n" + "Print last measured values\n" + "\n" + "$ sht3x reset\n" + "Reinitialize senzor, reset flags"); PRINT_MODULE_USAGE_NAME("sht3x", "driver"); @@ -319,7 +316,7 @@ CLI usage example: PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); PRINT_MODULE_USAGE_COMMAND_DESCR("values", "Print actual data"); - PRINT_MODULE_USAGE_COMMAND_DESCR("reset", "Reinitialize sensor"); + PRINT_MODULE_USAGE_COMMAND_DESCR("reset", "Reinitialize sensor"); } diff --git a/src/drivers/ins/vectornav/VectorNav.cpp b/src/drivers/ins/vectornav/VectorNav.cpp index 85dd4c1846af..2844ed50f764 100644 --- a/src/drivers/ins/vectornav/VectorNav.cpp +++ b/src/drivers/ins/vectornav/VectorNav.cpp @@ -825,22 +825,20 @@ int VectorNav::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -Serial bus driver for the VectorNav VN-100, VN-200, VN-300. - -Most boards are configured to enable/start the driver on a specified UART using the SENS_VN_CFG parameter. - -Setup/usage information: https://docs.px4.io/main/en/sensor/vectornav.html - -### Examples - -Attempt to start driver on a specified serial device. -$ vectornav start -d /dev/ttyS1 -Stop driver -$ vectornav stop -)DESCR_STR"); + "### Description\n" + "\n" + "Serial bus driver for the VectorNav VN-100, VN-200, VN-300.\n" + "\n" + "Most boards are configured to enable/start the driver on a specified UART using the SENS_VN_CFG parameter.\n" + "\n" + "Setup/usage information: https://docs.px4.io/main/en/sensor/vectornav.html\n" + "\n" + "### Examples\n" + "\n" + "Attempt to start driver on a specified serial device.\n" + "$ vectornav start -d /dev/ttyS1\n" + "Stop driver\n" + "$ vectornav stop"); PRINT_MODULE_USAGE_NAME("vectornav", "driver"); PRINT_MODULE_USAGE_SUBCATEGORY("ins"); diff --git a/src/drivers/lights/neopixel/neopixel.cpp b/src/drivers/lights/neopixel/neopixel.cpp index f5ebacd6340e..0186282a7731 100644 --- a/src/drivers/lights/neopixel/neopixel.cpp +++ b/src/drivers/lights/neopixel/neopixel.cpp @@ -163,24 +163,22 @@ int NEOPIXEL::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This module is responsible for driving interfasing to the Neopixel Serial LED - -### Examples -It is typically started with: -$ neopixel -n 8 -To drive all available leds. -)DESCR_STR"); - -PRINT_MODULE_USAGE_NAME("newpixel", "driver"); -PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); -return 0; + "### Description\n" + "This module is responsible for driving interfasing to the Neopixel Serial LED\n" + "\n" + "### Examples\n" + "It is typically started with:\n" + "$ neopixel -n 8\n" + "To drive all available leds."); + + PRINT_MODULE_USAGE_NAME("newpixel", "driver"); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); + return 0; } int NEOPIXEL::custom_command(int argc, char *argv[]) { - return print_usage("unrecognized option"); + return print_usage("unrecognized option"); } /** @@ -188,56 +186,57 @@ int NEOPIXEL::custom_command(int argc, char *argv[]) */ void NEOPIXEL::Run() { - if (should_exit()) { - ScheduleClear(); - exit_and_cleanup(); - return; - } + if (should_exit()) { + ScheduleClear(); + exit_and_cleanup(); + return; + } LedControlData led_control_data; if (_led_controller.update(led_control_data) == 1) { - for (unsigned int led = 0; led < math::min(_number_of_packages, arraySize(led_control_data.leds)); led++) { + for (unsigned int led = 0; led < math::min(_number_of_packages, arraySize(led_control_data.leds)); led++) { - uint8_t brightness = led_control_data.leds[led].brightness; + uint8_t brightness = led_control_data.leds[led].brightness; - switch (led_control_data.leds[led].color) { - case led_control_s::COLOR_RED: - _leds[led].R() = brightness; _leds[led].G() = 0; _leds[led].B() = 0; - break; + switch (led_control_data.leds[led].color) { + case led_control_s::COLOR_RED: + _leds[led].R() = brightness; _leds[led].G() = 0; _leds[led].B() = 0; + break; - case led_control_s::COLOR_GREEN: - _leds[led].R() = 0; _leds[led].G() = brightness; _leds[led].B() = 0; - break; + case led_control_s::COLOR_GREEN: + _leds[led].R() = 0; _leds[led].G() = brightness; _leds[led].B() = 0; + break; - case led_control_s::COLOR_BLUE: - _leds[led].R() = 0; _leds[led].G() = 0; _leds[led].B() = brightness; - break; + case led_control_s::COLOR_BLUE: + _leds[led].R() = 0; _leds[led].G() = 0; _leds[led].B() = brightness; + break; - case led_control_s::COLOR_AMBER: //make it the same as yellow - case led_control_s::COLOR_YELLOW: - _leds[led].R() = brightness; _leds[led].G() = brightness; _leds[led].B() = 0; - break; + case led_control_s::COLOR_AMBER: //make it the same as yellow + case led_control_s::COLOR_YELLOW: + _leds[led].R() = brightness; _leds[led].G() = brightness; _leds[led].B() = 0; + break; - case led_control_s::COLOR_PURPLE: - _leds[led].R() = brightness; _leds[led].G() = 0; _leds[led].B() = brightness; - break; + case led_control_s::COLOR_PURPLE: + _leds[led].R() = brightness; _leds[led].G() = 0; _leds[led].B() = brightness; + break; - case led_control_s::COLOR_CYAN: - _leds[led].R() = 0; _leds[led].G() = brightness; _leds[led].B() = brightness; - break; + case led_control_s::COLOR_CYAN: + _leds[led].R() = 0; _leds[led].G() = brightness; _leds[led].B() = brightness; + break; - case led_control_s::COLOR_WHITE: - _leds[led].R() = brightness; _leds[led].G() = brightness; _leds[led].B() = brightness; - break; + case led_control_s::COLOR_WHITE: + _leds[led].R() = brightness; _leds[led].G() = brightness; _leds[led].B() = brightness; + break; + + default: // led_control_s::COLOR_OFF + _leds[led].R() = 0; _leds[led].G() = 0; _leds[led].B() = 0; + break; + } + } - default: // led_control_s::COLOR_OFF - _leds[led].R() = 0; _leds[led].G() = 0; _leds[led].B() = 0; - break; - } - } - neopixel_write(_leds, _number_of_packages); + neopixel_write(_leds, _number_of_packages); } /* re-queue ourselves to run again later */ @@ -246,5 +245,5 @@ void NEOPIXEL::Run() extern "C" __EXPORT int neopixel_main(int argc, char *argv[]) { - return NEOPIXEL::main(argc, argv); + return NEOPIXEL::main(argc, argv); } diff --git a/src/drivers/lights/rgbled_lp5562/rgbled_lp5562.cpp b/src/drivers/lights/rgbled_lp5562/rgbled_lp5562.cpp index 7d795d105c62..ffb60892334c 100644 --- a/src/drivers/lights/rgbled_lp5562/rgbled_lp5562.cpp +++ b/src/drivers/lights/rgbled_lp5562/rgbled_lp5562.cpp @@ -259,14 +259,12 @@ void RGBLED_LP5562::print_usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Driver for [LP5562](https://www.ti.com/product/LP5562) LED driver connected via I2C. - -This used in some GPS modules by Holybro for [PX4 status notification](../getting_started/led_meanings.md) - -The driver is included by default in firmware (KConfig key DRIVERS_LIGHTS_RGBLED_LP5562) and is always enabled. -)DESCR_STR"); + "### Description\n" + "Driver for [LP5562](https://www.ti.com/product/LP5562) LED driver connected via I2C.\n" + "\n" + "This used in some GPS modules by Holybro for [PX4 status notification](../getting_started/led_meanings.md)\n" + "\n" + "The driver is included by default in firmware (KConfig key DRIVERS_LIGHTS_RGBLED_LP5562) and is always enabled."); PRINT_MODULE_USAGE_NAME("rgbled_lp5562", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false); diff --git a/src/drivers/linux_pwm_out/linux_pwm_out.cpp b/src/drivers/linux_pwm_out/linux_pwm_out.cpp index 771297305126..de00759eb778 100644 --- a/src/drivers/linux_pwm_out/linux_pwm_out.cpp +++ b/src/drivers/linux_pwm_out/linux_pwm_out.cpp @@ -152,10 +152,8 @@ int LinuxPWMOut::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Linux PWM output driver with board-specific backend implementation. -)DESCR_STR"); + "### Description\n" + "Linux PWM output driver with board-specific backend implementation."); PRINT_MODULE_USAGE_NAME("linux_pwm_out", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/optical_flow/thoneflow/thoneflow.cpp b/src/drivers/optical_flow/thoneflow/thoneflow.cpp index 71110f040375..440dc1aaa072 100644 --- a/src/drivers/optical_flow/thoneflow/thoneflow.cpp +++ b/src/drivers/optical_flow/thoneflow/thoneflow.cpp @@ -421,79 +421,77 @@ void usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description + "### Description\n" + "\n" + "Serial bus driver for the ThoneFlow-3901U optical flow sensor.\n" + "\n" + "Most boards are configured to enable/start the driver on a specified UART using the SENS_TFLOW_CFG parameter.\n" + "\n" + "Setup/usage information: https://docs.px4.io/main/en/sensor/pmw3901.html#thone-thoneflow-3901u\n" + "\n" + "### Examples\n" + "\n" + "Attempt to start driver on a specified serial device.\n" + "$ thoneflow start -d /dev/ttyS1\n" + "Stop driver\n" + "$ thoneflow stop"); + + PRINT_MODULE_USAGE_NAME("thoneflow", "driver"); + PRINT_MODULE_USAGE_SUBCATEGORY("optical_flow"); + PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start driver"); + PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, nullptr, "Serial device", false); + PRINT_MODULE_USAGE_COMMAND_DESCR("stop", "Stop driver"); + PRINT_MODULE_USAGE_COMMAND_DESCR("info", "Print driver information"); +} -Serial bus driver for the ThoneFlow-3901U optical flow sensor. +} // namespace -Most boards are configured to enable/start the driver on a specified UART using the SENS_TFLOW_CFG parameter. +extern "C" __EXPORT int thoneflow_main(int argc, char *argv[]) +{ + int ch; + const char *device_path = ""; + int myoptind = 1; + const char *myoptarg = nullptr; + + while ((ch = px4_getopt(argc, argv, "d:", &myoptind, &myoptarg)) != EOF) { + switch (ch) { + case 'd': + device_path = myoptarg; + break; -Setup/usage information: https://docs.px4.io/main/en/sensor/pmw3901.html#thone-thoneflow-3901u + default: + PX4_WARN("Unknown option!"); + return -1; + } + } -### Examples + if (myoptind >= argc) { + goto out_error; + } -Attempt to start driver on a specified serial device. -$ thoneflow start -d /dev/ttyS1 -Stop driver -$ thoneflow stop -)DESCR_STR"); + /* + * Start/load the driver. + */ + if (!strcmp(argv[myoptind], "start")) { + if (strcmp(device_path, "") != 0) { + return thoneflow::start(device_path); - PRINT_MODULE_USAGE_NAME("thoneflow", "driver"); - PRINT_MODULE_USAGE_SUBCATEGORY("optical_flow"); - PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start driver"); - PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, nullptr, "Serial device", false); - PRINT_MODULE_USAGE_COMMAND_DESCR("stop", "Stop driver"); - PRINT_MODULE_USAGE_COMMAND_DESCR("info", "Print driver information"); -} + } else { + PX4_WARN("Please specify device path!"); + thoneflow::usage(); + return -1; + } -} // namespace + } else if (!strcmp(argv[myoptind], "stop")) { + return thoneflow::stop(); -extern "C" __EXPORT int thoneflow_main(int argc, char *argv[]) -{ - int ch; - const char *device_path = ""; - int myoptind = 1; - const char *myoptarg = nullptr; - - while ((ch = px4_getopt(argc, argv, "d:", &myoptind, &myoptarg)) != EOF) { - switch (ch) { - case 'd': - device_path = myoptarg; - break; - - default: - PX4_WARN("Unknown option!"); - return -1; - } - } - - if (myoptind >= argc) { - goto out_error; - } - - /* - * Start/load the driver. - */ - if (!strcmp(argv[myoptind], "start")) { - if (strcmp(device_path, "") != 0) { - return thoneflow::start(device_path); - - } else { - PX4_WARN("Please specify device path!"); - thoneflow::usage(); - return -1; - } - - } else if (!strcmp(argv[myoptind], "stop")) { - return thoneflow::stop(); - - } else if (!strcmp(argv[myoptind], "info") || !strcmp(argv[myoptind], "status")) { - thoneflow::info(); - return 0; - } + } else if (!strcmp(argv[myoptind], "info") || !strcmp(argv[myoptind], "status")) { + thoneflow::info(); + return 0; + } out_error: - PX4_ERR("unrecognized command"); - thoneflow::usage(); - return -1; + PX4_ERR("unrecognized command"); + thoneflow::usage(); + return -1; } diff --git a/src/drivers/osd/atxxxx/atxxxx.cpp b/src/drivers/osd/atxxxx/atxxxx.cpp index a5acabd3919d..4348bdadd492 100644 --- a/src/drivers/osd/atxxxx/atxxxx.cpp +++ b/src/drivers/osd/atxxxx/atxxxx.cpp @@ -489,12 +489,10 @@ void OSDatxxxx::print_usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -OSD driver for the ATXXXX chip that is mounted on the OmnibusF4SD board for example. - -It can be enabled with the OSD_ATXXXX_CFG parameter. -)DESCR_STR"); + "### Description\n" + "OSD driver for the ATXXXX chip that is mounted on the OmnibusF4SD board for example.\n" + "\n" + "It can be enabled with the OSD_ATXXXX_CFG parameter."); PRINT_MODULE_USAGE_NAME("atxxxx", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/osd/msp_osd/msp_osd.cpp b/src/drivers/osd/msp_osd/msp_osd.cpp index e6e7f236f72a..34dab6d9c17a 100644 --- a/src/drivers/osd/msp_osd/msp_osd.cpp +++ b/src/drivers/osd/msp_osd/msp_osd.cpp @@ -498,18 +498,15 @@ int MspOsd::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -MSP telemetry streamer - -### Implementation -Converts uORB messages to MSP telemetry packets - -### Examples -CLI usage example: -$ msp_osd - -)DESCR_STR"); + "### Description\n" + "MSP telemetry streamer\n" + "\n" + "### Implementation\n" + "Converts uORB messages to MSP telemetry packets\n" + "\n" + "### Examples\n" + "CLI usage example:\n" + "$ msp_osd"); PRINT_MODULE_USAGE_NAME("msp_osd", "driver"); PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); diff --git a/src/drivers/pca9685_pwm_out/main.cpp b/src/drivers/pca9685_pwm_out/main.cpp index ffe53ce3e7b8..c1c9737d1424 100644 --- a/src/drivers/pca9685_pwm_out/main.cpp +++ b/src/drivers/pca9685_pwm_out/main.cpp @@ -246,137 +246,153 @@ int PCA9685Wrapper::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This is a PCA9685 PWM output driver. - -It runs on I2C workqueue which is asynchronous with FC control loop, -fetching the latest mixing result and write them to PCA9685 at its scheduling ticks. - -It can do full 12bits output as duty-cycle mode, while also able to output precious pulse width -that can be accepted by most ESCs and servos. - -### Examples -It is typically started with: -$ pca9685_pwm_out start -a 0x40 -b 1 - -)DESCR_STR"); - - PRINT_MODULE_USAGE_NAME("pca9685_pwm_out", "driver"); - PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start the task"); - PRINT_MODULE_USAGE_PARAM_STRING('a',"0x40","","7-bits I2C address of PCA9685",true); - PRINT_MODULE_USAGE_PARAM_INT('b',1,0,255,"bus that pca9685 is connected to",true); - PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); - - return 0; + "### Description\n" + "This is a PCA9685 PWM output driver.\n" + "\n" + "It runs on I2C workqueue which is asynchronous with FC control loop,\n" + "fetching the latest mixing result and write them to PCA9685 at its scheduling ticks.\n" + "\n" + "It can do full 12bits output as duty-cycle mode, while also able to output precious pulse width\n" + "that can be accepted by most ESCs and servos.\n" + "\n" + "### Examples\n" + "It is typically started with:\n" + "$ pca9685_pwm_out start -a 0x40 -b 1"); + + PRINT_MODULE_USAGE_NAME("pca9685_pwm_out", "driver"); + PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start the task"); + PRINT_MODULE_USAGE_PARAM_STRING('a', "0x40", "", "7-bits I2C address of PCA9685", true); + PRINT_MODULE_USAGE_PARAM_INT('b', 1, 0, 255, "bus that pca9685 is connected to", true); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); + + return 0; } -int PCA9685Wrapper::print_status() { - int ret = ModuleBase::print_status(); - PX4_INFO("PCA9685 @I2C Bus %d, address 0x%.2x, real frequency %.2f", - pca9685->get_device_bus(), - pca9685->get_device_address(), - (double)(pca9685->getFreq())); +int PCA9685Wrapper::print_status() +{ + int ret = ModuleBase::print_status(); + PX4_INFO("PCA9685 @I2C Bus %d, address 0x%.2x, real frequency %.2f", + pca9685->get_device_bus(), + pca9685->get_device_address(), + (double)(pca9685->getFreq())); - return ret; + return ret; } -int PCA9685Wrapper::custom_command(int argc, char **argv) { - return PX4_OK; +int PCA9685Wrapper::custom_command(int argc, char **argv) +{ + return PX4_OK; } -int PCA9685Wrapper::task_spawn(int argc, char **argv) { +int PCA9685Wrapper::task_spawn(int argc, char **argv) +{ int ch; - int address=PCA9685_DEFAULT_ADDRESS; - int iicbus=PCA9685_DEFAULT_IICBUS; + int address = PCA9685_DEFAULT_ADDRESS; + int iicbus = PCA9685_DEFAULT_IICBUS; int myoptind = 1; const char *myoptarg = nullptr; + while ((ch = px4_getopt(argc, argv, "a:b:", &myoptind, &myoptarg)) != EOF) { switch (ch) { - case 'a': - errno = 0; - address = strtol(myoptarg, nullptr, 16); - if (errno != 0) { - PX4_WARN("Invalid address"); - return PX4_ERROR; - } - break; - - case 'b': - iicbus = strtol(myoptarg, nullptr, 10); - if (errno != 0) { - PX4_WARN("Invalid bus"); - return PX4_ERROR; - } - break; - - case '?': - PX4_WARN("Unsupported args"); + case 'a': + errno = 0; + address = strtol(myoptarg, nullptr, 16); + + if (errno != 0) { + PX4_WARN("Invalid address"); return PX4_ERROR; + } + + break; + + case 'b': + iicbus = strtol(myoptarg, nullptr, 10); + + if (errno != 0) { + PX4_WARN("Invalid bus"); + return PX4_ERROR; + } + + break; + + case '?': + PX4_WARN("Unsupported args"); + return PX4_ERROR; + + default: + break; + } + } - default: - break; + auto *instance = new PCA9685Wrapper(); + + if (instance) { + _object.store(instance); + _task_id = task_id_is_work_queue; + + instance->pca9685 = new PCA9685(iicbus, address); + + if (instance->pca9685 == nullptr) { + PX4_ERR("alloc failed"); + goto driverInstanceAllocFailed; + } + + if (instance->init() == PX4_OK) { + return PX4_OK; + + } else { + PX4_ERR("driver init failed"); + delete instance->pca9685; + instance->pca9685 = nullptr; } + + } else { + PX4_ERR("alloc failed"); + return PX4_ERROR; } - auto *instance = new PCA9685Wrapper(); - - if (instance) { - _object.store(instance); - _task_id = task_id_is_work_queue; - - instance->pca9685 = new PCA9685(iicbus, address); - if(instance->pca9685==nullptr){ - PX4_ERR("alloc failed"); - goto driverInstanceAllocFailed; - } - - if (instance->init() == PX4_OK) { - return PX4_OK; - } else { - PX4_ERR("driver init failed"); - delete instance->pca9685; - instance->pca9685=nullptr; - } - } else { - PX4_ERR("alloc failed"); - return PX4_ERROR; - } - - driverInstanceAllocFailed: - delete instance; - _object.store(nullptr); - _task_id = -1; - - return PX4_ERROR; +driverInstanceAllocFailed: + delete instance; + _object.store(nullptr); + _task_id = -1; + + return PX4_ERROR; } -void PCA9685Wrapper::updateParams() { - ModuleParams::updateParams(); - - param_t param = param_find("PCA9685_SCHD_HZ"); - if (param != PARAM_INVALID) { - param_get(param, ¶m_schd_rate); - } else { - PX4_ERR("param PCA9685_SCHD_HZ not found"); - } - - param = param_find("PCA9685_PWM_FREQ"); - if (param != PARAM_INVALID) { - param_get(param, ¶m_pwm_freq); - } else { - PX4_ERR("param PCA9685_PWM_FREQ not found"); - } - - param = param_find("PCA9685_DUTY_EN"); - if (param != PARAM_INVALID) { - param_get(param, (int32_t*)¶m_duty_mode); - } else { - PX4_ERR("param PCA9685_DUTY_EN not found"); - } +void PCA9685Wrapper::updateParams() +{ + ModuleParams::updateParams(); + + param_t param = param_find("PCA9685_SCHD_HZ"); + + if (param != PARAM_INVALID) { + param_get(param, ¶m_schd_rate); + + } else { + PX4_ERR("param PCA9685_SCHD_HZ not found"); + } + + param = param_find("PCA9685_PWM_FREQ"); + + if (param != PARAM_INVALID) { + param_get(param, ¶m_pwm_freq); + + } else { + PX4_ERR("param PCA9685_PWM_FREQ not found"); + } + + param = param_find("PCA9685_DUTY_EN"); + + if (param != PARAM_INVALID) { + param_get(param, (int32_t *)¶m_duty_mode); + + } else { + PX4_ERR("param PCA9685_DUTY_EN not found"); + } } -extern "C" __EXPORT int pca9685_pwm_out_main(int argc, char *argv[]){ +extern "C" __EXPORT int pca9685_pwm_out_main(int argc, char *argv[]) +{ return PCA9685Wrapper::main(argc, argv); } diff --git a/src/drivers/power_monitor/ina220/ina220_main.cpp b/src/drivers/power_monitor/ina220/ina220_main.cpp index fba9c3657b85..639757e6e82e 100644 --- a/src/drivers/power_monitor/ina220/ina220_main.cpp +++ b/src/drivers/power_monitor/ina220/ina220_main.cpp @@ -61,20 +61,17 @@ void INA220::print_usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Driver for the INA220 power monitor. - -Multiple instances of this driver can run simultaneously, if each instance has a separate bus OR I2C address. - -For example, one instance can run on Bus 2, address 0x41, and one can run on Bus 2, address 0x43. - -If the INA220 module is not powered, then by default, initialization of the driver will fail. To change this, use -the -f flag. If this flag is set, then if initialization fails, the driver will keep trying to initialize again -every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without -this flag set, the battery must be plugged in before starting the driver. - -)DESCR_STR"); + "### Description\n" + "Driver for the INA220 power monitor.\n" + "\n" + "Multiple instances of this driver can run simultaneously, if each instance has a separate bus OR I2C address.\n" + "\n" + "For example, one instance can run on Bus 2, address 0x41, and one can run on Bus 2, address 0x43.\n" + "\n" + "If the INA220 module is not powered, then by default, initialization of the driver will fail. To change this, use\n" + "the -f flag. If this flag is set, then if initialization fails, the driver will keep trying to initialize again\n" + "every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without\n" + "this flag set, the battery must be plugged in before starting the driver."); PRINT_MODULE_USAGE_NAME("ina220", "driver"); @@ -99,11 +96,13 @@ ina220_main(int argc, char *argv[]) cli.custom1 = 1; cli.custom2 = PM_CH_TYPE_VBATT; + while ((ch = cli.getOpt(argc, argv, "T:")) != EOF) { switch (ch) { case 't': // battery index cli.custom1 = (int)strtol(cli.optArg(), NULL, 0); break; + case 'T': if (strcmp(cli.optArg(), "VBATT") == 0) { cli.custom2 = PM_CH_TYPE_VBATT; @@ -121,6 +120,7 @@ ina220_main(int argc, char *argv[]) } const char *verb = cli.optArg(); + if (!verb) { ThisDriver::print_usage(); return -1; diff --git a/src/drivers/power_monitor/ina226/ina226_main.cpp b/src/drivers/power_monitor/ina226/ina226_main.cpp index a02095e3fb22..f2b1daefae3d 100644 --- a/src/drivers/power_monitor/ina226/ina226_main.cpp +++ b/src/drivers/power_monitor/ina226/ina226_main.cpp @@ -61,20 +61,17 @@ void INA226::print_usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Driver for the INA226 power monitor. - -Multiple instances of this driver can run simultaneously, if each instance has a separate bus OR I2C address. - -For example, one instance can run on Bus 2, address 0x41, and one can run on Bus 2, address 0x43. - -If the INA226 module is not powered, then by default, initialization of the driver will fail. To change this, use -the -f flag. If this flag is set, then if initialization fails, the driver will keep trying to initialize again -every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without -this flag set, the battery must be plugged in before starting the driver. - -)DESCR_STR"); + "### Description\n" + "Driver for the INA226 power monitor.\n" + "\n" + "Multiple instances of this driver can run simultaneously, if each instance has a separate bus OR I2C address.\n" + "\n" + "For example, one instance can run on Bus 2, address 0x41, and one can run on Bus 2, address 0x43.\n" + "\n" + "If the INA226 module is not powered, then by default, initialization of the driver will fail. To change this, use\n" + "the -f flag. If this flag is set, then if initialization fails, the driver will keep trying to initialize again\n" + "every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without\n" + "this flag set, the battery must be plugged in before starting the driver."); PRINT_MODULE_USAGE_NAME("ina226", "driver"); @@ -106,6 +103,7 @@ ina226_main(int argc, char *argv[]) } const char *verb = cli.optArg(); + if (!verb) { ThisDriver::print_usage(); return -1; diff --git a/src/drivers/power_monitor/ina228/ina228_main.cpp b/src/drivers/power_monitor/ina228/ina228_main.cpp index cf7d49ddd8b0..04849045143c 100644 --- a/src/drivers/power_monitor/ina228/ina228_main.cpp +++ b/src/drivers/power_monitor/ina228/ina228_main.cpp @@ -61,20 +61,17 @@ void INA228::print_usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Driver for the INA228 power monitor. - -Multiple instances of this driver can run simultaneously, if each instance has a separate bus OR I2C address. - -For example, one instance can run on Bus 2, address 0x45, and one can run on Bus 2, address 0x45. - -If the INA228 module is not powered, then by default, initialization of the driver will fail. To change this, use -the -f flag. If this flag is set, then if initialization fails, the driver will keep trying to initialize again -every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without -this flag set, the battery must be plugged in before starting the driver. - -)DESCR_STR"); + "### Description\n" + "Driver for the INA228 power monitor.\n" + "\n" + "Multiple instances of this driver can run simultaneously, if each instance has a separate bus OR I2C address.\n" + "\n" + "For example, one instance can run on Bus 2, address 0x45, and one can run on Bus 2, address 0x45.\n" + "\n" + "If the INA228 module is not powered, then by default, initialization of the driver will fail. To change this, use\n" + "the -f flag. If this flag is set, then if initialization fails, the driver will keep trying to initialize again\n" + "every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without\n" + "this flag set, the battery must be plugged in before starting the driver."); PRINT_MODULE_USAGE_NAME("ina228", "driver"); @@ -106,6 +103,7 @@ ina228_main(int argc, char *argv[]) } const char *verb = cli.optArg(); + if (!verb) { ThisDriver::print_usage(); return -1; diff --git a/src/drivers/power_monitor/ina238/ina238_main.cpp b/src/drivers/power_monitor/ina238/ina238_main.cpp index 608c03313062..dca6fc285e68 100644 --- a/src/drivers/power_monitor/ina238/ina238_main.cpp +++ b/src/drivers/power_monitor/ina238/ina238_main.cpp @@ -61,20 +61,17 @@ void INA238::print_usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Driver for the INA238 power monitor. - -Multiple instances of this driver can run simultaneously, if each instance has a separate bus OR I2C address. - -For example, one instance can run on Bus 2, address 0x45, and one can run on Bus 2, address 0x45. - -If the INA238 module is not powered, then by default, initialization of the driver will fail. To change this, use -the -f flag. If this flag is set, then if initialization fails, the driver will keep trying to initialize again -every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without -this flag set, the battery must be plugged in before starting the driver. - -)DESCR_STR"); + "### Description\n" + "Driver for the INA238 power monitor.\n" + "\n" + "Multiple instances of this driver can run simultaneously, if each instance has a separate bus OR I2C address.\n" + "\n" + "For example, one instance can run on Bus 2, address 0x45, and one can run on Bus 2, address 0x45.\n" + "\n" + "If the INA238 module is not powered, then by default, initialization of the driver will fail. To change this, use\n" + "the -f flag. If this flag is set, then if initialization fails, the driver will keep trying to initialize again\n" + "every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without\n" + "this flag set, the battery must be plugged in before starting the driver."); PRINT_MODULE_USAGE_NAME("ina238", "driver"); @@ -106,6 +103,7 @@ ina238_main(int argc, char *argv[]) } const char *verb = cli.optArg(); + if (!verb) { ThisDriver::print_usage(); return -1; diff --git a/src/drivers/power_monitor/pm_selector_auterion/PowerMonitorSelectorAuterion.cpp b/src/drivers/power_monitor/pm_selector_auterion/PowerMonitorSelectorAuterion.cpp index baa54bcd7038..e9dfa3e4735c 100644 --- a/src/drivers/power_monitor/pm_selector_auterion/PowerMonitorSelectorAuterion.cpp +++ b/src/drivers/power_monitor/pm_selector_auterion/PowerMonitorSelectorAuterion.cpp @@ -196,11 +196,8 @@ int PowerMonitorSelectorAuterion::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Driver for starting and auto-detecting different power monitors. - -)DESCR_STR"); + "### Description\n" + "Driver for starting and auto-detecting different power monitors."); PRINT_MODULE_USAGE_NAME("pm_selector_auterion", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/pps_capture/PPSCapture.cpp b/src/drivers/pps_capture/PPSCapture.cpp index 9bb8d47fba8d..1dc14903364a 100644 --- a/src/drivers/pps_capture/PPSCapture.cpp +++ b/src/drivers/pps_capture/PPSCapture.cpp @@ -200,11 +200,8 @@ int PPSCapture::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This implements capturing PPS information from the GNSS module and calculates the drift between PPS and Real-time clock. - -)DESCR_STR"); + "### Description\n" + "This implements capturing PPS information from the GNSS module and calculates the drift between PPS and Real-time clock."); PRINT_MODULE_USAGE_NAME("pps_capture", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/pwm_input/pwm_input.cpp b/src/drivers/pwm_input/pwm_input.cpp index b5df8f3cc6f7..2ccc6a49b883 100644 --- a/src/drivers/pwm_input/pwm_input.cpp +++ b/src/drivers/pwm_input/pwm_input.cpp @@ -197,11 +197,8 @@ PWMIN::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Measures the PWM input on AUX5 (or MAIN5) via a timer capture ISR and publishes via the uORB 'pwm_input` message. - -)DESCR_STR"); + "### Description\n" + "Measures the PWM input on AUX5 (or MAIN5) via a timer capture ISR and publishes via the uORB 'pwm_input` message."); PRINT_MODULE_USAGE_NAME("pwm_input", "system"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/pwm_out/PWMOut.cpp b/src/drivers/pwm_out/PWMOut.cpp index 0a3cbad4cad3..c1f6cdb04581 100644 --- a/src/drivers/pwm_out/PWMOut.cpp +++ b/src/drivers/pwm_out/PWMOut.cpp @@ -315,13 +315,10 @@ int PWMOut::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This module is responsible for driving the output pins. For boards without a separate IO chip -(eg. Pixracer), it uses the main channels. On boards with an IO chip (eg. Pixhawk), it uses the AUX channels, and the -px4io driver is used for main ones. - -)DESCR_STR"); + "### Description\n" + "This module is responsible for driving the output pins. For boards without a separate IO chip\n" + "(eg. Pixracer), it uses the main channels. On boards with an IO chip (eg. Pixhawk), it uses the AUX channels, and the\n" + "px4io driver is used for main ones."); PRINT_MODULE_USAGE_NAME("pwm_out", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 52ad8325144e..d50c8001ab65 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1727,10 +1727,8 @@ int PX4IO::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Output driver communicating with the IO co-processor. -)DESCR_STR"); + "### Description\n" + "Output driver communicating with the IO co-processor."); PRINT_MODULE_USAGE_NAME("px4io", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); @@ -1761,5 +1759,6 @@ extern "C" __EXPORT int px4io_main(int argc, char *argv[]) PX4_INFO("PX4IO Not Supported"); return -1; } + return PX4IO::main(argc, argv); } diff --git a/src/drivers/rc/crsf_rc/CrsfRc.cpp b/src/drivers/rc/crsf_rc/CrsfRc.cpp index 3ea6c0ac273d..2dbe3a77b50d 100644 --- a/src/drivers/rc/crsf_rc/CrsfRc.cpp +++ b/src/drivers/rc/crsf_rc/CrsfRc.cpp @@ -519,11 +519,8 @@ int CrsfRc::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This module parses the CRSF RC uplink protocol and generates CRSF downlink telemetry data - -)DESCR_STR"); + "### Description\n" + "This module parses the CRSF RC uplink protocol and generates CRSF downlink telemetry data"); PRINT_MODULE_USAGE_NAME("crsf_rc", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/rc/dsm_rc/DsmRc.cpp b/src/drivers/rc/dsm_rc/DsmRc.cpp index f35bc4487ff0..792545af5b13 100644 --- a/src/drivers/rc/dsm_rc/DsmRc.cpp +++ b/src/drivers/rc/dsm_rc/DsmRc.cpp @@ -392,11 +392,8 @@ int DsmRc::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This module does Spektrum DSM RC input parsing. - -)DESCR_STR"); + "### Description\n" + "This module does Spektrum DSM RC input parsing."); PRINT_MODULE_USAGE_NAME("dsm_rc", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/rc/ghst_rc/GhstRc.cpp b/src/drivers/rc/ghst_rc/GhstRc.cpp index 1960c84ce6d4..b6e930ed2687 100644 --- a/src/drivers/rc/ghst_rc/GhstRc.cpp +++ b/src/drivers/rc/ghst_rc/GhstRc.cpp @@ -284,11 +284,8 @@ int GhstRc::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This module does Ghost (GHST) RC input parsing. - -)DESCR_STR"); + "### Description\n" + "This module does Ghost (GHST) RC input parsing."); PRINT_MODULE_USAGE_NAME("ghst_rc", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/rc/sbus_rc/SbusRc.cpp b/src/drivers/rc/sbus_rc/SbusRc.cpp index 12d57da141e1..1026b901fd0c 100644 --- a/src/drivers/rc/sbus_rc/SbusRc.cpp +++ b/src/drivers/rc/sbus_rc/SbusRc.cpp @@ -295,11 +295,8 @@ int SbusRc::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This module does SBUS RC input parsing. - -)DESCR_STR"); + "### Description\n" + "This module does SBUS RC input parsing."); PRINT_MODULE_USAGE_NAME("sbus_rc", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/rc_input/RCInput.cpp b/src/drivers/rc_input/RCInput.cpp index 12cd1ab0bf40..e1f5f302c910 100644 --- a/src/drivers/rc_input/RCInput.cpp +++ b/src/drivers/rc_input/RCInput.cpp @@ -974,17 +974,14 @@ RCInput::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This module does the RC input parsing and auto-selecting the method. Supported methods are: -- PPM -- SBUS -- DSM -- SUMD -- ST24 -- TBS Crossfire (CRSF) - -)DESCR_STR"); + "### Description\n" + "This module does the RC input parsing and auto-selecting the method. Supported methods are:\n" + "- PPM\n" + "- SBUS\n" + "- DSM\n" + "- SUMD\n" + "- ST24\n" + "- TBS Crossfire (CRSF)"); PRINT_MODULE_USAGE_NAME("rc_input", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/roboclaw/Roboclaw.cpp b/src/drivers/roboclaw/Roboclaw.cpp index d4aeeee5d3ee..5224005a656b 100644 --- a/src/drivers/roboclaw/Roboclaw.cpp +++ b/src/drivers/roboclaw/Roboclaw.cpp @@ -511,22 +511,21 @@ int Roboclaw::print_usage(const char *reason) PX4_WARN("%s\n", reason); } - PRINT_MODULE_DESCRIPTION(R"DESCR_STR( -### Description - -This driver communicates over UART with the [Roboclaw motor driver](https://www.basicmicro.com/motor-controller). -It performs two tasks: - - - Control the motors based on the OutputModuleInterface. - - Read the wheel encoders and publish the raw data in the `wheel_encoders` uORB topic - -In order to use this driver, the Roboclaw should be put into Packet Serial mode (see the linked documentation), and -your flight controller's UART port should be connected to the Roboclaw as shown in the documentation. -The driver needs to be enabled using the parameter `RBCLW_SER_CFG`, the baudrate needs to be set correctly and -the address `RBCLW_ADDRESS` needs to match the ESC configuration. - -The command to start this driver is: `$ roboclaw start ` -)DESCR_STR"); + PRINT_MODULE_DESCRIPTION( + "### Description\n" + "\n" + "This driver communicates over UART with the [Roboclaw motor driver](https://www.basicmicro.com/motor-controller).\n" + "It performs two tasks:\n" + "\n" + "- Control the motors based on the OutputModuleInterface.\n" + "- Read the wheel encoders and publish the raw data in the `wheel_encoders` uORB topic\n" + "\n" + "In order to use this driver, the Roboclaw should be put into Packet Serial mode (see the linked documentation), and\n" + "your flight controller's UART port should be connected to the Roboclaw as shown in the documentation.\n" + "The driver needs to be enabled using the parameter `RBCLW_SER_CFG`, the baudrate needs to be set correctly and\n" + "the address `RBCLW_ADDRESS` needs to match the ESC configuration.\n" + "\n" + "The command to start this driver is: `$ roboclaw start `"); PRINT_MODULE_USAGE_NAME("roboclaw", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/safety_button/SafetyButton.cpp b/src/drivers/safety_button/SafetyButton.cpp index aa5c45e8d921..150386c83336 100644 --- a/src/drivers/safety_button/SafetyButton.cpp +++ b/src/drivers/safety_button/SafetyButton.cpp @@ -211,12 +211,9 @@ SafetyButton::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This module is responsible for the safety button. -Pressing the safety button 3 times quickly will trigger a GCS pairing request. - -)DESCR_STR"); + "### Description\n" + "This module is responsible for the safety button.\n" + "Pressing the safety button 3 times quickly will trigger a GCS pairing request."); PRINT_MODULE_USAGE_NAME("safety_button", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/smart_battery/batmon/batmon.cpp b/src/drivers/smart_battery/batmon/batmon.cpp index 9061a6d3e4aa..f9d567ae5cb7 100644 --- a/src/drivers/smart_battery/batmon/batmon.cpp +++ b/src/drivers/smart_battery/batmon/batmon.cpp @@ -96,15 +96,12 @@ I2CSPIDriverBase *Batmon::instantiate(const I2CSPIDriverConfig &config, int runt void Batmon::print_usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Driver for SMBUS Communication with BatMon enabled smart-battery -Setup/usage information: https://rotoye.com/batmon-tutorial/ -### Examples -To start at address 0x0B, on bus 4 -$ batmon start -X -a 11 -b 4 - -)DESCR_STR"); + "### Description\n" + "Driver for SMBUS Communication with BatMon enabled smart-battery\n" + "Setup/usage information: https://rotoye.com/batmon-tutorial/\n" + "### Examples\n" + "To start at address 0x0B, on bus 4\n" + "$ batmon start -X -a 11 -b 4"); PRINT_MODULE_USAGE_NAME("batmon", "driver"); @@ -245,19 +242,21 @@ int Batmon::get_batmon_startup_info() void Batmon::custom_method(const BusCLIArguments &cli) { - switch(cli.custom1) { - case 1: - // TODO: analyze why these statements are not printed - PX4_INFO("The manufacturer name: %s", _manufacturer_name); - PX4_INFO("The manufacturer date: %d", _manufacture_date); - PX4_INFO("The serial number: %d", _serial_number); - break; - case 4: - suspend(); - break; - case 5: - resume(); - break; + switch (cli.custom1) { + case 1: + // TODO: analyze why these statements are not printed + PX4_INFO("The manufacturer name: %s", _manufacturer_name); + PX4_INFO("The manufacturer date: %d", _manufacture_date); + PX4_INFO("The serial number: %d", _serial_number); + break; + + case 4: + suspend(); + break; + + case 5: + resume(); + break; } } @@ -302,6 +301,7 @@ extern "C" __EXPORT int batmon_main(int argc, char *argv[]) cli.i2c_address = batmon_addr_batt1; const char *verb = cli.parseDefaultArguments(argc, argv); + if (!verb) { ThisDriver::print_usage(); return -1; @@ -325,10 +325,12 @@ extern "C" __EXPORT int batmon_main(int argc, char *argv[]) cli.custom1 = 1; return ThisDriver::module_custom_method(cli, iterator); } + if (!strcmp(verb, "suspend")) { cli.custom1 = 4; return ThisDriver::module_custom_method(cli, iterator); } + if (!strcmp(verb, "resume")) { cli.custom1 = 5; return ThisDriver::module_custom_method(cli, iterator); diff --git a/src/drivers/tap_esc/TAP_ESC.cpp b/src/drivers/tap_esc/TAP_ESC.cpp index 0d37dda2c0a4..a52bd6bae807 100644 --- a/src/drivers/tap_esc/TAP_ESC.cpp +++ b/src/drivers/tap_esc/TAP_ESC.cpp @@ -480,25 +480,21 @@ int TAP_ESC::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -This module controls the TAP_ESC hardware via UART. It listens on the -actuator_controls topics, does the mixing and writes the PWM outputs. - -### Implementation - -Currently the module is implemented as a threaded version only, meaning that it -runs in its own thread instead of on the work queue. - -### Example - -The module is typically started with: - -``` -tap_esc start -d /dev/ttyS2 -n <1-8> -``` -)DESCR_STR"); + "### Description\n" + "\n" + "This module controls the TAP_ESC hardware via UART. It listens on the\n" + "actuator_controls topics, does the mixing and writes the PWM outputs.\n" + "\n" + "### Implementation\n" + "\n" + "Currently the module is implemented as a threaded version only, meaning that it\n" + "runs in its own thread instead of on the work queue.\n" + "\n" + "### Example\n" + "\n" + "The module is typically started with:\n" + "\n" + "$ tap_esc start -d /dev/ttyS2 -n <1-8>"); PRINT_MODULE_USAGE_NAME("tap_esc", "driver"); diff --git a/src/drivers/tattu_can/TattuCan.cpp b/src/drivers/tattu_can/TattuCan.cpp index 1f414c090796..57891d2dac71 100644 --- a/src/drivers/tattu_can/TattuCan.cpp +++ b/src/drivers/tattu_can/TattuCan.cpp @@ -206,11 +206,8 @@ int TattuCan::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Driver for reading data from the Tattu 12S 16000mAh smart battery. - -)DESCR_STR"); + "### Description\n" + "Driver for reading data from the Tattu 12S 16000mAh smart battery."); PRINT_MODULE_USAGE_NAME("tattu_can", "system"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/telemetry/iridiumsbd/IridiumSBD.cpp b/src/drivers/telemetry/iridiumsbd/IridiumSBD.cpp index 1ee9d2c6276a..4581be440737 100644 --- a/src/drivers/telemetry/iridiumsbd/IridiumSBD.cpp +++ b/src/drivers/telemetry/iridiumsbd/IridiumSBD.cpp @@ -1060,12 +1060,10 @@ int IridiumSBD::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -IridiumSBD driver. - -Creates a virtual serial port that another module can use for communication (e.g. mavlink). -)DESCR_STR"); + "### Description\n" + "IridiumSBD driver.\n" + "\n" + "Creates a virtual serial port that another module can use for communication (e.g. mavlink)."); PRINT_MODULE_USAGE_NAME("iridiumsbd", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/tone_alarm/ToneAlarm.cpp b/src/drivers/tone_alarm/ToneAlarm.cpp index 256f218b76f8..a73ae46580f5 100644 --- a/src/drivers/tone_alarm/ToneAlarm.cpp +++ b/src/drivers/tone_alarm/ToneAlarm.cpp @@ -260,11 +260,8 @@ int ToneAlarm::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This module is responsible for the tone alarm. - -)DESCR_STR"); + "### Description\n" + "This module is responsible for the tone alarm."); PRINT_MODULE_USAGE_NAME("tone_alarm", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/drivers/transponder/sagetech_mxs/SagetechMXS.cpp b/src/drivers/transponder/sagetech_mxs/SagetechMXS.cpp index b11f13f237ba..ff3054cb7ccb 100644 --- a/src/drivers/transponder/sagetech_mxs/SagetechMXS.cpp +++ b/src/drivers/transponder/sagetech_mxs/SagetechMXS.cpp @@ -218,25 +218,23 @@ int SagetechMXS::custom_command(int argc, char *argv[]) int SagetechMXS::print_usage(const char *reason) { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( - ### Description - - This driver integrates the Sagetech MXS Certified Transponder to send and receive ADSB messages and traffic. - - ### Examples - - Attempt to start driver on a specified serial device. - $ sagetech_mxs start -d /dev/ttyS1 - Stop driver - $ sagetech_mxs stop - Set Flight ID (8 char max) - $ sagetech_mxs flight_id MXS12345 - Set MXS Operating Mode - $ sagetech_mxs opmode off/on/stby/alt - $ sagetech_mxs opmode 0/1/2/3 - Set the Squawk Code - $ sagetech_mxs squawk 1200 - )DESCR_STR"); + "### Description\n" + "\n" + "This driver integrates the Sagetech MXS Certified Transponder to send and receive ADSB messages and traffic.\n" + "\n" + "### Examples\n" + "\n" + "Attempt to start driver on a specified serial device.\n" + "$ sagetech_mxs start -d /dev/ttyS1\n" + "Stop driver\n" + "$ sagetech_mxs stop\n" + "Set Flight ID (8 char max)\n" + "$ sagetech_mxs flight_id MXS12345\n" + "Set MXS Operating Mode\n" + "$ sagetech_mxs opmode off/on/stby/alt\n" + "$ sagetech_mxs opmode 0/1/2/3\n" + "Set the Squawk Code\n" + "$ sagetech_mxs squawk 1200"); PRINT_MODULE_USAGE_NAME("sagetech_mxs", "driver"); PRINT_MODULE_USAGE_SUBCATEGORY("transponder"); diff --git a/src/drivers/voxl2_io/voxl2_io.cpp b/src/drivers/voxl2_io/voxl2_io.cpp index 352b47490618..d1b5c9538c92 100644 --- a/src/drivers/voxl2_io/voxl2_io.cpp +++ b/src/drivers/voxl2_io/voxl2_io.cpp @@ -1088,13 +1088,10 @@ int Voxl2IO::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This module is responsible for driving the output pins. For boards without a separate IO chip -(eg. Pixracer), it uses the main channels. On boards with an IO chip (eg. Pixhawk), it uses the AUX channels, and the -px4io driver is used for main ones. - -)DESCR_STR"); + "### Description\n" + "This module is responsible for driving the output pins. For boards without a separate IO chip\n" + "(eg. Pixracer), it uses the main channels. On boards with an IO chip (eg. Pixhawk), it uses the AUX channels, and the\n" + "px4io driver is used for main ones."); PRINT_MODULE_USAGE_NAME("voxl2_io", "driver"); PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start the task"); @@ -1107,8 +1104,9 @@ px4io driver is used for main ones. PRINT_MODULE_USAGE_COMMAND_DESCR("pwm", "Open-Loop PWM test control request"); PRINT_MODULE_USAGE_PARAM_INT('c', 0, 0, 3, "PWM OUTPUT Channel, 0-3", false); PRINT_MODULE_USAGE_PARAM_INT('r', 0, 0, 800, "Duty Cycle value, 0 to 800", false); - PRINT_MODULE_USAGE_PARAM_INT('n', 100, 0, 1<<31, "Command repeat count, 0 to INT_MAX", false); - PRINT_MODULE_USAGE_PARAM_INT('t', 10000, 0, 1<<31, "Delay between repeated commands (microseconds), 0 to INT_MAX", false); + PRINT_MODULE_USAGE_PARAM_INT('n', 100, 0, 1 << 31, "Command repeat count, 0 to INT_MAX", false); + PRINT_MODULE_USAGE_PARAM_INT('t', 10000, 0, 1 << 31, "Delay between repeated commands (microseconds), 0 to INT_MAX", + false); PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); return 0; diff --git a/src/drivers/wind_sensor/ft_technologies/ft7_technologies_main.cpp b/src/drivers/wind_sensor/ft_technologies/ft7_technologies_main.cpp index 85ec29b182ec..e57fceed1c50 100644 --- a/src/drivers/wind_sensor/ft_technologies/ft7_technologies_main.cpp +++ b/src/drivers/wind_sensor/ft_technologies/ft7_technologies_main.cpp @@ -98,21 +98,19 @@ static int status() static int usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -Serial bus driver for the FT Technologies Digital Wind Sensor FT742. This driver is required to operate alongside -a RS485 to UART signal transfer module. - -Most boards are configured to enable/start the driver on a specified UART using the SENS_FTX_CFG parameter. - -### Examples - -Attempt to start driver on a specified serial device. -$ ft_technologies_serial start -d /dev/ttyS1 -Stop driver -$ ft_technologies_serial stop -)DESCR_STR"); + "### Description\n" + "\n" + "Serial bus driver for the FT Technologies Digital Wind Sensor FT742. This driver is required to operate alongside\n" + "a RS485 to UART signal transfer module.\n" + "\n" + "Most boards are configured to enable/start the driver on a specified UART using the SENS_FTX_CFG parameter.\n" + "\n" + "### Examples\n" + "\n" + "Attempt to start driver on a specified serial device.\n" + "$ ft_technologies_serial start -d /dev/ttyS1\n" + "Stop driver\n" + "$ ft_technologies_serial stop"); PRINT_MODULE_USAGE_NAME("ft_technologies_serial", "driver"); PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start driver"); diff --git a/src/examples/fake_gps/FakeGps.cpp b/src/examples/fake_gps/FakeGps.cpp index e2f966e023ca..670c76f49b54 100644 --- a/src/examples/fake_gps/FakeGps.cpp +++ b/src/examples/fake_gps/FakeGps.cpp @@ -124,10 +124,7 @@ int FakeGps::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -)DESCR_STR"); + "### Description"); PRINT_MODULE_USAGE_NAME("fake_gps", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/examples/fake_imu/FakeImu.cpp b/src/examples/fake_imu/FakeImu.cpp index d88a0ffb134d..6555cbf68a9b 100644 --- a/src/examples/fake_imu/FakeImu.cpp +++ b/src/examples/fake_imu/FakeImu.cpp @@ -198,10 +198,7 @@ int FakeImu::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -)DESCR_STR"); + "### Description"); PRINT_MODULE_USAGE_NAME("fake_imu", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/examples/fake_magnetometer/FakeMagnetometer.cpp b/src/examples/fake_magnetometer/FakeMagnetometer.cpp index 56878ec9855c..e80676f51b7c 100644 --- a/src/examples/fake_magnetometer/FakeMagnetometer.cpp +++ b/src/examples/fake_magnetometer/FakeMagnetometer.cpp @@ -124,11 +124,9 @@ int FakeMagnetometer::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Publish the earth magnetic field as a fake magnetometer (sensor_mag). -Requires vehicle_attitude and vehicle_gps_position. -)DESCR_STR"); + "### Description\n" + "Publish the earth magnetic field as a fake magnetometer (sensor_mag).\n" + "Requires vehicle_attitude and vehicle_gps_position."); PRINT_MODULE_USAGE_NAME("fake_magnetometer", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/examples/work_item/WorkItemExample.cpp b/src/examples/work_item/WorkItemExample.cpp index e7329e6e13e6..0df84ab2b214 100644 --- a/src/examples/work_item/WorkItemExample.cpp +++ b/src/examples/work_item/WorkItemExample.cpp @@ -169,11 +169,8 @@ int WorkItemExample::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Example of a simple module running out of a work queue. - -)DESCR_STR"); + "### Description\n" + "Example of a simple module running out of a work queue."); PRINT_MODULE_USAGE_NAME("work_item_example", "template"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/airship_att_control/airship_att_control_main.cpp b/src/modules/airship_att_control/airship_att_control_main.cpp index 2a18b349da97..fb1c8604ce72 100644 --- a/src/modules/airship_att_control/airship_att_control_main.cpp +++ b/src/modules/airship_att_control/airship_att_control_main.cpp @@ -185,18 +185,15 @@ int AirshipAttitudeControl::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This implements the airship attitude and rate controller. Ideally it would -take attitude setpoints (`vehicle_attitude_setpoint`) or rate setpoints (in acro mode -via `manual_control_setpoint` topic) as inputs and outputs actuator control messages. - -Currently it is feeding the `manual_control_setpoint` topic directly to the actuators. - -### Implementation -To reduce control latency, the module directly polls on the gyro topic published by the IMU driver. - -)DESCR_STR"); + "### Description\n" + "This implements the airship attitude and rate controller. Ideally it would\n" + "take attitude setpoints (`vehicle_attitude_setpoint`) or rate setpoints (in acro mode\n" + "via `manual_control_setpoint` topic) as inputs and outputs actuator control messages.\n" + "\n" + "Currently it is feeding the `manual_control_setpoint` topic directly to the actuators.\n" + "\n" + "### Implementation\n" + "To reduce control latency, the module directly polls on the gyro topic published by the IMU driver."); PRINT_MODULE_USAGE_NAME("airship_att_control", "controller"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/airspeed_selector/airspeed_selector_main.cpp b/src/modules/airspeed_selector/airspeed_selector_main.cpp index f8012529e1c1..70e2727d79e5 100644 --- a/src/modules/airspeed_selector/airspeed_selector_main.cpp +++ b/src/modules/airspeed_selector/airspeed_selector_main.cpp @@ -775,17 +775,14 @@ int AirspeedModule::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This module provides a single airspeed_validated topic, containing indicated (IAS), -calibrated (CAS), true airspeed (TAS) and the information if the estimation currently -is invalid and if based sensor readings or on groundspeed minus windspeed. -Supporting the input of multiple "raw" airspeed inputs, this module automatically switches -to a valid sensor in case of failure detection. For failure detection as well as for -the estimation of a scale factor from IAS to CAS, it runs several wind estimators -and also publishes those. - -)DESCR_STR"); + "### Description\n" + "This module provides a single airspeed_validated topic, containing indicated (IAS),\n" + "calibrated (CAS), true airspeed (TAS) and the information if the estimation currently\n" + "is invalid and if based sensor readings or on groundspeed minus windspeed.\n" + "Supporting the input of multiple 'raw' airspeed inputs, this module automatically switches\n" + "to a valid sensor in case of failure detection. For failure detection as well as for\n" + "the estimation of a scale factor from IAS to CAS, it runs several wind estimators\n" + "and also publishes those."); PRINT_MODULE_USAGE_NAME("airspeed_estimator", "estimator"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp index f6b645397a3d..625bb56e9c9f 100644 --- a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp +++ b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp @@ -619,11 +619,8 @@ int AttitudeEstimatorQ::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Attitude estimator q. - -)DESCR_STR"); + "### Description\n" + "Attitude estimator q."); PRINT_MODULE_USAGE_NAME("AttitudeEstimatorQ", "estimator"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/battery_status/battery_status.cpp b/src/modules/battery_status/battery_status.cpp index 1d104e4087e8..2be031772205 100644 --- a/src/modules/battery_status/battery_status.cpp +++ b/src/modules/battery_status/battery_status.cpp @@ -294,17 +294,14 @@ int BatteryStatus::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -The provided functionality includes: -- Read the output from the ADC driver (via ioctl interface) and publish `battery_status`. - - -### Implementation -It runs in its own thread and polls on the currently selected gyro topic. - -)DESCR_STR"); + "### Description\n" + "\n" + "The provided functionality includes:\n" + "- Read the output from the ADC driver (via ioctl interface) and publish `battery_status`.\n" + "\n" + "\n" + "### Implementation\n" + "It runs in its own thread and polls on the currently selected gyro topic."); PRINT_MODULE_USAGE_NAME("battery_status", "system"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/camera_feedback/CameraFeedback.cpp b/src/modules/camera_feedback/CameraFeedback.cpp index a4c89f59715a..26219555fc60 100644 --- a/src/modules/camera_feedback/CameraFeedback.cpp +++ b/src/modules/camera_feedback/CameraFeedback.cpp @@ -191,30 +191,27 @@ CameraFeedback::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -The camera_feedback module publishes `CameraCapture` UORB topics when image capture has been triggered. - -If camera capture is enabled, then trigger information from the camera capture pin is published; -otherwise trigger information at the point the camera was commanded to trigger is published -(from the `camera_trigger` module). - -The `CAMERA_IMAGE_CAPTURED` message is then emitted (by streaming code) following `CameraCapture` updates. -`CameraCapture` topics are also logged and can be used for geotagging. - -### Implementation - -`CameraTrigger` topics are published by the `camera_trigger` module (`feedback` field set `false`) -when image capture is triggered, and may also be published by the `camera_capture` driver -(with `feedback` field set `true`) if the camera capture pin is activated. - -The `camera_feedback` module subscribes to `CameraTrigger`. -It discards topics from the `camera_trigger` module if camera capture is enabled. -For the topics that are not discarded it creates a `CameraCapture` topic with the timestamp information -from the `CameraTrigger` and position information from the vehicle. - -)DESCR_STR"); + "### Description\n" + "\n" + "The camera_feedback module publishes `CameraCapture` UORB topics when image capture has been triggered.\n" + "\n" + "If camera capture is enabled, then trigger information from the camera capture pin is published;\n" + "otherwise trigger information at the point the camera was commanded to trigger is published\n" + "(from the `camera_trigger` module).\n" + "\n" + "The `CAMERA_IMAGE_CAPTURED` message is then emitted (by streaming code) following `CameraCapture` updates.\n" + "`CameraCapture` topics are also logged and can be used for geotagging.\n" + "\n" + "### Implementation\n" + "\n" + "`CameraTrigger` topics are published by the `camera_trigger` module (`feedback` field set `false`)\n" + "when image capture is triggered, and may also be published by the `camera_capture` driver\n" + "(with `feedback` field set `true`) if the camera capture pin is activated.\n" + "\n" + "The `camera_feedback` module subscribes to `CameraTrigger`.\n" + "It discards topics from the `camera_trigger` module if camera capture is enabled.\n" + "For the topics that are not discarded it creates a `CameraCapture` topic with the timestamp information\n" + "from the `CameraTrigger` and position information from the vehicle."); PRINT_MODULE_USAGE_NAME("camera_feedback", "system"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index fef03b92c28e..19ea78552543 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -3025,10 +3025,8 @@ int Commander::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -The commander module contains the state machine for mode switching and failsafe behavior. -)DESCR_STR"); + "### Description\n" + "The commander module contains the state machine for mode switching and failsafe behavior."); PRINT_MODULE_USAGE_NAME("commander", "system"); PRINT_MODULE_USAGE_COMMAND("start"); @@ -3047,7 +3045,7 @@ The commander module contains the state machine for mode switching and failsafe 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|altctl|posctl|position:slow|auto:mission|auto:loiter|auto:rtl|auto:takeoff|auto:land|auto:precland|ext1", - "Flight mode", false); + "Flight mode", false); PRINT_MODULE_USAGE_COMMAND("pair"); PRINT_MODULE_USAGE_COMMAND("lockdown"); PRINT_MODULE_USAGE_ARG("on|off", "Turn lockdown on or off", false); diff --git a/src/modules/control_allocator/ControlAllocator.cpp b/src/modules/control_allocator/ControlAllocator.cpp index 0bc3f9c86e9d..ab551e0f5ce7 100644 --- a/src/modules/control_allocator/ControlAllocator.cpp +++ b/src/modules/control_allocator/ControlAllocator.cpp @@ -855,11 +855,9 @@ int ControlAllocator::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This implements control allocation. It takes torque and thrust setpoints -as inputs and outputs actuator setpoint messages. -)DESCR_STR"); + "### Description\n" + "This implements control allocation. It takes torque and thrust setpoints\n" + "as inputs and outputs actuator setpoint messages."); PRINT_MODULE_USAGE_NAME("control_allocator", "controller"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/dataman/dataman.cpp b/src/modules/dataman/dataman.cpp index b1c1a057e14a..88e8326f0305 100644 --- a/src/modules/dataman/dataman.cpp +++ b/src/modules/dataman/dataman.cpp @@ -868,20 +868,17 @@ static void usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Module to provide persistent storage for the rest of the system in form of a simple database through a C API. -Multiple backends are supported: -- a file (eg. on the SD card) -- RAM (this is obviously not persistent) - -It is used to store structured data of different types: mission waypoints, mission state and geofence polygons. -Each type has a specific type and a fixed maximum amount of storage items, so that fast random access is possible. - -### Implementation -Reading and writing a single item is always atomic. - -)DESCR_STR"); + "### Description\n" + "Module to provide persistent storage for the rest of the system in form of a simple database through a C API.\n" + "Multiple backends are supported:\n" + "- a file (eg. on the SD card)\n" + "- RAM (this is obviously not persistent)\n" + "\n" + "It is used to store structured data of different types: mission waypoints, mission state and geofence polygons.\n" + "Each type has a specific type and a fixed maximum amount of storage items, so that fast random access is possible.\n" + "\n" + "### Implementation\n" + "Reading and writing a single item is always atomic."); PRINT_MODULE_USAGE_NAME("dataman", "system"); PRINT_MODULE_USAGE_COMMAND("start"); @@ -990,10 +987,14 @@ dataman_main(int argc, char *argv[]) return 0; } -static_assert(sizeof(dataman_request_s::data) == sizeof(dataman_response_s::data), "request and response data are not the same size"); -static_assert(sizeof(dataman_response_s::data) >= MISSION_SAFE_POINT_SIZE, "mission_item_s can't fit in the response data"); -static_assert(sizeof(dataman_response_s::data) >= MISSION_FENCE_POINT_SIZE, "mission_fance_point_s can't fit in the response data"); +static_assert(sizeof(dataman_request_s::data) == sizeof(dataman_response_s::data), + "request and response data are not the same size"); +static_assert(sizeof(dataman_response_s::data) >= MISSION_SAFE_POINT_SIZE, + "mission_item_s can't fit in the response data"); +static_assert(sizeof(dataman_response_s::data) >= MISSION_FENCE_POINT_SIZE, + "mission_fance_point_s can't fit in the response data"); static_assert(sizeof(dataman_response_s::data) >= MISSION_ITEM_SIZE, "mission_item_s can't fit in the response data"); static_assert(sizeof(dataman_response_s::data) >= MISSION_SIZE, "mission_s can't fit in the response data"); -static_assert(sizeof(dataman_response_s::data) >= DATAMAN_COMPAT_SIZE, "dataman_compat_s can't fit in the response data"); +static_assert(sizeof(dataman_response_s::data) >= DATAMAN_COMPAT_SIZE, + "dataman_compat_s can't fit in the response data"); static_assert(sizeof(dataman_response_s::data) >= sizeof(hrt_abstime), "hrt_abstime can't fit in the response data"); diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index c85527b9121a..91d00c2b9411 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -2913,16 +2913,13 @@ int EKF2::print_usage(const char *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/main/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"); + "### Description\n" + "Attitude and position estimator using an Extended Kalman Filter. It is used for Multirotors and Fixed-Wing.\n" + "\n" + "The documentation can be found on the [ECL/EKF Overview & Tuning](https://docs.px4.io/main/en/advanced_config/tuning_the_ecl_ekf.html) page.\n" + "\n" + "ekf2 can be started in replay mode (`-r`): in this mode, it does not access the system time, but only uses the\n" + "timestamps from the sensor topics."); PRINT_MODULE_USAGE_NAME("ekf2", "estimator"); PRINT_MODULE_USAGE_COMMAND("start"); @@ -2959,6 +2956,7 @@ extern "C" __EXPORT int ekf2_main(int argc, char *argv[]) return ret; #if defined(CONFIG_EKF2_MULTI_INSTANCE) + } else if (strcmp(argv[1], "select_instance") == 0) { if (EKF2::trylock_module()) { @@ -2966,6 +2964,7 @@ extern "C" __EXPORT int ekf2_main(int argc, char *argv[]) if (argc > 2) { int instance = atoi(argv[2]); _ekf2_selector.load()->RequestInstance(instance); + } else { EKF2::unlock_module(); return EKF2::print_usage("instance required"); @@ -2983,20 +2982,25 @@ extern "C" __EXPORT int ekf2_main(int argc, char *argv[]) return 0; #endif // CONFIG_EKF2_MULTI_INSTANCE + } else if (strcmp(argv[1], "status") == 0) { if (EKF2::trylock_module()) { #if defined(CONFIG_EKF2_MULTI_INSTANCE) + if (_ekf2_selector.load()) { _ekf2_selector.load()->PrintStatus(); } + #endif // CONFIG_EKF2_MULTI_INSTANCE bool verbose_status = false; #if defined(CONFIG_EKF2_VERBOSE_STATUS) + if (argc > 2 && (strcmp(argv[2], "-v") == 0)) { verbose_status = true; } + #endif // CONFIG_EKF2_VERBOSE_STATUS for (int i = 0; i < EKF2_MAX_INSTANCES; i++) { @@ -3030,6 +3034,7 @@ extern "C" __EXPORT int ekf2_main(int argc, char *argv[]) delete inst; _objects[instance].store(nullptr); } + } else { PX4_ERR("invalid instance %d", instance); } @@ -3039,6 +3044,7 @@ extern "C" __EXPORT int ekf2_main(int argc, char *argv[]) bool was_running = false; #if defined(CONFIG_EKF2_MULTI_INSTANCE) + if (_ekf2_selector.load()) { PX4_INFO("stopping ekf2 selector"); _ekf2_selector.load()->Stop(); @@ -3046,6 +3052,7 @@ extern "C" __EXPORT int ekf2_main(int argc, char *argv[]) _ekf2_selector.store(nullptr); was_running = true; } + #endif // CONFIG_EKF2_MULTI_INSTANCE for (int i = 0; i < EKF2_MAX_INSTANCES; i++) { diff --git a/src/modules/esc_battery/EscBattery.cpp b/src/modules/esc_battery/EscBattery.cpp index 6a6a21f02ada..25c6db1c1281 100644 --- a/src/modules/esc_battery/EscBattery.cpp +++ b/src/modules/esc_battery/EscBattery.cpp @@ -143,11 +143,8 @@ int EscBattery::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This implements using information from the ESC status and publish it as battery status. - -)DESCR_STR"); + "### Description\n" + "This implements using information from the ESC status and publish it as battery status."); PRINT_MODULE_USAGE_NAME("esc_battery", "system"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/events/send_event.cpp b/src/modules/events/send_event.cpp index bc92d44117a0..cdd79fdf0634 100644 --- a/src/modules/events/send_event.cpp +++ b/src/modules/events/send_event.cpp @@ -137,13 +137,11 @@ int SendEvent::print_usage(const char *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 tone alarm on RC Loss. - -The tasks can be started via CLI or uORB topics (vehicle_command from MAVLink, etc.). -)DESCR_STR"); + "### Description\n" + "Background process running periodically on the LP work queue to perform housekeeping tasks.\n" + "It is currently only responsible for tone alarm on RC Loss.\n" + "\n" + "The tasks can be started via CLI or uORB topics (vehicle_command from MAVLink, etc.)."); PRINT_MODULE_USAGE_NAME("send_event", "system"); PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start the background task"); diff --git a/src/modules/flight_mode_manager/FlightModeManager.cpp b/src/modules/flight_mode_manager/FlightModeManager.cpp index c58a7fa1572b..d103b8fb1998 100644 --- a/src/modules/flight_mode_manager/FlightModeManager.cpp +++ b/src/modules/flight_mode_manager/FlightModeManager.cpp @@ -478,12 +478,9 @@ int FlightModeManager::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This implements the setpoint generation for all modes. It takes the current mode state of the vehicle as input -and outputs setpoints for controllers. - -)DESCR_STR"); + "### Description\n" + "This implements the setpoint generation for all modes. It takes the current mode state of the vehicle as input\n" + "and outputs setpoints for controllers."); PRINT_MODULE_USAGE_NAME("flight_mode_manager", "controller"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/fw_att_control/FixedwingAttitudeControl.cpp b/src/modules/fw_att_control/FixedwingAttitudeControl.cpp index 9057d792b996..6bd600f40510 100644 --- a/src/modules/fw_att_control/FixedwingAttitudeControl.cpp +++ b/src/modules/fw_att_control/FixedwingAttitudeControl.cpp @@ -467,11 +467,8 @@ int FixedwingAttitudeControl::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -fw_att_control is the fixed wing attitude controller. - -)DESCR_STR"); + "### Description\n" + "fw_att_control is the fixed wing attitude controller."); PRINT_MODULE_USAGE_NAME("fw_att_control", "controller"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp index 5e63924d3b57..311606a64355 100644 --- a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp +++ b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp @@ -746,10 +746,7 @@ int FwAutotuneAttitudeControl::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -)DESCR_STR"); + "### Description"); PRINT_MODULE_USAGE_NAME("fw_autotune_attitude_control", "autotune"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index a15f1e8f7154..11656dbe182e 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -3350,11 +3350,8 @@ int FixedwingPositionControl::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -fw_pos_control is the fixed-wing position controller. - -)DESCR_STR"); + "### Description\n" + "fw_pos_control is the fixed-wing position controller."); PRINT_MODULE_USAGE_NAME("fw_pos_control", "controller"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/fw_rate_control/FixedwingRateControl.cpp b/src/modules/fw_rate_control/FixedwingRateControl.cpp index 9841ea8ca6f8..2639e113af58 100644 --- a/src/modules/fw_rate_control/FixedwingRateControl.cpp +++ b/src/modules/fw_rate_control/FixedwingRateControl.cpp @@ -552,11 +552,8 @@ int FixedwingRateControl::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -fw_rate_control is the fixed-wing rate controller. - -)DESCR_STR"); + "### Description\n" + "fw_rate_control is the fixed-wing rate controller."); PRINT_MODULE_USAGE_NAME("fw_rate_control", "controller"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/gimbal/gimbal.cpp b/src/modules/gimbal/gimbal.cpp index 9179055b31ca..313822b0e9ac 100644 --- a/src/modules/gimbal/gimbal.cpp +++ b/src/modules/gimbal/gimbal.cpp @@ -604,25 +604,25 @@ bool initialize_params(ParameterHandles ¶m_handles, Parameters ¶ms) static void usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Mount/gimbal Gimbal control driver. It maps several different input methods (eg. RC or MAVLink) to a configured -output (eg. AUX channels or MAVLink). - -Documentation how to use it is on the [gimbal_control](https://docs.px4.io/main/en/advanced/gimbal_control.html) page. - -### Examples -Test the output by setting a angles (all omitted axes are set to 0): -$ gimbal test pitch -45 yaw 30 -)DESCR_STR"); + "### Description\n" + "Mount/gimbal Gimbal control driver. It maps several different input methods (eg. RC or MAVLink) to a configured\n" + "output (eg. AUX channels or MAVLink).\n" + "\n" + "Documentation how to use it is on the [gimbal_control](https://docs.px4.io/main/en/advanced/gimbal_control.html) page.\n" + "\n" + "### Examples\n" + "Test the output by setting a angles (all omitted axes are set to 0):\n" + "$ gimbal test pitch -45 yaw 30"); PRINT_MODULE_USAGE_NAME("gimbal", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_COMMAND("status"); PRINT_MODULE_USAGE_COMMAND_DESCR("primary-control", "Set who is in control of gimbal"); PRINT_MODULE_USAGE_ARG(" ", "MAVLink system ID and MAVLink component ID", false); - PRINT_MODULE_USAGE_COMMAND_DESCR("test", "Test the output: set a fixed angle for one or multiple axes (gimbal must be running)"); + PRINT_MODULE_USAGE_COMMAND_DESCR("test", + "Test the output: set a fixed angle for one or multiple axes (gimbal must be running)"); PRINT_MODULE_USAGE_ARG("roll|pitch|yaw ", "Specify an axis and an angle in degrees", false); - PRINT_MODULE_USAGE_ARG("rollrate|pitchrate|yawrate ", "Specify an axis and an angle rate in degrees / second", false); + PRINT_MODULE_USAGE_ARG("rollrate|pitchrate|yawrate ", + "Specify an axis and an angle rate in degrees / second", false); PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); } diff --git a/src/modules/gyro_calibration/GyroCalibration.cpp b/src/modules/gyro_calibration/GyroCalibration.cpp index 7bca0b6869f0..9ffbe3fcb055 100644 --- a/src/modules/gyro_calibration/GyroCalibration.cpp +++ b/src/modules/gyro_calibration/GyroCalibration.cpp @@ -332,11 +332,8 @@ int GyroCalibration::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Simple online gyroscope calibration. - -)DESCR_STR"); + "### Description\n" + "Simple online gyroscope calibration."); PRINT_MODULE_USAGE_NAME("gyro_calibration", "system"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/gyro_fft/GyroFFT.cpp b/src/modules/gyro_fft/GyroFFT.cpp index 51818c342552..df52041e6548 100644 --- a/src/modules/gyro_fft/GyroFFT.cpp +++ b/src/modules/gyro_fft/GyroFFT.cpp @@ -723,10 +723,7 @@ int GyroFFT::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -)DESCR_STR"); + "### Description"); PRINT_MODULE_USAGE_NAME("gyro_fft", "system"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/land_detector/land_detector_main.cpp b/src/modules/land_detector/land_detector_main.cpp index a64bdc9e0034..634e0fd11503 100644 --- a/src/modules/land_detector/land_detector_main.cpp +++ b/src/modules/land_detector/land_detector_main.cpp @@ -115,30 +115,28 @@ int LandDetector::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Module to detect the freefall and landed state of the vehicle, and publishing the `vehicle_land_detected` topic. -Each vehicle type (multirotor, fixedwing, vtol, ...) provides its own algorithm, taking into account various -states, such as commanded thrust, arming state and vehicle motion. - -### Implementation -Every type is implemented in its own class with a common base class. The base class maintains a state (landed, -maybe_landed, ground_contact). Each possible state is implemented in the derived classes. A hysteresis and a fixed -priority of each internal state determines the actual land_detector state. - -#### Multicopter Land Detector -**ground_contact**: thrust setpoint and velocity in z-direction must be below a defined threshold for time -GROUND_CONTACT_TRIGGER_TIME_US. When ground_contact is detected, the position controller turns off the thrust setpoint -in body x and y. - -**maybe_landed**: it requires ground_contact together with a tighter thrust setpoint threshold and no velocity in the -horizontal direction. The trigger time is defined by MAYBE_LAND_TRIGGER_TIME. When maybe_landed is detected, the -position controller sets the thrust setpoint to zero. - -**landed**: it requires maybe_landed to be true for time LAND_DETECTOR_TRIGGER_TIME_US. - -The module runs periodically on the HP work queue. -)DESCR_STR"); + "### Description\n" + "Module to detect the freefall and landed state of the vehicle, and publishing the `vehicle_land_detected` topic.\n" + "Each vehicle type (multirotor, fixedwing, vtol, ...) provides its own algorithm, taking into account various\n" + "states, such as commanded thrust, arming state and vehicle motion.\n" + "\n" + "### Implementation\n" + "Every type is implemented in its own class with a common base class. The base class maintains a state (landed,\n" + "maybe_landed, ground_contact). Each possible state is implemented in the derived classes. A hysteresis and a fixed\n" + "priority of each internal state determines the actual land_detector state.\n" + "\n" + "#### Multicopter Land Detector\n" + "**ground_contact**: thrust setpoint and velocity in z-direction must be below a defined threshold for time\n" + "GROUND_CONTACT_TRIGGER_TIME_US. When ground_contact is detected, the position controller turns off the thrust setpoint\n" + "in body x and y.\n" + "\n" + "**maybe_landed**: it requires ground_contact together with a tighter thrust setpoint threshold and no velocity in the\n" + "horizontal direction. The trigger time is defined by MAYBE_LAND_TRIGGER_TIME. When maybe_landed is detected, the\n" + "position controller sets the thrust setpoint to zero.\n" + "\n" + "**landed**: it requires maybe_landed to be true for time LAND_DETECTOR_TRIGGER_TIME_US.\n" + "\n" + "The module runs periodically on the HP work queue."); PRINT_MODULE_USAGE_NAME("land_detector", "system"); PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start the background task"); diff --git a/src/modules/load_mon/LoadMon.cpp b/src/modules/load_mon/LoadMon.cpp index 937d02c03e12..35a8293059dd 100644 --- a/src/modules/load_mon/LoadMon.cpp +++ b/src/modules/load_mon/LoadMon.cpp @@ -310,14 +310,12 @@ int LoadMon::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Background process running periodically on the low priority work queue to calculate the CPU load and RAM -usage and publish the `cpuload` topic. - -On NuttX it also checks the stack usage of each process and if it falls below 300 bytes, a warning is output, -which will also appear in the log file. -)DESCR_STR"); + "### Description\n" + "Background process running periodically on the low priority work queue to calculate the CPU load and RAM\n" + "usage and publish the `cpuload` topic.\n" + "\n" + "On NuttX it also checks the stack usage of each process and if it falls below 300 bytes, a warning is output,\n" + "which will also appear in the log file."); PRINT_MODULE_USAGE_NAME("load_mon", "system"); PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start the background task"); diff --git a/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp b/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp index 8517ff03b0eb..03b00e8b830e 100644 --- a/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp +++ b/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp @@ -1054,11 +1054,8 @@ BlockLocalPositionEstimator::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Attitude and position estimator using an Extended Kalman Filter. - -)DESCR_STR"); + "### Description\n" + "Attitude and position estimator using an Extended Kalman Filter."); PRINT_MODULE_USAGE_NAME("local_position_estimator", "estimator"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/logger/logger.cpp b/src/modules/logger/logger.cpp index 99ec75898c2c..2e2befe9f80a 100644 --- a/src/modules/logger/logger.cpp +++ b/src/modules/logger/logger.cpp @@ -2404,39 +2404,37 @@ int Logger::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -System logger which logs a configurable set of uORB topics and system printf messages -(`PX4_WARN` and `PX4_ERR`) to ULog files. These can be used for system and flight performance evaluation, -tuning, replay and crash analysis. - -It supports 2 backends: -- Files: write ULog files to the file system (SD card) -- MAVLink: stream ULog data via MAVLink to a client (the client must support this) - -Both backends can be enabled and used at the same time. - -The file backend supports 2 types of log files: full (the normal log) and a mission -log. The mission log is a reduced ulog file and can be used for example for geotagging or -vehicle management. It can be enabled and configured via SDLOG_MISSION parameter. -The normal log is always a superset of the mission log. - -### Implementation -The implementation uses two threads: -- The main thread, running at a fixed rate (or polling on a topic if started with -p) and checking for - data updates -- The writer thread, writing data to the file - -In between there is a write buffer with configurable size (and another fixed-size buffer for -the mission log). It should be large to avoid dropouts. - -### Examples -Typical usage to start logging immediately: -$ logger start -e -t - -Or if already running: -$ logger on -)DESCR_STR"); + "### Description\n" + "System logger which logs a configurable set of uORB topics and system printf messages\n" + "(`PX4_WARN` and `PX4_ERR`) to ULog files. These can be used for system and flight performance evaluation,\n" + "tuning, replay and crash analysis.\n" + "\n" + "It supports 2 backends:\n" + "- Files: write ULog files to the file system (SD card)\n" + "- MAVLink: stream ULog data via MAVLink to a client (the client must support this)\n" + "\n" + "Both backends can be enabled and used at the same time.\n" + "\n" + "The file backend supports 2 types of log files: full (the normal log) and a mission\n" + "log. The mission log is a reduced ulog file and can be used for example for geotagging or\n" + "vehicle management. It can be enabled and configured via SDLOG_MISSION parameter.\n" + "The normal log is always a superset of the mission log.\n" + "\n" + "### Implementation\n" + "The implementation uses two threads:\n" + "- The main thread, running at a fixed rate (or polling on a topic if started with -p) and checking for\n" + "data updates\n" + "- The writer thread, writing data to the file\n" + "\n" + "In between there is a write buffer with configurable size (and another fixed-size buffer for\n" + "the mission log). It should be large to avoid dropouts.\n" + "\n" + "### Examples\n" + "Typical usage to start logging immediately:\n" + "$ logger start -e -t\n" + "\n" + "Or if already running:\n" + "$ logger on"); PRINT_MODULE_USAGE_NAME("logger", "system"); PRINT_MODULE_USAGE_COMMAND("start"); @@ -2449,7 +2447,7 @@ Or if already running: PRINT_MODULE_USAGE_PARAM_INT('r', 280, 0, 8000, "Log rate in Hz, 0 means unlimited rate", true); PRINT_MODULE_USAGE_PARAM_INT('b', 12, 4, 10000, "Log buffer size in KiB", true); PRINT_MODULE_USAGE_PARAM_STRING('p', nullptr, "", - "Poll on a topic instead of running with fixed rate (Log rate and topic intervals are ignored if this is set)", true); + "Poll on a topic instead of running with fixed rate (Log rate and topic intervals are ignored if this is set)", true); PRINT_MODULE_USAGE_PARAM_FLOAT('c', 1.0, 0.2, 2.0, "Log rate factor (higher is faster)", true); PRINT_MODULE_USAGE_COMMAND_DESCR("on", "start logging now, override arming (logger must be running)"); PRINT_MODULE_USAGE_COMMAND_DESCR("off", "stop logging now, override arming (logger must be running)"); diff --git a/src/modules/mag_bias_estimator/MagBiasEstimator.cpp b/src/modules/mag_bias_estimator/MagBiasEstimator.cpp index e386170a210c..f44a980c0cb8 100644 --- a/src/modules/mag_bias_estimator/MagBiasEstimator.cpp +++ b/src/modules/mag_bias_estimator/MagBiasEstimator.cpp @@ -280,10 +280,8 @@ int MagBiasEstimator::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Online magnetometer bias estimator. -)DESCR_STR"); + "### Description\n" + "Online magnetometer bias estimator."); PRINT_MODULE_USAGE_NAME("mag_bias_estimator", "system"); PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start the background task"); diff --git a/src/modules/manual_control/ManualControl.cpp b/src/modules/manual_control/ManualControl.cpp index a927035f931f..740c9964450d 100644 --- a/src/modules/manual_control/ManualControl.cpp +++ b/src/modules/manual_control/ManualControl.cpp @@ -551,11 +551,8 @@ int ManualControl::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Module consuming manual_control_inputs publishing one manual_control_setpoint. - -)DESCR_STR"); + "### Description\n" + "Module consuming manual_control_inputs publishing one manual_control_setpoint."); PRINT_MODULE_USAGE_NAME("manual_control", "system"); PRINT_MODULE_USAGE_COMMAND("start"); @@ -567,33 +564,56 @@ Module consuming manual_control_inputs publishing one manual_control_setpoint. int8_t ManualControl::navStateFromParam(int32_t param_value) { // See src/modules/commander/module.yaml COM_FLTMODE${i} - switch(param_value) { - case 0: return vehicle_status_s::NAVIGATION_STATE_MANUAL; - case 1: return vehicle_status_s::NAVIGATION_STATE_ALTCTL; - case 2: return vehicle_status_s::NAVIGATION_STATE_POSCTL; - case 3: return vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION; - case 4: return vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER; - case 5: return vehicle_status_s::NAVIGATION_STATE_AUTO_RTL; - case 6: return vehicle_status_s::NAVIGATION_STATE_ACRO; - case 7: return vehicle_status_s::NAVIGATION_STATE_OFFBOARD; - case 8: return vehicle_status_s::NAVIGATION_STATE_STAB; - case 9: return vehicle_status_s::NAVIGATION_STATE_POSITION_SLOW; - case 10: return vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF; - case 11: return vehicle_status_s::NAVIGATION_STATE_AUTO_LAND; - case 12: return vehicle_status_s::NAVIGATION_STATE_AUTO_FOLLOW_TARGET; - case 13: return vehicle_status_s::NAVIGATION_STATE_AUTO_PRECLAND; - case 14: return vehicle_status_s::NAVIGATION_STATE_ORBIT; - case 15: return vehicle_status_s::NAVIGATION_STATE_AUTO_VTOL_TAKEOFF; - - case 100: return vehicle_status_s::NAVIGATION_STATE_EXTERNAL1; - case 101: return vehicle_status_s::NAVIGATION_STATE_EXTERNAL2; - case 102: return vehicle_status_s::NAVIGATION_STATE_EXTERNAL3; - case 103: return vehicle_status_s::NAVIGATION_STATE_EXTERNAL4; - case 104: return vehicle_status_s::NAVIGATION_STATE_EXTERNAL5; - case 105: return vehicle_status_s::NAVIGATION_STATE_EXTERNAL6; - case 106: return vehicle_status_s::NAVIGATION_STATE_EXTERNAL7; - case 107: return vehicle_status_s::NAVIGATION_STATE_EXTERNAL8; + switch (param_value) { + case 0: return vehicle_status_s::NAVIGATION_STATE_MANUAL; + + case 1: return vehicle_status_s::NAVIGATION_STATE_ALTCTL; + + case 2: return vehicle_status_s::NAVIGATION_STATE_POSCTL; + + case 3: return vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION; + + case 4: return vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER; + + case 5: return vehicle_status_s::NAVIGATION_STATE_AUTO_RTL; + + case 6: return vehicle_status_s::NAVIGATION_STATE_ACRO; + + case 7: return vehicle_status_s::NAVIGATION_STATE_OFFBOARD; + + case 8: return vehicle_status_s::NAVIGATION_STATE_STAB; + + case 9: return vehicle_status_s::NAVIGATION_STATE_POSITION_SLOW; + + case 10: return vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF; + + case 11: return vehicle_status_s::NAVIGATION_STATE_AUTO_LAND; + + case 12: return vehicle_status_s::NAVIGATION_STATE_AUTO_FOLLOW_TARGET; + + case 13: return vehicle_status_s::NAVIGATION_STATE_AUTO_PRECLAND; + + case 14: return vehicle_status_s::NAVIGATION_STATE_ORBIT; + + case 15: return vehicle_status_s::NAVIGATION_STATE_AUTO_VTOL_TAKEOFF; + + case 100: return vehicle_status_s::NAVIGATION_STATE_EXTERNAL1; + + case 101: return vehicle_status_s::NAVIGATION_STATE_EXTERNAL2; + + case 102: return vehicle_status_s::NAVIGATION_STATE_EXTERNAL3; + + case 103: return vehicle_status_s::NAVIGATION_STATE_EXTERNAL4; + + case 104: return vehicle_status_s::NAVIGATION_STATE_EXTERNAL5; + + case 105: return vehicle_status_s::NAVIGATION_STATE_EXTERNAL6; + + case 106: return vehicle_status_s::NAVIGATION_STATE_EXTERNAL7; + + case 107: return vehicle_status_s::NAVIGATION_STATE_EXTERNAL8; } + return -1; } diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 6e8184960030..91f34b042114 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -3294,34 +3294,32 @@ static void usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This module implements the MAVLink protocol, which can be used on a Serial link or UDP network connection. -It communicates with the system via uORB: some messages are directly handled in the module (eg. mission -protocol), others are published via uORB (eg. vehicle_command). - -Streams are used to send periodic messages with a specific rate, such as the vehicle attitude. -When starting the mavlink instance, a mode can be specified, which defines the set of enabled streams with their rates. -For a running instance, streams can be configured via `mavlink stream` command. - -There can be multiple independent instances of the module, each connected to one serial device or network port. - -### Implementation -The implementation uses 2 threads, a sending and a receiving thread. The sender runs at a fixed rate and dynamically -reduces the rates of the streams if the combined bandwidth is higher than the configured rate (`-r`) or the -physical link becomes saturated. This can be checked with `mavlink status`, see if `rate mult` is less than 1. - -**Careful**: some of the data is accessed and modified from both threads, so when changing code or extend the -functionality, this needs to be take into account, in order to avoid race conditions and corrupt data. - -### Examples -Start mavlink on ttyS1 serial with baudrate 921600 and maximum sending rate of 80kB/s: -$ mavlink start -d /dev/ttyS1 -b 921600 -m onboard -r 80000 - -Start mavlink on UDP port 14556 and enable the HIGHRES_IMU message with 50Hz: -$ mavlink start -u 14556 -r 1000000 -$ mavlink stream -u 14556 -s HIGHRES_IMU -r 50 -)DESCR_STR"); + "### Description\n" + "This module implements the MAVLink protocol, which can be used on a Serial link or UDP network connection.\n" + "It communicates with the system via uORB: some messages are directly handled in the module (eg. mission\n" + "protocol), others are published via uORB (eg. vehicle_command).\n" + "\n" + "Streams are used to send periodic messages with a specific rate, such as the vehicle attitude.\n" + "When starting the mavlink instance, a mode can be specified, which defines the set of enabled streams with their rates.\n" + "For a running instance, streams can be configured via `mavlink stream` command.\n" + "\n" + "There can be multiple independent instances of the module, each connected to one serial device or network port.\n" + "\n" + "### Implementation\n" + "The implementation uses 2 threads, a sending and a receiving thread. The sender runs at a fixed rate and dynamically\n" + "reduces the rates of the streams if the combined bandwidth is higher than the configured rate (`-r`) or the\n" + "physical link becomes saturated. This can be checked with `mavlink status`, see if `rate mult` is less than 1.\n" + "\n" + "**Careful**: some of the data is accessed and modified from both threads, so when changing code or extend the\n" + "functionality, this needs to be take into account, in order to avoid race conditions and corrupt data.\n" + "\n" + "### Examples\n" + "Start mavlink on ttyS1 serial with baudrate 921600 and maximum sending rate of 80kB/s:\n" + "$ mavlink start -d /dev/ttyS1 -b 921600 -m onboard -r 80000\n" + "\n" + "Start mavlink on UDP port 14556 and enable the HIGHRES_IMU message with 50Hz:\n" + "$ mavlink start -u 14556 -r 1000000\n" + "$ mavlink stream -u 14556 -s HIGHRES_IMU -r 50"); PRINT_MODULE_USAGE_NAME("mavlink", "communication"); PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start a new instance"); @@ -3332,13 +3330,16 @@ Start mavlink on UDP port 14556 and enable the HIGHRES_IMU message with 50Hz: PRINT_MODULE_USAGE_PARAM_FLAG('p', "Enable Broadcast", true); PRINT_MODULE_USAGE_PARAM_INT('u', 14556, 0, 65536, "Select UDP Network Port (local)", true); PRINT_MODULE_USAGE_PARAM_INT('o', 14550, 0, 65536, "Select UDP Network Port (remote)", true); - PRINT_MODULE_USAGE_PARAM_STRING('t', "127.0.0.1", nullptr, "Partner IP (broadcasting can be enabled via -p flag)", true); + PRINT_MODULE_USAGE_PARAM_STRING('t', "127.0.0.1", nullptr, "Partner IP (broadcasting can be enabled via -p flag)", + true); #endif - PRINT_MODULE_USAGE_PARAM_STRING('m', "normal", "custom|camera|onboard|osd|magic|config|iridium|minimal|extvision|extvisionmin|gimbal|uavionix", + PRINT_MODULE_USAGE_PARAM_STRING('m', "normal", + "custom|camera|onboard|osd|magic|config|iridium|minimal|extvision|extvisionmin|gimbal|uavionix", "Mode: sets default streams and rates", true); PRINT_MODULE_USAGE_PARAM_STRING('n', nullptr, "", "wifi/ethernet interface name", true); #if defined(CONFIG_NET_IGMP) && defined(CONFIG_NET_ROUTE) - PRINT_MODULE_USAGE_PARAM_STRING('c', nullptr, "Multicast address in the range [239.0.0.0,239.255.255.255]", "Multicast address (multicasting can be enabled via MAV_{i}_BROADCAST param)", true); + PRINT_MODULE_USAGE_PARAM_STRING('c', nullptr, "Multicast address in the range [239.0.0.0,239.255.255.255]", + "Multicast address (multicasting can be enabled via MAV_{i}_BROADCAST param)", true); #endif PRINT_MODULE_USAGE_PARAM_FLOAT('F', 0.015, 0.0, 50.0, "Sets the transmission frequency for iridium mode", true); PRINT_MODULE_USAGE_PARAM_FLAG('f', "Enable message forwarding to other Mavlink instances", true); diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 22b78d519c2b..be9fc6b2bf8f 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -415,21 +415,18 @@ int MulticopterAttitudeControl::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This implements the multicopter attitude controller. It takes attitude -setpoints (`vehicle_attitude_setpoint`) as inputs and outputs a rate setpoint. - -The controller has a P loop for angular error - -Publication documenting the implemented Quaternion Attitude Control: -Nonlinear Quadrocopter Attitude Control (2013) -by Dario Brescianini, Markus Hehn and Raffaello D'Andrea -Institute for Dynamic Systems and Control (IDSC), ETH Zurich - -https://www.research-collection.ethz.ch/bitstream/handle/20.500.11850/154099/eth-7387-01.pdf - -)DESCR_STR"); + "### Description\n" + "This implements the multicopter attitude controller. It takes attitude\n" + "setpoints (`vehicle_attitude_setpoint`) as inputs and outputs a rate setpoint.\n" + "\n" + "The controller has a P loop for angular error\n" + "\n" + "Publication documenting the implemented Quaternion Attitude Control:\n" + "Nonlinear Quadrocopter Attitude Control (2013)\n" + "by Dario Brescianini, Markus Hehn and Raffaello D'Andrea\n" + "Institute for Dynamic Systems and Control (IDSC), ETH Zurich\n" + "\n" + "https://www.research-collection.ethz.ch/bitstream/handle/20.500.11850/154099/eth-7387-01.pdf"); PRINT_MODULE_USAGE_NAME("mc_att_control", "controller"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/mc_autotune_attitude_control/mc_autotune_attitude_control.cpp b/src/modules/mc_autotune_attitude_control/mc_autotune_attitude_control.cpp index 3d2c0dab7fc2..db864dc3eb77 100644 --- a/src/modules/mc_autotune_attitude_control/mc_autotune_attitude_control.cpp +++ b/src/modules/mc_autotune_attitude_control/mc_autotune_attitude_control.cpp @@ -668,10 +668,7 @@ int McAutotuneAttitudeControl::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -)DESCR_STR"); + "### Description"); PRINT_MODULE_USAGE_NAME("mc_autotune_attitude_control", "autotune"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/mc_hover_thrust_estimator/MulticopterHoverThrustEstimator.cpp b/src/modules/mc_hover_thrust_estimator/MulticopterHoverThrustEstimator.cpp index d8b97336b960..39edb63b5663 100644 --- a/src/modules/mc_hover_thrust_estimator/MulticopterHoverThrustEstimator.cpp +++ b/src/modules/mc_hover_thrust_estimator/MulticopterHoverThrustEstimator.cpp @@ -302,10 +302,7 @@ int MulticopterHoverThrustEstimator::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -)DESCR_STR"); + "### Description"); PRINT_MODULE_USAGE_NAME("mc_hover_thrust_estimator", "estimator"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/mc_pos_control/MulticopterPositionControl.cpp b/src/modules/mc_pos_control/MulticopterPositionControl.cpp index 83e5e8d8ff3e..0fa0aa418a2d 100644 --- a/src/modules/mc_pos_control/MulticopterPositionControl.cpp +++ b/src/modules/mc_pos_control/MulticopterPositionControl.cpp @@ -750,15 +750,13 @@ int MulticopterPositionControl::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -The controller has two loops: a P loop for position error and a PID loop for velocity error. -Output of the velocity controller is thrust vector that is split to thrust direction -(i.e. rotation matrix for multicopter orientation) and thrust scalar (i.e. multicopter thrust itself). - -The controller doesn't use Euler angles for its work, they are generated only for more human-friendly control and -logging. -)DESCR_STR"); + "### Description\n" + "The controller has two loops: a P loop for position error and a PID loop for velocity error.\n" + "Output of the velocity controller is thrust vector that is split to thrust direction\n" + "(i.e. rotation matrix for multicopter orientation) and thrust scalar (i.e. multicopter thrust itself).\n" + "\n" + "The controller doesn't use Euler angles for its work, they are generated only for more human-friendly control and\n" + "logging."); PRINT_MODULE_USAGE_NAME("mc_pos_control", "controller"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/mc_rate_control/MulticopterRateControl.cpp b/src/modules/mc_rate_control/MulticopterRateControl.cpp index 39311252892c..575b970e8317 100644 --- a/src/modules/mc_rate_control/MulticopterRateControl.cpp +++ b/src/modules/mc_rate_control/MulticopterRateControl.cpp @@ -338,14 +338,11 @@ int MulticopterRateControl::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This implements the multicopter rate controller. It takes rate setpoints (in acro mode -via `manual_control_setpoint` topic) as inputs and outputs actuator control messages. - -The controller has a PID loop for angular rate error. - -)DESCR_STR"); + "### Description\n" + "This implements the multicopter rate controller. It takes rate setpoints (in acro mode\n" + "via `manual_control_setpoint` topic) as inputs and outputs actuator control messages.\n" + "\n" + "The controller has a PID loop for angular rate error."); PRINT_MODULE_USAGE_NAME("mc_rate_control", "controller"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 201eeb6123f6..6447e0aea882 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -1655,20 +1655,17 @@ int Navigator::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Module that is responsible for autonomous flight modes. This includes missions (read from dataman), -takeoff and RTL. -It is also responsible for geofence violation checking. - -### Implementation -The different internal modes are implemented as separate classes that inherit from a common base class `NavigatorMode`. -The member `_navigation_mode` contains the current active mode. - -Navigator publishes position setpoint triplets (`position_setpoint_triplet_s`), which are then used by the position -controller. - -)DESCR_STR"); + "### Description\n" + "Module that is responsible for autonomous flight modes. This includes missions (read from dataman),\n" + "takeoff and RTL.\n" + "It is also responsible for geofence violation checking.\n" + "\n" + "### Implementation\n" + "The different internal modes are implemented as separate classes that inherit from a common base class `NavigatorMode`.\n" + "The member `_navigation_mode` contains the current active mode.\n" + "\n" + "Navigator publishes position setpoint triplets (`position_setpoint_triplet_s`), which are then used by the position\n" + "controller."); PRINT_MODULE_USAGE_NAME("navigator", "controller"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/payload_deliverer/payload_deliverer.cpp b/src/modules/payload_deliverer/payload_deliverer.cpp index 0edb3a527051..967439f5aa6b 100644 --- a/src/modules/payload_deliverer/payload_deliverer.cpp +++ b/src/modules/payload_deliverer/payload_deliverer.cpp @@ -340,12 +340,9 @@ int PayloadDeliverer::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Handles payload delivery with either Gripper or a Winch with an appropriate timeout / feedback sensor setting, -and communicates back the delivery result as an acknowledgement internally - -)DESCR_STR"); + "### Description\n" + "Handles payload delivery with either Gripper or a Winch with an appropriate timeout / feedback sensor setting,\n" + "and communicates back the delivery result as an acknowledgement internally"); PRINT_MODULE_USAGE_NAME("payload_deliverer", "command"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/rc_update/rc_update.cpp b/src/modules/rc_update/rc_update.cpp index 98fef8eb10cd..02d03fff9150 100644 --- a/src/modules/rc_update/rc_update.cpp +++ b/src/modules/rc_update/rc_update.cpp @@ -730,16 +730,13 @@ int RCUpdate::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -The rc_update module handles RC channel mapping: read the raw input channels (`input_rc`), -then apply the calibration, map the RC channels to the configured channels & mode switches -and then publish as `rc_channels` and `manual_control_input`. - -### Implementation -To reduce control latency, the module is scheduled on input_rc publications. - -)DESCR_STR"); + "### Description\n" + "The rc_update module handles RC channel mapping: read the raw input channels (`input_rc`),\n" + "then apply the calibration, map the RC channels to the configured channels & mode switches\n" + "and then publish as `rc_channels` and `manual_control_input`.\n" + "\n" + "### Implementation\n" + "To reduce control latency, the module is scheduled on input_rc publications."); PRINT_MODULE_USAGE_NAME("rc_update", "system"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/replay/Replay.cpp b/src/modules/replay/Replay.cpp index a49c005bb5b4..86325103b263 100644 --- a/src/modules/replay/Replay.cpp +++ b/src/modules/replay/Replay.cpp @@ -1226,24 +1226,22 @@ Replay::print_usage(const char *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://docs.px4.io/main/en/debug/system_wide_replay.html) -page. -)DESCR_STR"); + "### Description\n" + "This module is used to replay ULog files.\n" + "\n" + "There are 2 environment variables used for configuration: `replay`, which must be set to an ULog file name - it's\n" + "the log file to be replayed. The second is the mode, specified via `replay_mode`:\n" + "- `replay_mode=ekf2`: specific EKF2 replay mode. It can only be used with the ekf2 module, but allows the replay\n" + "to run as fast as possible.\n" + "- Generic otherwise: this can be used to replay any module(s), but the replay will be done with the same speed as the\n" + "log was recorded.\n" + "\n" + "The module is typically used together with uORB publisher rules, to specify which messages should be replayed.\n" + "The replay module will just publish all messages that are found in the log. It also applies the parameters from\n" + "the log.\n" + "\n" + "The replay procedure is documented on the [System-wide Replay](https://docs.px4.io/main/en/debug/system_wide_replay.html)\n" + "page."); PRINT_MODULE_USAGE_NAME("replay", "system"); PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start replay, using log file from ENV variable 'replay'"); diff --git a/src/modules/rover_ackermann/RoverAckermann.cpp b/src/modules/rover_ackermann/RoverAckermann.cpp index 5fea7e5174a7..77bdc7eb316e 100644 --- a/src/modules/rover_ackermann/RoverAckermann.cpp +++ b/src/modules/rover_ackermann/RoverAckermann.cpp @@ -258,10 +258,8 @@ int RoverAckermann::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Rover ackermann module. -)DESCR_STR"); + "### Description\n" + "Rover ackermann module."); PRINT_MODULE_USAGE_NAME("rover_ackermann", "controller"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/rover_differential/RoverDifferential.cpp b/src/modules/rover_differential/RoverDifferential.cpp index c5fe294cd3e2..f0789b695e35 100644 --- a/src/modules/rover_differential/RoverDifferential.cpp +++ b/src/modules/rover_differential/RoverDifferential.cpp @@ -298,10 +298,8 @@ int RoverDifferential::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Rover Differential controller. -)DESCR_STR"); + "### Description\n" + "Rover Differential controller."); PRINT_MODULE_USAGE_NAME("rover_differential", "controller"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/rover_mecanum/RoverMecanum.cpp b/src/modules/rover_mecanum/RoverMecanum.cpp index b0729acc024d..c41fb4bdde19 100644 --- a/src/modules/rover_mecanum/RoverMecanum.cpp +++ b/src/modules/rover_mecanum/RoverMecanum.cpp @@ -350,10 +350,8 @@ int RoverMecanum::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Rover Mecanum controller. -)DESCR_STR"); + "### Description\n" + "Rover Mecanum controller."); PRINT_MODULE_USAGE_NAME("rover_mecanum", "controller"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/rover_pos_control/RoverPositionControl.cpp b/src/modules/rover_pos_control/RoverPositionControl.cpp index 7466077a9334..a67f9f0aff2d 100644 --- a/src/modules/rover_pos_control/RoverPositionControl.cpp +++ b/src/modules/rover_pos_control/RoverPositionControl.cpp @@ -520,26 +520,23 @@ int RoverPositionControl::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Controls the position of a ground rover using an L1 controller. - -Publishes `vehicle_thrust_setpoint (only in x) and vehicle_torque_setpoint (only yaw)` messages at IMU_GYRO_RATEMAX. - -### Implementation -Currently, this implementation supports only a few modes: - - * Full manual: Throttle and yaw controls are passed directly through to the actuators - * Auto mission: The rover runs missions - * Loiter: The rover will navigate to within the loiter radius, then stop the motors - -### Examples -CLI usage example: -$ rover_pos_control start -$ rover_pos_control status -$ rover_pos_control stop - -)DESCR_STR"); + "### Description\n" + "Controls the position of a ground rover using an L1 controller.\n" + "\n" + "Publishes `vehicle_thrust_setpoint (only in x) and vehicle_torque_setpoint (only yaw)` messages at IMU_GYRO_RATEMAX.\n" + "\n" + "### Implementation\n" + "Currently, this implementation supports only a few modes:\n" + "\n" + "* Full manual: Throttle and yaw controls are passed directly through to the actuators\n" + "* Auto mission: The rover runs missions\n" + "* Loiter: The rover will navigate to within the loiter radius, then stop the motors\n" + "\n" + "### Examples\n" + "CLI usage example:\n" + "$ rover_pos_control start\n" + "$ rover_pos_control status\n" + "$ rover_pos_control stop"); PRINT_MODULE_USAGE_NAME("rover_pos_control", "controller"); PRINT_MODULE_USAGE_COMMAND("start") diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 26cc3329da09..7e0aa3e6d129 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -765,25 +765,22 @@ int Sensors::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -The sensors module is central to the whole system. It takes low-level output from drivers, turns -it into a more usable form, and publishes it for the rest of the system. - -The provided functionality includes: -- Read the output from the sensor drivers (`SensorGyro`, etc.). - If there are multiple of the same type, do voting and failover handling. - Then apply the board rotation and temperature calibration (if enabled). And finally publish the data; one of the - topics is `SensorCombined`, used by many parts of the system. -- Make sure the sensor drivers get the updated calibration parameters (scale & offset) when the parameters change or - on startup. The sensor drivers use the ioctl interface for parameter updates. For this to work properly, the - sensor drivers must already be running when `sensors` is started. -- Do sensor consistency checks and publish the `SensorsStatusImu` topic. - -### Implementation -It runs in its own thread and polls on the currently selected gyro topic. - -)DESCR_STR"); + "### Description\n" + "The sensors module is central to the whole system. It takes low-level output from drivers, turns\n" + "it into a more usable form, and publishes it for the rest of the system.\n" + "\n" + "The provided functionality includes:\n" + "- Read the output from the sensor drivers (`SensorGyro`, etc.).\n" + "If there are multiple of the same type, do voting and failover handling.\n" + "Then apply the board rotation and temperature calibration (if enabled). And finally publish the data; one of the\n" + "topics is `SensorCombined`, used by many parts of the system.\n" + "- Make sure the sensor drivers get the updated calibration parameters (scale & offset) when the parameters change or\n" + "on startup. The sensor drivers use the ioctl interface for parameter updates. For this to work properly, the\n" + "sensor drivers must already be running when `sensors` is started.\n" + "- Do sensor consistency checks and publish the `SensorsStatusImu` topic.\n" + "\n" + "### Implementation\n" + "It runs in its own thread and polls on the currently selected gyro topic."); PRINT_MODULE_USAGE_NAME("sensors", "system"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/simulation/battery_simulator/BatterySimulator.cpp b/src/modules/simulation/battery_simulator/BatterySimulator.cpp index 45e8fde168d1..c4d5e5886c07 100644 --- a/src/modules/simulation/battery_simulator/BatterySimulator.cpp +++ b/src/modules/simulation/battery_simulator/BatterySimulator.cpp @@ -205,11 +205,7 @@ int BatterySimulator::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - - -)DESCR_STR"); + "### Description"); PRINT_MODULE_USAGE_NAME("battery_simulator", "system"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/simulation/gz_bridge/GZBridge.cpp b/src/modules/simulation/gz_bridge/GZBridge.cpp index 2dc1ef13e4f4..314053226959 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.cpp +++ b/src/modules/simulation/gz_bridge/GZBridge.cpp @@ -1071,10 +1071,7 @@ int GZBridge::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -)DESCR_STR"); + "### Description"); PRINT_MODULE_USAGE_NAME("gz_bridge", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/simulation/pwm_out_sim/PWMSim.cpp b/src/modules/simulation/pwm_out_sim/PWMSim.cpp index c11a5eb365fe..8e7725386ae4 100644 --- a/src/modules/simulation/pwm_out_sim/PWMSim.cpp +++ b/src/modules/simulation/pwm_out_sim/PWMSim.cpp @@ -173,17 +173,14 @@ int PWMSim::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Driver for simulated PWM outputs. - -Its only function is to take `actuator_control` uORB messages, -mix them with any loaded mixer and output the result to the -`actuator_output` uORB topic. - -It is used in SITL and HITL. - -)DESCR_STR"); + "### Description\n" + "Driver for simulated PWM outputs.\n" + "\n" + "Its only function is to take `actuator_control` uORB messages,\n" + "mix them with any loaded mixer and output the result to the\n" + "`actuator_output` uORB topic.\n" + "\n" + "It is used in SITL and HITL."); PRINT_MODULE_USAGE_NAME("pwm_out_sim", "driver"); PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start the module"); diff --git a/src/modules/simulation/sensor_agp_sim/SensorAgpSim.cpp b/src/modules/simulation/sensor_agp_sim/SensorAgpSim.cpp index 4de5d46c2d54..23c363e580e9 100644 --- a/src/modules/simulation/sensor_agp_sim/SensorAgpSim.cpp +++ b/src/modules/simulation/sensor_agp_sim/SensorAgpSim.cpp @@ -183,11 +183,8 @@ int SensorAgpSim::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Module to simulate auxiliary global position measurements with optional failure modes for SIH simulation. - -)DESCR_STR"); + "### Description\n" + "Module to simulate auxiliary global position measurements with optional failure modes for SIH simulation."); PRINT_MODULE_USAGE_NAME("sensor_agp_sim", "system"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp b/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp index 7b0d9556cadf..77cb8c97b7e5 100644 --- a/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp +++ b/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp @@ -189,11 +189,7 @@ int SensorAirspeedSim::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - - -)DESCR_STR"); + "### Description"); PRINT_MODULE_USAGE_NAME("sensor_arispeed_sim", "system"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/simulation/sensor_baro_sim/SensorBaroSim.cpp b/src/modules/simulation/sensor_baro_sim/SensorBaroSim.cpp index fc70998e9aeb..e369034e5054 100644 --- a/src/modules/simulation/sensor_baro_sim/SensorBaroSim.cpp +++ b/src/modules/simulation/sensor_baro_sim/SensorBaroSim.cpp @@ -213,11 +213,7 @@ int SensorBaroSim::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - - -)DESCR_STR"); + "### Description"); PRINT_MODULE_USAGE_NAME("sensor_baro_sim", "system"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/simulation/sensor_gps_sim/SensorGpsSim.cpp b/src/modules/simulation/sensor_gps_sim/SensorGpsSim.cpp index 5641706345a0..a3328d335b07 100644 --- a/src/modules/simulation/sensor_gps_sim/SensorGpsSim.cpp +++ b/src/modules/simulation/sensor_gps_sim/SensorGpsSim.cpp @@ -217,11 +217,7 @@ int SensorGpsSim::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - - -)DESCR_STR"); + "### Description"); PRINT_MODULE_USAGE_NAME("sensor_gps_sim", "system"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/simulation/sensor_mag_sim/SensorMagSim.cpp b/src/modules/simulation/sensor_mag_sim/SensorMagSim.cpp index 97c2626f75b4..120bc59f8806 100644 --- a/src/modules/simulation/sensor_mag_sim/SensorMagSim.cpp +++ b/src/modules/simulation/sensor_mag_sim/SensorMagSim.cpp @@ -177,11 +177,7 @@ int SensorMagSim::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - - -)DESCR_STR"); + "### Description"); PRINT_MODULE_USAGE_NAME("sensor_mag_sim", "system"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/simulation/simulator_sih/sih.cpp b/src/modules/simulation/simulator_sih/sih.cpp index f90805dd660e..e597f29f6162 100644 --- a/src/modules/simulation/simulator_sih/sih.cpp +++ b/src/modules/simulation/simulator_sih/sih.cpp @@ -789,31 +789,27 @@ int Sih::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This module provides a simulator for quadrotors and fixed-wings running fully -inside the hardware autopilot. + "### Description\n" + "This module provides a simulator for quadrotors and fixed-wings running fully\n" + "inside the hardware autopilot.\n" + "\n" + "This simulator subscribes to 'actuator_outputs' which are the actuator pwm\n" + "signals given by the control allocation module.\n" + "\n" + "This simulator publishes the sensors signals corrupted with realistic noise\n" + "in order to incorporate the state estimator in the loop.\n" + "\n" + "### Implementation\n" + "The simulator implements the equations of motion using matrix algebra.\n" + "Quaternion representation is used for the attitude.\n" + "Forward Euler is used for integration.\n" + "Most of the variables are declared global in the .hpp file to avoid stack overflow."); + + PRINT_MODULE_USAGE_NAME("simulator_sih", "simulation"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); -This simulator subscribes to "actuator_outputs" which are the actuator pwm -signals given by the control allocation module. - -This simulator publishes the sensors signals corrupted with realistic noise -in order to incorporate the state estimator in the loop. - -### Implementation -The simulator implements the equations of motion using matrix algebra. -Quaternion representation is used for the attitude. -Forward Euler is used for integration. -Most of the variables are declared global in the .hpp file to avoid stack overflow. - - -)DESCR_STR"); - - PRINT_MODULE_USAGE_NAME("simulator_sih", "simulation"); - PRINT_MODULE_USAGE_COMMAND("start"); - PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); - - return 0; + return 0; } extern "C" __EXPORT int simulator_sih_main(int argc, char *argv[]) diff --git a/src/modules/simulation/system_power_simulator/SystemPowerSimulator.cpp b/src/modules/simulation/system_power_simulator/SystemPowerSimulator.cpp index 2c7671c2d2e8..2f8cc2de98ef 100644 --- a/src/modules/simulation/system_power_simulator/SystemPowerSimulator.cpp +++ b/src/modules/simulation/system_power_simulator/SystemPowerSimulator.cpp @@ -112,11 +112,7 @@ int SystemPowerSimulator::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - - -)DESCR_STR"); + "### Description"); PRINT_MODULE_USAGE_NAME("system_power_simulation", "system"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/temperature_compensation/TemperatureCompensationModule.cpp b/src/modules/temperature_compensation/TemperatureCompensationModule.cpp index ec1935918164..1a561375f582 100644 --- a/src/modules/temperature_compensation/TemperatureCompensationModule.cpp +++ b/src/modules/temperature_compensation/TemperatureCompensationModule.cpp @@ -477,18 +477,16 @@ int TemperatureCompensationModule::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -The temperature compensation module allows all of the gyro(s), accel(s), and baro(s) in the system to be temperature -compensated. The module monitors the data coming from the sensors and updates the associated sensor_correction topic -whenever a change in temperature is detected. The module can also be configured to perform the coeffecient calculation -routine at next boot, which allows the thermal calibration coeffecients to be calculated while the vehicle undergoes -a temperature cycle. - -)DESCR_STR"); + "### Description\n" + "The temperature compensation module allows all of the gyro(s), accel(s), and baro(s) in the system to be temperature\n" + "compensated. The module monitors the data coming from the sensors and updates the associated sensor_correction topic\n" + "whenever a change in temperature is detected. The module can also be configured to perform the coeffecient calculation\n" + "routine at next boot, which allows the thermal calibration coeffecients to be calculated while the vehicle undergoes\n" + "a temperature cycle."); PRINT_MODULE_USAGE_NAME("temperature_compensation", "system"); - PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start the module, which monitors the sensors and updates the sensor_correction topic"); + PRINT_MODULE_USAGE_COMMAND_DESCR("start", + "Start the module, which monitors the sensors and updates the sensor_correction topic"); PRINT_MODULE_USAGE_COMMAND_DESCR("calibrate", "Run temperature calibration process"); PRINT_MODULE_USAGE_PARAM_FLAG('a', "calibrate the accel", true); PRINT_MODULE_USAGE_PARAM_FLAG('g', "calibrate the gyro", true); diff --git a/src/modules/time_persistor/TimePersistor.cpp b/src/modules/time_persistor/TimePersistor.cpp index 92d310c14c0b..299a7b4c59a1 100644 --- a/src/modules/time_persistor/TimePersistor.cpp +++ b/src/modules/time_persistor/TimePersistor.cpp @@ -107,13 +107,10 @@ int TimePersistor::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Writes the RTC time cyclically to a file and reloads this value on startup. -This allows monotonic time on systems that only have a software RTC (that is not battery powered). -Explicitly setting the time backwards (e.g. via system_time) is still possible. - -)DESCR_STR"); + "### Description\n" + "Writes the RTC time cyclically to a file and reloads this value on startup.\n" + "This allows monotonic time on systems that only have a software RTC (that is not battery powered).\n" + "Explicitly setting the time backwards (e.g. via system_time) is still possible."); PRINT_MODULE_USAGE_NAME("time_persistor", "system"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/modules/uuv_att_control/uuv_att_control.cpp b/src/modules/uuv_att_control/uuv_att_control.cpp index 52baccb8dde6..ee6cb4dae6bd 100644 --- a/src/modules/uuv_att_control/uuv_att_control.cpp +++ b/src/modules/uuv_att_control/uuv_att_control.cpp @@ -312,25 +312,22 @@ int UUVAttitudeControl::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Controls the attitude of an unmanned underwater vehicle (UUV). - -Publishes `vehicle_thrust_setpont` and `vehicle_torque_setpoint` messages at a constant 250Hz. - -### Implementation -Currently, this implementation supports only a few modes: - - * Full manual: Roll, pitch, yaw, and throttle controls are passed directly through to the actuators - * Auto mission: The uuv runs missions - -### Examples -CLI usage example: -$ uuv_att_control start -$ uuv_att_control status -$ uuv_att_control stop - -)DESCR_STR"); + "### Description\n" + "Controls the attitude of an unmanned underwater vehicle (UUV).\n" + "\n" + "Publishes `vehicle_thrust_setpont` and `vehicle_torque_setpoint` messages at a constant 250Hz.\n" + "\n" + "### Implementation\n" + "Currently, this implementation supports only a few modes:\n" + "\n" + "* Full manual: Roll, pitch, yaw, and throttle controls are passed directly through to the actuators\n" + "* Auto mission: The uuv runs missions\n" + "\n" + "### Examples\n" + "CLI usage example:\n" + "$ uuv_att_control start\n" + "$ uuv_att_control status\n" + "$ uuv_att_control stop"); PRINT_MODULE_USAGE_NAME("uuv_att_control", "controller"); PRINT_MODULE_USAGE_COMMAND("start") diff --git a/src/modules/uuv_pos_control/uuv_pos_control.cpp b/src/modules/uuv_pos_control/uuv_pos_control.cpp index 272ea56def8d..db5538776c8f 100644 --- a/src/modules/uuv_pos_control/uuv_pos_control.cpp +++ b/src/modules/uuv_pos_control/uuv_pos_control.cpp @@ -238,29 +238,27 @@ int UUVPOSControl::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Controls the attitude of an unmanned underwater vehicle (UUV). -Publishes `attitude_setpoint` messages. -### Implementation -Currently, this implementation supports only a few modes: - * Full manual: Roll, pitch, yaw, and throttle controls are passed directly through to the actuators - * Auto mission: The uuv runs missions -### Examples -CLI usage example: -$ uuv_pos_control start -$ uuv_pos_control status -$ uuv_pos_control stop -)DESCR_STR"); - - PRINT_MODULE_USAGE_NAME("uuv_pos_control", "controller"); - PRINT_MODULE_USAGE_COMMAND("start") - PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); - - return 0; + "### Description\n" + "Controls the attitude of an unmanned underwater vehicle (UUV).\n" + "Publishes `attitude_setpoint` messages.\n" + "### Implementation\n" + "Currently, this implementation supports only a few modes:\n" + "* Full manual: Roll, pitch, yaw, and throttle controls are passed directly through to the actuators\n" + "* Auto mission: The uuv runs missions\n" + "### Examples\n" + "CLI usage example:\n" + "$ uuv_pos_control start\n" + "$ uuv_pos_control status\n" + "$ uuv_pos_control stop"); + + PRINT_MODULE_USAGE_NAME("uuv_pos_control", "controller"); + PRINT_MODULE_USAGE_COMMAND("start") + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); + + return 0; } int uuv_pos_control_main(int argc, char *argv[]) { - return UUVPOSControl::main(argc, argv); + return UUVPOSControl::main(argc, argv); } diff --git a/src/modules/uxrce_dds_client/uxrce_dds_client.cpp b/src/modules/uxrce_dds_client/uxrce_dds_client.cpp index 339bedd7a906..3ee4eb25e6e6 100644 --- a/src/modules/uxrce_dds_client/uxrce_dds_client.cpp +++ b/src/modules/uxrce_dds_client/uxrce_dds_client.cpp @@ -1036,14 +1036,12 @@ int UxrceddsClient::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -UXRCE-DDS Client used to communicate uORB topics with an Agent over serial or UDP. - -### Examples -$ uxrce_dds_client start -t serial -d /dev/ttyS3 -b 921600 -$ uxrce_dds_client start -t udp -h 127.0.0.1 -p 15555 -)DESCR_STR"); + "### Description\n" + "UXRCE-DDS Client used to communicate uORB topics with an Agent over serial or UDP.\n" + "\n" + "### Examples\n" + "$ uxrce_dds_client start -t serial -d /dev/ttyS3 -b 921600\n" + "$ uxrce_dds_client start -t udp -h 127.0.0.1 -p 15555"); PRINT_MODULE_USAGE_NAME("uxrce_dds_client", "system"); PRINT_MODULE_USAGE_COMMAND("start"); @@ -1051,7 +1049,8 @@ UXRCE-DDS Client used to communicate uORB topics with an Agent over serial or UD PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, "", "serial device", true); PRINT_MODULE_USAGE_PARAM_INT('b', 0, 0, 3000000, "Baudrate (can also be p:)", true); PRINT_MODULE_USAGE_PARAM_STRING('h', nullptr, "", "Agent IP. If not provided, defaults to UXRCE_DDS_AG_IP", true); - PRINT_MODULE_USAGE_PARAM_INT('p', -1, 0, 65535, "Agent listening port. If not provided, defaults to UXRCE_DDS_PRT", true); + PRINT_MODULE_USAGE_PARAM_INT('p', -1, 0, 65535, "Agent listening port. If not provided, defaults to UXRCE_DDS_PRT", + true); PRINT_MODULE_USAGE_PARAM_STRING('n', nullptr, nullptr, "Client DDS namespace", true); PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); 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 afcde463da34..6e88737d7a6b 100644 --- a/src/modules/vtol_att_control/vtol_att_control_main.cpp +++ b/src/modules/vtol_att_control/vtol_att_control_main.cpp @@ -498,10 +498,8 @@ VtolAttitudeControl::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -fw_att_control is the fixed wing attitude controller. -)DESCR_STR"); + "### Description\n" + "fw_att_control is the fixed wing attitude controller."); PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_NAME("vtol_att_control", "controller"); diff --git a/src/systemcmds/actuator_test/actuator_test.cpp b/src/systemcmds/actuator_test/actuator_test.cpp index 97d39c72fb23..e078e2fe906b 100644 --- a/src/systemcmds/actuator_test/actuator_test.cpp +++ b/src/systemcmds/actuator_test/actuator_test.cpp @@ -70,11 +70,9 @@ static void usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -Utility to test actuators. - -WARNING: remove all props before using this command. -)DESCR_STR"); + "Utility to test actuators.\n" + "\n" + "WARNING: remove all props before using this command."); PRINT_MODULE_USAGE_NAME("actuator_test", "command"); PRINT_MODULE_USAGE_COMMAND_DESCR("set", "Set an actuator to a specific output value"); @@ -122,6 +120,7 @@ int actuator_test_main(int argc, char *argv[]) usage("value invalid"); return 1; } + break; case 't': @@ -162,27 +161,33 @@ int actuator_test_main(int argc, char *argv[]) } actuator_test(function, NAN, 0, true); + } else { actuator_test(function, value, timeout_ms, false); } + return 0; } else if (strcmp("iterate-motors", argv[myoptind]) == 0) { value = 0.15f; + for (int i = 0; i < actuator_test_s::MAX_NUM_MOTORS; ++i) { - PX4_INFO("Motor %i (%.0f%%)", i, (double)(value*100.f)); - actuator_test(actuator_test_s::FUNCTION_MOTOR1+i, value, 400, false); + PX4_INFO("Motor %i (%.0f%%)", i, (double)(value * 100.f)); + actuator_test(actuator_test_s::FUNCTION_MOTOR1 + i, value, 400, false); px4_usleep(600000); } + return 0; } else if (strcmp("iterate-servos", argv[myoptind]) == 0) { value = 0.3f; + for (int i = 0; i < actuator_test_s::MAX_NUM_SERVOS; ++i) { - PX4_INFO("Servo %i (%.0f%%)", i, (double)(value*100.f)); - actuator_test(actuator_test_s::FUNCTION_SERVO1+i, value, 800, false); + PX4_INFO("Servo %i (%.0f%%)", i, (double)(value * 100.f)); + actuator_test(actuator_test_s::FUNCTION_SERVO1 + i, value, 800, false); px4_usleep(1000000); } + return 0; } } diff --git a/src/systemcmds/dmesg/dmesg.cpp b/src/systemcmds/dmesg/dmesg.cpp index 44e416f19b14..26c05d1a9f71 100644 --- a/src/systemcmds/dmesg/dmesg.cpp +++ b/src/systemcmds/dmesg/dmesg.cpp @@ -77,17 +77,15 @@ 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"); + "### Description\n" + "\n" + "Command-line tool to show bootup console messages.\n" + "Note that output from NuttX's work queues and syslog are not captured.\n" + "\n" + "### Examples\n" + "\n" + "Keep printing all messages in the background:\n" + "$ dmesg -f &"); PRINT_MODULE_USAGE_NAME("dmesg", "system"); PRINT_MODULE_USAGE_PARAM_FLAG('f', "Follow: wait for new messages", true); diff --git a/src/systemcmds/failure/failure.cpp b/src/systemcmds/failure/failure.cpp index 2b28aefde879..7116542ae8fd 100644 --- a/src/systemcmds/failure/failure.cpp +++ b/src/systemcmds/failure/failure.cpp @@ -88,18 +88,16 @@ static constexpr FailureType failure_types[] = { static void print_usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Inject failures into system. - -### Implementation -This system command sends a vehicle command over uORB to trigger failure. - -### Examples -Test the GPS failsafe by stopping GPS: - -failure gps off -)DESCR_STR"); + "### Description\n" + "Inject failures into system.\n" + "\n" + "### Implementation\n" + "This system command sends a vehicle command over uORB to trigger failure.\n" + "\n" + "### Examples\n" + "Test the GPS failsafe by stopping GPS:\n" + "\n" + "failure gps off"); PRINT_MODULE_USAGE_NAME_SIMPLE("failure", "command"); PRINT_MODULE_USAGE_COMMAND_DESCR("help", "Show this help text"); @@ -108,19 +106,22 @@ failure gps off PRINT_MODULE_USAGE_PARAM_INT('i', 0, 0, 4, "sensor instance (0=all)", true); PX4_INFO_RAW("\nComponents:\n"); + for (const auto &failure_unit : failure_units) { PX4_INFO_RAW("- %s\n", failure_unit.key); } PX4_INFO_RAW("\nFailure types:\n"); + for (const auto &failure_type : failure_types) { PX4_INFO_RAW("- %s\n", failure_type.key); } } -int inject_failure(const FailureUnit& unit, const FailureType& type, uint8_t instance) +int inject_failure(const FailureUnit &unit, const FailureType &type, uint8_t instance) { - PX4_WARN("inject failure unit: %s (%d), type: %s (%d), instance: %d", unit.key, unit.value, type.key, type.value, instance); + PX4_WARN("inject failure unit: %s (%d), type: %s (%d), instance: %d", unit.key, unit.value, type.key, type.value, + instance); uORB::Subscription command_ack_sub{ORB_ID(vehicle_command_ack)}; diff --git a/src/systemcmds/gpio/gpio.cpp b/src/systemcmds/gpio/gpio.cpp index db5ce34783a0..d65056fd3009 100644 --- a/src/systemcmds/gpio/gpio.cpp +++ b/src/systemcmds/gpio/gpio.cpp @@ -298,26 +298,21 @@ void usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -This command is used to read and write GPIOs -``` -gpio read / [PULLDOWN|PULLUP] [--force] -gpio write / [PUSHPULL|OPENDRAIN] [--force] -``` - -### Examples -Read the value on port H pin 4 configured as pullup, and it is high -$ gpio read H4 PULLUP -1 OK - -Set the output value on Port E pin 7 to high -$ gpio write E7 1 --force - -Set the output value on device /dev/gpio1 to high -$ gpio write /dev/gpio1 1 - -)DESCR_STR"); + "### Description\n" + "This command is used to read and write GPIOs\n" + "$ gpio read / [PULLDOWN|PULLUP] [--force]\n" + "$ gpio write / [PUSHPULL|OPENDRAIN] [--force]\n" + "\n" + "### Examples\n" + "Read the value on port H pin 4 configured as pullup, and it is high\n" + "$ gpio read H4 PULLUP\n" + "1 OK\n" + "\n" + "Set the output value on Port E pin 7 to high\n" + "$ gpio write E7 1 --force\n" + "\n" + "Set the output value on device /dev/gpio1 to high\n" + "$ gpio write /dev/gpio1 1"); PRINT_MODULE_USAGE_NAME_SIMPLE("gpio", "command"); diff --git a/src/systemcmds/i2c_launcher/i2c_launcher.cpp b/src/systemcmds/i2c_launcher/i2c_launcher.cpp index db8b52213218..f0bfb14c565a 100644 --- a/src/systemcmds/i2c_launcher/i2c_launcher.cpp +++ b/src/systemcmds/i2c_launcher/i2c_launcher.cpp @@ -195,11 +195,8 @@ int I2CLauncher::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Daemon that starts drivers based on found I2C devices. - -)DESCR_STR"); + "### Description\n" + "Daemon that starts drivers based on found I2C devices."); PRINT_MODULE_USAGE_NAME("i2c_launcher", "system"); PRINT_MODULE_USAGE_COMMAND("start"); @@ -213,7 +210,7 @@ extern "C" __EXPORT int i2c_launcher_main(int argc, char *argv[]) { using ThisDriver = I2CLauncher; - static I2CLauncher* instances[I2C_BUS_MAX_BUS_ITEMS]; + static I2CLauncher *instances[I2C_BUS_MAX_BUS_ITEMS]; int bus = -1; int myoptind = 1; int ch; diff --git a/src/systemcmds/led_control/led_control.cpp b/src/systemcmds/led_control/led_control.cpp index 7b54e82892bb..f5e7ba979463 100644 --- a/src/systemcmds/led_control/led_control.cpp +++ b/src/systemcmds/led_control/led_control.cpp @@ -239,21 +239,18 @@ static void usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Command-line tool to control & test the (external) LED's. - -To use it make sure there's a driver running, which handles the led_control uorb topic. - -There are different priorities, such that for example one module can set a color with low priority, and another -module can blink N times with high priority, and the LED's automatically return to the lower priority state -after the blinking. The `reset` command can also be used to return to a lower priority. - -### Examples -Blink the first LED 5 times in blue: -$ led_control blink -c blue -l 0 -n 5 - -)DESCR_STR"); + "### Description\n" + "Command-line tool to control & test the (external) LED's.\n" + "\n" + "To use it make sure there's a driver running, which handles the led_control uorb topic.\n" + "\n" + "There are different priorities, such that for example one module can set a color with low priority, and another\n" + "module can blink N times with high priority, and the LED's automatically return to the lower priority state\n" + "after the blinking. The `reset` command can also be used to return to a lower priority.\n" + "\n" + "### Examples\n" + "Blink the first LED 5 times in blue:\n" + "$ led_control blink -c blue -l 0 -n 5"); PRINT_MODULE_USAGE_NAME("led_control", "command"); diff --git a/src/systemcmds/netman/netman.cpp b/src/systemcmds/netman/netman.cpp index a7014c62de28..740cb3358f92 100644 --- a/src/systemcmds/netman/netman.cpp +++ b/src/systemcmds/netman/netman.cpp @@ -399,37 +399,35 @@ static void usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( - ### Description - Network configuration manager saves the network settings in non-volatile - memory. On boot the `update` option will be run. If a network configuration - does not exist. The default setting will be saved in non-volatile and the - system rebooted. - - #### update - - `netman update` is run automatically by [a startup script](../concept/system_startup.md#system-startup). - When run, the `update` option will check for the existence of `net.cfg` in the root of the SD Card. - It then saves the network settings from `net.cfg` in non-volatile memory, - deletes the file and reboots the system. - - #### save - - The `save` option will save settings from non-volatile memory to a file named - `net.cfg` on the SD Card filesystem for editing. Use this to edit the settings. - Save does not immediately apply the network settings; the user must reboot the flight stack. - By contrast, the `update` command is run by the start-up script, commits the settings to non-volatile memory, - and reboots the flight controller (which will then use the new settings). - - #### show - - The `show` option will display the network settings in `net.cfg` to the console. - - ### Examples - $ netman save # Save the parameters to the SD card. - $ netman show # display current settings. - $ netman update -i eth0 # do an update -)DESCR_STR"); + "### Description\n" + "Network configuration manager saves the network settings in non-volatile\n" + "memory. On boot the `update` option will be run. If a network configuration\n" + "does not exist. The default setting will be saved in non-volatile and the\n" + "system rebooted.\n" + "\n" + "#### update\n" + "\n" + "`netman update` is run automatically by [a startup script](../concept/system_startup.md#system-startup).\n" + "When run, the `update` option will check for the existence of `net.cfg` in the root of the SD Card.\n" + "It then saves the network settings from `net.cfg` in non-volatile memory,\n" + "deletes the file and reboots the system.\n" + "\n" + "#### save\n" + "\n" + "The `save` option will save settings from non-volatile memory to a file named\n" + "`net.cfg` on the SD Card filesystem for editing. Use this to edit the settings.\n" + "Save does not immediately apply the network settings; the user must reboot the flight stack.\n" + "By contrast, the `update` command is run by the start-up script, commits the settings to non-volatile memory,\n" + "and reboots the flight controller (which will then use the new settings).\n" + "\n" + "#### show\n" + "\n" + "The `show` option will display the network settings in `net.cfg` to the console.\n" + "\n" + "### Examples\n" + "$ netman save # Save the parameters to the SD card.\n" + "$ netman show # display current settings.\n" + "$ netman update -i eth0 # do an update"); PRINT_MODULE_USAGE_NAME("netman", "system"); PRINT_MODULE_USAGE_COMMAND_DESCR("show", "Display the current persistent network settings to the console."); diff --git a/src/systemcmds/param/param.cpp b/src/systemcmds/param/param.cpp index 8194cfffa5ab..e5e88353af4a 100644 --- a/src/systemcmds/param/param.cpp +++ b/src/systemcmds/param/param.cpp @@ -97,29 +97,27 @@ static int do_find(const char *name); static void print_usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Command to access and manipulate parameters via shell or script. - -This is used for example in the startup script to set airframe-specific parameters. - -Parameters are automatically saved when changed, eg. with `param set`. They are typically stored to FRAM -or to the SD card. `param select` can be used to change the storage location for subsequent saves (this will -need to be (re-)configured on every boot). - -If the FLASH-based backend is enabled (which is done at compile time, e.g. for the Intel Aero or Omnibus), -`param select` has no effect and the default is always the FLASH backend. However `param save/load ` -can still be used to write to/read from files. - -Each parameter has a 'used' flag, which is set when it's read during boot. It is used to only show relevant -parameters to a ground control station. - -### Examples -Change the airframe and make sure the airframe's default parameters are loaded: -$ param set SYS_AUTOSTART 4001 -$ param set SYS_AUTOCONFIG 1 -$ reboot -)DESCR_STR"); + "### Description\n" + "Command to access and manipulate parameters via shell or script.\n" + "\n" + "This is used for example in the startup script to set airframe-specific parameters.\n" + "\n" + "Parameters are automatically saved when changed, eg. with `param set`. They are typically stored to FRAM\n" + "or to the SD card. `param select` can be used to change the storage location for subsequent saves (this will\n" + "need to be (re-)configured on every boot).\n" + "\n" + "If the FLASH-based backend is enabled (which is done at compile time, e.g. for the Intel Aero or Omnibus),\n" + "`param select` has no effect and the default is always the FLASH backend. However `param save/load `\n" + "can still be used to write to/read from files.\n" + "\n" + "Each parameter has a 'used' flag, which is set when it's read during boot. It is used to only show relevant\n" + "parameters to a ground control station.\n" + "\n" + "### Examples\n" + "Change the airframe and make sure the airframe's default parameters are loaded:\n" + "$ param set SYS_AUTOSTART 4001\n" + "$ param set SYS_AUTOCONFIG 1\n" + "$ reboot"); PRINT_MODULE_USAGE_NAME("param", "command"); PRINT_MODULE_USAGE_COMMAND_DESCR("load", "Load params from a file (overwrite all)"); @@ -522,9 +520,11 @@ do_show_for_airframe() param_foreach(do_show_print_for_airframe, nullptr, true, true); int32_t sys_autostart = 0; param_get(param_find("SYS_AUTOSTART"), &sys_autostart); + if (sys_autostart != 0) { PX4_INFO_RAW("# Make sure to add all params from the current airframe (ID=%" PRId32 ") as well\n", sys_autostart); } + return 0; } @@ -608,8 +608,8 @@ do_show_index(const char *index, bool used_index) } PX4_INFO_RAW("index %d: %c %c %s [%d,%d] : ", i, (param_used(param) ? 'x' : ' '), - param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'), - param_name(param), param_get_used_index(param), param_get_index(param)); + param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'), + param_name(param), param_get_used_index(param), param_get_index(param)); switch (param_type(param)) { case PARAM_TYPE_INT32: @@ -678,8 +678,8 @@ do_show_print(void *arg, param_t param) } PX4_INFO_RAW("%c %c %s [%d,%d] : ", (param_used(param) ? 'x' : ' '), - param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'), - param_name(param), param_get_used_index(param), param_get_index(param)); + param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'), + param_name(param), param_get_used_index(param), param_get_index(param)); /* * This case can be expanded to handle printing common structure types. @@ -786,8 +786,8 @@ do_set(const char *name, const char *val, bool fail_on_not_found) if (i != newval) { PX4_INFO_RAW("%c %s: ", - param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'), - param_name(param)); + param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'), + param_name(param)); PX4_INFO_RAW("curr: %ld", (long)i); param_set(param, &newval); PX4_INFO_RAW(" -> new: %ld\n", (long)newval); @@ -808,8 +808,8 @@ do_set(const char *name, const char *val, bool fail_on_not_found) if (f != newval) { #pragma GCC diagnostic pop PX4_INFO_RAW("%c %s: ", - param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'), - param_name(param)); + param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'), + param_name(param)); PX4_INFO_RAW("curr: %4.4f", (double)f); param_set(param, &newval); PX4_INFO_RAW(" -> new: %4.4f\n", (double)newval); diff --git a/src/systemcmds/system_time/system_time.cpp b/src/systemcmds/system_time/system_time.cpp index 361e7578618c..827c53d886ce 100644 --- a/src/systemcmds/system_time/system_time.cpp +++ b/src/systemcmds/system_time/system_time.cpp @@ -110,17 +110,15 @@ usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -Command-line tool to set and get system time. - -### Examples - -Set the system time and read it back -$ system_time set 1600775044 -$ system_time get -)DESCR_STR"); + "### Description\n" + "\n" + "Command-line tool to set and get system time.\n" + "\n" + "### Examples\n" + "\n" + "Set the system time and read it back\n" + "$ system_time set 1600775044\n" + "$ system_time get"); PRINT_MODULE_USAGE_NAME("system_time", "command"); PRINT_MODULE_USAGE_COMMAND_DESCR("set", "Set the system time, provide time in unix epoch time format"); diff --git a/src/systemcmds/topic_listener/listener_main.cpp b/src/systemcmds/topic_listener/listener_main.cpp index 28244869f90f..29e1765715a3 100644 --- a/src/systemcmds/topic_listener/listener_main.cpp +++ b/src/systemcmds/topic_listener/listener_main.cpp @@ -247,11 +247,9 @@ static void usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -Utility to listen on uORB topics and print the data to the console. - -The listener can be exited any time by pressing Ctrl+C, Esc, or Q. -)DESCR_STR"); + "Utility to listen on uORB topics and print the data to the console.\n" + "\n" + "The listener can be exited any time by pressing Ctrl+C, Esc, or Q."); PRINT_MODULE_USAGE_NAME("listener", "command"); PRINT_MODULE_USAGE_ARG("", "uORB topic name", false); diff --git a/src/systemcmds/tune_control/tune_control.cpp b/src/systemcmds/tune_control/tune_control.cpp index a2521ba2fa41..07da8034b140 100644 --- a/src/systemcmds/tune_control/tune_control.cpp +++ b/src/systemcmds/tune_control/tune_control.cpp @@ -235,22 +235,20 @@ extern "C" __EXPORT int tune_control_main(int argc, char *argv[]) static void usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -Command-line tool to control & test the (external) tunes. - -Tunes are used to provide audible notification and warnings (e.g. when the system arms, gets position lock, etc.). -The tool requires that a driver is running that can handle the tune_control uorb topic. - -Information about the tune format and predefined system tunes can be found here: -https://github.com/PX4/PX4-Autopilot/blob/main/src/lib/tunes/tune_definition.desc - -### Examples - -Play system tune #2: -$ tune_control play -t 2 -)DESCR_STR"); + "### Description\n" + "\n" + "Command-line tool to control & test the (external) tunes.\n" + "\n" + "Tunes are used to provide audible notification and warnings (e.g. when the system arms, gets position lock, etc.).\n" + "The tool requires that a driver is running that can handle the tune_control uorb topic.\n" + "\n" + "Information about the tune format and predefined system tunes can be found here:\n" + "https://github.com/PX4/PX4-Autopilot/blob/main/src/lib/tunes/tune_definition.desc\n" + "\n" + "### Examples\n" + "\n" + "Play system tune #2:\n" + "$ tune_control play -t 2"); PRINT_MODULE_USAGE_NAME("tune_control", "system"); PRINT_MODULE_USAGE_COMMAND_DESCR("play", "Play system tune or single note."); diff --git a/src/systemcmds/uorb/uorb.cpp b/src/systemcmds/uorb/uorb.cpp index b9fb565c143b..3ade3e473d0c 100644 --- a/src/systemcmds/uorb/uorb.cpp +++ b/src/systemcmds/uorb/uorb.cpp @@ -66,25 +66,23 @@ int uorb_main(int argc, char *argv[]) void usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -uORB is the internal pub-sub messaging system, used for communication between modules. - -### Implementation -The implementation is asynchronous and lock-free, ie. a publisher does not wait for a subscriber and vice versa. -This is achieved by having a separate buffer between a publisher and a subscriber. - -The code is optimized to minimize the memory footprint and the latency to exchange messages. - -Messages are defined in the `/msg` directory. They are converted into C/C++ code at build-time. - -If compiled with ORB_USE_PUBLISHER_RULES, a file with uORB publication rules can be used to configure which -modules are allowed to publish which topics. This is used for system-wide replay. - -### Examples -Monitor topic publication rates. Besides `top`, this is an important command for general system inspection: -$ uorb top -)DESCR_STR"); + "### Description\n" + "uORB is the internal pub-sub messaging system, used for communication between modules.\n" + "\n" + "### Implementation\n" + "The implementation is asynchronous and lock-free, ie. a publisher does not wait for a subscriber and vice versa.\n" + "This is achieved by having a separate buffer between a publisher and a subscriber.\n" + "\n" + "The code is optimized to minimize the memory footprint and the latency to exchange messages.\n" + "\n" + "Messages are defined in the `/msg` directory. They are converted into C/C++ code at build-time.\n" + "\n" + "If compiled with ORB_USE_PUBLISHER_RULES, a file with uORB publication rules can be used to configure which\n" + "modules are allowed to publish which topics. This is used for system-wide replay.\n" + "\n" + "### Examples\n" + "Monitor topic publication rates. Besides `top`, this is an important command for general system inspection:\n" + "$ uorb top"); PRINT_MODULE_USAGE_NAME("uorb", "communication"); PRINT_MODULE_USAGE_COMMAND_DESCR("status", "Print topic statistics"); diff --git a/src/systemcmds/work_queue/work_queue_main.cpp b/src/systemcmds/work_queue/work_queue_main.cpp index 3764712c69b6..7f9331ba4172 100644 --- a/src/systemcmds/work_queue/work_queue_main.cpp +++ b/src/systemcmds/work_queue/work_queue_main.cpp @@ -73,12 +73,9 @@ usage() { PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description - -Command-line tool to show work queue status. - -)DESCR_STR"); + "### Description\n" + "\n" + "Command-line tool to show work queue status."); PRINT_MODULE_USAGE_NAME("work_queue", "system"); PRINT_MODULE_USAGE_COMMAND("start"); diff --git a/src/templates/template_module/template_module.cpp b/src/templates/template_module/template_module.cpp index ad087d40ea33..d1a311e33ef7 100644 --- a/src/templates/template_module/template_module.cpp +++ b/src/templates/template_module/template_module.cpp @@ -195,20 +195,17 @@ int TemplateModule::print_usage(const char *reason) } PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Section that describes the provided module functionality. - -This is a template for a module running as a task in the background with start/stop/status functionality. - -### Implementation -Section describing the high-level implementation of this module. - -### Examples -CLI usage example: -$ module start -f -p 42 - -)DESCR_STR"); + "### Description\n" + "Section that describes the provided module functionality.\n" + "\n" + "This is a template for a module running as a task in the background with start/stop/status functionality.\n" + "\n" + "### Implementation\n" + "Section describing the high-level implementation of this module.\n" + "\n" + "### Examples\n" + "CLI usage example:\n" + "$ module start -f -p 42"); PRINT_MODULE_USAGE_NAME("module", "template"); PRINT_MODULE_USAGE_COMMAND("start");