mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Sub: Change default pwm frequency to 200Hz
This commit is contained in:
parent
2bb3286faa
commit
b108620742
@ -588,7 +588,7 @@ const AP_Param::Info Sub::var_info[] = {
|
|||||||
// @Range: 50 490
|
// @Range: 50 490
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
GSCALAR(rc_speed, "RC_SPEED", RC_FAST_SPEED),
|
GSCALAR(rc_speed, "RC_SPEED", RC_SPEED_DEFAULT),
|
||||||
|
|
||||||
// @Param: ACRO_RP_P
|
// @Param: ACRO_RP_P
|
||||||
// @DisplayName: Acro Roll and Pitch P gain
|
// @DisplayName: Acro Roll and Pitch P gain
|
||||||
|
@ -82,8 +82,8 @@
|
|||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// PWM control
|
// PWM control
|
||||||
// default RC speed in Hz
|
// default RC speed in Hz
|
||||||
#ifndef RC_FAST_SPEED
|
#ifndef RC_SPEED_DEFAULT
|
||||||
# define RC_FAST_SPEED 490
|
# define RC_SPEED_DEFAULT 200
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
Loading…
Reference in New Issue
Block a user