18 #if (CONFIG_HAL_BOARD == HAL_BOARD_PX4) || ((CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN) && (!defined(CONFIG_ARCH_BOARD_VRBRAIN_V51) && !defined(CONFIG_ARCH_BOARD_VRUBRAIN_V52))) 22 #include <sys/types.h> 27 #include <drivers/drv_pwm_input.h> 28 #include <drivers/drv_hrt.h> 29 #include <drivers/drv_sensor.h> 30 #include <uORB/topics/pwm_input.h> 49 #if HAL_PX4_HAVE_PWM_INPUT 54 _fd =
open(PWMIN0_DEVICE_PATH, O_RDONLY);
56 hal.
console->
printf(
"Unable to open %s\n", PWMIN0_DEVICE_PATH);
61 if (ioctl(
_fd, SENSORIOCSQUEUEDEPTH, 5) != 0) {
72 _logfd =
open(
"/fs/microsd/pwm.log", O_WRONLY|O_CREAT|O_TRUNC, 0644);
95 ioctl(
_fd, PWMINIOSRESOLUTION, newres);
99 struct pwm_input_s pwm;
106 while (::
read(
_fd, &pwm,
sizeof(pwm)) ==
sizeof(pwm)) {
108 if (pwm.period == 0) {
111 float rpm = scaling * (1.0e6f * 60) / pwm.period;
114 if ((maximum <= 0 || rpm <= maximum) && (rpm >= minimum)) {
118 quality = 1 -
constrain_float((fabsf(rpm-filter_value))/filter_value, 0.0, 1.0);
119 quality = powf(quality, 2.0);
128 dprintf(
_logfd,
"%u %u %u\n",
129 (
unsigned)pwm.timestamp/1000,
130 (
unsigned)pwm.period,
131 (
unsigned)pwm.pulse_width);
148 #endif // CONFIG_HAL_BOARD
AP_Float _minimum[RPM_MAX_INSTANCES]
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
AP_HAL::UARTDriver * console
ModeFilterFloat_Size5 signal_quality_filter
AP_RPM_PX4_PWM(AP_RPM &ranger, uint8_t instance, AP_RPM::RPM_State &_state)
virtual T apply(T sample)
virtual void printf(const char *,...) FMT_PRINTF(2
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
AP_RPM::RPM_State & state
uint32_t _resolution_usec
bool is_zero(const T fVal1)
static bool px4_start_driver(main_fn_t main_function, const char *name, const char *arguments)
int close(int fileno)
POSIX Close a file with fileno handel.
float constrain_float(const float amt, const float low, const float high)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
int pwm_input_main(int, char **)
AP_Float _maximum[RPM_MAX_INSTANCES]
AP_Float _scaling[RPM_MAX_INSTANCES]