most functionality to splashdwon, find neutral and start mission. short timeouts still in code for testing, will adjust to go directly to sit_idle after splashdown
Dependencies: mbed MODSERIAL FATFileSystem
OuterLoop/OuterLoop.hpp@92:52a91656458a, 2019-05-13 (annotated)
- Committer:
- joel_ssc
- Date:
- Mon May 13 19:25:26 2019 +0000
- Revision:
- 92:52a91656458a
- Parent:
- 73:f6f378311c8d
version for first flight test, timeouts not yet set correctly
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
tnhnrl | 62:d502889e74f1 | 1 | #ifndef OUTERLOOP_HPP |
tnhnrl | 62:d502889e74f1 | 2 | #define OUTERLOOP_HPP |
tnhnrl | 62:d502889e74f1 | 3 | |
tnhnrl | 62:d502889e74f1 | 4 | #include "mbed.h" |
tnhnrl | 62:d502889e74f1 | 5 | #include "PidController.hpp" |
tnhnrl | 62:d502889e74f1 | 6 | #include "PosVelFilter.hpp" |
tnhnrl | 62:d502889e74f1 | 7 | |
tnhnrl | 62:d502889e74f1 | 8 | // This class is an outer loop controller with its own instance of a position velocity filter. |
tnhnrl | 62:d502889e74f1 | 9 | |
tnhnrl | 62:d502889e74f1 | 10 | class OuterLoop { |
tnhnrl | 62:d502889e74f1 | 11 | public: |
tnhnrl | 62:d502889e74f1 | 12 | OuterLoop(float interval, int sensor); |
tnhnrl | 62:d502889e74f1 | 13 | |
tnhnrl | 62:d502889e74f1 | 14 | // functions for setting up |
tnhnrl | 62:d502889e74f1 | 15 | void init(); |
tnhnrl | 62:d502889e74f1 | 16 | void update(); |
tnhnrl | 62:d502889e74f1 | 17 | void start(); |
tnhnrl | 62:d502889e74f1 | 18 | void stop(); |
tnhnrl | 62:d502889e74f1 | 19 | |
tnhnrl | 62:d502889e74f1 | 20 | void runOuterLoop(); |
tnhnrl | 62:d502889e74f1 | 21 | |
tnhnrl | 62:d502889e74f1 | 22 | // setting and getting variables |
tnhnrl | 62:d502889e74f1 | 23 | void setCommand(float cmd); |
tnhnrl | 62:d502889e74f1 | 24 | float getCommand(); |
tnhnrl | 62:d502889e74f1 | 25 | |
tnhnrl | 62:d502889e74f1 | 26 | float getOutput(); |
tnhnrl | 62:d502889e74f1 | 27 | |
tnhnrl | 62:d502889e74f1 | 28 | float getPosition(); |
tnhnrl | 62:d502889e74f1 | 29 | float getVelocity(); |
tnhnrl | 62:d502889e74f1 | 30 | |
tnhnrl | 62:d502889e74f1 | 31 | void setControllerP(float P); |
tnhnrl | 62:d502889e74f1 | 32 | float getControllerP(); |
tnhnrl | 62:d502889e74f1 | 33 | |
tnhnrl | 62:d502889e74f1 | 34 | void setControllerI(float I); |
tnhnrl | 62:d502889e74f1 | 35 | float getControllerI(); |
tnhnrl | 62:d502889e74f1 | 36 | |
tnhnrl | 62:d502889e74f1 | 37 | void setControllerD(float D); |
tnhnrl | 62:d502889e74f1 | 38 | float getControllerD(); |
tnhnrl | 62:d502889e74f1 | 39 | |
tnhnrl | 62:d502889e74f1 | 40 | void setTravelLimit(float limit); |
tnhnrl | 62:d502889e74f1 | 41 | float getTravelLimit(); |
tnhnrl | 62:d502889e74f1 | 42 | |
tnhnrl | 62:d502889e74f1 | 43 | void setFilterFrequency(float frequency); |
tnhnrl | 73:f6f378311c8d | 44 | float getFilterFrequency(); |
tnhnrl | 62:d502889e74f1 | 45 | |
tnhnrl | 62:d502889e74f1 | 46 | void setDeadband(float deadband); |
tnhnrl | 62:d502889e74f1 | 47 | float getDeadband(); |
tnhnrl | 62:d502889e74f1 | 48 | bool toggleDeadband(bool toggle); |
tnhnrl | 62:d502889e74f1 | 49 | |
tnhnrl | 62:d502889e74f1 | 50 | void setOutputOffset(float offset); |
tnhnrl | 62:d502889e74f1 | 51 | float getOutputOffset(); |
tnhnrl | 62:d502889e74f1 | 52 | |
tnhnrl | 62:d502889e74f1 | 53 | void setIHiLimit (float limit); // TZY, 3/1/18 Set saturation limit on controller integral |
tnhnrl | 62:d502889e74f1 | 54 | void setILoLimit (float limit); // TZY, 3/1/18 Set saturation limit on controller integral |
tnhnrl | 62:d502889e74f1 | 55 | |
tnhnrl | 62:d502889e74f1 | 56 | protected: |
tnhnrl | 62:d502889e74f1 | 57 | PosVelFilter _filter; |
tnhnrl | 62:d502889e74f1 | 58 | PIDController _pid; |
tnhnrl | 62:d502889e74f1 | 59 | Ticker _pulse; |
tnhnrl | 62:d502889e74f1 | 60 | |
tnhnrl | 62:d502889e74f1 | 61 | void refreshPVState(); |
tnhnrl | 62:d502889e74f1 | 62 | |
tnhnrl | 62:d502889e74f1 | 63 | float _SetPoint; |
tnhnrl | 62:d502889e74f1 | 64 | float _sensorVal; |
tnhnrl | 62:d502889e74f1 | 65 | |
tnhnrl | 62:d502889e74f1 | 66 | // position and velocity in raw units |
tnhnrl | 62:d502889e74f1 | 67 | float _position; |
tnhnrl | 62:d502889e74f1 | 68 | float _velocity; |
tnhnrl | 62:d502889e74f1 | 69 | |
tnhnrl | 62:d502889e74f1 | 70 | // setup parameters |
tnhnrl | 62:d502889e74f1 | 71 | float _Pgain; |
tnhnrl | 62:d502889e74f1 | 72 | float _Igain; |
tnhnrl | 62:d502889e74f1 | 73 | float _Dgain; |
tnhnrl | 62:d502889e74f1 | 74 | float _dt; |
tnhnrl | 62:d502889e74f1 | 75 | float _filterFrequency; |
tnhnrl | 62:d502889e74f1 | 76 | float _deadband; |
tnhnrl | 62:d502889e74f1 | 77 | char _sensor; |
tnhnrl | 62:d502889e74f1 | 78 | float _offset; |
tnhnrl | 62:d502889e74f1 | 79 | }; |
tnhnrl | 62:d502889e74f1 | 80 | |
tnhnrl | 62:d502889e74f1 | 81 | #endif |