PWM command: Switch default to status, leave info

This commit is contained in:
Lorenz Meier
2021-03-16 14:43:46 +01:00
parent 0efa7556fe
commit 8cc3247d21
2 changed files with 7 additions and 8 deletions

View File

@@ -36,8 +36,8 @@ px4_add_board(
imu/invensense/icm20689
irlock
lights/rgbled
lights/rgbled_ncp5623c
lights/rgbled_pwm
#lights/rgbled_ncp5623c
#lights/rgbled_pwm
magnetometer # all available magnetometer drivers
optical_flow # all available optical flow drivers
#osd
@@ -47,7 +47,6 @@ px4_add_board(
pwm_out_sim
pwm_out
rc_input
roboclaw
safety_button
telemetry # all available telemetry drivers
test_ppm

View File

@@ -85,14 +85,14 @@ This command is used to configure PWM outputs for servo and ESC control.
The default device `/dev/pwm_output0` are the Main channels, AUX channels are on `/dev/pwm_output1` (`-d` parameter).
It is used in the startup script to make sure the PWM parameters (`PWM_*`) are applied (or the ones provided
by the airframe config if specified). `pwm info` shows the current settings (the trim value is an offset
by the airframe config if specified). `pwm status` shows the current settings (the trim value is an offset
and configured with `PWM_MAIN_TRIMx` and `PWM_AUX_TRIMx`).
The disarmed value should be set such that the motors don't spin (it's also used for the kill switch), at the
minimum value they should spin.
Channels are assigned to a group. Due to hardware limitations, the update rate can only be set per group. Use
`pwm info` to display the groups. If the `-c` argument is used, all channels of any included group must be included.
`pwm status` to display the groups. If the `-c` argument is used, all channels of any included group must be included.
The parameters `-p` and `-r` can be set to a parameter instead of specifying an integer: use -p p:PWM_MIN for example.
@@ -113,7 +113,7 @@ $ pwm test -c 13 -p 1200
PRINT_MODULE_USAGE_COMMAND_DESCR("arm", "Arm output");
PRINT_MODULE_USAGE_COMMAND_DESCR("disarm", "Disarm output");
PRINT_MODULE_USAGE_COMMAND_DESCR("info", "Print current configuration of all channels");
PRINT_MODULE_USAGE_COMMAND_DESCR("status", "Print current configuration of all channels");
PRINT_MODULE_USAGE_COMMAND_DESCR("forcefail", "Force Failsafe mode. "
"PWM outputs are set to failsafe values.");
PRINT_MODULE_USAGE_ARG("on|off", "Turn on or off", false);
@@ -144,7 +144,7 @@ $ pwm test -c 13 -p 1200
PRINT_MODULE_USAGE_PARAM_STRING('c', nullptr, nullptr, "select channels in the form: 1234 (1 digit per channel, 1=first)",
true);
PRINT_MODULE_USAGE_PARAM_INT('m', -1, 0, 4096, "Select channels via bitmask (eg. 0xF, 3)", true);
PRINT_MODULE_USAGE_PARAM_INT('g', -1, 0, 10, "Select channels by group (eg. 0, 1, 2. use 'pwm info' to show groups)",
PRINT_MODULE_USAGE_PARAM_INT('g', -1, 0, 10, "Select channels by group (eg. 0, 1, 2. use 'pwm status' to show groups)",
true);
PRINT_MODULE_USAGE_PARAM_FLAG('a', "Select all channels", true);
@@ -843,7 +843,7 @@ err_out_no_test:
goto err_out;
} else if (!strcmp(command, "info")) {
} else if (!strcmp(command, "status") || !strcmp(command, "info")) {
printf("device: %s\n", dev);