From 79fb10d9e841107f9d5c147e04042a52b7490033 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 14 May 2014 18:13:34 +0530 Subject: [PATCH] HAL_Linux: correct AP_HAL_Linux::RCOutput::enable_ch method change the mode of file open which was set as RDONLY mistakenly --- libraries/AP_HAL_Linux/RCOutput.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_Linux/RCOutput.cpp b/libraries/AP_HAL_Linux/RCOutput.cpp index e0954817b5..ad612bec32 100644 --- a/libraries/AP_HAL_Linux/RCOutput.cpp +++ b/libraries/AP_HAL_Linux/RCOutput.cpp @@ -136,12 +136,12 @@ void LinuxRCOutput::enable_ch(uint8_t ch) char run_sysfs_path[20],buffer[]="1"; sprintf(run_sysfs_path,"%s/pwm%d%s",PWM_DIR,chan_pru_map[ch],"/run"); - _fd=open(run_sysfs_path,O_RDONLY); + _fd=open(run_sysfs_path,O_WRONLY); if(_fd < 0){ perror("run: file open failed"); } - ret = ::read(_fd,&buffer,sizeof(buffer)); + ret = ::write(_fd,&buffer,sizeof(buffer)); if(ret < 0){ perror("run: read failed"); }