mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RCMapper: Remove RCMAP_FORWARD and LATERAL from rover docs
This commit is contained in:
parent
1638e3c778
commit
1e15787dab
@ -38,7 +38,7 @@ const AP_Param::GroupInfo RCMapper::var_info[] = {
|
|||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("YAW", 3, RCMapper, _ch_yaw, 4),
|
AP_GROUPINFO("YAW", 3, RCMapper, _ch_yaw, 4),
|
||||||
|
|
||||||
// @Param{Rover,Sub}: FORWARD
|
// @Param{Sub}: FORWARD
|
||||||
// @DisplayName: Forward channel
|
// @DisplayName: Forward channel
|
||||||
// @Description: Forward channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Forward is normally on channel 5, but you can move it to any channel with this parameter. Reboot is required for changes to take effect.
|
// @Description: Forward channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Forward is normally on channel 5, but you can move it to any channel with this parameter. Reboot is required for changes to take effect.
|
||||||
// @Range: 1 8
|
// @Range: 1 8
|
||||||
@ -47,7 +47,7 @@ const AP_Param::GroupInfo RCMapper::var_info[] = {
|
|||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO_FRAME("FORWARD", 4, RCMapper, _ch_forward, 6, AP_PARAM_FRAME_SUB),
|
AP_GROUPINFO_FRAME("FORWARD", 4, RCMapper, _ch_forward, 6, AP_PARAM_FRAME_SUB),
|
||||||
|
|
||||||
// @Param{Rover,Sub}: LATERAL
|
// @Param{Sub}: LATERAL
|
||||||
// @DisplayName: Lateral channel
|
// @DisplayName: Lateral channel
|
||||||
// @Description: Lateral channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Lateral is normally on channel 6, but you can move it to any channel with this parameter. Reboot is required for changes to take effect.
|
// @Description: Lateral channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Lateral is normally on channel 6, but you can move it to any channel with this parameter. Reboot is required for changes to take effect.
|
||||||
// @Range: 1 8
|
// @Range: 1 8
|
||||||
|
Loading…
Reference in New Issue
Block a user