From f5727524123f5ecc9733cbff8aa0bdeda00439df Mon Sep 17 00:00:00 2001 From: Michael Schaeuble Date: Mon, 26 Dec 2016 15:02:33 +0100 Subject: [PATCH] BebopFlow: Add initial PX4 app and structure --- cmake/configs/posix_bebop_default.cmake | 1 + .../posix/drivers/bebop_flow/CMakeLists.txt | 46 ++++ .../posix/drivers/bebop_flow/bebop_flow.cpp | 208 ++++++++++++++++++ .../posix/drivers/bebop_flow/video_device.cpp | 26 +++ .../posix/drivers/bebop_flow/video_device.h | 58 +++++ 5 files changed, 339 insertions(+) create mode 100644 src/platforms/posix/drivers/bebop_flow/CMakeLists.txt create mode 100644 src/platforms/posix/drivers/bebop_flow/bebop_flow.cpp create mode 100644 src/platforms/posix/drivers/bebop_flow/video_device.cpp create mode 100644 src/platforms/posix/drivers/bebop_flow/video_device.h diff --git a/cmake/configs/posix_bebop_default.cmake b/cmake/configs/posix_bebop_default.cmake index 5abbb4c782..8b3b897dc9 100644 --- a/cmake/configs/posix_bebop_default.cmake +++ b/cmake/configs/posix_bebop_default.cmake @@ -27,6 +27,7 @@ set(config_module_list platforms/posix/drivers/df_ak8963_wrapper platforms/posix/drivers/df_bebop_bus_wrapper platforms/posix/drivers/df_bebop_rangefinder_wrapper + platforms/posix/drivers/bebop_flow # # System commands diff --git a/src/platforms/posix/drivers/bebop_flow/CMakeLists.txt b/src/platforms/posix/drivers/bebop_flow/CMakeLists.txt new file mode 100644 index 0000000000..b73d689039 --- /dev/null +++ b/src/platforms/posix/drivers/bebop_flow/CMakeLists.txt @@ -0,0 +1,46 @@ +############################################################################ +# +# Copyright (c) 2016 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 +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +include_directories(../../../../lib/DriverFramework/drivers) + +px4_add_module( + MODULE platforms__posix__drivers__bebop_flow + MAIN bebop_flow + SRCS + bebop_flow.cpp + video_device.cpp + DEPENDS + platforms__common + df_driver_framework + ) +# vim: set noet ft=cmake fenc=utf-8 ff=unix : diff --git a/src/platforms/posix/drivers/bebop_flow/bebop_flow.cpp b/src/platforms/posix/drivers/bebop_flow/bebop_flow.cpp new file mode 100644 index 0000000000..1eab0c8779 --- /dev/null +++ b/src/platforms/posix/drivers/bebop_flow/bebop_flow.cpp @@ -0,0 +1,208 @@ + +/**************************************************************************** + * + * Copyright (c) 2016 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 + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + + +/** + * @file bebop_flow.cpp + * + * This is a wrapper around the Parrot Bebop's downward-facing camera and integrates + * an optical flow computation. + */ + +#include + +#include +#include +#include + +#include "video_device.h" + +extern "C" { __EXPORT int bebop_flow_main(int argc, char *argv[]); } + +namespace bebop_flow +{ +VideoDevice *g_dev = nullptr; // interface to the video device +volatile bool _task_should_exit = false; // flag indicating if bebop flow task should exit +static bool _is_running = false; // flag indicating if bebop flow app is running +static px4_task_t _task_handle = -1; // handle to the task main thread + +static char *dev_name = "/dev/video0"; + +int start(); +int stop(); +int info(); +int clear_errors(); +void usage(); +void task_main(int argc, char *argv[]); + + +void task_main(int argc, char *argv[]) +{ + _is_running = true; + + // Main loop + while (!_task_should_exit) { + + } + + _is_running = false; + +} + +int start() +{ + g_dev = new VideoDevice(); + + if (g_dev == nullptr) { + PX4_ERR("failed instantiating video device object"); + return -1; + } + + int ret = g_dev->start(); + + if (ret != 0) { + PX4_ERR("Video device start failed"); + return ret; + } + + /* start the task */ + _task_handle = px4_task_spawn_cmd("bebop_flow", + SCHED_DEFAULT, + SCHED_PRIORITY_DEFAULT, + 2000, + (px4_main_t)&task_main, + nullptr); + + if (_task_handle < 0) { + warn("task start failed"); + return -1; + } + + return 0; +} + +int stop() +{ + // Stop bebop flow task + _task_should_exit = true; + + while (_is_running) { + usleep(200000); + PX4_INFO("."); + } + + _task_handle = -1; + + if (g_dev == nullptr) { + PX4_ERR("driver not running"); + return 1; + } + + // Stop DF device + int ret = g_dev->stop(); + + if (ret != 0) { + PX4_ERR("driver could not be stopped"); + return ret; + } + + delete g_dev; + g_dev = nullptr; + return 0; +} + +/** + * Print a little info about the driver. + */ +int +info() +{ + if (g_dev == nullptr) { + PX4_ERR("driver not running"); + return 1; + } + + PX4_DEBUG("state @ %p", g_dev); + + int ret = g_dev->print_info(); + + if (ret != 0) { + PX4_ERR("Unable to print info"); + return ret; + } + + return 0; +} + +void +usage() +{ + PX4_INFO("Usage: bebop_flow 'start', 'info', 'stop'"); +} + +} /* bebop flow namespace*/ + +int +bebop_flow_main(int argc, char *argv[]) +{ + int ret = 0; + int myoptind = 1; + + if (argc <= 1) { + bebop_flow::usage(); + return 1; + } + + const char *verb = argv[myoptind]; + + + if (!strcmp(verb, "start")) { + ret = bebop_flow::start(); + } + + else if (!strcmp(verb, "stop")) { + ret = bebop_flow::stop(); + } + + else if (!strcmp(verb, "info")) { + ret = bebop_flow::info(); + } + + else { + bebop_flow::usage(); + return 1; + } + + return ret; +} diff --git a/src/platforms/posix/drivers/bebop_flow/video_device.cpp b/src/platforms/posix/drivers/bebop_flow/video_device.cpp new file mode 100644 index 0000000000..7bd437db1f --- /dev/null +++ b/src/platforms/posix/drivers/bebop_flow/video_device.cpp @@ -0,0 +1,26 @@ +#include "video_device.h" + +int VideoDevice::start() +{ + return -1; +} + +int VideoDevice::stop() +{ + return -1; +} + +int VideoDevice::print_info() +{ + return -1; +} + +int VideoDevice::open_device() +{ + return -1; +} + +int VideoDevice::close_device() +{ + return -1; +} diff --git a/src/platforms/posix/drivers/bebop_flow/video_device.h b/src/platforms/posix/drivers/bebop_flow/video_device.h new file mode 100644 index 0000000000..9c08ca4418 --- /dev/null +++ b/src/platforms/posix/drivers/bebop_flow/video_device.h @@ -0,0 +1,58 @@ +/**************************************************************************** + * + * Copyright (c) 2016 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 + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +class VideoDevice +{ +public: + VideoDevice(const char *dev_name) : + _dev_name(dev_name) {}; + + ~VideoDevice() = default; + + /// Start the device + int start(); + + /// Stop the device + int stop(); + + /// Print various infos + int print_info(); + +private: + char *_dev_name; + + int open_device(); + int close_device(); +};