From d0c59ffe54dfffdef750684f5d8de09b83135862 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 28 Aug 2013 11:14:22 +0200 Subject: First stab at actual controller --- src/lib/ecl/attitude_fw/ecl_roll_controller.cpp | 11 +++++++ src/lib/ecl/attitude_fw/ecl_roll_controller.h | 4 ++- src/lib/ecl/ecl.h | 43 +++++++++++++++++++++++++ 3 files changed, 57 insertions(+), 1 deletion(-) create mode 100644 src/lib/ecl/ecl.h (limited to 'src/lib') diff --git a/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp b/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp index 2f8129e82..b28ecdabe 100644 --- a/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp +++ b/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp @@ -37,10 +37,12 @@ * */ +#include "../ecl.h" #include "ecl_roll_controller.h" ECL_RollController::ECL_RollController() : _last_run(0), + _tc(0.1f), _last_output(0.0f), _integrator(0.0f), _rate_error(0.0f), @@ -52,6 +54,15 @@ ECL_RollController::ECL_RollController() : float ECL_RollController::control(float roll_setpoint, float roll, float roll_rate, float scaler, bool lock_integrator, float airspeed_min, float airspeed_max, float aspeed) { + /* get the usual dt estimate */ + uint64_t dt_micros = ecl_elapsed_time(&_last_run); + _last_run = ecl_absolute_time(); + + float dt = (dt_micros > 500000) ? 0.0f : dt_micros / 1000000; + + + + return 0.0f; } diff --git a/src/lib/ecl/attitude_fw/ecl_roll_controller.h b/src/lib/ecl/attitude_fw/ecl_roll_controller.h index d2b796131..bba9ae163 100644 --- a/src/lib/ecl/attitude_fw/ecl_roll_controller.h +++ b/src/lib/ecl/attitude_fw/ecl_roll_controller.h @@ -54,7 +54,9 @@ public: void reset_integrator(); void set_time_constant(float time_constant) { - _tc = time_constant; + if (time_constant > 0.1f && time_constant < 3.0f) { + _tc = time_constant; + } } void set_k_p(float k_p) { _k_p = k_p; diff --git a/src/lib/ecl/ecl.h b/src/lib/ecl/ecl.h new file mode 100644 index 000000000..2bd76ce97 --- /dev/null +++ b/src/lib/ecl/ecl.h @@ -0,0 +1,43 @@ +/**************************************************************************** + * + * Copyright (c) 2013 Estimation and Control Library (ECL). 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 APL 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 ecl.h + * Adapter / shim layer for system calls needed by ECL + * + */ + +#include + +#define ecl_absolute_time hrt_absolute_time +#define ecl_elapsed_time hrt_elapsed_time \ No newline at end of file -- cgit v1.2.3