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
Diff: LinearActuator/LinearActuator.cpp
- Revision:
- 10:085ab7328054
- Parent:
- 9:d5fcdcb3c89d
- Child:
- 11:3b241ecb75ed
--- a/LinearActuator/LinearActuator.cpp Fri Oct 20 11:41:22 2017 +0000 +++ b/LinearActuator/LinearActuator.cpp Mon Oct 23 12:50:53 2017 +0000 @@ -3,16 +3,16 @@ #include "StaticDefs.hpp" #include "ConfigFile.h" +// this is where the variables that can be set are set when the object is created LinearActuator::LinearActuator(float interval, PinName pwm, PinName dir, PinName reset, PinName limit, int adc_ch): _motor(pwm, dir, reset), _filter(), _pid(), - //_time(), _pulse(), _limitSwitch(limit) { _limitSwitch.fall(callback(this, &LinearActuator::_switchPressed)); - // this is where the variables that can be set are set when the object is created + _Pgain = 0.10; _Igain = 0.0; _Dgain = 0.0; @@ -31,8 +31,7 @@ } -void LinearActuator::init() -{ +void LinearActuator::init() { // initialize and start all of the member objects. // The pos-velocity filter for this item needs to be allowed to converge // Before turning over control to the motor @@ -48,14 +47,10 @@ //set deadband and limits toggleDeadband(true); setDeadband(_deadband); - } -void LinearActuator::update() -{ - - - //update the position velocity filter +void LinearActuator::update() { + // update the position velocity filter if (_adc_channel == 0) { _filter.update(_dt, adc().readCh0()); } else if (_adc_channel == 1) { @@ -64,7 +59,7 @@ error("\n\r This ADC channel does not exist"); } - //refresh the filter results and load into class variables + // refresh the filter results and load into class variables refreshPVState(); // update the PID controller with latest data @@ -110,183 +105,154 @@ //dont run return; } - _motor.run(_pid.getOutput()); + + // clamp the output to the motor to -1.0 to 1.0 + if (_pid.getOutput() > 1.0) + _motor.run(1.0); + else if (_pid.getOutput() < -1.0) + _motor.run(-1.0); + else + _motor.run(_pid.getOutput()); } } -void LinearActuator::start() -{ +void LinearActuator::start() { _init = true; _pulse.attach(this,&LinearActuator::update, _dt); - } -void LinearActuator::stop() -{ +void LinearActuator::stop() { _motor.stop(); _pulse.detach(); } -void LinearActuator::pause() -{ +void LinearActuator::pause() { //this allows the controller to keep running while turning off the motor output _motor.stop(); //paused flag causes controller output not to be piped to the motor _paused = true; } -void LinearActuator::unpause() -{ +void LinearActuator::unpause() { //this resumes motor operation _paused = false; } -void LinearActuator::refreshPVState() -{ +void LinearActuator::refreshPVState() { _position = _filter.getPosition(); _velocity = _filter.getVelocity(); _position_mm = counts_to_dist(_position); _velocity_mms = counts_to_velocity(_velocity); - -// _position_mL = _mm_to_mL(_position_mm); -// _velocity_mLs = _mm_to_mL(_velocity_mms); - } // setting and getting variables -void LinearActuator::setPosition_mm(float dist) -{ - // convert mm representation to volume in mL -// _SetPoint_mL = _mm_to_mL(dist); +void LinearActuator::setPosition_mm(float dist) { _SetPoint_mm = clamp<float>(dist, 0.0, _extendLimit); //this is another spot that prevents the requested set point from going out of range, this template function is defined in the controller header file fyi _pid.writeSetPoint(_SetPoint_mm); - } -float LinearActuator::getPosition_mm() -{ +float LinearActuator::getPosition_mm() { return _position_mm; } -float LinearActuator::getPosition_counts() -{ - return _position; // returns raw adc counts (useful for zeroing) -} +//float LinearActuator::getPosition_counts() { +// return _position; // returns raw adc counts (useful for zeroing) +//} -float LinearActuator::getVelocity_mms() -{ +float LinearActuator::getVelocity_mms() { return _velocity_mms; } -void LinearActuator::setControllerP(float P) -{ +void LinearActuator::setControllerP(float P) { _Pgain = P; _pid.setPgain(_Pgain); return; } -float LinearActuator::getControllerP() -{ +float LinearActuator::getControllerP() { return _Pgain; } -void LinearActuator::setControllerI(float I) -{ +void LinearActuator::setControllerI(float I) { _Igain = I; _pid.setIgain(_Igain); return; } -float LinearActuator::getControllerI() -{ +float LinearActuator::getControllerI() { return _Igain; } -void LinearActuator::setControllerD(float D) -{ +void LinearActuator::setControllerD(float D) { _Dgain = D; _pid.setDgain(_Dgain); return; } -float LinearActuator::getControllerD() -{ +float LinearActuator::getControllerD() { return _Dgain; } -float LinearActuator::getOutput() -{ +float LinearActuator::getOutput() { return _pid.getOutput(); } - -void LinearActuator::setZeroCounts(int zero) -{ + +void LinearActuator::setZeroCounts(int zero) { _zeroCounts = clamp<int>(zero, 0, 4096); return; } -int LinearActuator::getZeroCounts() -{ +int LinearActuator::getZeroCounts() { return _zeroCounts; } -void LinearActuator::setTravelLimit(float limit) -{ +void LinearActuator::setTravelLimit(float limit) { _extendLimit = limit; return; } -float LinearActuator::getTravelLimit() -{ +float LinearActuator::getTravelLimit() { return _extendLimit; } -void LinearActuator::setPotSlope(float slope) -{ +void LinearActuator::setPotSlope(float slope) { _slope = slope; return; } -float LinearActuator::getPotSlope() -{ +float LinearActuator::getPotSlope() { return _slope; } -float LinearActuator::counts_to_dist(int count) -{ +float LinearActuator::counts_to_dist(int count) { float conv = _slope*(count-_zeroCounts); return conv; } -void LinearActuator::setFilterFrequency(float frequency) -{ +void LinearActuator::setFilterFrequency(float frequency) { _filterFrequency = frequency; _filter.writeWn(frequency); } -int LinearActuator::dist_to_counts(float dist) -{ +int LinearActuator::dist_to_counts(float dist) { float conv = (dist/_slope)+_zeroCounts; return (int) conv; } -float LinearActuator::counts_to_velocity(int count) -{ +float LinearActuator::counts_to_velocity(int count) { float conv = count*_slope; return conv; } -void LinearActuator::_switchPressed() -{ +void LinearActuator::_switchPressed() { //first thing to do is stop the motor _motor.stop(); _limit = true; } -void LinearActuator::homePiston() -{ +void LinearActuator::homePiston() { //start calling the update for the Linear Actuator //start the controller update and immediatley pause the motor output start(); @@ -299,8 +265,8 @@ //Now that the readings are stabilized // This sends the motor on a kamakaze mission toward the limit switch - // The interrupt should catch and stop it and the piston is now at home - //position + // The interrupt should catch and stop it, and the piston is now at home + // position _motor.run(-1.0); while (1) { @@ -323,21 +289,17 @@ } } -bool LinearActuator::getSwitch() -{ +bool LinearActuator::getSwitch() { return _limit; } - void LinearActuator::setDeadband(float deadband) -{ + void LinearActuator::setDeadband(float deadband) { _deadband = deadband; _pid.setDeadBand(_deadband); return; } -bool LinearActuator::toggleDeadband(bool toggle) -{ +bool LinearActuator::toggleDeadband(bool toggle) { _pid.toggleDeadBand(toggle); return toggle; -} - \ No newline at end of file +} \ No newline at end of file