forked from Archive/PX4-Autopilot
ll40ls: changed I2C driver to new ringbuffer namespace, and various style stuff
This commit is contained in:
parent
fbc4ca61ac
commit
ef658cf926
|
@ -46,7 +46,6 @@
|
||||||
#include <poll.h>
|
#include <poll.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <drivers/device/ringbuffer.h>
|
|
||||||
#include <drivers/drv_hrt.h>
|
#include <drivers/drv_hrt.h>
|
||||||
|
|
||||||
/* oddly, ERROR is not defined for c++ */
|
/* oddly, ERROR is not defined for c++ */
|
||||||
|
@ -57,17 +56,17 @@ static const int ERROR = -1;
|
||||||
|
|
||||||
LidarLiteI2C::LidarLiteI2C(int bus, const char *path, int address) :
|
LidarLiteI2C::LidarLiteI2C(int bus, const char *path, int address) :
|
||||||
I2C("LL40LS", path, bus, address, 100000),
|
I2C("LL40LS", path, bus, address, 100000),
|
||||||
_work(),
|
_work{},
|
||||||
_reports(nullptr),
|
_reports(nullptr),
|
||||||
_sensor_ok(false),
|
_sensor_ok(false),
|
||||||
_collect_phase(false),
|
_collect_phase(false),
|
||||||
_class_instance(-1),
|
_class_instance(-1),
|
||||||
_range_finder_topic(-1),
|
_range_finder_topic(-1),
|
||||||
_sample_perf(perf_alloc(PC_ELAPSED, "ll40ls_read")),
|
_sample_perf(perf_alloc(PC_ELAPSED, "ll40ls_i2c_read")),
|
||||||
_comms_errors(perf_alloc(PC_COUNT, "ll40ls_comms_errors")),
|
_comms_errors(perf_alloc(PC_COUNT, "ll40ls_i2c_comms_errors")),
|
||||||
_buffer_overflows(perf_alloc(PC_COUNT, "ll40ls_buffer_overflows")),
|
_buffer_overflows(perf_alloc(PC_COUNT, "ll40ls_buffer_i2c_overflows")),
|
||||||
_sensor_resets(perf_alloc(PC_COUNT, "ll40ls_resets")),
|
_sensor_resets(perf_alloc(PC_COUNT, "ll40ls_i2c_resets")),
|
||||||
_sensor_zero_resets(perf_alloc(PC_COUNT, "ll40ls_zero_resets")),
|
_sensor_zero_resets(perf_alloc(PC_COUNT, "ll40ls_i2c_zero_resets")),
|
||||||
_last_distance(0),
|
_last_distance(0),
|
||||||
_zero_counter(0),
|
_zero_counter(0),
|
||||||
_acquire_time_usec(0),
|
_acquire_time_usec(0),
|
||||||
|
@ -116,7 +115,7 @@ int LidarLiteI2C::init()
|
||||||
}
|
}
|
||||||
|
|
||||||
/* allocate basic report buffers */
|
/* allocate basic report buffers */
|
||||||
_reports = new RingBuffer(2, sizeof(range_finder_report));
|
_reports = new ringbuffer::RingBuffer(2, sizeof(range_finder_report));
|
||||||
|
|
||||||
if (_reports == nullptr) {
|
if (_reports == nullptr) {
|
||||||
goto out;
|
goto out;
|
||||||
|
|
|
@ -40,9 +40,6 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
//Forward declaration
|
|
||||||
class RingBuffer;
|
|
||||||
|
|
||||||
#include "LidarLite.h"
|
#include "LidarLite.h"
|
||||||
|
|
||||||
#include <nuttx/wqueue.h>
|
#include <nuttx/wqueue.h>
|
||||||
|
@ -50,6 +47,7 @@ class RingBuffer;
|
||||||
#include <systemlib/perf_counter.h>
|
#include <systemlib/perf_counter.h>
|
||||||
|
|
||||||
#include <drivers/device/i2c.h>
|
#include <drivers/device/i2c.h>
|
||||||
|
#include <drivers/device/ringbuffer.h>
|
||||||
|
|
||||||
#include <uORB/uORB.h>
|
#include <uORB/uORB.h>
|
||||||
#include <uORB/topics/subsystem_info.h>
|
#include <uORB/topics/subsystem_info.h>
|
||||||
|
@ -76,10 +74,10 @@ public:
|
||||||
LidarLiteI2C(int bus, const char *path, int address = LL40LS_BASEADDR);
|
LidarLiteI2C(int bus, const char *path, int address = LL40LS_BASEADDR);
|
||||||
virtual ~LidarLiteI2C();
|
virtual ~LidarLiteI2C();
|
||||||
|
|
||||||
virtual int init() override;
|
int init() override;
|
||||||
|
|
||||||
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
|
ssize_t read(struct file *filp, char *buffer, size_t buflen);
|
||||||
virtual int ioctl(struct file *filp, int cmd, unsigned long arg) override;
|
int ioctl(struct file *filp, int cmd, unsigned long arg) override;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Diagnostics - print some basic information about the driver.
|
* Diagnostics - print some basic information about the driver.
|
||||||
|
@ -92,15 +90,15 @@ public:
|
||||||
void print_registers() override;
|
void print_registers() override;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
virtual int probe();
|
int probe();
|
||||||
virtual int read_reg(uint8_t reg, uint8_t &val);
|
int read_reg(uint8_t reg, uint8_t &val);
|
||||||
|
|
||||||
int measure() override;
|
int measure() override;
|
||||||
int reset_sensor() override;
|
int reset_sensor();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
work_s _work;
|
work_s _work;
|
||||||
RingBuffer *_reports;
|
ringbuffer::RingBuffer *_reports;
|
||||||
bool _sensor_ok;
|
bool _sensor_ok;
|
||||||
bool _collect_phase;
|
bool _collect_phase;
|
||||||
int _class_instance;
|
int _class_instance;
|
||||||
|
|
Loading…
Reference in New Issue