mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
HAL_Linux: change initial PWM values to 490Hz, 1000us
This commit is contained in:
parent
73d42f3e33
commit
65fef59dfa
@ -34,8 +34,8 @@ void LinuxRCOutput::init(void* machtnicht)
|
||||
sharedMem_cmd->cmd = PWM_CMD_CONFIG;
|
||||
sharedMem_cmd->u.cfg.enmask = 0xFFF;
|
||||
for(int i=0;i<PWM_CHAN_COUNT;i++){
|
||||
sharedMem_cmd->u.cfg.hilo[i][0] = 1000;
|
||||
sharedMem_cmd->u.cfg.hilo[i][1] = 1000;
|
||||
sharedMem_cmd->u.cfg.hilo[i][0] = TICK_PER_US*1000;
|
||||
sharedMem_cmd->u.cfg.hilo[i][1] = (TICK_PER_S/490)-TICK_PER_US*1000;
|
||||
}
|
||||
sharedMem_cmd->magic = PWM_CMD_MAGIC;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user