mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
ArduCopter APM_Config.h: add sample custom channel config
* uses new config variables introduced in 8a19543fd1e09621ba
This commit is contained in:
parent
470fd8788e
commit
6573cec611
@ -63,11 +63,29 @@
|
||||
// Ensure the defined file exists and is in the arducopter directory
|
||||
#define USERHOOK_VARIABLES "UserVariables.h"
|
||||
|
||||
|
||||
// to enable, set to 1
|
||||
// to disable, set to 0
|
||||
#define AUTO_THROTTLE_HOLD 1
|
||||
|
||||
|
||||
|
||||
//# define LOGGING_ENABLED DISABLED
|
||||
|
||||
|
||||
// Custom channel config - Expert Use Only.
|
||||
// this for defining your own MOT_n to CH_n mapping.
|
||||
// Overrides defaults (for APM1 or APM2) found in config_channels.h
|
||||
// MOT_n variables are used by the Frame mixing code. You must define
|
||||
// MOT_1 through MOT_m where m is the number of motors on your frame.
|
||||
// CH_n variables are used for RC output. These can be CH_1 through CH_8,
|
||||
// and CH_10 or CH_12.
|
||||
// Sample channel config. Must define all MOT_ chanels used by
|
||||
// your FRAME_TYPE.
|
||||
// #define CONFIG_CHANNELS CHANNEL_CONFIG_CUSTOM
|
||||
// #define MOT_1 CH_6
|
||||
// #define MOT_2 CH_3
|
||||
// #define MOT_3 CH_2
|
||||
// #define MOT_4 CH_5
|
||||
// #define MOT_5 CH_1
|
||||
// #define MOT_6 CH_4
|
||||
// #define MOT_7 CH_7
|
||||
// #define MOT_8 CH_8
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user