Skip to content

Commit

Permalink
sf1xx move to px4 work queue
Browse files Browse the repository at this point in the history
  • Loading branch information
dagar committed May 24, 2019
1 parent a6bbf0b commit 5920378
Showing 1 changed file with 23 additions and 48 deletions.
71 changes: 23 additions & 48 deletions src/drivers/distance_sensor/sf1xx/sf1xx.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@
#include <px4_config.h>
#include <px4_defines.h>
#include <px4_getopt.h>
#include <px4_workqueue.h>
#include <px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_module.h>

#include <drivers/device/i2c.h>
Expand Down Expand Up @@ -78,29 +78,26 @@
#define SF1XX_DEVICE_PATH "/dev/sf1xx"


#ifndef CONFIG_SCHED_WORKQUEUE
# error This requires CONFIG_SCHED_WORKQUEUE.
#endif

class SF1XX : public device::I2C
class SF1XX : public device::I2C, public px4::ScheduledWorkItem
{
public:
SF1XX(uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING, int bus = SF1XX_BUS_DEFAULT,
int address = SF1XX_BASEADDR);
virtual ~SF1XX();

virtual int init();
virtual ~SF1XX() override;

int init() override;

virtual ssize_t read(device::file_t *filp, char *buffer, size_t buflen);
virtual int ioctl(device::file_t *filp, int cmd, unsigned long arg);
ssize_t read(device::file_t *filp, char *buffer, size_t buflen) override;
int ioctl(device::file_t *filp, int cmd, unsigned long arg) override;

/**
* Diagnostics - print some basic information about the driver.
*/
void print_info();

protected:
virtual int probe();
int probe() override;

private:
/**
Expand Down Expand Up @@ -139,32 +136,22 @@ class SF1XX : public device::I2C
* Perform a poll cycle; collect from the previous measurement
* and start a new one.
*/
void cycle();
void Run() override;
int measure();
int collect();

/**
* Static trampoline from the workq context; because we don't have a
* generic workqueue wrapper yet.
*
* @param arg Instance pointer for the driver that is polling.
*/
static void cycle_trampoline(void *arg);

bool _sensor_ok{false};

int _class_instance{-1};
int _conversion_interval{-1};
int _measure_ticks{0};
int _measure_interval{0};
int _orb_class_instance{-1};

float _max_distance{-1.0f};
float _min_distance{-1.0f};

uint8_t _rotation{0};

work_s _work{};

ringbuffer::RingBuffer *_reports{nullptr};

orb_advert_t _distance_sensor_topic{nullptr};
Expand All @@ -180,6 +167,7 @@ extern "C" __EXPORT int sf1xx_main(int argc, char *argv[]);

SF1XX::SF1XX(uint8_t rotation, int bus, int address) :
I2C("SF1XX", SF1XX_DEVICE_PATH, bus, address, 400000),
ScheduledWorkItem(px4::device_bus_to_wq(get_device_id())),
_rotation(rotation)
{
}
Expand Down Expand Up @@ -340,10 +328,10 @@ SF1XX::ioctl(device::file_t *filp, int cmd, unsigned long arg)
/* set default polling rate */
case SENSOR_POLLRATE_DEFAULT: {
/* do we need to start internal polling? */
bool want_start = (_measure_ticks == 0);
bool want_start = (_measure_interval == 0);

/* set interval for next measurement to minimum legal value */
_measure_ticks = USEC2TICK(_conversion_interval);
_measure_interval = (_conversion_interval);

/* if we need to start the poll state machine, do it */
if (want_start) {
Expand All @@ -357,18 +345,18 @@ SF1XX::ioctl(device::file_t *filp, int cmd, unsigned long arg)
/* adjust to a legal polling interval in Hz */
default: {
/* do we need to start internal polling? */
bool want_start = (_measure_ticks == 0);
bool want_start = (_measure_interval == 0);

/* convert hz to tick interval via microseconds */
int ticks = USEC2TICK(1000000 / arg);
int interval = (1000000 / arg);

/* check against maximum rate */
if (ticks < USEC2TICK(_conversion_interval)) {
if (interval < _conversion_interval) {
return -EINVAL;
}

/* update interval for next measurement */
_measure_ticks = ticks;
_measure_interval = interval;

/* if we need to start the poll state machine, do it */
if (want_start) {
Expand Down Expand Up @@ -399,7 +387,7 @@ SF1XX::read(device::file_t *filp, char *buffer, size_t buflen)
}

/* if automatic measurement is enabled */
if (_measure_ticks > 0) {
if (_measure_interval > 0) {

/*
* While there is space in the caller's buffer, and reports, copy them.
Expand Down Expand Up @@ -528,25 +516,17 @@ SF1XX::start()
measure();

/* schedule a cycle to start things */
work_queue(HPWORK, &_work, (worker_t)&SF1XX::cycle_trampoline, this, USEC2TICK(_conversion_interval));
ScheduleDelayed(_conversion_interval);
}

void
SF1XX::stop()
{
work_cancel(HPWORK, &_work);
ScheduleClear();
}

void
SF1XX::cycle_trampoline(void *arg)
{
SF1XX *dev = (SF1XX *)arg;

dev->cycle();
}

void
SF1XX::cycle()
SF1XX::Run()
{
/* Collect results */
if (OK != collect()) {
Expand All @@ -557,20 +537,15 @@ SF1XX::cycle()
}

/* schedule a fresh cycle call when the measurement is done */
work_queue(HPWORK,
&_work,
(worker_t)&SF1XX::cycle_trampoline,
this,
USEC2TICK(_conversion_interval));

ScheduleDelayed(_conversion_interval);
}

void
SF1XX::print_info()
{
perf_print_counter(_sample_perf);
perf_print_counter(_comms_errors);
printf("poll interval: %u ticks\n", _measure_ticks);
printf("poll interval: %u\n", _measure_interval);
_reports->print_info("report queue");
}

Expand Down

0 comments on commit 5920378

Please sign in to comment.