Browse Source

AP_Hal_Linux: PCA9685: do not shutdown

Shutting down causes the pulses to be cut short, often causing
ESCs to interpret this pulse
gps-1.3.1
Willian Galvani 3 years ago committed by Andrew Tridgell
parent
commit
b5de26c1f2
  1. 2
      libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp

2
libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp

@ -173,8 +173,6 @@ bool RCOutput_PCA9685::force_safety_on() {
} }
/* Shutdown before sleeping. */ /* Shutdown before sleeping. */
_dev->write_register(PCA9685_RA_ALL_LED_OFF_H, PCA9685_ALL_LED_OFF_H_SHUT); _dev->write_register(PCA9685_RA_ALL_LED_OFF_H, PCA9685_ALL_LED_OFF_H_SHUT);
/* Put PCA9685 to sleep */
_dev->write_register(PCA9685_RA_MODE1, PCA9685_MODE1_SLEEP_BIT);
_dev->get_semaphore()->give(); _dev->get_semaphore()->give();
return true; return true;

Loading…
Cancel
Save