From 4b3095d13c1f59da9242de0058991469986c74d7 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 17 Aug 2018 11:31:04 +0200 Subject: [PATCH 1/2] example: use thread instead of boost eventloop I'd rather not have the boost dependency, therefore I replaced the usage of the boost event loop with just a thread with a sleep. --- example/follow_me/CMakeLists.txt | 10 +-- example/follow_me/fake_location_provider.cpp | 94 +++++++++++--------- example/follow_me/fake_location_provider.h | 26 +++--- example/follow_me/follow_me.cpp | 6 +- 4 files changed, 67 insertions(+), 69 deletions(-) diff --git a/example/follow_me/CMakeLists.txt b/example/follow_me/CMakeLists.txt index 3139053fe2..3a137263b3 100644 --- a/example/follow_me/CMakeLists.txt +++ b/example/follow_me/CMakeLists.txt @@ -2,31 +2,27 @@ cmake_minimum_required(VERSION 2.8.12) project(follow_me) +find_package(Threads REQUIRED) + if(NOT MSVC) add_definitions("-std=c++11 -Wall -Wextra -Werror") # Line below required if /usr/local/include is not in your default includes #include_directories(/usr/local/include) # Line below required if /usr/local/lib is not in your default linker path #link_directories(/usr/local/lib) - find_package(Boost 1.58 COMPONENTS system REQUIRED ) else() include_directories(${CMAKE_SOURCE_DIR}/../../install/include) link_directories(${CMAKE_SOURCE_DIR}/../../install/lib) add_definitions("-std=c++11 -WX -W2") - find_package(Boost 1.64 COMPONENTS system date_time REQUIRED ) - # This is to avoid auto-linking of libraries that we don't build - add_definitions("-DBOOST_ALL_NO_LIB") endif() -include_directories(${Boost_INCLUDE_DIR}) - add_executable(follow_me follow_me.cpp fake_location_provider.cpp ) target_link_libraries(follow_me - LINK_PUBLIC ${Boost_LIBRARIES} + ${CMAKE_THREAD_LIBS_INIT} dronecode_sdk dronecode_sdk_action dronecode_sdk_follow_me diff --git a/example/follow_me/fake_location_provider.cpp b/example/follow_me/fake_location_provider.cpp index e72b17d002..83050f2e35 100644 --- a/example/follow_me/fake_location_provider.cpp +++ b/example/follow_me/fake_location_provider.cpp @@ -6,56 +6,66 @@ using std::this_thread::sleep_for; using std::chrono::seconds; +FakeLocationProvider::FakeLocationProvider() {} + +FakeLocationProvider::~FakeLocationProvider() +{ + stop(); +} + void FakeLocationProvider::request_location_updates(location_callback_t callback) { location_callback_ = callback; - timer_.async_wait(std::bind(&FakeLocationProvider::compute_next_location, this)); + stop(); + start(); +} + +void FakeLocationProvider::start() +{ + should_exit_ = false; + thread_ = new std::thread(&FakeLocationProvider::compute_locations, this); +} + +void FakeLocationProvider::stop() +{ + should_exit_ = true; + + if (thread_) { + thread_->join(); + delete thread_; + thread_ = nullptr; + } } // Rudimentary location provider whose successive lat, lon combination // makes Drone revolve in a semi-circular path. -void FakeLocationProvider::compute_next_location() +void FakeLocationProvider::compute_locations() { - if (count_++ < 10) { - location_callback_(latitude_deg_, longitude_deg_); - latitude_deg_ -= LATITUDE_DEG_PER_METER * 4; - timer_.expires_at(timer_.expires_at() + boost::posix_time::seconds(1)); - timer_.async_wait(std::bind(&FakeLocationProvider::compute_next_location, this)); - sleep_for(seconds(1)); - } - if (count_++ < 20) { - location_callback_(latitude_deg_, longitude_deg_); - longitude_deg_ += LONGITUDE_DEG_PER_METER * 4; - timer_.expires_at(timer_.expires_at() + boost::posix_time::seconds(1)); - timer_.async_wait(std::bind(&FakeLocationProvider::compute_next_location, this)); - sleep_for(seconds(1)); - } - if (count_++ < 30) { - location_callback_(latitude_deg_, longitude_deg_); - latitude_deg_ += LATITUDE_DEG_PER_METER * 4; - timer_.expires_at(timer_.expires_at() + boost::posix_time::seconds(1)); - timer_.async_wait(std::bind(&FakeLocationProvider::compute_next_location, this)); - sleep_for(seconds(1)); - } - if (count_++ < 40) { - location_callback_(latitude_deg_, longitude_deg_); - longitude_deg_ -= LONGITUDE_DEG_PER_METER * 4; - timer_.expires_at(timer_.expires_at() + boost::posix_time::seconds(1)); - timer_.async_wait(std::bind(&FakeLocationProvider::compute_next_location, this)); - sleep_for(seconds(1)); - } - if (count_++ < 50) { - location_callback_(latitude_deg_, longitude_deg_); - latitude_deg_ -= LATITUDE_DEG_PER_METER * 3; - timer_.expires_at(timer_.expires_at() + boost::posix_time::seconds(1)); - timer_.async_wait(std::bind(&FakeLocationProvider::compute_next_location, this)); - sleep_for(seconds(1)); - } - if (count_++ < MAX_LOCATIONS) { - location_callback_(latitude_deg_, longitude_deg_); - longitude_deg_ += LONGITUDE_DEG_PER_METER * 3; - timer_.expires_at(timer_.expires_at() + boost::posix_time::seconds(1)); - timer_.async_wait(std::bind(&FakeLocationProvider::compute_next_location, this)); + while (!should_exit_) { + if (count_++ < 10) { + location_callback_(latitude_deg_, longitude_deg_); + latitude_deg_ -= LATITUDE_DEG_PER_METER * 4; + } + if (count_++ < 20) { + location_callback_(latitude_deg_, longitude_deg_); + longitude_deg_ += LONGITUDE_DEG_PER_METER * 4; + } + if (count_++ < 30) { + location_callback_(latitude_deg_, longitude_deg_); + latitude_deg_ += LATITUDE_DEG_PER_METER * 4; + } + if (count_++ < 40) { + location_callback_(latitude_deg_, longitude_deg_); + longitude_deg_ -= LONGITUDE_DEG_PER_METER * 4; + } + if (count_++ < 50) { + location_callback_(latitude_deg_, longitude_deg_); + latitude_deg_ -= LATITUDE_DEG_PER_METER * 3; + } + if (count_++ < MAX_LOCATIONS) { + location_callback_(latitude_deg_, longitude_deg_); + longitude_deg_ += LONGITUDE_DEG_PER_METER * 3; + } sleep_for(seconds(1)); } } diff --git a/example/follow_me/fake_location_provider.h b/example/follow_me/fake_location_provider.h index adadc66060..04e273ed69 100644 --- a/example/follow_me/fake_location_provider.h +++ b/example/follow_me/fake_location_provider.h @@ -1,18 +1,8 @@ #pragma once #include -/** - ******************************************************************************************** - ******************************************************************************************** - Important note: Boost isn't a dependency for the Dronecode SDK library. - We're using Boost::Asio in this example ONLY to simulate asynchronous Fake location provider. - Applications on platforms Android, Windows, Apple, etc should make use of their platform-specific - Location Provider in place of FakeLocationProvider. - ******************************************************************************************** - ******************************************************************************************** - */ -#include -#include +#include +#include /** * @brief The FakeLocationProvider class @@ -22,16 +12,20 @@ class FakeLocationProvider { public: typedef std::function location_callback_t; - FakeLocationProvider(boost::asio::io_service &io) : timer_(io, boost::posix_time::seconds(1)) {} + FakeLocationProvider(); - ~FakeLocationProvider() {} + ~FakeLocationProvider(); void request_location_updates(location_callback_t callback); private: - void compute_next_location(); + void start(); + void stop(); + void compute_locations(); + + std::thread *thread_{nullptr}; + std::atomic should_exit_{false}; - boost::asio::deadline_timer timer_; location_callback_t location_callback_ = nullptr; double latitude_deg_ = 47.3977419; double longitude_deg_ = 8.5455938; diff --git a/example/follow_me/follow_me.cpp b/example/follow_me/follow_me.cpp index c6298cdf0f..8592d6eee3 100644 --- a/example/follow_me/follow_me.cpp +++ b/example/follow_me/follow_me.cpp @@ -116,14 +116,12 @@ int main(int argc, char **argv) follow_me_result = follow_me->start(); follow_me_error_exit(follow_me_result, "Failed to start FollowMe mode"); - boost::asio::io_service io; // for event loop - std::unique_ptr location_provider(new FakeLocationProvider(io)); + FakeLocationProvider location_provider; // Register for platform-specific Location provider. We're using FakeLocationProvider for the // example. - location_provider->request_location_updates([&system, &follow_me](double lat, double lon) { + location_provider.request_location_updates([&system, &follow_me](double lat, double lon) { follow_me->set_target_location({lat, lon, 0.0, 0.f, 0.f, 0.f}); }); - io.run(); // will run as long as location updates continue to happen. // Stop Follow Me follow_me_result = follow_me->stop(); From c027f9c94361f6e3e341d59d0f5979008772ae5a Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 17 Aug 2018 11:35:51 +0200 Subject: [PATCH 2/2] appveyor: boost is not required anymore --- appveyor.yml | 13 +------------ 1 file changed, 1 insertion(+), 12 deletions(-) diff --git a/appveyor.yml b/appveyor.yml index 1b3aa6844e..bd16823c8e 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -37,8 +37,6 @@ before_build: - cd C:\ - appveyor DownloadFile https://curl.haxx.se/download/curl-7.56.1.zip - 7z x -y curl-7.56.1.zip - - appveyor DownloadFile https://dl.bintray.com/boostorg/release/1.64.0/source/boost_1_64_0.7z - - 7z x -y boost_1_64_0.7z build: on @@ -65,15 +63,6 @@ build_script: ) else ( cmake --build . --target install --config Release ) - - cd C:\boost_1_64_0 - - set boost_dir=C:\boost_1_64_0 - - set cores=%NUMBER_OF_PROCESSORS% - - set msvcver=msvc-14.1 - - cd %boost_dir% - - bootstrap.bat - - b2 --with-system --with-date_time --j%cores% toolset=%msvcver% address-model=64 architecture=x86 link=static threading=multi runtime-link=shared --build-type=minimal stage --stagedir=stage/x64 - - set BOOST_ROOT=%boost_dir% - - set BOOST_LIBRARYDIR=%boost_dir%\stage\x64\lib - cd %dronecode_sdk_dir% - cd example\takeoff_land - md build @@ -118,7 +107,7 @@ build_script: - cd example\follow_me - md build - cd build - - cmake .. -G "Visual Studio 15 2017 Win64" -DBoost_USE_STATIC_LIBS=ON + - cmake .. -G "Visual Studio 15 2017 Win64" - if "%configuration%"=="Debug" ( cmake --build . --config Debug ) else (