gyrosim and adcsim now compile with DriverFramework enabled

Only the posix build is tested for compilation

Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
Mark Charlebois 2015-11-03 01:24:02 -08:00 committed by Lorenz Meier
parent 847b604841
commit de1a7b30ce
5 changed files with 22 additions and 21 deletions

View File

@ -121,6 +121,9 @@
# and leads to wrong toolchain detection
cmake_minimum_required(VERSION 2.8 FATAL_ERROR)
SET (CMAKE_C_COMPILER /usr/bin/clang-3.6)
SET (CMAKE_CXX_COMPILER /usr/bin/clang++-3.6)
#=============================================================================
# parameters
#
@ -320,6 +323,7 @@ foreach(module ${config_module_list})
endforeach()
add_subdirectory(src/firmware/${OS})
add_subdirectory(src/lib/DriverFramework)
if (config_io_board)
add_subdirectory(src/modules/px4iofirmware)

View File

@ -14,7 +14,8 @@ if (NOT ${CMAKE_C_COMPILER_ID} STREQUAL "Clang" OR NOT APPLE)
target_link_libraries(mainapp
-Wl,--start-group
${module_libraries}
${driver_framework_libraries}
df_driver_framework
${df_driver_libraries}
pthread m rt
-Wl,--end-group
)

@ -1 +1 @@
Subproject commit 3ddb6b5e34d870b487dbd57949a7d9c718730701
Subproject commit c2afd878071e8fb0b1d80070e44ba98780492fc1

View File

@ -78,10 +78,9 @@ public:
ADCSIM(uint32_t channels);
virtual ~ADCSIM();
virtual ssize_t read(void *buffer, ssize_t len);
virtual ssize_t devRead(void *buffer, size_t len);
private:
WorkHandle _call;
perf_counter_t _sample_perf;
unsigned _channel_count;
@ -144,7 +143,7 @@ ADCSIM::~ADCSIM()
}
ssize_t
ADCSIM::read(void *buffer, ssize_t len)
ADCSIM::devRead(void *buffer, size_t len)
{
const size_t maxsize = sizeof(adc_msg_s) * _channel_count;

View File

@ -69,10 +69,10 @@
#include <board_config.h>
#include <drivers/drv_hrt.h>
//#include <drivers/device/device.h>
#include <drivers/device/device.h>
#include <drivers/device/ringbuffer.h>
//#include <drivers/drv_accel.h>
//#include <drivers/drv_gyro.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_gyro.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
#include <lib/conversion/rotation.h>
@ -281,7 +281,7 @@ class GYROSIM_gyro : public VirtDevObj
{
public:
GYROSIM_gyro(GYROSIM *parent, const char *path);
virtual ~GYROSIM_gyro();
virtual ~GYROSIM_gyro() {}
virtual ssize_t devRead(void *buffer, size_t buflen);
virtual int devIOCTL(unsigned long cmd, void *arg);
@ -293,12 +293,11 @@ protected:
void parent_poll_notify();
virtual void _measure();
virtual void _measure() {};
private:
GYROSIM *_parent;
orb_advert_t _gyro_topic;
int _gyro_orb_class_instance;
int _gyro_class_instance;
/* do not allow to copy this class due to pointer data members */
GYROSIM_gyro(const GYROSIM_gyro &);
@ -385,7 +384,7 @@ GYROSIM::~GYROSIM()
int
GYROSIM::init()
{
int ret;
int ret = 1;
struct accel_report arp = {};
@ -1102,9 +1101,8 @@ GYROSIM::_measure()
/* notify anyone waiting for data */
// FIXME
//poll_notify(POLLIN);
//_gyro->parent_poll_notify();
updateNotify();
_gyro->parent_poll_notify();
if (!(_pub_blocked)) {
/* log the time of this report */
@ -1162,27 +1160,26 @@ GYROSIM::print_registers()
GYROSIM_gyro::GYROSIM_gyro(GYROSIM *parent, const char *path) :
// Set sample interval to 0 since device is read by parent
VirtDevObj("GYROSIM_gyro", path, 0),
_parent(parent),
_gyro_topic(nullptr),
_gyro_orb_class_instance(-1),
_gyro_class_instance(-1)
_gyro_orb_class_instance(-1)
{
}
int
GYROSIM_gyro::init()
{
return start();
}
#if 0
void
GYROSIM_gyro::parent_poll_notify()
{
poll_notify(POLLIN);
updateNotify();
}
#endif
ssize_t
GYROSIM_gyro::devRead(void *buffer, size_t buflen)