1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2024-12-02 10:24:11 +01:00
LibrePilot/flight/modules/Actuator/actuator.c
abeck70 88494e2745 OP-1696 PathFollower rewrite in C++ and Landing Squashed commit of the following:
commit 580cd8addafadc3109b90b1fd183130ea8add7f2
Author: abeck70 <abeck70@icloud.com>
Date:   Fri Mar 20 21:32:33 2015 +1100

    OP-1696 Cleanup and bug fix

    1. Code review cleanup
    2. Fixed gps assist braking - the thrust limits in piddown were not being set.

commit 31ac4494f6e2bc5859f49d1f76f19fe3a4d32862
Author: abeck70 <abeck70@icloud.com>
Date:   Wed Mar 18 08:31:16 2015 +1100

    OP-1696 fix initialisation of down pid control parameters

commit a7bd737459249530bde9546b8247dd45b40dced4
Author: abeck70 <abeck70@icloud.com>
Date:   Tue Mar 17 21:18:38 2015 +1100

    OP-1769 Actuator fix from code review

commit 968172b8fb46c91b2611be4825e17faf2fa13411
Author: abeck70 <abeck70@icloud.com>
Date:   Tue Mar 17 21:01:11 2015 +1100

    OP-1696 fixed ground pathfollower settings xml

commit 721c07b67a87911ed67d0b62aa658cfac6d3eb97
Merge: f556215 be9f4ae
Author: abeck70 <abeck70@icloud.com>
Date:   Tue Mar 17 20:52:01 2015 +1100

    Merge branch 'next' of ssh://git.openpilot.org/OpenPilot into abeck/OP-1696

commit f556215ddbd5a29b22c2e6124372d74a0d6b9a0f
Author: abeck70 <abeck70@icloud.com>
Date:   Tue Mar 17 20:51:22 2015 +1100

    OP-1696 ground pathfollower fixes

commit 4584b22d6a2d33d3efb1cd11ac46804a5623a236
Author: abeck70 <abeck70@icloud.com>
Date:   Tue Mar 17 18:11:52 2015 +1100

    OP-1696 Ground redesign

    1. Move to new PID loop design
    2. Prototype steering control

commit b70c3373646fa758ae30a59765b8a56df7d2fbeb
Author: abeck70 <abeck70@icloud.com>
Date:   Sun Mar 15 18:42:06 2015 +1100

    OP-1696 ground pathfollower added missing call to update velocity state

commit a282bfb14dffcd486466b60be3100d26c11649ef
Author: abeck70 <abeck70@icloud.com>
Date:   Sun Mar 15 17:22:02 2015 +1100

    OP-1696 ground pathfollower improvements

commit f56ea4f9b101415e32e4464e51e087ee350be969
Author: abeck70 <abeck70@icloud.com>
Date:   Sun Mar 15 07:44:01 2015 +1100

    OP-1696 remove unused PID controller in ground for vertical

commit 6424aa0a84c3718a5a7b51fab1c9e04587d325b8
Author: abeck70 <abeck70@icloud.com>
Date:   Sat Mar 14 21:40:58 2015 +1100

    OP-1696 Initialise vtolemergencyfallback variables

commit 5d6110499bb06fe9b397e09dea5aafe994f03d13
Author: abeck70 <abeck70@icloud.com>
Date:   Sat Mar 14 21:30:21 2015 +1100

    OP-1696 vtolflycontroller segv fixed and uncrustify

commit bef23ea3dc2b5aff5b9b8713802586719b8f68cf
Author: abeck70 <abeck70@icloud.com>
Date:   Sat Mar 14 20:50:05 2015 +1100

    OP-1783 PathPlanner

    Instead of config alarm if no pathplan, simply continue to alarm pathplan, but allow normal arming and flight in other modes.  If pathplan enabled, simply enter position hold.

commit 370f1747209cca7c01c071a43224ad83b04bdd55
Author: abeck70 <abeck70@icloud.com>
Date:   Sat Mar 14 20:48:22 2015 +1100

    OP-1769 Ground code review comment

    1. Remove idx1 < 0 check not needed
    2. Should return abs_input in the corner case that curve is "invalid".

commit 01973c656d783e035ad823c267d3387bf473eebe
Merge: be07d12 5c9b6fa
Author: abeck70 <abeck70@icloud.com>
Date:   Sat Mar 14 12:17:31 2015 +1100

    Merge branch 'next' of ssh://git.openpilot.org/OpenPilot into abeck/OP-1696

commit be07d125f42b5ca1aabce0f5c0fcf592e8cddf98
Merge: 44afdc7 ad44b31
Author: abeck70 <abeck70@icloud.com>
Date:   Thu Mar 12 21:55:52 2015 +1100

    Merge branch 'next' of ssh://git.openpilot.org/OpenPilot into abeck/OP-1696

commit 44afdc77987049dc58cdf42e3be88b7eae38de02
Author: abeck70 <abeck70@icloud.com>
Date:   Thu Mar 12 19:35:55 2015 +1100

    OP-1696 fix startup

    Fix initialisation and void use of pios_malloc at startup

commit 962f5f75756883cec6726c0347310d60264f6989
Author: abeck70 <abeck70@icloud.com>
Date:   Thu Mar 12 18:48:04 2015 +1100

    OP-1696 undo changes to make file

commit 7fa71d5c614d492cb4026312672068f92a4bcd3e
Merge: 672732e 5a9cfa6
Author: abeck70 <abeck70@icloud.com>
Date:   Thu Mar 12 18:06:59 2015 +1100

    Merge branch 'next' of ssh://git.openpilot.org/OpenPilot into abeck/OP-1696

commit 672732e95d555946300ef5093f687f3fa88bfd3a
Author: abeck70 <abeck70@icloud.com>
Date:   Wed Mar 11 12:59:44 2015 +1100

    OP-1696 code review comments

commit 73b295d6515f2489b3b3a61459c975b0c37afe3d
Author: abeck70 <abeck70@icloud.com>
Date:   Wed Mar 11 12:47:24 2015 +1100

    OP-1696 code review comments

commit 524b72f537fe922bf3c4385b418872f13819a5cf
Merge: 6beef01 ba5f395
Author: abeck70 <abeck70@icloud.com>
Date:   Tue Mar 10 23:19:06 2015 +1100

    Merge branch 'next' of ssh://git.openpilot.org/OpenPilot into abeck/OP-1696

commit 6beef01476d06598652a10de4857e6ae55015417
Merge: 100cf33 8c31f96
Author: abeck70 <abeck70@icloud.com>
Date:   Sat Mar 7 16:50:32 2015 +1100

    Merge branch 'next' of ssh://git.openpilot.org/OpenPilot into abeck/OP-1696

commit 100cf335d187fe696d3678371b194fc3044a1c7e
Author: Alex Beck <abeck70@icloud.com>
Date:   Thu Mar 5 22:32:30 2015 +1100

    OP-1696 simposix c++ compilation fix

commit 9ebf846d1ec8fef30ffc1204546fc5dc648ec10b
Author: Alex Beck <abeck70@icloud.com>
Date:   Thu Mar 5 21:35:39 2015 +1100

    OP-1696 fix simposix c++ compile of pathfollower

commit a86b4b1db46dba569739587ee57b03460381ebab
Author: abeck70 <abeck70@icloud.com>
Date:   Thu Mar 5 18:03:51 2015 +1100

    OP-1696 resolve linux build issue

commit 1d7695f81293534bc17f69b0fcd9de3876867f6a
Author: abeck70 <abeck70@icloud.com>
Date:   Wed Mar 4 18:10:09 2015 +1100

    OP-1696 Return to Base & Land implemented

    Enabled via FlightModeSettings ReturnToBaseNextCommand = LAND

commit 4e5ca807b18a40ea60c05c1b46f738462595a6b2
Author: abeck70 <abeck70@icloud.com>
Date:   Wed Mar 4 16:38:06 2015 +1100

    OP-1696 reduce memory footprint by only allocating controllers required for a particular frame type

commit 78e8f559cd25ffaeac68b563e25d1ad357205fd6
Author: abeck70 <abeck70@icloud.com>
Date:   Wed Mar 4 13:51:05 2015 +1100

    OP-1696 move fsm initialisation to controller implementations

commit 848c78a84e5c7e11b2da953c9d9549b11fc5b1d8
Author: abeck70 <abeck70@icloud.com>
Date:   Wed Mar 4 13:27:11 2015 +1100

    OP-1696 reduce memory through re-use of pointers to data objects in base class.

commit bc8794601142055942910ba9f938c03c8a3ca547
Merge: 24bc3de 843325d
Author: abeck70 <abeck70@icloud.com>
Date:   Tue Mar 3 22:06:01 2015 +1100

    Merge branch 'next' of ssh://git.openpilot.org/OpenPilot into abeck/OP-1696

commit 24bc3de6155a74850b17ca7706f6b592923e027c
Author: abeck70 <abeck70@icloud.com>
Date:   Tue Mar 3 17:56:12 2015 +1100

    OP-1696 update gcs path planner options to align to new modes

commit dc659891882ea0624a6436550425c54b347f4101
Author: abeck70 <abeck70@icloud.com>
Date:   Tue Mar 3 13:51:55 2015 +1100

    OP-1696 pathfollower class renaming and uncrustify

commit af19d114b8e0ff23159bdaca37e5f5bf1c1f8beb
Merge: b07c1fd 04f4cd9
Author: abeck70 <abeck70@icloud.com>
Date:   Mon Mar 2 21:47:12 2015 +1100

    Merge branch 'rel-15.02' of ssh://git.openpilot.org/OpenPilot into abeck/OP-1696

commit b07c1fdd0544a555678bc7a8510cd92861f17e46
Author: abeck70 <abeck70@icloud.com>
Date:   Mon Mar 2 21:27:27 2015 +1100

    OP-1696 remainder of changes to integrate drive and fly objectives

commit c824c53cf30889a468ecb25ae3d705fa011b23ba
Merge: b89751c 1102243
Author: abeck70 <abeck70@icloud.com>
Date:   Mon Mar 2 17:06:13 2015 +1100

    Merge branch 'next' of ssh://git.openpilot.org/OpenPilot into abeck/OP-1696

commit b89751caa5d6dc06e1e20391aa4e12b5484056d4
Author: abeck70 <abeck70@icloud.com>
Date:   Mon Mar 2 17:04:27 2015 +1100

    OP-1696 merge fly and drive pathdesired/action objectives

commit c463132cb7da5cdf9fc5395ae0650b081bc9fb55
Author: abeck70 <abeck70@icloud.com>
Date:   Sun Mar 1 10:25:29 2015 +1100

    OP-1696 merge ground pathfollower and refactored into C++

    commit 6ed504b32f9e502e4f02d50b9e85ba91591417ba
    Merge: bcf245e deafed6
    Author: abeck70 <abeck70@icloud.com>
    Date:   Fri Feb 27 18:12:32 2015 +1100

        Merge branch 'next' into corvuscorax/OP-1642_tank-support

        Conflicts:
        	flight/modules/PathFollower/pathfollower.c
        	shared/uavobjectdefinition/vtolpathfollowersettings.xml

    commit bcf245e08c3348f2e6e5eddceee6d6cc268bdc23
    Author: Corvus Corax <corvuscorax@cybertrench.com>
    Date:   Sat Dec 6 19:45:29 2014 +0100

        OP-1642 added new uavobject to discovery target, too

    commit 6b9e8a7d7dad0739b4ffd2ce7f2f78ed4f597077
    Author: Corvus Corax <corvuscorax@cybertrench.com>
    Date:   Sat Dec 6 17:58:18 2014 +0100

        OP-1642 added very simple path control for ground vehicles

    commit e8d8440e049c06158e7fc542627fac6420abaf65
    Author: Corvus Corax <corvuscorax@cybertrench.com>
    Date:   Sat Dec 6 17:17:09 2014 +0100

        OP-1642 added new settings uavobject for tank path follower

commit 71dd726eb5b52614b417236c22e8a5cc3a487faf
Author: abeck70 <abeck70@icloud.com>
Date:   Fri Feb 27 18:05:10 2015 +1100

    OP-1696 align pathaction to pathdesired

commit 8a88af83be457aafbb63e4f94fad3b1cd54264ca
Author: abeck70 <abeck70@icloud.com>
Date:   Thu Feb 26 08:06:34 2015 +1100

    OP-1696 fixed wing control refactored and compiling

commit fd9850b5e5680f5b422dbc468a94c5ec4b6dd518
Author: abeck70 <abeck70@icloud.com>
Date:   Wed Feb 25 17:47:19 2015 +1100

    OP-1696 Removed vtol stuff from pathfollower.cpp after having replaced it with class impl

commit 9127d8d6d8c345c5bbf8622ce4e5eb76b03d1356
Merge: 4054c73 93fb2d5
Author: abeck70 <abeck70@icloud.com>
Date:   Wed Feb 25 13:09:06 2015 +1100

    Merge branch 'next' of ssh://git.openpilot.org/OpenPilot into abeck/OP-1696

commit 4054c73ac98b54188a0a5367c5ca913b7fee6a89
Author: abeck70 <abeck70@icloud.com>
Date:   Tue Feb 24 12:29:28 2015 +1100

    OP-1696 fix compile errors

commit b398db3d4de8cd621a059da1f0dbb00868be0fb9
Merge: 94c795a 3e15cac
Author: abeck70 <abeck70@icloud.com>
Date:   Tue Feb 24 12:06:35 2015 +1100

    Merge branch 'next' of ssh://git.openpilot.org/OpenPilot into abeck/OP-1696

commit 94c795af386cf0f1072a88e99a80cb1080bf85e7
Merge: d2115de 57e0a8b
Author: abeck70 <abeck70@icloud.com>
Date:   Mon Feb 23 17:54:33 2015 +1100

    Merge branch 'next' of ssh://git.openpilot.org/OpenPilot into abeck/OP-1696

    Conflicts:
    	flight/modules/Sensors/sensors.c
    	make/common-defs.mk

commit d2115dee4e8e9b6a02f7b7700e4715480a56b18f
Author: abeck70 <abeck70@icloud.com>
Date:   Mon Feb 23 14:35:02 2015 +1100

    OP-1696 preliminary checkin for refactor of fly

    TODO:
    1. Finalise and test fly, brake
    2. Remove patfhollower vtol fly
    3. Rename all objects adding vtol in name

commit 95804b1d591d194cce3596187c74cdb2dd0d192f
Merge: 58cebb0 31c1385
Author: abeck70 <abeck70@icloud.com>
Date:   Sat Feb 21 22:10:03 2015 +1100

    Merge branch 'next' of ssh://git.openpilot.org/OpenPilot into abeck/OP-1696

commit 58cebb0658deaece1555cfa24e50f1b86fd68c96
Author: abeck70 <abeck70@icloud.com>
Date:   Sat Feb 21 22:09:29 2015 +1100

    OP-1696 refactor neutral thrust and add pos hold implementation

commit 2c3cadfef3de9e092bd66bbabc58ac7847aca7e4
Author: abeck70 <abeck70@icloud.com>
Date:   Fri Feb 20 18:32:11 2015 +1100

    OP-1696 start of refactor of braking

commit 991c2124e834f3432f5e34c5c9f4966cb42a7be3
Merge: 1ab5798 db7d605
Author: abeck70 <abeck70@icloud.com>
Date:   Thu Feb 19 12:17:54 2015 +1100

    Merge branch 'next' of ssh://git.openpilot.org/OpenPilot into abeck/OP-1696

commit 1ab579865f04aeaa5899f5065a983de29074e025
Author: abeck70 <abeck70@icloud.com>
Date:   Wed Feb 18 21:29:01 2015 +1100

    OP-1696 Rewrote velocity roam into new C++ OO architecture

    With use of new PID controller for NE.

commit 03edb049f06bf60054dce36a5b8b301a397284c4
Author: abeck70 <abeck70@icloud.com>
Date:   Wed Feb 18 12:19:17 2015 +1100

    OP-1696 Start of refactoring of VelocityRoam implementation in PathFollower

    Also TODOs:
    1. To support pathplanner, remove all references to FlightStatus object and add more fields to PathDesired
    2. Refactor Braking to use C++
    3. Test and optimise Velocity Roam
    4. Add more config options to Landing. For example disable disarming. And add more setting objects.
    5. Consider moving all landing settings to one object.

commit 1f5dba821d4535a9a14f333efdeec1af5afcc281
Author: abeck70 <abeck70@icloud.com>
Date:   Mon Feb 16 22:51:31 2015 +1100

    OP-1696 Landing tuning

commit 5133956c717fba871dd5700333806e298038a3d0
Author: abeck70 <abeck70@icloud.com>
Date:   Mon Feb 16 21:05:06 2015 +1100

    OP-1696 Landing

    Multiple fixes

commit cf22055ecb8eb7304174c730f249a2332ebc599b
Author: abeck70 <abeck70@icloud.com>
Date:   Sun Feb 15 20:52:29 2015 +1100

    OP-1696 Add PIDStatus debug object

commit bc13d732601e7c7cb48db17f1a75b33cc96c0c34
Author: abeck70 <abeck70@icloud.com>
Date:   Sat Feb 14 15:53:16 2015 +1100

    OP-1696 Landing sanity tested

commit 6e913076c1dfcb8b90153e9eca8acf6c9e51f293
Author: abeck70 <abeck70@icloud.com>
Date:   Sat Feb 14 11:16:06 2015 +1100

    OP-1696 completed refactoring

    1. Completed refactoring of NE and Thrust control
    2. Fixed velocity roam

    TODO Tuning and testing

commit 63b62fbd0ac105029e54163b98c3beebc2d73c3a
Author: abeck70 <abeck70@icloud.com>
Date:   Fri Feb 13 08:54:23 2015 +1100

    OP-1696 New PID Controller and refactoring of PID implementation for thrust management

commit 7474331529477d0badd2ef0d609c84c556be9cec
Author: abeck70 <abeck70@icloud.com>
Date:   Tue Feb 10 16:39:44 2015 +1100

    OP-1696 Landing Refactor Thrust PID Loop for landing

commit 904ab2a9241e40c19da6a1508b4ce5243c75d7a3
Author: abeck70 <abeck70@icloud.com>
Date:   Mon Feb 9 22:13:39 2015 +1100

    OP-1696 Uncrustify

commit b3d30e298d8a0343782a29bc91be6677105b325e
Author: abeck70 <abeck70@icloud.com>
Date:   Mon Feb 9 22:05:05 2015 +1100

    OP-1696 Create new OO design

    Added PathFollowerControl which has an Landing implementation.  The landing implementation runs its own set of PIDs.  And interfaces to the FSM for Landing.

commit 1ffd8d67cf7310c1c18c90f3ba18b08221d185a3
Author: abeck70 <abeck70@icloud.com>
Date:   Sat Feb 7 18:04:42 2015 +1100

    OP-1696 Upgrade arm tools

commit 3df01f97021d13694027b92ba0b13cc9fe70d437
Author: abeck70 <abeck70@icloud.com>
Date:   Fri Feb 6 21:52:38 2015 +1100

    OP-1696 Landing uncrustify and start of refactoring landing to make more use of FSMLand

commit 7a753b65fb69d52c89875b9a182ef5210ee8ef2d
Author: abeck70 <abeck70@icloud.com>
Date:   Fri Feb 6 15:08:29 2015 +1100

    OP-1696 Landing: fix compilation of all exes

commit 692459874acf2b7ae07aa3ab88a2c78a09f26ee6
Author: abeck70 <abeck70@icloud.com>
Date:   Fri Feb 6 14:45:06 2015 +1100

    OP-1696 Landing startup fixes

commit 9851f29b9238a969efd0110f01a4fad6bdbc5a5d
Author: abeck70 <abeck70@icloud.com>
Date:   Fri Feb 6 10:21:52 2015 +1100

    OP-1696 Landing pathfollower CPP refactoring

commit 9b3a54d41f14f07cd0d78426026d12ae9ac4e5b5
Author: abeck70 <abeck70@icloud.com>
Date:   Wed Feb 4 13:02:44 2015 +1100

    OP-1696 Moved to FSMLand class and fixed CPP problems

    1. Additional methods, compile options, and need to have main as a cpp to solve various link issues when using static constructors but to avoid adding unnecessary libs.

commit 7ebe739bfdb4e0f598f4408c1488f01bc033c044
Author: abeck70 <abeck70@icloud.com>
Date:   Tue Feb 3 22:17:08 2015 +1100

    OP-1696 Initial Landing prototype

    Proof of concept. To be refactored into C++

commit 11d6754b9766efb76cc1cd57e9894badaf33ef2d
Author: abeck70 <abeck70@icloud.com>
Date:   Tue Feb 3 22:13:10 2015 +1100

    OP-1696 CPP Enablement

    revo c++
    Enable optional revo C++ support:
    1. Set USE_CXX to enable compliation and linkage of C++ source code
    2. Disables rtti and exceptions
    3. operator new and delete call pios malloc/free
    4. Static constructor invocation supported
2015-03-20 21:42:20 +11:00

925 lines
34 KiB
C

/**
******************************************************************************
* @addtogroup OpenPilotModules OpenPilot Modules
* @{
* @addtogroup ActuatorModule Actuator Module
* @brief Compute servo/motor settings based on @ref ActuatorDesired "desired actuator positions" and aircraft type.
* This is where all the mixing of channels is computed.
* @{
*
* @file actuator.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Actuator module. Drives the actuators (servos, motors etc).
*
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include <openpilot.h>
#include "accessorydesired.h"
#include "actuator.h"
#include "actuatorsettings.h"
#include "systemsettings.h"
#include "actuatordesired.h"
#include "actuatorcommand.h"
#include "flightstatus.h"
#include "mixersettings.h"
#include "mixerstatus.h"
#include "cameradesired.h"
#include "manualcontrolcommand.h"
#include "taskinfo.h"
#include <systemsettings.h>
#include <sanitycheck.h>
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
#include <vtolpathfollowersettings.h>
#endif
#undef PIOS_INCLUDE_INSTRUMENTATION
#ifdef PIOS_INCLUDE_INSTRUMENTATION
#include <pios_instrumentation.h>
static int8_t counter;
// Counter 0xAC700001 total Actuator body execution time(excluding queue waits etc).
#endif
// Private constants
#define MAX_QUEUE_SIZE 2
#if defined(PIOS_ACTUATOR_STACK_SIZE)
#define STACK_SIZE_BYTES PIOS_ACTUATOR_STACK_SIZE
#else
#define STACK_SIZE_BYTES 1312
#endif
#define TASK_PRIORITY (tskIDLE_PRIORITY + 4) // device driver
#define FAILSAFE_TIMEOUT_MS 100
#define MAX_MIX_ACTUATORS ACTUATORCOMMAND_CHANNEL_NUMELEM
#define CAMERA_BOOT_DELAY_MS 7000
#define ACTUATOR_ONESHOT125_CLOCK 2000000
#define ACTUATOR_ONESHOT125_PULSE_SCALE 4
#define ACTUATOR_PWM_CLOCK 1000000
// Private types
// Private variables
static xQueueHandle queue;
static xTaskHandle taskHandle;
static FrameType_t frameType = FRAME_TYPE_MULTIROTOR;
static SystemSettingsThrustControlOptions thrustType = SYSTEMSETTINGS_THRUSTCONTROL_THROTTLE;
static float lastResult[MAX_MIX_ACTUATORS] = { 0 };
static float filterAccumulator[MAX_MIX_ACTUATORS] = { 0 };
static uint8_t pinsMode[MAX_MIX_ACTUATORS];
// used to inform the actuator thread that actuator update rate is changed
static ActuatorSettingsData actuatorSettings;
static bool spinWhileArmed;
// used to inform the actuator thread that mixer settings are changed
static MixerSettingsData mixerSettings;
static int mixer_settings_count = 2;
// Private functions
static void actuatorTask(void *parameters);
static int16_t scaleChannel(float value, int16_t max, int16_t min, int16_t neutral);
static void setFailsafe();
static float MixerCurveFullRangeProportional(const float input, const float *curve, uint8_t elements);
static float MixerCurveFullRangeAbsolute(const float input, const float *curve, uint8_t elements);
static bool set_channel(uint8_t mixer_channel, uint16_t value);
static void actuator_update_rate_if_changed(bool force_update);
static void MixerSettingsUpdatedCb(UAVObjEvent *ev);
static void ActuatorSettingsUpdatedCb(UAVObjEvent *ev);
static void SettingsUpdatedCb(UAVObjEvent *ev);
float ProcessMixer(const int index, const float curve1, const float curve2,
ActuatorDesiredData *desired,
const float period);
// this structure is equivalent to the UAVObjects for one mixer.
typedef struct {
uint8_t type;
int8_t matrix[5];
} __attribute__((packed)) Mixer_t;
/**
* @brief Module initialization
* @return 0
*/
int32_t ActuatorStart()
{
// Start main task
xTaskCreate(actuatorTask, "Actuator", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_ACTUATOR, taskHandle);
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_RegisterFlag(PIOS_WDG_ACTUATOR);
#endif
SettingsUpdatedCb(NULL);
MixerSettingsUpdatedCb(NULL);
ActuatorSettingsUpdatedCb(NULL);
return 0;
}
/**
* @brief Module initialization
* @return 0
*/
int32_t ActuatorInitialize()
{
// Register for notification of changes to ActuatorSettings
ActuatorSettingsInitialize();
ActuatorSettingsConnectCallback(ActuatorSettingsUpdatedCb);
// Register for notification of changes to MixerSettings
MixerSettingsInitialize();
MixerSettingsConnectCallback(MixerSettingsUpdatedCb);
// Listen for ActuatorDesired updates (Primary input to this module)
ActuatorDesiredInitialize();
queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent));
ActuatorDesiredConnectQueue(queue);
// Register AccessoryDesired (Secondary input to this module)
AccessoryDesiredInitialize();
// Primary output of this module
ActuatorCommandInitialize();
#ifdef DIAG_MIXERSTATUS
// UAVO only used for inspecting the internal status of the mixer during debug
MixerStatusInitialize();
#endif
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
VtolPathFollowerSettingsInitialize();
VtolPathFollowerSettingsConnectCallback(&SettingsUpdatedCb);
#endif
SystemSettingsInitialize();
SystemSettingsConnectCallback(&SettingsUpdatedCb);
return 0;
}
MODULE_INITCALL(ActuatorInitialize, ActuatorStart);
/**
* @brief Main Actuator module task
*
* Universal matrix based mixer for VTOL, helis and fixed wing.
* Converts desired roll,pitch,yaw and throttle to servo/ESC outputs.
*
* Because of how the Throttle ranges from 0 to 1, the motors should too!
*
* Note this code depends on the UAVObjects for the mixers being all being the same
* and in sequence. If you change the object definition, make sure you check the code!
*
* @return -1 if error, 0 if success
*/
static void actuatorTask(__attribute__((unused)) void *parameters)
{
UAVObjEvent ev;
portTickType lastSysTime;
portTickType thisSysTime;
float dTSeconds;
uint32_t dTMilliseconds;
ActuatorCommandData command;
ActuatorDesiredData desired;
MixerStatusData mixerStatus;
FlightStatusData flightStatus;
float throttleDesired;
float collectiveDesired;
#ifdef PIOS_INCLUDE_INSTRUMENTATION
counter = PIOS_Instrumentation_CreateCounter(0xAC700001);
#endif
/* Read initial values of ActuatorSettings */
ActuatorSettingsGet(&actuatorSettings);
/* Read initial values of MixerSettings */
MixerSettingsGet(&mixerSettings);
/* Force an initial configuration of the actuator update rates */
actuator_update_rate_if_changed(true);
// Go to the neutral (failsafe) values until an ActuatorDesired update is received
setFailsafe();
// Main task loop
lastSysTime = xTaskGetTickCount();
while (1) {
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_UpdateFlag(PIOS_WDG_ACTUATOR);
#endif
// Wait until the ActuatorDesired object is updated
uint8_t rc = xQueueReceive(queue, &ev, FAILSAFE_TIMEOUT_MS / portTICK_RATE_MS);
#ifdef PIOS_INCLUDE_INSTRUMENTATION
PIOS_Instrumentation_TimeStart(counter);
#endif
if (rc != pdTRUE) {
/* Update of ActuatorDesired timed out. Go to failsafe */
setFailsafe();
continue;
}
// Check how long since last update
thisSysTime = xTaskGetTickCount();
dTMilliseconds = (thisSysTime == lastSysTime) ? 1 : (thisSysTime - lastSysTime) * portTICK_RATE_MS;
lastSysTime = thisSysTime;
dTSeconds = dTMilliseconds * 0.001f;
FlightStatusGet(&flightStatus);
ActuatorDesiredGet(&desired);
ActuatorCommandGet(&command);
// read in throttle and collective -demultiplex thrust
switch (thrustType) {
case SYSTEMSETTINGS_THRUSTCONTROL_THROTTLE:
throttleDesired = desired.Thrust;
ManualControlCommandCollectiveGet(&collectiveDesired);
break;
case SYSTEMSETTINGS_THRUSTCONTROL_COLLECTIVE:
ManualControlCommandThrottleGet(&throttleDesired);
collectiveDesired = desired.Thrust;
break;
default:
ManualControlCommandThrottleGet(&throttleDesired);
ManualControlCommandCollectiveGet(&collectiveDesired);
}
bool armed = flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED;
bool activeThrottle = (throttleDesired < -0.001f || throttleDesired > 0.001f); // for ground and reversible motors
bool positiveThrottle = (throttleDesired > 0.00f);
// safety settings
if (!armed) {
throttleDesired = 0;
}
if ((frameType == FRAME_TYPE_GROUND && !activeThrottle) || (frameType != FRAME_TYPE_GROUND && throttleDesired <= 0.00f) || !armed) {
// force set all other controls to zero if throttle is cut (previously set in Stabilization)
if (actuatorSettings.LowThrottleZeroAxis.Roll == ACTUATORSETTINGS_LOWTHROTTLEZEROAXIS_TRUE) {
desired.Roll = 0;
}
if (actuatorSettings.LowThrottleZeroAxis.Pitch == ACTUATORSETTINGS_LOWTHROTTLEZEROAXIS_TRUE) {
desired.Pitch = 0;
}
if (actuatorSettings.LowThrottleZeroAxis.Yaw == ACTUATORSETTINGS_LOWTHROTTLEZEROAXIS_TRUE) {
desired.Yaw = 0;
}
}
#ifdef DIAG_MIXERSTATUS
MixerStatusGet(&mixerStatus);
#endif
if ((mixer_settings_count < 2) && !ActuatorCommandReadOnly()) { // Nothing can fly with less than two mixers.
setFailsafe();
continue;
}
AlarmsClear(SYSTEMALARMS_ALARM_ACTUATOR);
float curve1 = 0.0f;
float curve2 = 0.0f;
// Interpolate curve 1 from throttleDesired as input.
// assume reversible motor/mixer initially. We can later reverse this. The difference is simply that -ve throttleDesired values
// map differently
curve1 = MixerCurveFullRangeProportional(throttleDesired, mixerSettings.ThrottleCurve1, MIXERSETTINGS_THROTTLECURVE1_NUMELEM);
// The source for the secondary curve is selectable
AccessoryDesiredData accessory;
uint8_t curve2Source = mixerSettings.Curve2Source;
switch (curve2Source) {
case MIXERSETTINGS_CURVE2SOURCE_THROTTLE:
// assume reversible motor/mixer initially
curve2 = MixerCurveFullRangeProportional(throttleDesired, mixerSettings.ThrottleCurve2, MIXERSETTINGS_THROTTLECURVE2_NUMELEM);
break;
case MIXERSETTINGS_CURVE2SOURCE_ROLL:
// Throttle curve contribution the same for +ve vs -ve roll
curve2 = MixerCurveFullRangeAbsolute(desired.Roll, mixerSettings.ThrottleCurve2, MIXERSETTINGS_THROTTLECURVE2_NUMELEM);
break;
case MIXERSETTINGS_CURVE2SOURCE_PITCH:
// Throttle curve contribution the same for +ve vs -ve pitch
curve2 = MixerCurveFullRangeAbsolute(desired.Pitch, mixerSettings.ThrottleCurve2,
MIXERSETTINGS_THROTTLECURVE2_NUMELEM);
break;
case MIXERSETTINGS_CURVE2SOURCE_YAW:
// Throttle curve contribution the same for +ve vs -ve yaw
curve2 = MixerCurveFullRangeAbsolute(desired.Yaw, mixerSettings.ThrottleCurve2, MIXERSETTINGS_THROTTLECURVE2_NUMELEM);
break;
case MIXERSETTINGS_CURVE2SOURCE_COLLECTIVE:
// assume reversible motor/mixer initially
curve2 = MixerCurveFullRangeProportional(collectiveDesired, mixerSettings.ThrottleCurve2,
MIXERSETTINGS_THROTTLECURVE2_NUMELEM);
break;
case MIXERSETTINGS_CURVE2SOURCE_ACCESSORY0:
case MIXERSETTINGS_CURVE2SOURCE_ACCESSORY1:
case MIXERSETTINGS_CURVE2SOURCE_ACCESSORY2:
case MIXERSETTINGS_CURVE2SOURCE_ACCESSORY3:
case MIXERSETTINGS_CURVE2SOURCE_ACCESSORY4:
case MIXERSETTINGS_CURVE2SOURCE_ACCESSORY5:
if (AccessoryDesiredInstGet(mixerSettings.Curve2Source - MIXERSETTINGS_CURVE2SOURCE_ACCESSORY0, &accessory) == 0) {
// Throttle curve contribution the same for +ve vs -ve accessory....maybe not want we want.
curve2 = MixerCurveFullRangeAbsolute(accessory.AccessoryVal, mixerSettings.ThrottleCurve2, MIXERSETTINGS_THROTTLECURVE2_NUMELEM);
} else {
curve2 = 0.0f;
}
break;
default:
curve2 = 0.0f;
break;
}
float *status = (float *)&mixerStatus; // access status objects as an array of floats
Mixer_t *mixers = (Mixer_t *)&mixerSettings.Mixer1Type;
for (int ct = 0; ct < MAX_MIX_ACTUATORS; ct++) {
// During boot all camera actuators should be completely disabled (PWM pulse = 0).
// command.Channel[i] is reused below as a channel PWM activity flag:
// 0 - PWM disabled, >0 - PWM set to real mixer value using scaleChannel() later.
// Setting it to 1 by default means "Rescale this channel and enable PWM on its output".
command.Channel[ct] = 1;
uint8_t mixer_type = mixers[ct].type;
if (mixer_type == MIXERSETTINGS_MIXER1TYPE_DISABLED) {
// Set to minimum if disabled. This is not the same as saying PWM pulse = 0 us
status[ct] = -1;
continue;
}
if ((mixer_type == MIXERSETTINGS_MIXER1TYPE_MOTOR)) {
float nonreversible_curve1 = curve1;
float nonreversible_curve2 = curve2;
if (nonreversible_curve1 < 0.0f) {
nonreversible_curve1 = 0.0f;
}
if (nonreversible_curve2 < 0.0f) {
nonreversible_curve2 = 0.0f;
}
status[ct] = ProcessMixer(ct, nonreversible_curve1, nonreversible_curve2, &desired, dTSeconds);
// If not armed or motors aren't meant to spin all the time
if (!armed ||
(!spinWhileArmed && !positiveThrottle)) {
filterAccumulator[ct] = 0;
lastResult[ct] = 0;
status[ct] = -1; // force min throttle
}
// If armed meant to keep spinning,
else if ((spinWhileArmed && !positiveThrottle) ||
(status[ct] < 0)) {
status[ct] = 0;
}
} else if (mixer_type == MIXERSETTINGS_MIXER1TYPE_REVERSABLEMOTOR) {
status[ct] = ProcessMixer(ct, curve1, curve2, &desired, dTSeconds);
// Reversable Motors are like Motors but go to neutral instead of minimum
// If not armed or motor is inactive - no "spinwhilearmed" for this engine type
if (!armed || !activeThrottle) {
filterAccumulator[ct] = 0;
lastResult[ct] = 0;
status[ct] = 0; // force neutral throttle
}
} else if (mixer_type == MIXERSETTINGS_MIXER1TYPE_SERVO) {
status[ct] = ProcessMixer(ct, curve1, curve2, &desired, dTSeconds);
} else {
status[ct] = -1;
// If an accessory channel is selected for direct bypass mode
// In this configuration the accessory channel is scaled and mapped
// directly to output. Note: THERE IS NO SAFETY CHECK HERE FOR ARMING
// these also will not be updated in failsafe mode. I'm not sure what
// the correct behavior is since it seems domain specific. I don't love
// this code
if ((mixer_type >= MIXERSETTINGS_MIXER1TYPE_ACCESSORY0) &&
(mixer_type <= MIXERSETTINGS_MIXER1TYPE_ACCESSORY5)) {
if (AccessoryDesiredInstGet(mixer_type - MIXERSETTINGS_MIXER1TYPE_ACCESSORY0, &accessory) == 0) {
status[ct] = accessory.AccessoryVal;
} else {
status[ct] = -1;
}
}
if ((mixer_type >= MIXERSETTINGS_MIXER1TYPE_CAMERAROLLORSERVO1) &&
(mixer_type <= MIXERSETTINGS_MIXER1TYPE_CAMERAYAW)) {
CameraDesiredData cameraDesired;
if (CameraDesiredGet(&cameraDesired) == 0) {
switch (mixer_type) {
case MIXERSETTINGS_MIXER1TYPE_CAMERAROLLORSERVO1:
status[ct] = cameraDesired.RollOrServo1;
break;
case MIXERSETTINGS_MIXER1TYPE_CAMERAPITCHORSERVO2:
status[ct] = cameraDesired.PitchOrServo2;
break;
case MIXERSETTINGS_MIXER1TYPE_CAMERAYAW:
status[ct] = cameraDesired.Yaw;
break;
default:
break;
}
} else {
status[ct] = -1;
}
// Disable camera actuators for CAMERA_BOOT_DELAY_MS after boot
if (thisSysTime < (CAMERA_BOOT_DELAY_MS / portTICK_RATE_MS)) {
command.Channel[ct] = 0;
}
}
}
}
// Set real actuator output values scaling them from mixers. All channels
// will be set except explicitly disabled (which will have PWM pulse = 0).
for (int i = 0; i < MAX_MIX_ACTUATORS; i++) {
if (command.Channel[i]) {
command.Channel[i] = scaleChannel(status[i],
actuatorSettings.ChannelMax[i],
actuatorSettings.ChannelMin[i],
actuatorSettings.ChannelNeutral[i]);
}
}
// Store update time
command.UpdateTime = dTMilliseconds;
if (command.UpdateTime > command.MaxUpdateTime) {
command.MaxUpdateTime = command.UpdateTime;
}
// Update output object
ActuatorCommandSet(&command);
// Update in case read only (eg. during servo configuration)
ActuatorCommandGet(&command);
#ifdef DIAG_MIXERSTATUS
MixerStatusSet(&mixerStatus);
#endif
// Update servo outputs
bool success = true;
for (int n = 0; n < ACTUATORCOMMAND_CHANNEL_NUMELEM; ++n) {
success &= set_channel(n, command.Channel[n]);
}
PIOS_Servo_Update();
if (!success) {
command.NumFailedUpdates++;
ActuatorCommandSet(&command);
AlarmsSet(SYSTEMALARMS_ALARM_ACTUATOR, SYSTEMALARMS_ALARM_CRITICAL);
}
#ifdef PIOS_INCLUDE_INSTRUMENTATION
PIOS_Instrumentation_TimeEnd(counter);
#endif
}
}
/**
* Process mixing for one actuator
*/
float ProcessMixer(const int index, const float curve1, const float curve2,
ActuatorDesiredData *desired, const float period)
{
static float lastFilteredResult[MAX_MIX_ACTUATORS];
const Mixer_t *mixers = (Mixer_t *)&mixerSettings.Mixer1Type; // pointer to array of mixers in UAVObjects
const Mixer_t *mixer = &mixers[index];
float result = ((((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_THROTTLECURVE1]) * curve1) +
(((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_THROTTLECURVE2]) * curve2) +
(((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_ROLL]) * desired->Roll) +
(((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_PITCH]) * desired->Pitch) +
(((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_YAW]) * desired->Yaw)) / 128.0f;
// note: no feedforward for reversable motors yet for safety reasons
if (mixer->type == MIXERSETTINGS_MIXER1TYPE_MOTOR) {
if (result < 0.0f) { // idle throttle
result = 0.0f;
}
// feed forward
float accumulator = filterAccumulator[index];
accumulator += (result - lastResult[index]) * mixerSettings.FeedForward;
lastResult[index] = result;
result += accumulator;
if (period > 0.0f) {
if (accumulator > 0.0f) {
float invFilter = period / mixerSettings.AccelTime;
if (invFilter > 1) {
invFilter = 1;
}
accumulator -= accumulator * invFilter;
} else {
float invFilter = period / mixerSettings.DecelTime;
if (invFilter > 1) {
invFilter = 1;
}
accumulator -= accumulator * invFilter;
}
}
filterAccumulator[index] = accumulator;
result += accumulator;
// acceleration limit
float dt = result - lastFilteredResult[index];
float maxDt = mixerSettings.MaxAccel * period;
if (dt > maxDt) { // we are accelerating too hard
result = lastFilteredResult[index] + maxDt;
}
lastFilteredResult[index] = result;
}
return result;
}
/**
* Interpolate a throttle curve
* Full range input (-1 to 1) for yaw, roll, pitch
* Output range (-1 to 1) reversible motor/throttle curve
*
* Input of -1 -> -lookup(1)
* Input of 0 -> lookup(0)
* Input of 1 -> lookup(1)
*/
static float MixerCurveFullRangeProportional(const float input, const float *curve, uint8_t elements)
{
float unsigned_value = MixerCurveFullRangeAbsolute(input, curve, elements);
if (input < 0.0f) {
return -unsigned_value;
} else {
return unsigned_value;
}
}
/**
* Interpolate a throttle curve
* Full range input (-1 to 1) for yaw, roll, pitch
* Output range (0 to 1) non-reversible motor/throttle curve
*
* Input of -1 -> lookup(1)
* Input of 0 -> lookup(0)
* Input of 1 -> lookup(1)
*/
static float MixerCurveFullRangeAbsolute(const float input, const float *curve, uint8_t elements)
{
float abs_input = fabsf(input);
float scale = abs_input * (float)(elements - 1);
int idx1 = scale;
scale -= (float)idx1; // remainder
if (curve[0] < -1) {
return abs_input;
}
int idx2 = idx1 + 1;
if (idx2 >= elements) {
idx2 = elements - 1; // clamp to highest entry in table
if (idx1 >= elements) {
idx1 = elements - 1;
}
}
float unsigned_value = curve[idx1] * (1.0f - scale) + curve[idx2] * scale;
return unsigned_value;
}
/**
* Convert channel from -1/+1 to servo pulse duration in microseconds
*/
static int16_t scaleChannel(float value, int16_t max, int16_t min, int16_t neutral)
{
int16_t valueScaled;
// Scale
if (value >= 0.0f) {
valueScaled = (int16_t)(value * ((float)(max - neutral))) + neutral;
} else {
valueScaled = (int16_t)(value * ((float)(neutral - min))) + neutral;
}
if (max > min) {
if (valueScaled > max) {
valueScaled = max;
}
if (valueScaled < min) {
valueScaled = min;
}
} else {
if (valueScaled < max) {
valueScaled = max;
}
if (valueScaled > min) {
valueScaled = min;
}
}
return valueScaled;
}
/**
* Set actuator output to the neutral values (failsafe)
*/
static void setFailsafe()
{
/* grab only the parts that we are going to use */
int16_t Channel[ACTUATORCOMMAND_CHANNEL_NUMELEM];
ActuatorCommandChannelGet(Channel);
const Mixer_t *mixers = (Mixer_t *)&mixerSettings.Mixer1Type; // pointer to array of mixers in UAVObjects
// Reset ActuatorCommand to safe values
for (int n = 0; n < ACTUATORCOMMAND_CHANNEL_NUMELEM; ++n) {
if (mixers[n].type == MIXERSETTINGS_MIXER1TYPE_MOTOR) {
Channel[n] = actuatorSettings.ChannelMin[n];
} else if (mixers[n].type == MIXERSETTINGS_MIXER1TYPE_SERVO || mixers[n].type == MIXERSETTINGS_MIXER1TYPE_REVERSABLEMOTOR) {
// reversible motors need calibration wizard that allows channel neutral to be the 0 velocity point
Channel[n] = actuatorSettings.ChannelNeutral[n];
} else {
Channel[n] = 0;
}
}
// Set alarm
AlarmsSet(SYSTEMALARMS_ALARM_ACTUATOR, SYSTEMALARMS_ALARM_CRITICAL);
// Update servo outputs
for (int n = 0; n < ACTUATORCOMMAND_CHANNEL_NUMELEM; ++n) {
set_channel(n, Channel[n]);
}
// Send the updated command
PIOS_Servo_Update();
// Update output object's parts that we changed
ActuatorCommandChannelSet(Channel);
}
/**
* determine buzzer or blink sequence
**/
typedef enum { BUZZ_BUZZER = 0, BUZZ_ARMING = 1, BUZZ_INFO = 2, BUZZ_MAX = 3 } buzzertype;
static inline bool buzzerState(buzzertype type)
{
// This is for buzzers that take a PWM input
static uint32_t tune[BUZZ_MAX] = { 0 };
static uint32_t tunestate[BUZZ_MAX] = { 0 };
uint32_t newTune = 0;
if (type == BUZZ_BUZZER) {
// Decide what tune to play
if (AlarmsGet(SYSTEMALARMS_ALARM_BATTERY) > SYSTEMALARMS_ALARM_WARNING) {
newTune = 0b11110110110000; // pause, short, short, short, long
} else if (AlarmsGet(SYSTEMALARMS_ALARM_GPS) >= SYSTEMALARMS_ALARM_WARNING) {
newTune = 0x80000000; // pause, short
} else {
newTune = 0;
}
} else { // BUZZ_ARMING || BUZZ_INFO
uint8_t arming;
FlightStatusArmedGet(&arming);
// base idle tune
newTune = 0x80000000; // 0b1000...
// Merge the error pattern for InfoLed
if (type == BUZZ_INFO) {
if (AlarmsGet(SYSTEMALARMS_ALARM_BATTERY) > SYSTEMALARMS_ALARM_WARNING) {
newTune |= 0b00000000001111111011111110000000;
} else if (AlarmsGet(SYSTEMALARMS_ALARM_GPS) >= SYSTEMALARMS_ALARM_WARNING) {
newTune |= 0b00000000000000110110110000000000;
}
}
// fast double blink pattern if armed
if (arming == FLIGHTSTATUS_ARMED_ARMED) {
newTune |= 0xA0000000; // 0b101000...
}
}
// Do we need to change tune?
if (newTune != tune[type]) {
tune[type] = newTune;
// resynchronize all tunes on change, so they stay in sync
for (int i = 0; i < BUZZ_MAX; i++) {
tunestate[i] = tune[i];
}
}
// Play tune
bool buzzOn = false;
static portTickType lastSysTime = 0;
portTickType thisSysTime = xTaskGetTickCount();
portTickType dT = 0;
// For now, only look at the battery alarm, because functions like AlarmsHasCritical() can block for some time; to be discussed
if (tune[type]) {
if (thisSysTime > lastSysTime) {
dT = thisSysTime - lastSysTime;
} else {
lastSysTime = 0; // avoid the case where SysTimeMax-lastSysTime <80
}
buzzOn = (tunestate[type] & 1);
if (dT > 80) {
// Go to next bit in alarm_seq_state
for (int i = 0; i < BUZZ_MAX; i++) {
tunestate[i] >>= 1;
if (tunestate[i] == 0) { // All done, re-start the tune
tunestate[i] = tune[i];
}
}
lastSysTime = thisSysTime;
}
}
return buzzOn;
}
#if defined(ARCH_POSIX) || defined(ARCH_WIN32)
static bool set_channel(uint8_t mixer_channel, uint16_t value)
{
return true;
}
#else
static bool set_channel(uint8_t mixer_channel, uint16_t value)
{
switch (actuatorSettings.ChannelType[mixer_channel]) {
case ACTUATORSETTINGS_CHANNELTYPE_PWMALARMBUZZER:
PIOS_Servo_Set(actuatorSettings.ChannelAddr[mixer_channel],
buzzerState(BUZZ_BUZZER) ? actuatorSettings.ChannelMax[mixer_channel] : actuatorSettings.ChannelMin[mixer_channel]);
return true;
case ACTUATORSETTINGS_CHANNELTYPE_ARMINGLED:
PIOS_Servo_Set(actuatorSettings.ChannelAddr[mixer_channel],
buzzerState(BUZZ_ARMING) ? actuatorSettings.ChannelMax[mixer_channel] : actuatorSettings.ChannelMin[mixer_channel]);
return true;
case ACTUATORSETTINGS_CHANNELTYPE_INFOLED:
PIOS_Servo_Set(actuatorSettings.ChannelAddr[mixer_channel],
buzzerState(BUZZ_INFO) ? actuatorSettings.ChannelMax[mixer_channel] : actuatorSettings.ChannelMin[mixer_channel]);
return true;
case ACTUATORSETTINGS_CHANNELTYPE_PWM:
{
uint8_t mode = pinsMode[actuatorSettings.ChannelAddr[mixer_channel]];
switch (mode) {
case ACTUATORSETTINGS_BANKMODE_ONESHOT125:
// Remap 1000-2000 range to 125-250
PIOS_Servo_Set(actuatorSettings.ChannelAddr[mixer_channel], value / ACTUATOR_ONESHOT125_PULSE_SCALE);
break;
default:
PIOS_Servo_Set(actuatorSettings.ChannelAddr[mixer_channel], value);
break;
}
return true;
}
#if defined(PIOS_INCLUDE_I2C_ESC)
case ACTUATORSETTINGS_CHANNELTYPE_MK:
return PIOS_SetMKSpeed(actuatorSettings->ChannelAddr[mixer_channel], value);
case ACTUATORSETTINGS_CHANNELTYPE_ASTEC4:
return PIOS_SetAstec4Speed(actuatorSettings->ChannelAddr[mixer_channel], value);
#endif
default:
return false;
}
return false;
}
#endif /* if defined(ARCH_POSIX) || defined(ARCH_WIN32) */
/**
* @brief Update the servo update rate
*/
static void actuator_update_rate_if_changed(bool force_update)
{
static uint16_t prevBankUpdateFreq[ACTUATORSETTINGS_BANKUPDATEFREQ_NUMELEM];
static uint8_t prevBankMode[ACTUATORSETTINGS_BANKMODE_NUMELEM];
bool updateMode = force_update || (memcmp(prevBankMode, actuatorSettings.BankMode, sizeof(prevBankMode)) != 0);
bool updateFreq = force_update || (memcmp(prevBankUpdateFreq, actuatorSettings.BankUpdateFreq, sizeof(prevBankUpdateFreq)) != 0);
// check if any setting is changed
if (updateMode || updateFreq) {
/* Something has changed, apply the settings to HW */
uint16_t freq[ACTUATORSETTINGS_BANKUPDATEFREQ_NUMELEM];
uint32_t clock[ACTUATORSETTINGS_BANKUPDATEFREQ_NUMELEM] = { 0 };
for (uint8_t i = 0; i < ACTUATORSETTINGS_BANKMODE_NUMELEM; i++) {
if (force_update || (actuatorSettings.BankMode[i] != prevBankMode[i])) {
PIOS_Servo_SetBankMode(i,
actuatorSettings.BankMode[i] ==
ACTUATORSETTINGS_BANKMODE_PWM ?
PIOS_SERVO_BANK_MODE_PWM :
PIOS_SERVO_BANK_MODE_SINGLE_PULSE
);
}
switch (actuatorSettings.BankMode[i]) {
case ACTUATORSETTINGS_BANKMODE_ONESHOT125:
freq[i] = 100; // Value must be small enough so CCr isn't update until the PIOS_Servo_Update is triggered
clock[i] = ACTUATOR_ONESHOT125_CLOCK; // Setup an 2MHz timer clock
break;
case ACTUATORSETTINGS_BANKMODE_PWMSYNC:
freq[i] = 100;
clock[i] = ACTUATOR_PWM_CLOCK;
break;
default: // PWM
freq[i] = actuatorSettings.BankUpdateFreq[i];
clock[i] = ACTUATOR_PWM_CLOCK;
break;
}
}
memcpy(prevBankMode,
actuatorSettings.BankMode,
sizeof(prevBankMode));
PIOS_Servo_SetHz(freq, clock, ACTUATORSETTINGS_BANKUPDATEFREQ_NUMELEM);
memcpy(prevBankUpdateFreq,
actuatorSettings.BankUpdateFreq,
sizeof(prevBankUpdateFreq));
// retrieve mode from related bank
for (uint8_t i = 0; i < MAX_MIX_ACTUATORS; i++) {
uint8_t bank = PIOS_Servo_GetPinBank(i);
pinsMode[i] = actuatorSettings.BankMode[bank];
}
}
}
static void ActuatorSettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
{
ActuatorSettingsGet(&actuatorSettings);
spinWhileArmed = actuatorSettings.MotorsSpinWhileArmed == ACTUATORSETTINGS_MOTORSSPINWHILEARMED_TRUE;
if (frameType == FRAME_TYPE_GROUND) {
spinWhileArmed = false;
}
actuator_update_rate_if_changed(false);
}
static void MixerSettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
{
MixerSettingsGet(&mixerSettings);
mixer_settings_count = 0;
Mixer_t *mixers = (Mixer_t *)&mixerSettings.Mixer1Type;
for (int ct = 0; ct < MAX_MIX_ACTUATORS; ct++) {
if (mixers[ct].type != MIXERSETTINGS_MIXER1TYPE_DISABLED) {
mixer_settings_count++;
}
}
}
static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
{
frameType = GetCurrentFrameType();
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
uint8_t TreatCustomCraftAs;
VtolPathFollowerSettingsTreatCustomCraftAsGet(&TreatCustomCraftAs);
if (frameType == FRAME_TYPE_CUSTOM) {
switch (TreatCustomCraftAs) {
case VTOLPATHFOLLOWERSETTINGS_TREATCUSTOMCRAFTAS_FIXEDWING:
frameType = FRAME_TYPE_FIXED_WING;
break;
case VTOLPATHFOLLOWERSETTINGS_TREATCUSTOMCRAFTAS_VTOL:
frameType = FRAME_TYPE_MULTIROTOR;
break;
case VTOLPATHFOLLOWERSETTINGS_TREATCUSTOMCRAFTAS_GROUND:
frameType = FRAME_TYPE_GROUND;
break;
}
}
#endif
SystemSettingsThrustControlGet(&thrustType);
}
/**
* @}
* @}
*/