// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License along with this program. If not, see . */ #include #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN #include "RPM_PX4_PWM.h" #include #include #include #include #include #include #include #include #include #include #include extern const AP_HAL::HAL& hal; /* open the sensor in constructor */ AP_RPM_PX4_PWM::AP_RPM_PX4_PWM(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_State &_state) : AP_RPM_Backend(_ap_rpm, instance, _state) { _fd = open(PWMIN0_DEVICE_PATH, O_RDONLY); if (_fd == -1) { hal.console->printf("Unable to open %s\n", PWMIN0_DEVICE_PATH); return; } // keep a queue of 5 samples to reduce noise by averaging if (ioctl(_fd, SENSORIOCSQUEUEDEPTH, 5) != 0) { hal.console->printf("Failed to setup RPM queue\n"); close(_fd); _fd = -1; return; } } /* close the file descriptor */ AP_RPM_PX4_PWM::~AP_RPM_PX4_PWM() { if (_fd != -1) { close(_fd); _fd = -1; } } void AP_RPM_PX4_PWM::update(void) { if (_fd == -1) { return; } struct pwm_input_s pwm; uint16_t count = 0; const float scaling = ap_rpm._scaling[state.instance]; float sum = 0; while (::read(_fd, &pwm, sizeof(pwm)) == sizeof(pwm)) { // the px4 pwm_input driver reports the period in microseconds if (pwm.period > 0) { sum += (1.0e6f * 60) / pwm.period; count++; } } if (count != 0) { state.rate_rpm = scaling * sum / count; state.last_reading_ms = hal.scheduler->millis(); } } #endif // CONFIG_HAL_BOARD