Browse Source

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
sbg
David Sidrane 8 years ago committed by Lorenz Meier
parent
commit
b2b9a0be9f
  1. 19
      src/drivers/drv_pwm_output.h

19
src/drivers/drv_pwm_output.h

@ -75,18 +75,11 @@ __BEGIN_DECLS @@ -75,18 +75,11 @@ __BEGIN_DECLS
*/
//#define PWM_OUTPUT_MAX_CHANNELS 16
#if defined(CONFIG_ARCH_BOARD_CRAZYFLIE)
/* PWM directly wired to transistor. Duty cycle directly corresponds to power */
#define PWM_LOWEST_MIN 0
#define PWM_MOTOR_OFF 0
#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
/* Use defaults unless the board override the defaults by providing
* PX4_PWM_ALTERNATE_RANGES and a replacement set of
* constants
*/
#if !defined(PX4_PWM_ALTERNATE_RANGES)
/**
* Lowest minimum PWM in us
@ -123,7 +116,7 @@ __BEGIN_DECLS @@ -123,7 +116,7 @@ __BEGIN_DECLS
*/
#define PWM_LOWEST_MAX 200
#endif
#endif // PX4_PWM_ALTERNATE_RANGES
/**
* Do not output a channel with this value

Loading…
Cancel
Save