drivers: use new ringbuffer namespace everywhere

This commit is contained in:
Ban Siesta 2015-05-24 10:04:38 +01:00
parent aac276872b
commit 21dfd0243d
14 changed files with 29 additions and 31 deletions

View File

@ -128,7 +128,7 @@ Airspeed::init()
goto out; goto out;
/* allocate basic report buffers */ /* allocate basic report buffers */
_reports = new RingBuffer(2, sizeof(differential_pressure_s)); _reports = new ringbuffer::RingBuffer(2, sizeof(differential_pressure_s));
if (_reports == nullptr) if (_reports == nullptr)
goto out; goto out;

View File

@ -109,7 +109,7 @@ public:
virtual void print_info(); virtual void print_info();
private: private:
RingBuffer *_reports; ringbuffer::RingBuffer *_reports;
perf_counter_t _buffer_overflows; perf_counter_t _buffer_overflows;
/* this class has pointer data members and should not be copied */ /* this class has pointer data members and should not be copied */

View File

@ -156,7 +156,7 @@ private:
work_s _work; work_s _work;
unsigned _measure_ticks; unsigned _measure_ticks;
RingBuffer *_reports; ringbuffer::RingBuffer *_reports;
mag_scale _scale; mag_scale _scale;
float _range_scale; float _range_scale;
float _range_ga; float _range_ga;
@ -423,7 +423,7 @@ HMC5883::init()
} }
/* allocate basic report buffers */ /* allocate basic report buffers */
_reports = new RingBuffer(2, sizeof(mag_report)); _reports = new ringbuffer::RingBuffer(2, sizeof(mag_report));
if (_reports == nullptr) if (_reports == nullptr)
goto out; goto out;

View File

@ -229,7 +229,7 @@ private:
struct hrt_call _call; struct hrt_call _call;
unsigned _call_interval; unsigned _call_interval;
RingBuffer *_reports; ringbuffer::RingBuffer *_reports;
struct gyro_scale _gyro_scale; struct gyro_scale _gyro_scale;
float _gyro_range_scale; float _gyro_range_scale;
@ -472,7 +472,7 @@ L3GD20::init()
goto out; goto out;
/* allocate basic report buffers */ /* allocate basic report buffers */
_reports = new RingBuffer(2, sizeof(gyro_report)); _reports = new ringbuffer::RingBuffer(2, sizeof(gyro_report));
if (_reports == nullptr) if (_reports == nullptr)
goto out; goto out;

View File

@ -275,8 +275,8 @@ private:
unsigned _call_accel_interval; unsigned _call_accel_interval;
unsigned _call_mag_interval; unsigned _call_mag_interval;
RingBuffer *_accel_reports; ringbuffer::RingBuffer *_accel_reports;
RingBuffer *_mag_reports; ringbuffer::RingBuffer *_mag_reports;
struct accel_scale _accel_scale; struct accel_scale _accel_scale;
unsigned _accel_range_m_s2; unsigned _accel_range_m_s2;
@ -646,12 +646,12 @@ LSM303D::init()
} }
/* allocate basic report buffers */ /* allocate basic report buffers */
_accel_reports = new RingBuffer(2, sizeof(accel_report)); _accel_reports = new ringbuffer::RingBuffer(2, sizeof(accel_report));
if (_accel_reports == nullptr) if (_accel_reports == nullptr)
goto out; goto out;
_mag_reports = new RingBuffer(2, sizeof(mag_report)); _mag_reports = new ringbuffer::RingBuffer(2, sizeof(mag_report));
if (_mag_reports == nullptr) if (_mag_reports == nullptr)
goto out; goto out;

View File

@ -125,7 +125,7 @@ private:
float _min_distance; float _min_distance;
float _max_distance; float _max_distance;
work_s _work; work_s _work;
RingBuffer *_reports; ringbuffer::RingBuffer *_reports;
bool _sensor_ok; bool _sensor_ok;
int _measure_ticks; int _measure_ticks;
bool _collect_phase; bool _collect_phase;
@ -255,7 +255,7 @@ MB12XX::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));
_index_counter = MB12XX_BASEADDR; /* set temp sonar i2c address to base adress */ _index_counter = MB12XX_BASEADDR; /* set temp sonar i2c address to base adress */
set_address(_index_counter); /* set I2c port to temp sonar i2c adress */ set_address(_index_counter); /* set I2c port to temp sonar i2c adress */

View File

@ -242,7 +242,7 @@ private:
struct hrt_call _call; struct hrt_call _call;
unsigned _call_interval; unsigned _call_interval;
RingBuffer *_accel_reports; ringbuffer::RingBuffer *_accel_reports;
struct accel_scale _accel_scale; struct accel_scale _accel_scale;
float _accel_range_scale; float _accel_range_scale;
@ -251,7 +251,7 @@ private:
int _accel_orb_class_instance; int _accel_orb_class_instance;
int _accel_class_instance; int _accel_class_instance;
RingBuffer *_gyro_reports; ringbuffer::RingBuffer *_gyro_reports;
struct gyro_scale _gyro_scale; struct gyro_scale _gyro_scale;
float _gyro_range_scale; float _gyro_range_scale;
@ -611,11 +611,11 @@ MPU6000::init()
} }
/* allocate basic report buffers */ /* allocate basic report buffers */
_accel_reports = new RingBuffer(2, sizeof(accel_report)); _accel_reports = new ringbuffer::RingBuffer(2, sizeof(accel_report));
if (_accel_reports == nullptr) if (_accel_reports == nullptr)
goto out; goto out;
_gyro_reports = new RingBuffer(2, sizeof(gyro_report)); _gyro_reports = new ringbuffer::RingBuffer(2, sizeof(gyro_report));
if (_gyro_reports == nullptr) if (_gyro_reports == nullptr)
goto out; goto out;

