mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
HAL_Linux: use dprintf() instead of sprintf and write
This commit is contained in:
parent
bec1c05773
commit
00526359b0
@ -74,22 +74,15 @@ void LinuxUtil::stop()
|
|||||||
|
|
||||||
void LinuxUtil::play(int tone,int duration)
|
void LinuxUtil::play(int tone,int duration)
|
||||||
{
|
{
|
||||||
|
|
||||||
char buf[10];
|
|
||||||
if(tune_num != prev_tune_num){
|
if(tune_num != prev_tune_num){
|
||||||
tune_changed = true;
|
tune_changed = true;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if(tone != 0){
|
if(tone != 0){
|
||||||
write(run_fd,"0",sizeof(char));
|
dprintf(run_fd,"0");
|
||||||
|
dprintf(period_fd,"%u",1000000000/tone);
|
||||||
sprintf(buf,"%u",1000000000/tone);
|
dprintf(duty_fd,"%u",500000000/tone);
|
||||||
write(period_fd,buf,sizeof(buf));
|
dprintf(run_fd,"1");
|
||||||
|
|
||||||
sprintf(buf,"%u",500000000/tone);
|
|
||||||
write(duty_fd,buf,sizeof(buf));
|
|
||||||
|
|
||||||
write(run_fd,"1",sizeof(char));
|
|
||||||
}
|
}
|
||||||
hal.scheduler->delay(duration);
|
hal.scheduler->delay(duration);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user