Browse Source

drivers/device/ringbuffer: move into crazyflie syslink (only remaining user)

release/1.12
Daniel Agar 4 years ago
parent
commit
3f9e5a6934
  1. 1
      boards/bitcraze/crazyflie/syslink/CMakeLists.txt
  2. 0
      boards/bitcraze/crazyflie/syslink/ringbuffer.cpp
  3. 0
      boards/bitcraze/crazyflie/syslink/ringbuffer.h
  4. 2
      boards/bitcraze/crazyflie/syslink/syslink_main.h
  5. 10
      src/drivers/camera_capture/camera_capture.cpp
  6. 3
      src/drivers/camera_capture/camera_capture.hpp
  7. 1
      src/drivers/distance_sensor/mb12xx/mb12xx.cpp
  8. 1
      src/drivers/optical_flow/px4flow/px4flow.cpp
  9. 1
      src/lib/drivers/airspeed/airspeed.cpp
  10. 1
      src/lib/drivers/device/CMakeLists.txt

1
boards/bitcraze/crazyflie/syslink/CMakeLists.txt

@ -37,6 +37,7 @@ px4_add_module( @@ -37,6 +37,7 @@ px4_add_module(
COMPILE_FLAGS
-Wno-cast-align # TODO: fix and enable
SRCS
ringbuffer.cpp
syslink_main.cpp
syslink_bridge.cpp
syslink_memory.cpp

0
src/lib/drivers/device/ringbuffer.cpp → boards/bitcraze/crazyflie/syslink/ringbuffer.cpp

0
src/lib/drivers/device/ringbuffer.h → boards/bitcraze/crazyflie/syslink/ringbuffer.h

2
boards/bitcraze/crazyflie/syslink/syslink_main.h

@ -38,7 +38,7 @@ @@ -38,7 +38,7 @@
#include <battery/battery.h>
#include <drivers/device/device.h>
#include <drivers/device/ringbuffer.h>
#include "ringbuffer.h"
#include <uORB/PublicationMulti.hpp>
#include <uORB/topics/parameter_update.h>

10
src/drivers/camera_capture/camera_capture.cpp

@ -68,9 +68,6 @@ CameraCapture::CameraCapture() : @@ -68,9 +68,6 @@ CameraCapture::CameraCapture() :
CameraCapture::~CameraCapture()
{
/* free any existing reports */
delete _trig_buffer;
camera_capture::g_camera_capture = nullptr;
}
@ -295,13 +292,6 @@ CameraCapture::reset_statistics(bool reset_seq) @@ -295,13 +292,6 @@ CameraCapture::reset_statistics(bool reset_seq)
int
CameraCapture::start()
{
/* allocate basic report buffers */
_trig_buffer = new ringbuffer::RingBuffer(2, sizeof(_trig_s));
if (_trig_buffer == nullptr) {
return PX4_ERROR;
}
// run every 100 ms (10 Hz)
ScheduleOnInterval(100000, 10000);

3
src/drivers/camera_capture/camera_capture.hpp

@ -38,7 +38,6 @@ @@ -38,7 +38,6 @@
#pragma once
#include <drivers/device/ringbuffer.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_input_capture.h>
#include <drivers/drv_pwm_output.h>
@ -115,8 +114,6 @@ private: @@ -115,8 +114,6 @@ private:
uint32_t overflow;
} _trigger{};
ringbuffer::RingBuffer *_trig_buffer{nullptr};
bool _capture_enabled{false};
bool _gpio_capture{false};

1
src/drivers/distance_sensor/mb12xx/mb12xx.cpp

@ -56,7 +56,6 @@ @@ -56,7 +56,6 @@
#include <containers/Array.hpp>
#include <drivers/device/device.h>
#include <drivers/device/i2c.h>
#include <drivers/device/ringbuffer.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_range_finder.h>
#include <perf/perf_counter.h>

1
src/drivers/optical_flow/px4flow/px4flow.cpp

@ -40,7 +40,6 @@ @@ -40,7 +40,6 @@
*/
#include <drivers/device/i2c.h>
#include <drivers/device/ringbuffer.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_range_finder.h>
#include <lib/conversion/rotation.h>

1
src/lib/drivers/airspeed/airspeed.cpp

@ -49,7 +49,6 @@ @@ -49,7 +49,6 @@
#include <drivers/drv_airspeed.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/ringbuffer.h>
#include <uORB/uORB.h>
#include <uORB/topics/differential_pressure.h>

1
src/lib/drivers/device/CMakeLists.txt

@ -55,7 +55,6 @@ endif() @@ -55,7 +55,6 @@ endif()
px4_add_library(drivers__device
CDev.cpp
ringbuffer.cpp
${SRCS_PLATFORM}
)

Loading…
Cancel
Save