AP_Periph: correct parameter documentation

This commit is contained in:
Peter Barker 2023-11-23 10:07:41 +11:00 committed by Tom Pittenger
parent 4b61b3d64e
commit 47a18596db
1 changed files with 4 additions and 5 deletions

View File

@ -33,7 +33,7 @@ extern const AP_HAL::HAL &hal;
const AP_Param::GroupInfo Parameters_RCIN::var_info[] {
// RC_PROTOCOLS copied from RC_Channel/RC_Channels_Varinfo.h
// @Param: RC_PROTOCOLS
// @Param: _PROTOCOLS
// @DisplayName: RC protocols enabled
// @Description: Bitmask of enabled RC protocols. Allows narrowing the protocol detection to only specific types of RC receivers which can avoid issues with incorrect detection. Set to 1 to enable all protocols.
// @User: Advanced
@ -41,7 +41,7 @@ const AP_Param::GroupInfo Parameters_RCIN::var_info[] {
AP_GROUPINFO("_PROTOCOLS", 1, Parameters_RCIN, rcin_protocols, 1),
// RC_PROTOCOLS copied from RC_Channel/RC_Channels_Varinfo.h
// @Param: RC_MSGRATE
// @Param: _MSGRATE
// @DisplayName: DroneCAN RC Message rate
// @Description: Rate at which RC input is sent via DroneCAN
// @User: Advanced
@ -50,7 +50,7 @@ const AP_Param::GroupInfo Parameters_RCIN::var_info[] {
// @Units: Hz
AP_GROUPINFO("_MSGRATE", 2, Parameters_RCIN, rcin_rate_hz, 50),
// @Param: RC1_PORT
// @Param: 1_PORT
// @DisplayName: RC input port
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to RC input.
// @Range: 0 10
@ -59,9 +59,8 @@ const AP_Param::GroupInfo Parameters_RCIN::var_info[] {
// @RebootRequired: True
AP_GROUPINFO("_PORT", 3, Parameters_RCIN, rcin1_port, AP_PERIPH_RC1_PORT_DEFAULT),
// @Param: RC1_PORT_OPTIONS
// @Param: 1_PORT_OPTIONS
// @DisplayName: RC input port serial options
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to RC input.
// @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire. The Swap option allows the RX and TX pins to be swapped on STM32F7 based boards.
// @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 3:SwapTXRX, 4: RX_PullDown, 5: RX_PullUp, 6: TX_PullDown, 7: TX_PullUp, 8: RX_NoDMA, 9: TX_NoDMA, 10: Don't forward mavlink to/from, 11: DisableFIFO, 12: Ignore Streamrate
AP_GROUPINFO("1_PORT_OPTIONS", 4, Parameters_RCIN, rcin1_port_options, AP_PERIPH_RC1_PORT_OPTIONS_DEFAULT),