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
LinearActuator/LinearActuator.hpp@9:d5fcdcb3c89d, 2017-10-20 (annotated)
- Committer:
- mkelly10
- Date:
- Fri Oct 20 11:41:22 2017 +0000
- Revision:
- 9:d5fcdcb3c89d
- Child:
- 10:085ab7328054
Tested 10/19/17 Folders
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
mkelly10 | 9:d5fcdcb3c89d | 1 | #ifndef BCE_HPP |
mkelly10 | 9:d5fcdcb3c89d | 2 | #define BCE_HPP |
mkelly10 | 9:d5fcdcb3c89d | 3 | |
mkelly10 | 9:d5fcdcb3c89d | 4 | #include "mbed.h" |
mkelly10 | 9:d5fcdcb3c89d | 5 | #include "PololuHbridge.hpp" |
mkelly10 | 9:d5fcdcb3c89d | 6 | #include "controller.hpp" |
mkelly10 | 9:d5fcdcb3c89d | 7 | #include "ltc1298.hpp" |
mkelly10 | 9:d5fcdcb3c89d | 8 | #include "PosVelFilter.hpp" |
mkelly10 | 9:d5fcdcb3c89d | 9 | |
mkelly10 | 9:d5fcdcb3c89d | 10 | //Dependencies |
mkelly10 | 9:d5fcdcb3c89d | 11 | //This Class requires adc readings to sense the position of the piston |
mkelly10 | 9:d5fcdcb3c89d | 12 | //This is a resource that ends up being shared among other classes in the vehicle |
mkelly10 | 9:d5fcdcb3c89d | 13 | //for this reason it makes sense for it to be its own entity that is started in |
mkelly10 | 9:d5fcdcb3c89d | 14 | //the main line code |
mkelly10 | 9:d5fcdcb3c89d | 15 | |
mkelly10 | 9:d5fcdcb3c89d | 16 | class LinearActuator |
mkelly10 | 9:d5fcdcb3c89d | 17 | { |
mkelly10 | 9:d5fcdcb3c89d | 18 | public: |
mkelly10 | 9:d5fcdcb3c89d | 19 | //BuoyancyEngine(PololuHBridge motor, SpiADC adc, PosVelFilter filter, PositionController pid); |
mkelly10 | 9:d5fcdcb3c89d | 20 | LinearActuator(float interval, PinName pwm, PinName dir, PinName reset, PinName limit, int adc_ch); |
mkelly10 | 9:d5fcdcb3c89d | 21 | |
mkelly10 | 9:d5fcdcb3c89d | 22 | // functions for setting up |
mkelly10 | 9:d5fcdcb3c89d | 23 | void init(); |
mkelly10 | 9:d5fcdcb3c89d | 24 | void update(); |
mkelly10 | 9:d5fcdcb3c89d | 25 | void start(); |
mkelly10 | 9:d5fcdcb3c89d | 26 | void stop(); |
mkelly10 | 9:d5fcdcb3c89d | 27 | void pause(); |
mkelly10 | 9:d5fcdcb3c89d | 28 | void unpause(); |
mkelly10 | 9:d5fcdcb3c89d | 29 | |
mkelly10 | 9:d5fcdcb3c89d | 30 | void refreshPVState(); |
mkelly10 | 9:d5fcdcb3c89d | 31 | |
mkelly10 | 9:d5fcdcb3c89d | 32 | // setting and getting variables |
mkelly10 | 9:d5fcdcb3c89d | 33 | void setPosition_mm(float dist); |
mkelly10 | 9:d5fcdcb3c89d | 34 | |
mkelly10 | 9:d5fcdcb3c89d | 35 | float getPosition_mm(); |
mkelly10 | 9:d5fcdcb3c89d | 36 | float getPosition_counts(); |
mkelly10 | 9:d5fcdcb3c89d | 37 | |
mkelly10 | 9:d5fcdcb3c89d | 38 | float getVelocity_mms(); |
mkelly10 | 9:d5fcdcb3c89d | 39 | |
mkelly10 | 9:d5fcdcb3c89d | 40 | void setControllerP(float P); |
mkelly10 | 9:d5fcdcb3c89d | 41 | float getControllerP(); |
mkelly10 | 9:d5fcdcb3c89d | 42 | |
mkelly10 | 9:d5fcdcb3c89d | 43 | void setControllerI(float I); |
mkelly10 | 9:d5fcdcb3c89d | 44 | float getControllerI(); |
mkelly10 | 9:d5fcdcb3c89d | 45 | |
mkelly10 | 9:d5fcdcb3c89d | 46 | void setControllerD(float D); |
mkelly10 | 9:d5fcdcb3c89d | 47 | float getControllerD(); |
mkelly10 | 9:d5fcdcb3c89d | 48 | |
mkelly10 | 9:d5fcdcb3c89d | 49 | void setZeroCounts(int zero); |
mkelly10 | 9:d5fcdcb3c89d | 50 | int getZeroCounts(); |
mkelly10 | 9:d5fcdcb3c89d | 51 | |
mkelly10 | 9:d5fcdcb3c89d | 52 | void setTravelLimit(float limit); |
mkelly10 | 9:d5fcdcb3c89d | 53 | float getTravelLimit(); |
mkelly10 | 9:d5fcdcb3c89d | 54 | |
mkelly10 | 9:d5fcdcb3c89d | 55 | void setPotSlope(float slope); |
mkelly10 | 9:d5fcdcb3c89d | 56 | float getPotSlope(); |
mkelly10 | 9:d5fcdcb3c89d | 57 | |
mkelly10 | 9:d5fcdcb3c89d | 58 | void homePiston(); |
mkelly10 | 9:d5fcdcb3c89d | 59 | void setFilterFrequency(float frequency); |
mkelly10 | 9:d5fcdcb3c89d | 60 | |
mkelly10 | 9:d5fcdcb3c89d | 61 | float getOutput(); |
mkelly10 | 9:d5fcdcb3c89d | 62 | |
mkelly10 | 9:d5fcdcb3c89d | 63 | bool getSwitch(); |
mkelly10 | 9:d5fcdcb3c89d | 64 | |
mkelly10 | 9:d5fcdcb3c89d | 65 | void setDeadband(float deadband); |
mkelly10 | 9:d5fcdcb3c89d | 66 | bool toggleDeadband(bool toggle); |
mkelly10 | 9:d5fcdcb3c89d | 67 | |
mkelly10 | 9:d5fcdcb3c89d | 68 | protected: |
mkelly10 | 9:d5fcdcb3c89d | 69 | PololuHBridge _motor; |
mkelly10 | 9:d5fcdcb3c89d | 70 | PosVelFilter _filter; |
mkelly10 | 9:d5fcdcb3c89d | 71 | PIDController _pid; |
mkelly10 | 9:d5fcdcb3c89d | 72 | //Timer _time; |
mkelly10 | 9:d5fcdcb3c89d | 73 | Ticker _pulse; |
mkelly10 | 9:d5fcdcb3c89d | 74 | InterruptIn _limitSwitch; |
mkelly10 | 9:d5fcdcb3c89d | 75 | |
mkelly10 | 9:d5fcdcb3c89d | 76 | void _switchPressed(); |
mkelly10 | 9:d5fcdcb3c89d | 77 | void _switchReleased(); |
mkelly10 | 9:d5fcdcb3c89d | 78 | void _calculateSensorSlope(); |
mkelly10 | 9:d5fcdcb3c89d | 79 | |
mkelly10 | 9:d5fcdcb3c89d | 80 | |
mkelly10 | 9:d5fcdcb3c89d | 81 | bool _init; |
mkelly10 | 9:d5fcdcb3c89d | 82 | bool _paused; |
mkelly10 | 9:d5fcdcb3c89d | 83 | bool _limit; |
mkelly10 | 9:d5fcdcb3c89d | 84 | |
mkelly10 | 9:d5fcdcb3c89d | 85 | int _adc_channel; |
mkelly10 | 9:d5fcdcb3c89d | 86 | |
mkelly10 | 9:d5fcdcb3c89d | 87 | float _filterFrequency; |
mkelly10 | 9:d5fcdcb3c89d | 88 | |
mkelly10 | 9:d5fcdcb3c89d | 89 | float _dt; |
mkelly10 | 9:d5fcdcb3c89d | 90 | |
mkelly10 | 9:d5fcdcb3c89d | 91 | float _SetPoint_mm; |
mkelly10 | 9:d5fcdcb3c89d | 92 | |
mkelly10 | 9:d5fcdcb3c89d | 93 | float _position; |
mkelly10 | 9:d5fcdcb3c89d | 94 | float _position_mm; |
mkelly10 | 9:d5fcdcb3c89d | 95 | |
mkelly10 | 9:d5fcdcb3c89d | 96 | float _velocity; |
mkelly10 | 9:d5fcdcb3c89d | 97 | float _velocity_mms; |
mkelly10 | 9:d5fcdcb3c89d | 98 | |
mkelly10 | 9:d5fcdcb3c89d | 99 | float _Pgain; |
mkelly10 | 9:d5fcdcb3c89d | 100 | float _Igain; |
mkelly10 | 9:d5fcdcb3c89d | 101 | float _Dgain; |
mkelly10 | 9:d5fcdcb3c89d | 102 | |
mkelly10 | 9:d5fcdcb3c89d | 103 | float _deadband; |
mkelly10 | 9:d5fcdcb3c89d | 104 | |
mkelly10 | 9:d5fcdcb3c89d | 105 | int _zeroCounts; //gets assigned by homing function. can also be stored in config |
mkelly10 | 9:d5fcdcb3c89d | 106 | float _extendLimit; //config variable, limits the extension of the piston, this is same as datum for normal operation, |
mkelly10 | 9:d5fcdcb3c89d | 107 | float _pos_vel_wn; //config variable, natural frequecny of the position velocity filter |
mkelly10 | 9:d5fcdcb3c89d | 108 | |
mkelly10 | 9:d5fcdcb3c89d | 109 | float _slope; |
mkelly10 | 9:d5fcdcb3c89d | 110 | int dist_to_counts(float dist); |
mkelly10 | 9:d5fcdcb3c89d | 111 | float counts_to_dist(int count); |
mkelly10 | 9:d5fcdcb3c89d | 112 | float counts_to_velocity(int count); |
mkelly10 | 9:d5fcdcb3c89d | 113 | |
mkelly10 | 9:d5fcdcb3c89d | 114 | }; |
mkelly10 | 9:d5fcdcb3c89d | 115 | |
mkelly10 | 9:d5fcdcb3c89d | 116 | #endif |