From 82dc3820955b1252dbd8e0c347dab23791ac3ec2 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 8 Aug 2015 14:14:48 +0200 Subject: [PATCH] Camera trigger: Fix param handle names, enable trigger if mode set to > 1 --- src/drivers/camera_trigger/camera_trigger.cpp | 31 ++++++++++++------- .../camera_trigger/camera_trigger_params.c | 18 ++--------- 2 files changed, 23 insertions(+), 26 deletions(-) diff --git a/src/drivers/camera_trigger/camera_trigger.cpp b/src/drivers/camera_trigger/camera_trigger.cpp index 2f04c7117a..d585e41c4a 100644 --- a/src/drivers/camera_trigger/camera_trigger.cpp +++ b/src/drivers/camera_trigger/camera_trigger.cpp @@ -108,6 +108,7 @@ private: int _gpio_fd; int _polarity; + int _mode; float _activation_time; float _interval; uint32_t _trigger_seq; @@ -117,10 +118,10 @@ private: orb_advert_t _trigger_pub; - param_t polarity; - param_t activation_time; - param_t interval; - param_t transfer_time ; + param_t _p_polarity; + param_t _p_mode; + param_t _p_activation_time; + param_t _p_interval; static constexpr uint32_t _gpios[6] = { GPIO_GPIO0_OUTPUT, @@ -161,6 +162,7 @@ CameraTrigger::CameraTrigger() : _disengagecall {}, _gpio_fd(-1), _polarity(0), + _mode(0), _activation_time(0.5f /* ms */), _interval(100.0f /* ms */), _trigger_seq(0), @@ -171,9 +173,10 @@ CameraTrigger::CameraTrigger() : memset(&_work, 0, sizeof(_work)); // Parameters - polarity = param_find("TRIG_POLARITY"); - interval = param_find("TRIG_INTERVAL"); - activation_time = param_find("TRIG_ACT_TIME"); + _p_polarity = param_find("TRIG_POLARITY"); + _p_interval = param_find("TRIG_INTERVAL"); + _p_activation_time = param_find("TRIG_ACT_TIME"); + _p_mode = param_find("TRIG_ACT_TIME"); struct camera_trigger_s trigger = {}; @@ -206,9 +209,10 @@ void CameraTrigger::start() { - param_get(polarity, &_polarity); - param_get(activation_time, &_activation_time); - param_get(interval, &_interval); + param_get(_p_polarity, &_polarity); + param_get(_p_activation_time, &_activation_time); + param_get(_p_interval, &_interval); + param_get(_p_mode, &_mode); stm32_configgpio(_gpios[_pin - 1]); @@ -223,6 +227,11 @@ CameraTrigger::start() stop(); } + // enable immediate if configured that way + if (_mode > 1) { + control(true); + } + // start to monitor at high rate for trigger enable command work_queue(LPWORK, &_work, (worker_t)&CameraTrigger::cycle_trampoline, this, USEC2TICK(1)); } @@ -266,7 +275,7 @@ CameraTrigger::cycle_trampoline(void *arg) // Set trigger rate from command if (cmd.param2 > 0) { trig->_interval = cmd.param2; - param_set(trig->interval, &(trig->_interval)); + param_set(trig->_p_interval, &(trig->_interval)); } if (cmd.param1 < 1.0f) { diff --git a/src/drivers/camera_trigger/camera_trigger_params.c b/src/drivers/camera_trigger/camera_trigger_params.c index 177844ff59..2098773992 100644 --- a/src/drivers/camera_trigger/camera_trigger_params.c +++ b/src/drivers/camera_trigger/camera_trigger_params.c @@ -41,29 +41,17 @@ #include #include -/** - * Camera trigger shutter integration time - * - * This parameter sets the time the shutter is open on the camera. - * - * @unit milliseconds - * @min 0.0 - * @max 500.0 - * @group Camera trigger - */ -PARAM_DEFINE_FLOAT(TRIG_INT_TIME, 1.0f); - /** * Camera trigger interval * * This parameter sets the time between two consecutive trigger events * * @unit milliseconds - * @min 15.0 - * @max 33.0 + * @min 4.0 + * @max 10000.0 * @group Camera trigger */ -PARAM_DEFINE_FLOAT(TRIG_INTERVAL, 15.0f); +PARAM_DEFINE_FLOAT(TRIG_INTERVAL, 40.0f); /** * Camera trigger polarity