View File

@ -127,7 +127,7 @@ protected:
struct work_s _work; struct work_s _work;
unsigned _measure_ticks; unsigned _measure_ticks;
RingBuffer *_reports; ringbuffer::RingBuffer *_reports;
bool _collect_phase; bool _collect_phase;
unsigned _measure_phase; unsigned _measure_phase;
@ -269,7 +269,7 @@ MS5611::init()
} }
/* allocate basic report buffers */ /* allocate basic report buffers */
_reports = new RingBuffer(2, sizeof(baro_report)); _reports = new ringbuffer::RingBuffer(2, sizeof(baro_report));
if (_reports == nullptr) { if (_reports == nullptr) {
debug("can't get memory for reports"); debug("can't get memory for reports");

View File

@ -121,7 +121,7 @@ private:
work_s _work; ///< work queue for scheduling reads work_s _work; ///< work queue for scheduling reads
bool _healthy[OREOLED_NUM_LEDS]; ///< health of each LED bool _healthy[OREOLED_NUM_LEDS]; ///< health of each LED
uint8_t _num_healthy; ///< number of healthy LEDs uint8_t _num_healthy; ///< number of healthy LEDs
RingBuffer *_cmd_queue; ///< buffer of commands to send to LEDs ringbuffer::RingBuffer *_cmd_queue; ///< buffer of commands to send to LEDs
uint64_t _last_gencall; uint64_t _last_gencall;
uint64_t _start_time; ///< system time we first attempt to communicate with battery uint64_t _start_time; ///< system time we first attempt to communicate with battery
}; };
@ -176,7 +176,7 @@ OREOLED::init()
} }
/* allocate command queue */ /* allocate command queue */
_cmd_queue = new RingBuffer(OREOLED_CMD_QUEUE_SIZE, sizeof(oreoled_cmd_t)); _cmd_queue = new ringbuffer::RingBuffer(OREOLED_CMD_QUEUE_SIZE, sizeof(oreoled_cmd_t));
if (_cmd_queue == nullptr) { if (_cmd_queue == nullptr) {
return ENOTTY; return ENOTTY;

View File

@ -120,7 +120,7 @@ protected:
private: private:
work_s _work; work_s _work;
RingBuffer *_reports; ringbuffer::RingBuffer *_reports;
bool _sensor_ok; bool _sensor_ok;
int _measure_ticks; int _measure_ticks;
bool _collect_phase; bool _collect_phase;
@ -217,7 +217,7 @@ PX4FLOW::init()
} }
/* allocate basic report buffers */ /* allocate basic report buffers */
_reports = new RingBuffer(2, sizeof(optical_flow_s)); _reports = new ringbuffer::RingBuffer(2, sizeof(optical_flow_s));
if (_reports == nullptr) { if (_reports == nullptr) {
goto out; goto out;

View File

@ -118,7 +118,7 @@ private:
float _min_distance; float _min_distance;
float _max_distance; float _max_distance;
work_s _work; work_s _work;
RingBuffer *_reports; ringbuffer::RingBuffer *_reports;
bool _sensor_ok; bool _sensor_ok;
int _measure_ticks; int _measure_ticks;
bool _collect_phase; bool _collect_phase;
@ -270,7 +270,7 @@ SF0X::init()
if (ret != OK) break; if (ret != OK) break;
/* 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) {
warnx("mem err"); warnx("mem err");
ret = -1; ret = -1;

View File

@ -122,7 +122,7 @@ private:
float _min_distance; float _min_distance;
float _max_distance; float _max_distance;
work_s _work; work_s _work;
RingBuffer *_reports; ringbuffer::RingBuffer *_reports;
bool _sensor_ok; bool _sensor_ok;
int _measure_ticks; int _measure_ticks;
bool _collect_phase; bool _collect_phase;
@ -281,7 +281,7 @@ TRONE::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;

View File

@ -36,7 +36,6 @@
*/ */
#include "baro.hpp" #include "baro.hpp"
#include <drivers/device/ringbuffer.h>
#include <cmath> #include <cmath>
const char *const UavcanBarometerBridge::NAME = "baro"; const char *const UavcanBarometerBridge::NAME = "baro";
@ -56,7 +55,7 @@ int UavcanBarometerBridge::init()
} }
/* allocate basic report buffers */ /* allocate basic report buffers */
_reports = new RingBuffer(2, sizeof(baro_report)); _reports = new ringbuffer::RingBuffer(2, sizeof(baro_report));
if (_reports == nullptr) if (_reports == nullptr)
return -1; return -1;

View File

@ -39,11 +39,10 @@
#include "sensor_bridge.hpp" #include "sensor_bridge.hpp"
#include <drivers/drv_baro.h> #include <drivers/drv_baro.h>
#include <drivers/device/ringbuffer.h>
#include <uavcan/equipment/air_data/StaticAirData.hpp> #include <uavcan/equipment/air_data/StaticAirData.hpp>
class RingBuffer;
class UavcanBarometerBridge : public UavcanCDevSensorBridgeBase class UavcanBarometerBridge : public UavcanCDevSensorBridgeBase
{ {
public: public:
@ -68,5 +67,5 @@ private:
uavcan::Subscriber<uavcan::equipment::air_data::StaticAirData, AirDataCbBinder> _sub_air_data; uavcan::Subscriber<uavcan::equipment::air_data::StaticAirData, AirDataCbBinder> _sub_air_data;
unsigned _msl_pressure = 101325; unsigned _msl_pressure = 101325;
RingBuffer *_reports; ringbuffer::RingBuffer *_reports;
}; };