From de1a7b30ce47f8fe9ee82cef86294b1187118d86 Mon Sep 17 00:00:00 2001 From: Mark Charlebois Date: Tue, 3 Nov 2015 01:24:02 -0800 Subject: [PATCH] gyrosim and adcsim now compile with DriverFramework enabled Only the posix build is tested for compilation Signed-off-by: Mark Charlebois --- CMakeLists.txt | 4 +++ src/firmware/posix/CMakeLists.txt | 3 +- src/lib/DriverFramework | 2 +- src/platforms/posix/drivers/adcsim/adcsim.cpp | 5 ++-- .../posix/drivers/gyrosim/gyrosim.cpp | 29 +++++++++---------- 5 files changed, 22 insertions(+), 21 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 6b395b6261..bbdff7c6c6 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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) diff --git a/src/firmware/posix/CMakeLists.txt b/src/firmware/posix/CMakeLists.txt index 48c4702785..208b0b689d 100644 --- a/src/firmware/posix/CMakeLists.txt +++ b/src/firmware/posix/CMakeLists.txt @@ -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 ) diff --git a/src/lib/DriverFramework b/src/lib/DriverFramework index 3ddb6b5e34..c2afd87807 160000 --- a/src/lib/DriverFramework +++ b/src/lib/DriverFramework @@ -1 +1 @@ -Subproject commit 3ddb6b5e34d870b487dbd57949a7d9c718730701 +Subproject commit c2afd878071e8fb0b1d80070e44ba98780492fc1 diff --git a/src/platforms/posix/drivers/adcsim/adcsim.cpp b/src/platforms/posix/drivers/adcsim/adcsim.cpp index a3d28f6d41..66372ad214 100644 --- a/src/platforms/posix/drivers/adcsim/adcsim.cpp +++ b/src/platforms/posix/drivers/adcsim/adcsim.cpp @@ -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; diff --git a/src/platforms/posix/drivers/gyrosim/gyrosim.cpp b/src/platforms/posix/drivers/gyrosim/gyrosim.cpp index 430e13a00a..7aef8cf392 100644 --- a/src/platforms/posix/drivers/gyrosim/gyrosim.cpp +++ b/src/platforms/posix/drivers/gyrosim/gyrosim.cpp @@ -69,10 +69,10 @@ #include #include -//#include +#include #include -//#include -//#include +#include +#include #include #include @@ -277,11 +277,11 @@ private: /** * Helper class implementing the gyro driver node. */ -class GYROSIM_gyro : public VirtDevObj +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)