mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-04 21:23:57 +08:00
PX4 System change to allow way to override the PWM_.*_{MIN|MAX} values
Add PX4_PWM_ALTERNATE_RANGES in suport of a board agnostic way
to override the PWM_.*_{MIN|MAX} values
This commit is contained in:
committed by
Lorenz Meier
parent
d77e107e31
commit
b2b9a0be9f
@@ -75,18 +75,11 @@ __BEGIN_DECLS
|
|||||||
*/
|
*/
|
||||||
//#define PWM_OUTPUT_MAX_CHANNELS 16
|
//#define PWM_OUTPUT_MAX_CHANNELS 16
|
||||||
|
|
||||||
#if defined(CONFIG_ARCH_BOARD_CRAZYFLIE)
|
/* Use defaults unless the board override the defaults by providing
|
||||||
|
* PX4_PWM_ALTERNATE_RANGES and a replacement set of
|
||||||
/* PWM directly wired to transistor. Duty cycle directly corresponds to power */
|
* constants
|
||||||
#define PWM_LOWEST_MIN 0
|
*/
|
||||||
#define PWM_MOTOR_OFF 0
|
#if !defined(PX4_PWM_ALTERNATE_RANGES)
|
||||||
#define PWM_DEFAULT_MIN 0
|
|
||||||
#define PWM_HIGHEST_MIN 0
|
|
||||||
#define PWM_HIGHEST_MAX 255
|
|
||||||
#define PWM_DEFAULT_MAX 255
|
|
||||||
#define PWM_LOWEST_MAX 255
|
|
||||||
|
|
||||||
#else
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Lowest minimum PWM in us
|
* Lowest minimum PWM in us
|
||||||
@@ -123,7 +116,7 @@ __BEGIN_DECLS
|
|||||||
*/
|
*/
|
||||||
#define PWM_LOWEST_MAX 200
|
#define PWM_LOWEST_MAX 200
|
||||||
|
|
||||||
#endif
|
#endif // PX4_PWM_ALTERNATE_RANGES
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Do not output a channel with this value
|
* Do not output a channel with this value
|
||||||
|
|||||||
Reference in New Issue
Block a user