18 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 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> 48 _powersave_range(powersave_range),
49 estimated_terrain_height(_estimated_terrain_height)
51 _fd =
open(PWMIN0_DEVICE_PATH, O_RDONLY);
59 if (ioctl(
_fd, SENSORIOCSQUEUEDEPTH, 20) != 0) {
85 #if !defined(CONFIG_ARCH_BOARD_PX4FMU_V1) && \ 86 !defined(CONFIG_ARCH_BOARD_AEROFC_V1) 91 int fd =
open(PWMIN0_DEVICE_PATH, O_RDONLY);
106 struct pwm_input_s pwm;
112 while (::
read(
_fd, &pwm,
sizeof(pwm)) ==
sizeof(pwm)) {
120 float _distance_cm = pwm.pulse_width * 0.1f * scaling +
state.
offset;
125 if (distance_delta_cm > 100) {
134 sum_cm += _distance_cm;
166 ioctl(
_fd, SENSORIOCRESET, 0);
171 if (stop_pin != -1) {
199 #endif // CONFIG_HAL_BOARD
int pwm_input_main(int, char **)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
AP_HAL::UARTDriver * console
bool out_of_range(void) const
~AP_RangeFinder_PX4_PWM(void)
virtual void write(uint8_t pin, uint8_t value)=0
uint64_t _last_pulse_time_ms
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.
uint32_t _good_sample_count
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.
virtual void pinMode(uint8_t pin, uint8_t output)=0
float _last_sample_distance_cm
AP_RangeFinder_PX4_PWM(RangeFinder::RangeFinder_State &_state, AP_Int16 &powersave_range, float &_estimated_terrain_height)
void set_status(RangeFinder::RangeFinder_Status status)
RangeFinder::RangeFinder_State & state
uint32_t _disable_time_ms