Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: mbed MODSERIAL FATFileSystem
LinearActuator/LinearActuator.hpp@54:d4990fb68404, 2018-06-08 (annotated)
- Committer:
 - tnhnrl
 - Date:
 - Fri Jun 08 13:56:30 2018 +0000
 - Revision:
 - 54:d4990fb68404
 - Parent:
 - 41:ed5b95ab97e3
 
heading not working
Who changed what in which revision?
| User | Revision | Line number | New contents of line | 
|---|---|---|---|
| danstrider | 10:085ab7328054 | 1 | #ifndef LINEARACTUATOR_HPP | 
| danstrider | 10:085ab7328054 | 2 | #define LINEARACTUATOR_HPP | 
| mkelly10 | 9:d5fcdcb3c89d | 3 | |
| mkelly10 | 9:d5fcdcb3c89d | 4 | #include "mbed.h" | 
| tnhnrl | 41:ed5b95ab97e3 | 5 | #include "PololuHBridge.hpp" | 
| danstrider | 10:085ab7328054 | 6 | #include "PidController.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 | |
| danstrider | 10:085ab7328054 | 16 | class LinearActuator { | 
| mkelly10 | 9:d5fcdcb3c89d | 17 | public: | 
| mkelly10 | 9:d5fcdcb3c89d | 18 | LinearActuator(float interval, PinName pwm, PinName dir, PinName reset, PinName limit, int adc_ch); | 
| mkelly10 | 9:d5fcdcb3c89d | 19 | |
| mkelly10 | 9:d5fcdcb3c89d | 20 | // functions for setting up | 
| mkelly10 | 9:d5fcdcb3c89d | 21 | void init(); | 
| mkelly10 | 9:d5fcdcb3c89d | 22 | void update(); | 
| mkelly10 | 9:d5fcdcb3c89d | 23 | void start(); | 
| mkelly10 | 9:d5fcdcb3c89d | 24 | void stop(); | 
| mkelly10 | 9:d5fcdcb3c89d | 25 | void pause(); | 
| mkelly10 | 9:d5fcdcb3c89d | 26 | void unpause(); | 
| mkelly10 | 9:d5fcdcb3c89d | 27 | |
| mkelly10 | 9:d5fcdcb3c89d | 28 | void refreshPVState(); | 
| mkelly10 | 9:d5fcdcb3c89d | 29 | |
| mkelly10 | 9:d5fcdcb3c89d | 30 | // setting and getting variables | 
| mkelly10 | 9:d5fcdcb3c89d | 31 | void setPosition_mm(float dist); | 
| danstrider | 11:3b241ecb75ed | 32 | float getSetPosition_mm(); | 
| danstrider | 11:3b241ecb75ed | 33 | |
| mkelly10 | 9:d5fcdcb3c89d | 34 | float getPosition_mm(); | 
| danstrider | 11:3b241ecb75ed | 35 | float getPosition_counts(); | 
| mkelly10 | 9:d5fcdcb3c89d | 36 | float getVelocity_mms(); | 
| mkelly10 | 9:d5fcdcb3c89d | 37 | |
| mkelly10 | 9:d5fcdcb3c89d | 38 | void setControllerP(float P); | 
| mkelly10 | 9:d5fcdcb3c89d | 39 | float getControllerP(); | 
| mkelly10 | 9:d5fcdcb3c89d | 40 | |
| mkelly10 | 9:d5fcdcb3c89d | 41 | void setControllerI(float I); | 
| mkelly10 | 9:d5fcdcb3c89d | 42 | float getControllerI(); | 
| mkelly10 | 9:d5fcdcb3c89d | 43 | |
| mkelly10 | 9:d5fcdcb3c89d | 44 | void setControllerD(float D); | 
| mkelly10 | 9:d5fcdcb3c89d | 45 | float getControllerD(); | 
| mkelly10 | 9:d5fcdcb3c89d | 46 | |
| mkelly10 | 9:d5fcdcb3c89d | 47 | void setZeroCounts(int zero); | 
| mkelly10 | 9:d5fcdcb3c89d | 48 | int getZeroCounts(); | 
| mkelly10 | 9:d5fcdcb3c89d | 49 | |
| mkelly10 | 9:d5fcdcb3c89d | 50 | void setTravelLimit(float limit); | 
| mkelly10 | 9:d5fcdcb3c89d | 51 | float getTravelLimit(); | 
| mkelly10 | 9:d5fcdcb3c89d | 52 | |
| mkelly10 | 9:d5fcdcb3c89d | 53 | void setPotSlope(float slope); | 
| mkelly10 | 9:d5fcdcb3c89d | 54 | float getPotSlope(); | 
| mkelly10 | 9:d5fcdcb3c89d | 55 | |
| mkelly10 | 9:d5fcdcb3c89d | 56 | void homePiston(); | 
| danstrider | 10:085ab7328054 | 57 | bool getSwitch(); | 
| mkelly10 | 9:d5fcdcb3c89d | 58 | |
| mkelly10 | 9:d5fcdcb3c89d | 59 | float getOutput(); | 
| mkelly10 | 9:d5fcdcb3c89d | 60 | |
| danstrider | 10:085ab7328054 | 61 | void setFilterFrequency(float frequency); | 
| mkelly10 | 9:d5fcdcb3c89d | 62 | |
| mkelly10 | 9:d5fcdcb3c89d | 63 | void setDeadband(float deadband); | 
| danstrider | 11:3b241ecb75ed | 64 | float getDeadband(); | 
| mkelly10 | 9:d5fcdcb3c89d | 65 | bool toggleDeadband(bool toggle); | 
| mkelly10 | 9:d5fcdcb3c89d | 66 | |
| tnhnrl | 54:d4990fb68404 | 67 | int getHWSwitchReading(); | 
| tnhnrl | 54:d4990fb68404 | 68 | |
| mkelly10 | 9:d5fcdcb3c89d | 69 | protected: | 
| mkelly10 | 9:d5fcdcb3c89d | 70 | PololuHBridge _motor; | 
| mkelly10 | 9:d5fcdcb3c89d | 71 | PosVelFilter _filter; | 
| mkelly10 | 9:d5fcdcb3c89d | 72 | PIDController _pid; | 
| 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 | bool _init; | 
| mkelly10 | 9:d5fcdcb3c89d | 81 | bool _paused; | 
| mkelly10 | 9:d5fcdcb3c89d | 82 | bool _limit; | 
| mkelly10 | 9:d5fcdcb3c89d | 83 | |
| mkelly10 | 9:d5fcdcb3c89d | 84 | int _adc_channel; | 
| mkelly10 | 9:d5fcdcb3c89d | 85 | |
| mkelly10 | 9:d5fcdcb3c89d | 86 | float _filterFrequency; | 
| mkelly10 | 9:d5fcdcb3c89d | 87 | |
| mkelly10 | 9:d5fcdcb3c89d | 88 | float _dt; | 
| mkelly10 | 9:d5fcdcb3c89d | 89 | |
| mkelly10 | 9:d5fcdcb3c89d | 90 | float _SetPoint_mm; | 
| mkelly10 | 9:d5fcdcb3c89d | 91 | |
| danstrider | 10:085ab7328054 | 92 | // position and velocity in counts (PVF runs on counts) | 
| mkelly10 | 9:d5fcdcb3c89d | 93 | float _position; | 
| danstrider | 10:085ab7328054 | 94 | float _velocity; | 
| danstrider | 10:085ab7328054 | 95 | |
| danstrider | 10:085ab7328054 | 96 | // position and velocity converted to mm and mm/s | 
| mkelly10 | 9:d5fcdcb3c89d | 97 | float _position_mm; | 
| mkelly10 | 9:d5fcdcb3c89d | 98 | float _velocity_mms; | 
| mkelly10 | 9:d5fcdcb3c89d | 99 | |
| danstrider | 10:085ab7328054 | 100 | // linear actuator servo PID gains | 
| mkelly10 | 9:d5fcdcb3c89d | 101 | float _Pgain; | 
| mkelly10 | 9:d5fcdcb3c89d | 102 | float _Igain; | 
| mkelly10 | 9:d5fcdcb3c89d | 103 | float _Dgain; | 
| mkelly10 | 9:d5fcdcb3c89d | 104 | |
| mkelly10 | 9:d5fcdcb3c89d | 105 | float _deadband; | 
| mkelly10 | 9:d5fcdcb3c89d | 106 | |
| mkelly10 | 9:d5fcdcb3c89d | 107 | int _zeroCounts; //gets assigned by homing function. can also be stored in config | 
| mkelly10 | 9:d5fcdcb3c89d | 108 | float _extendLimit; //config variable, limits the extension of the piston, this is same as datum for normal operation, | 
| mkelly10 | 9:d5fcdcb3c89d | 109 | |
| mkelly10 | 9:d5fcdcb3c89d | 110 | float _slope; | 
| mkelly10 | 9:d5fcdcb3c89d | 111 | int dist_to_counts(float dist); | 
| mkelly10 | 9:d5fcdcb3c89d | 112 | float counts_to_dist(int count); | 
| mkelly10 | 9:d5fcdcb3c89d | 113 | float counts_to_velocity(int count); | 
| mkelly10 | 9:d5fcdcb3c89d | 114 | }; | 
| danstrider | 10:085ab7328054 | 115 | |
| danstrider | 10:085ab7328054 | 116 | |
| danstrider | 10:085ab7328054 | 117 | template <typename T> | 
| danstrider | 10:085ab7328054 | 118 | T clamp(T value, T min, T max) | 
| danstrider | 10:085ab7328054 | 119 | { | 
| danstrider | 10:085ab7328054 | 120 | if(value < min) { | 
| danstrider | 10:085ab7328054 | 121 | return min; | 
| danstrider | 10:085ab7328054 | 122 | } else if(value > max) { | 
| danstrider | 10:085ab7328054 | 123 | return max; | 
| danstrider | 10:085ab7328054 | 124 | } else { | 
| danstrider | 10:085ab7328054 | 125 | return value; | 
| danstrider | 10:085ab7328054 | 126 | } | 
| danstrider | 10:085ab7328054 | 127 | }; | 
| danstrider | 10:085ab7328054 | 128 | |
| mkelly10 | 9:d5fcdcb3c89d | 129 | #endif |