forked from Archive/PX4-Autopilot
Merge branch 'fix_ringbuffer' into lidarlite_merge
This commit is contained in:
commit
d473b8bddd
|
@ -128,7 +128,7 @@ Airspeed::init()
|
|||
goto out;
|
||||
|
||||
/* allocate basic report buffers */
|
||||
_reports = new RingBuffer(2, sizeof(differential_pressure_s));
|
||||
_reports = new ringbuffer::RingBuffer(2, sizeof(differential_pressure_s));
|
||||
if (_reports == nullptr)
|
||||
goto out;
|
||||
|
||||
|
|
|
@ -109,7 +109,7 @@ public:
|
|||
virtual void print_info();
|
||||
|
||||
private:
|
||||
RingBuffer *_reports;
|
||||
ringbuffer::RingBuffer *_reports;
|
||||
perf_counter_t _buffer_overflows;
|
||||
|
||||
/* this class has pointer data members and should not be copied */
|
||||
|
|
|
@ -41,7 +41,8 @@ SRCS = \
|
|||
cdev.cpp \
|
||||
i2c_nuttx.cpp \
|
||||
pio.cpp \
|
||||
spi.cpp
|
||||
spi.cpp \
|
||||
ringbuffer.cpp
|
||||
else
|
||||
SRCS = \
|
||||
device_posix.cpp \
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
|
||||
* Copyright (C) 2013-2015 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
@ -40,6 +40,9 @@
|
|||
#include "ringbuffer.h"
|
||||
#include <string.h>
|
||||
|
||||
namespace ringbuffer
|
||||
{
|
||||
|
||||
RingBuffer::RingBuffer(unsigned num_items, size_t item_size) :
|
||||
_num_items(num_items),
|
||||
_item_size(item_size),
|
||||
|
@ -398,3 +401,5 @@ RingBuffer::print_info(const char *name)
|
|||
_tail,
|
||||
_buf);
|
||||
}
|
||||
|
||||
} // namespace ringbuffer
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
|
||||
* Copyright (C) 2013-2015 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
@ -43,6 +43,9 @@
|
|||
#include <stdint.h>
|
||||
#include <stdio.h>
|
||||
|
||||
namespace ringbuffer __EXPORT
|
||||
{
|
||||
|
||||
class RingBuffer {
|
||||
public:
|
||||
RingBuffer(unsigned ring_size, size_t entry_size);
|
||||
|
@ -172,9 +175,4 @@ private:
|
|||
RingBuffer operator=(const RingBuffer&);
|
||||
};
|
||||
|
||||
#ifdef __PX4_NUTTX
|
||||
// Not sure why NuttX requires these to be defined in the header file
|
||||
// but on other targets it causes a problem with multiple definitions
|
||||
// at link time
|
||||
#include "ringbuffer.cpp"
|
||||
#endif
|
||||
} // namespace ringbuffer
|
||||
|
|
|
@ -156,7 +156,7 @@ private:
|
|||
work_s _work;
|
||||
unsigned _measure_ticks;
|
||||
|
||||
RingBuffer *_reports;
|
||||
ringbuffer::RingBuffer *_reports;
|
||||
mag_scale _scale;
|
||||
float _range_scale;
|
||||
float _range_ga;
|
||||
|
@ -423,7 +423,7 @@ HMC5883::init()
|
|||
}
|
||||
|
||||
/* allocate basic report buffers */
|
||||
_reports = new RingBuffer(2, sizeof(mag_report));
|
||||
_reports = new ringbuffer::RingBuffer(2, sizeof(mag_report));
|
||||
if (_reports == nullptr)
|
||||
goto out;
|
||||
|
||||
|
|
|
@ -229,7 +229,7 @@ private:
|
|||
struct hrt_call _call;
|
||||
unsigned _call_interval;
|
||||
|
||||
RingBuffer *_reports;
|
||||
ringbuffer::RingBuffer *_reports;
|
||||
|
||||
struct gyro_scale _gyro_scale;
|
||||
float _gyro_range_scale;
|
||||
|
@ -472,7 +472,7 @@ L3GD20::init()
|
|||
goto out;
|
||||
|
||||
/* allocate basic report buffers */
|
||||
_reports = new RingBuffer(2, sizeof(gyro_report));
|
||||
_reports = new ringbuffer::RingBuffer(2, sizeof(gyro_report));
|
||||
|
||||
if (_reports == nullptr)
|
||||
goto out;
|
||||
|
|
|
@ -275,8 +275,8 @@ private:
|
|||
unsigned _call_accel_interval;
|
||||
unsigned _call_mag_interval;
|
||||
|
||||
RingBuffer *_accel_reports;
|
||||
RingBuffer *_mag_reports;
|
||||
ringbuffer::RingBuffer *_accel_reports;
|
||||
ringbuffer::RingBuffer *_mag_reports;
|
||||
|
||||
struct accel_scale _accel_scale;
|
||||
unsigned _accel_range_m_s2;
|
||||
|
@ -646,12 +646,12 @@ LSM303D::init()
|
|||
}
|
||||
|
||||
/* 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)
|
||||
goto out;
|
||||
|
||||
_mag_reports = new RingBuffer(2, sizeof(mag_report));
|
||||
_mag_reports = new ringbuffer::RingBuffer(2, sizeof(mag_report));
|
||||
|
||||
if (_mag_reports == nullptr)
|
||||
goto out;
|
||||
|
|
|
@ -125,7 +125,7 @@ private:
|
|||
float _min_distance;
|
||||
float _max_distance;
|
||||
work_s _work;
|
||||
RingBuffer *_reports;
|
||||
ringbuffer::RingBuffer *_reports;
|
||||
bool _sensor_ok;
|
||||
int _measure_ticks;
|
||||
bool _collect_phase;
|
||||
|
@ -255,7 +255,7 @@ MB12XX::init()
|
|||
}
|
||||
|
||||
/* 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 */
|
||||
set_address(_index_counter); /* set I2c port to temp sonar i2c adress */
|
||||
|
|
|
@ -242,7 +242,7 @@ private:
|
|||
struct hrt_call _call;
|
||||
unsigned _call_interval;
|
||||
|
||||
RingBuffer *_accel_reports;
|
||||
ringbuffer::RingBuffer *_accel_reports;
|
||||
|
||||
struct accel_scale _accel_scale;
|
||||
float _accel_range_scale;
|
||||
|
@ -251,7 +251,7 @@ private:
|
|||
int _accel_orb_class_instance;
|
||||
int _accel_class_instance;
|
||||
|
||||
RingBuffer *_gyro_reports;
|
||||
ringbuffer::RingBuffer *_gyro_reports;
|
||||
|
||||
struct gyro_scale _gyro_scale;
|
||||
float _gyro_range_scale;
|
||||
|
@ -611,11 +611,11 @@ MPU6000::init()
|
|||
}
|
||||
|
||||
/* 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)
|
||||
goto out;
|
||||
|
||||
_gyro_reports = new RingBuffer(2, sizeof(gyro_report));
|
||||
_gyro_reports = new ringbuffer::RingBuffer(2, sizeof(gyro_report));
|
||||
if (_gyro_reports == nullptr)
|
||||
goto out;
|
||||
|
||||
|
|
|
@ -127,7 +127,7 @@ protected:
|
|||
struct work_s _work;
|
||||
unsigned _measure_ticks;
|
||||
|
||||
RingBuffer *_reports;
|
||||
ringbuffer::RingBuffer *_reports;
|
||||
|
||||
bool _collect_phase;
|
||||
unsigned _measure_phase;
|
||||
|
@ -269,7 +269,7 @@ MS5611::init()
|
|||
}
|
||||
|
||||
/* allocate basic report buffers */
|
||||
_reports = new RingBuffer(2, sizeof(baro_report));
|
||||
_reports = new ringbuffer::RingBuffer(2, sizeof(baro_report));
|
||||
|
||||
if (_reports == nullptr) {
|
||||
debug("can't get memory for reports");
|
||||
|
|
|
@ -121,7 +121,7 @@ private:
|
|||
work_s _work; ///< work queue for scheduling reads
|
||||
bool _healthy[OREOLED_NUM_LEDS]; ///< health of each LED
|
||||
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 _start_time; ///< system time we first attempt to communicate with battery
|
||||
};
|
||||
|
@ -176,7 +176,7 @@ OREOLED::init()
|
|||
}
|
||||
|
||||
/* 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) {
|
||||
return ENOTTY;
|
||||
|
|
|
@ -120,7 +120,7 @@ protected:
|
|||
private:
|
||||
|
||||
work_s _work;
|
||||
RingBuffer *_reports;
|
||||
ringbuffer::RingBuffer *_reports;
|
||||
bool _sensor_ok;
|
||||
int _measure_ticks;
|
||||
bool _collect_phase;
|
||||
|
@ -217,7 +217,7 @@ PX4FLOW::init()
|
|||
}
|
||||
|
||||
/* allocate basic report buffers */
|
||||
_reports = new RingBuffer(2, sizeof(optical_flow_s));
|
||||
_reports = new ringbuffer::RingBuffer(2, sizeof(optical_flow_s));
|
||||
|
||||
if (_reports == nullptr) {
|
||||
goto out;
|
||||
|
|
|
@ -118,7 +118,7 @@ private:
|
|||
float _min_distance;
|
||||
float _max_distance;
|
||||
work_s _work;
|
||||
RingBuffer *_reports;
|
||||
ringbuffer::RingBuffer *_reports;
|
||||
bool _sensor_ok;
|
||||
int _measure_ticks;
|
||||
bool _collect_phase;
|
||||
|
@ -270,7 +270,7 @@ SF0X::init()
|
|||
if (ret != OK) break;
|
||||
|
||||
/* allocate basic report buffers */
|
||||
_reports = new RingBuffer(2, sizeof(range_finder_report));
|
||||
_reports = new ringbuffer::RingBuffer(2, sizeof(range_finder_report));
|
||||
if (_reports == nullptr) {
|
||||
warnx("mem err");
|
||||
ret = -1;
|
||||
|
|
|
@ -122,7 +122,7 @@ private:
|
|||
float _min_distance;
|
||||
float _max_distance;
|
||||
work_s _work;
|
||||
RingBuffer *_reports;
|
||||
ringbuffer::RingBuffer *_reports;
|
||||
bool _sensor_ok;
|
||||
int _measure_ticks;
|
||||
bool _collect_phase;
|
||||
|
@ -281,7 +281,7 @@ TRONE::init()
|
|||
}
|
||||
|
||||
/* allocate basic report buffers */
|
||||
_reports = new RingBuffer(2, sizeof(range_finder_report));
|
||||
_reports = new ringbuffer::RingBuffer(2, sizeof(range_finder_report));
|
||||
|
||||
if (_reports == nullptr) {
|
||||
goto out;
|
||||
|
|
|
@ -36,7 +36,6 @@
|
|||
*/
|
||||
|
||||
#include "baro.hpp"
|
||||
#include <drivers/device/ringbuffer.h>
|
||||
#include <cmath>
|
||||
|
||||
const char *const UavcanBarometerBridge::NAME = "baro";
|
||||
|
@ -56,7 +55,7 @@ int UavcanBarometerBridge::init()
|
|||
}
|
||||
|
||||
/* allocate basic report buffers */
|
||||
_reports = new RingBuffer(2, sizeof(baro_report));
|
||||
_reports = new ringbuffer::RingBuffer(2, sizeof(baro_report));
|
||||
if (_reports == nullptr)
|
||||
return -1;
|
||||
|
||||
|
|
|
@ -39,11 +39,10 @@
|
|||
|
||||
#include "sensor_bridge.hpp"
|
||||
#include <drivers/drv_baro.h>
|
||||
#include <drivers/device/ringbuffer.h>
|
||||
|
||||
#include <uavcan/equipment/air_data/StaticAirData.hpp>
|
||||
|
||||
class RingBuffer;
|
||||
|
||||
class UavcanBarometerBridge : public UavcanCDevSensorBridgeBase
|
||||
{
|
||||
public:
|
||||
|
@ -68,5 +67,5 @@ private:
|
|||
|
||||
uavcan::Subscriber<uavcan::equipment::air_data::StaticAirData, AirDataCbBinder> _sub_air_data;
|
||||
unsigned _msl_pressure = 101325;
|
||||
RingBuffer *_reports;
|
||||
ringbuffer::RingBuffer *_reports;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue