Skip to content
Snippets Groups Projects
Commit 647bdef8 authored by Beat Küng's avatar Beat Küng
Browse files

pwm.c: rename to pwm.cpp and add module documentation

use c++ so that raw string literals can be used
parent 3f6769d4
No related branches found
No related tags found
No related merge requests found
...@@ -37,7 +37,7 @@ px4_add_module( ...@@ -37,7 +37,7 @@ px4_add_module(
COMPILE_FLAGS COMPILE_FLAGS
-Wno-array-bounds -Wno-array-bounds
SRCS SRCS
pwm.c pwm.cpp
DEPENDS DEPENDS
platforms__common platforms__common
) )
......
...@@ -32,7 +32,7 @@ ...@@ -32,7 +32,7 @@
****************************************************************************/ ****************************************************************************/
/** /**
* @file pwm.c * @file pwm.cpp
* *
* PWM servo output configuration and monitoring tool. * PWM servo output configuration and monitoring tool.
*/ */
...@@ -67,7 +67,9 @@ ...@@ -67,7 +67,9 @@
#include "drivers/drv_pwm_output.h" #include "drivers/drv_pwm_output.h"
static void usage(const char *reason); static void usage(const char *reason);
__BEGIN_DECLS
__EXPORT int pwm_main(int argc, char *argv[]); __EXPORT int pwm_main(int argc, char *argv[]);
__END_DECLS
static void static void
...@@ -77,6 +79,34 @@ usage(const char *reason) ...@@ -77,6 +79,34 @@ usage(const char *reason)
PX4_WARN("%s", reason); PX4_WARN("%s", reason);
} }
PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
### Description
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
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.
The parameters `-p` and `-r` can be set to a parameter instead of specifying an integer: use -p p:PWM_MIN for example.
### Examples
Set the PWM rate for all channels to 400 Hz:
$ pwm rate -a -r 400
Test the outputs of eg. channels 1 and 3, and set the PWM value to 1200 us:
$ pwm arm
$ pwm test -c 13 -p 1200
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("pwm", "command"); PRINT_MODULE_USAGE_NAME("pwm", "command");
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment