mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 23:48:31 -04:00
b65eb110bd
Revert "Arducopter Motors Octa: Change V frame MOT_ output ordering." This reverts commit bdab02f408ddc5451fcb4c6390b2475d31ac657f. Revert "hexa frame FRAME_CONFIG fixup" This reverts commit d15e692df613cb728ec671a54dce166f6f1940a0. Revert "Arducopter Motors Octa: revert OCTA_V_FRAME back to part of OCTA_FRAME" This reverts commit cb0a8c62fbd07a8ae9dcb8d4fffce337ace1aa1c. Revert "Arducopter Motors Hexa: Change ordering of MOT designations in Plus frame" This reverts commit 120d7f9050d5ec9f8fbe02c0ed4f38621949f4ee. Revert "Arducopter Motors Hexa: Revert HEXA_PLUS_ and HEXA_X_ to single HEXA_FRAME" This reverts commit 7d65ec311fd2e1222a36d0b34c366e21f3869fcc. Revert "Arducopter Frames: revert to old HEXA_FRAME and OCTA_FRAME defines." This reverts commit 47c6e8662f4d5e8fb920f2049338541343d8d18e. Revert "Add Max's changes for new MOT mappings. Defines new FRAME_CONFIG types." This reverts commit 8259c90ec7cb29dedac19890cd9a4449b7399e36.
73 lines
1.8 KiB
C
73 lines
1.8 KiB
C
|
|
#ifndef __ARDUCOPTER_CONFIG_MOTORS_H__
|
|
#define __ARDUCOPTER_CONFIG_MOTORS_H__
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
//
|
|
// WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING
|
|
//
|
|
// DO NOT EDIT this file to adjust your configuration. Create your own
|
|
// APM_Config.h and use APM_Config.h.example as a reference.
|
|
//
|
|
// WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING
|
|
///
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
//
|
|
|
|
#include "config.h"
|
|
|
|
//
|
|
//
|
|
// Output CH mapping for ArduCopter motor channels
|
|
//
|
|
//
|
|
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
|
# define MOT_1 CH_1
|
|
# define MOT_2 CH_2
|
|
# define MOT_3 CH_3
|
|
# define MOT_4 CH_4
|
|
# define MOT_5 CH_5
|
|
# define MOT_6 CH_6
|
|
# define MOT_7 CH_7
|
|
# define MOT_8 CH_8
|
|
#elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
|
|
# define MOT_1 CH_1
|
|
# define MOT_2 CH_2
|
|
# define MOT_3 CH_3
|
|
# define MOT_4 CH_4
|
|
# define MOT_5 CH_7
|
|
# define MOT_6 CH_8
|
|
# define MOT_7 CH_10
|
|
# define MOT_8 CH_11
|
|
#endif
|
|
|
|
//
|
|
//
|
|
// Output CH mapping for TRI_FRAME yaw servo
|
|
//
|
|
//
|
|
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
|
# define CH_TRI_YAW CH_7
|
|
#elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
|
|
# define CH_TRI_YAW CH_7
|
|
#endif
|
|
|
|
//
|
|
//
|
|
// Output CH mapping for Aux channels
|
|
//
|
|
//
|
|
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
|
/* Camera Pitch and Camera Roll: Not yet defined for APM2
|
|
* They will likely be dependent on the frame config */
|
|
# define CH_CAM_PITCH CH_11
|
|
# define CH_CAM_ROLL CH_10
|
|
#elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
|
|
# define CH_CAM_PITCH CH_5
|
|
# define CH_CAM_ROLL CH_6
|
|
#endif
|
|
|
|
#endif // __ARDUCOPTER_CONFIG_MOTORS_H__
|