Beginn mit der Erstellung der Firmware-Config
This commit is contained in:
parent
370ddd9c60
commit
ce3380206c
40
Repetier-Firmware 1.0.3/README.txt
Normal file
40
Repetier-Firmware 1.0.3/README.txt
Normal file
@ -0,0 +1,40 @@
|
||||
Compilation instructions
|
||||
|
||||
1. Install Arduino IDE
|
||||
You get the latest Arduino IDE here:
|
||||
http://arduino.cc/en/Main/Software
|
||||
|
||||
You need at least 1.0 for the Atmel AVR based boards and 1.5 for the ARM based boards like the due.
|
||||
|
||||
2. Make sure the serial driver for your printer board is installed. The Arduino IDE contains signed drivers
|
||||
for the Arduino boards. Depending on your board you might need different drivers then these. For Linux and Mac
|
||||
you often do not need any additional drivers. Ask your printer/board vendor which driver you need,
|
||||
if that is not clear to you.
|
||||
|
||||
3. Some boards that are not original arduino boards and not 100% compatible to them, need separate extensions
|
||||
to the Arduino IDE. Install them.
|
||||
|
||||
4. Start Arduino IDE and open the file "Repetier.ino"
|
||||
|
||||
5. Select the board and port for upload in the arduino ide.
|
||||
|
||||
6. Check Configuration.h for hints, if something needs to be checked or modified.
|
||||
|
||||
7. Upload the firmware with the upload button (right arrow in toolbar).
|
||||
|
||||
If you have a normal mega 2560 compatible board, you can use codeblocks for arduino instead of the arduino ide:
|
||||
http://arduinodev.com/codeblocks/
|
||||
Open the Repetier.cbp file instead of the ino file and start with 6.
|
||||
|
||||
HINT: It you have enabled eeprom support, the first upload will copy the configurations into the eeprom. Later
|
||||
uploads will NOT overwrite these settings! Connect with Repetier-Host to your printer and open the eeprom editor
|
||||
to change these values. Alternatively, send the commands
|
||||
M502
|
||||
M500
|
||||
to copy the new values in Configuration.h to eeprom.
|
||||
|
||||
|
||||
IMPORTANT FOR DUE USERS
|
||||
|
||||
There is an additional folder AdditionalArduinoFiles with separate readme that describes how to get
|
||||
watchdog working. It is a very good idea to compile with working watchdog!!!
|
956
Repetier-Firmware 1.0.3/Repetier/BedLeveling.cpp
Normal file
956
Repetier-Firmware 1.0.3/Repetier/BedLeveling.cpp
Normal file
@ -0,0 +1,956 @@
|
||||
|
||||
/*
|
||||
More and more printers now have automatic bed leveling using an ever increasing variety of methods.
|
||||
This makes the leveling routine one of the most complex parts of the firmware and there is not one
|
||||
way to level but hundreds of combinations.
|
||||
|
||||
First you should decide on the correction method. Once we know how our bed is tilted we want to
|
||||
remove that. This correction is defined by BED_CORRECTION_METHOD and allows the following values:
|
||||
BED_CORRECTION_METHOD 0
|
||||
Use a rotation matrix. This will make z axis go up/down while moving in x/y direction to compensate
|
||||
the tilt. For multiple extruders make sure the height match the tilt of the bed or one will scratch.
|
||||
|
||||
BED_CORRECTION_METHOD 1
|
||||
Motorized correction. This method needs a bed that is fixed on 3 points from which 2 have a motor
|
||||
to change the height. The positions are defined by
|
||||
BED_MOTOR_1_X, BED_MOTOR_1_Y, BED_MOTOR_2_X, BED_MOTOR_2_Y, BED_MOTOR_3_X, BED_MOTOR_3_Y
|
||||
Motor 2 and 3 are the one driven by motor driver 0 and 1. These can be extra motors like Felix Pro 1
|
||||
uses them or a system with 3 z axis where motors can be controlled individually like the Sparkcube
|
||||
does.
|
||||
|
||||
Next we have to distinguish several methods of z probing sensors. Each have their own advantages and
|
||||
disadvantages. First the z probe has a position when activated and that position is defined by
|
||||
#define Z_PROBE_X_OFFSET 0
|
||||
#define Z_PROBE_Y_OFFSET 0
|
||||
This is needed since we need to know where we measure the height when the z probe triggers. When
|
||||
probing is activated you will see a move to make probe go over current extruder position. The
|
||||
position can be changed in eeprom later on.
|
||||
|
||||
Some probes need to be activated/deactivated so we can use them. This is defined in the scripts
|
||||
#define Z_PROBE_START_SCRIPT ""
|
||||
#define Z_PROBE_FINISHED_SCRIPT ""
|
||||
|
||||
Now when we probe we want to know the distance of the extruder to the bed. This is defined by
|
||||
#define Z_PROBE_HEIGHT 4
|
||||
The 4 means that when we trigger the distance of the nozzle tip is 4mm. If your switch tends
|
||||
to return different points you might repeat a measured point and use the average height:
|
||||
#define Z_PROBE_SWITCHING_DISTANCE 1
|
||||
#define Z_PROBE_REPETITIONS 5
|
||||
Switching distance is the z raise needed to turn back a signal reliably to off. Inductive sensors
|
||||
need only a bit while mechanical switches may require a bit more.
|
||||
|
||||
Next thing to consider is the force for switching. Some beds use a cantilever design and pushing on
|
||||
the outside easily bends the bed. If your sensor needs some force to trigger you add the error of
|
||||
bending. For this reason you might add a bending correction. Currently you define
|
||||
#define BENDING_CORRECTION_A 0
|
||||
#define BENDING_CORRECTION_B 0
|
||||
#define BENDING_CORRECTION_C 0
|
||||
which are the deflections at the 3 z probe points. For all other possible measurements these values
|
||||
get interpolated. You can modify the values later on in eeprom. For force less sensors set them to 0.
|
||||
|
||||
Next thing is endstop handling. Without bed leveling you normally home to minimum position for x,y and z.
|
||||
With bed leveling this is not that easy any more. Since we do bed leveling we already assume the bed is
|
||||
not leveled for x/y moves. So without correction we would hit the bed for different x/y positions at
|
||||
different heights. As a result we have no real minimum position. That makes a z min endstop quite useless.
|
||||
There is an exception to this. If your nozzle triggers z min or if a inductive sensor would trigger at a given
|
||||
position we could use that signal. With nozzle triggers you need to be careful as a drop of filament
|
||||
would change the height. The other problem is that while homing the auto leveling is not used. So
|
||||
the only position would be if the z min sensor is directly over the 0,0 coordinate which is the rotation point
|
||||
if we have matrix based correction. For motor based correction this will work everywhere correctly.
|
||||
|
||||
So the only useful position for a z endstop is z max position. Apart from not having the bed tilt problem it
|
||||
also allows homing with a full bed so you can continue an aborted print with some gcode tweaking. With z max
|
||||
homing we adjust the error by simply changing the max. z height. One thing you need to remember is setting
|
||||
#define ENDSTOP_Z_BACK_ON_HOME 4
|
||||
so we release the z max endstop. This is very important if we move xy at z max. Auto leveling might want to
|
||||
increase z and the endstop might prevent it causing wrong position and a head crash if we later go down.
|
||||
The value should be larger then the maximum expected tilt.
|
||||
|
||||
Now it is time to define how we measure the bed rotation. Here again we have several methods to choose.
|
||||
All methods need at least 3 points to define the bed rotation correctly. The quality we get comes
|
||||
from the selection of the right points and method.
|
||||
|
||||
BED_LEVELING_METHOD 0
|
||||
This method measures at the 3 probe points and creates a plane through these points. If you have
|
||||
a really planar bed this gives the optimum result. The 3 points must not be in one line and have
|
||||
a long distance to increase numerical stability.
|
||||
|
||||
BED_LEVELING_METHOD 1
|
||||
This measures a grid. Probe point 1 is the origin and points 2 and 3 span a grid. We measure
|
||||
BED_LEVELING_GRID_SIZE points in each direction and compute a regression plane through all
|
||||
points. This gives a good overall plane if you have small bumps measuring inaccuracies.
|
||||
|
||||
BED_LEVELING_METHOD 2
|
||||
Bending correcting 4 point measurement. This is for cantilevered beds that have the rotation axis
|
||||
not at the side but inside the bed. Here we can assume no bending on the axis and a symmetric
|
||||
bending to both sides of the axis. So probe points 2 and 3 build the symmetric axis and
|
||||
point 1 is mirrored to 1m across the axis. Using the symmetry we then remove the bending
|
||||
from 1 and use that as plane.
|
||||
|
||||
By now the leveling process is finished. All errors that remain are measuring errors and bumps on
|
||||
the bed it self. For deltas you can enable distortion correction to follow the bumps.
|
||||
|
||||
There are 2 ways to consider a changing bed coating, which are defined by Z_PROBE_Z_OFFSET_MODE.
|
||||
Z_PROBE_Z_OFFSET_MODE = 0 means we measure the surface of the bed below any coating. This is e.g.
|
||||
the case with inductive sensors where we put BuildTak on top. In that case we can set Z_PROBE_Z_OFFSET
|
||||
to the thickness of BuildTak to compensate. If we later change the coating, we only change Z_PROBE_Z_OFFSET
|
||||
to new coating thickness.
|
||||
|
||||
Z_PROBE_Z_OFFSET_MODE = 1 means we measure the surface of the coating, e.g. because we have a mechanical switch.
|
||||
In that case we add Z_PROBE_Z_OFFSET for the measured height to compensate for correct distance to bed surface.
|
||||
|
||||
In homing to max we reduce z length by Z_PROBE_Z_OFFSET to get a correct height.
|
||||
In homing to z min we assume z endstop is bed level so we move up Z_PROBE_Z_OFFSET after endstop is hit. This
|
||||
requires the extruder to bend the coating thickness without harm!
|
||||
*/
|
||||
|
||||
#include "Repetier.h"
|
||||
|
||||
#ifndef BED_LEVELING_METHOD
|
||||
#define BED_LEVELING_METHOD 0
|
||||
#endif
|
||||
|
||||
#ifndef BED_CORRECTION_METHOD
|
||||
#define BED_CORRECTION_METHOD 0
|
||||
#endif
|
||||
|
||||
#ifndef BED_LEVELING_GRID_SIZE
|
||||
#define BED_LEVELING_GRID_SIZE 5
|
||||
#endif
|
||||
|
||||
#ifndef BED_LEVELING_REPETITIONS
|
||||
#define BED_LEVELING_REPETITIONS 1
|
||||
#endif
|
||||
|
||||
#if FEATURE_Z_PROBE
|
||||
void Printer::prepareForProbing() {
|
||||
#ifndef SKIP_PROBE_PREPARE
|
||||
// 1. Ensure we are homed so positions make sense
|
||||
if(!Printer::isHomedAll()) {
|
||||
Printer::homeAxis(true, true, true);
|
||||
}
|
||||
// 2. Go to z probe bed distance for probing
|
||||
Printer::moveToReal(IGNORE_COORDINATE, IGNORE_COORDINATE, RMath::max(EEPROM::zProbeBedDistance() + (EEPROM::zProbeHeight() > 0 ? EEPROM::zProbeHeight() : 0), static_cast<float>(ZHOME_HEAT_HEIGHT)), IGNORE_COORDINATE, Printer::homingFeedrate[Z_AXIS]);
|
||||
// 3. Ensure we can activate z probe at current xy position
|
||||
// Delta is at center already so does not need special testing here!
|
||||
#if EXTRUDER_IS_Z_PROBE == 0
|
||||
float ZPOffsetX = EEPROM::zProbeXOffset();
|
||||
float ZPOffsetY = EEPROM::zProbeYOffset();
|
||||
#if DRIVE_SYSTEM != DELTA
|
||||
float targetX = Printer::currentPosition[X_AXIS];
|
||||
float targetY = Printer::currentPosition[Y_AXIS];
|
||||
if(ZPOffsetX > 0 && targetX - ZPOffsetX < Printer::xMin) {
|
||||
targetX = Printer::xMin + ZPOffsetX;
|
||||
}
|
||||
if(ZPOffsetY > 0 && targetY - ZPOffsetY < Printer::yMin) {
|
||||
targetY = Printer::yMin + ZPOffsetY;
|
||||
}
|
||||
if(ZPOffsetX < 0 && targetX - ZPOffsetX > Printer::xMin + Printer::xLength) {
|
||||
targetX = Printer::xMin + Printer::xLength + ZPOffsetX;
|
||||
}
|
||||
if(ZPOffsetY < 0 && targetY - ZPOffsetY > Printer::yMin + Printer::yLength) {
|
||||
targetY = Printer::yMin + Printer::yLength + ZPOffsetY;
|
||||
}
|
||||
Printer::moveToReal(targetX, targetY, IGNORE_COORDINATE, IGNORE_COORDINATE, EXTRUDER_SWITCH_XY_SPEED);
|
||||
Printer::updateCurrentPosition(true);
|
||||
Commands::waitUntilEndOfAllMoves();
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
#if FEATURE_AUTOLEVEL && FEATURE_Z_PROBE
|
||||
|
||||
bool measureAutolevelPlane(Plane &plane) {
|
||||
PlaneBuilder builder;
|
||||
builder.reset();
|
||||
#if BED_LEVELING_METHOD == 0 // 3 point
|
||||
float h;
|
||||
Printer::moveTo(EEPROM::zProbeX1(), EEPROM::zProbeY1(), IGNORE_COORDINATE, IGNORE_COORDINATE, EEPROM::zProbeXYSpeed());
|
||||
h = Printer::runZProbe(false, false);
|
||||
if(h == ILLEGAL_Z_PROBE)
|
||||
return false;
|
||||
builder.addPoint(EEPROM::zProbeX1(), EEPROM::zProbeY1(), h);
|
||||
Printer::moveTo(EEPROM::zProbeX2(), EEPROM::zProbeY2(), IGNORE_COORDINATE, IGNORE_COORDINATE, EEPROM::zProbeXYSpeed());
|
||||
h = Printer::runZProbe(false, false);
|
||||
if(h == ILLEGAL_Z_PROBE)
|
||||
return false;
|
||||
builder.addPoint(EEPROM::zProbeX2(), EEPROM::zProbeY2(), h);
|
||||
Printer::moveTo(EEPROM::zProbeX3(), EEPROM::zProbeY3(), IGNORE_COORDINATE, IGNORE_COORDINATE, EEPROM::zProbeXYSpeed());
|
||||
h = Printer::runZProbe(false, false);
|
||||
if(h == ILLEGAL_Z_PROBE)
|
||||
return false;
|
||||
builder.addPoint(EEPROM::zProbeX3(), EEPROM::zProbeY3(), h);
|
||||
#elif BED_LEVELING_METHOD == 1 // linear regression
|
||||
float delta = 1.0 / (BED_LEVELING_GRID_SIZE - 1);
|
||||
float ox = EEPROM::zProbeX1();
|
||||
float oy = EEPROM::zProbeY1();
|
||||
float ax = delta * (EEPROM::zProbeX2() - EEPROM::zProbeX1());
|
||||
float ay = delta * (EEPROM::zProbeY2() - EEPROM::zProbeY1());
|
||||
float bx = delta * (EEPROM::zProbeX3() - EEPROM::zProbeX1());
|
||||
float by = delta * (EEPROM::zProbeY3() - EEPROM::zProbeY1());
|
||||
for(int ix = 0; ix < BED_LEVELING_GRID_SIZE; ix++) {
|
||||
for(int iy = 0; iy < BED_LEVELING_GRID_SIZE; iy++) {
|
||||
float px = ox + static_cast<float>(ix) * ax + static_cast<float>(iy) * bx;
|
||||
float py = oy + static_cast<float>(ix) * ay + static_cast<float>(iy) * by;
|
||||
Printer::moveTo(px, py, IGNORE_COORDINATE, IGNORE_COORDINATE, EEPROM::zProbeXYSpeed());
|
||||
float h = Printer::runZProbe(false, false);
|
||||
if(h == ILLEGAL_Z_PROBE)
|
||||
return false;
|
||||
builder.addPoint(px, py, h);
|
||||
}
|
||||
}
|
||||
|
||||
#elif BED_LEVELING_METHOD == 2 // 4 point symmetric
|
||||
float h1, h2, h3, h4;
|
||||
float apx = EEPROM::zProbeX1() - EEPROM::zProbeX2();
|
||||
float apy = EEPROM::zProbeY1() - EEPROM::zProbeY2();
|
||||
float abx = EEPROM::zProbeX3() - EEPROM::zProbeX2();
|
||||
float aby = EEPROM::zProbeY3() - EEPROM::zProbeY2();
|
||||
float ab2 = abx * abx + aby * aby;
|
||||
float abap = apx * abx + apy * aby;
|
||||
float t = abap / ab2;
|
||||
float xx = EEPROM::zProbeX2() + t * abx;
|
||||
float xy = EEPROM::zProbeY2() + t * aby;
|
||||
float x1Mirror = EEPROM::zProbeX1() + 2.0 * (xx - EEPROM::zProbeX1());
|
||||
float y1Mirror = EEPROM::zProbeY1() + 2.0 * (xy - EEPROM::zProbeY1());
|
||||
Printer::moveTo(EEPROM::zProbeX1(), EEPROM::zProbeY1(), IGNORE_COORDINATE, IGNORE_COORDINATE, EEPROM::zProbeXYSpeed());
|
||||
h1 = Printer::runZProbe(false, false);
|
||||
if(h1 == ILLEGAL_Z_PROBE)
|
||||
return false;
|
||||
Printer::moveTo(EEPROM::zProbeX2(), EEPROM::zProbeY2(), IGNORE_COORDINATE, IGNORE_COORDINATE, EEPROM::zProbeXYSpeed());
|
||||
h2 = Printer::runZProbe(false, false);
|
||||
if(h2 == ILLEGAL_Z_PROBE)
|
||||
return false;
|
||||
Printer::moveTo(EEPROM::zProbeX3(), EEPROM::zProbeY3(), IGNORE_COORDINATE, IGNORE_COORDINATE, EEPROM::zProbeXYSpeed());
|
||||
h3 = Printer::runZProbe(false, false);
|
||||
if(h3 == ILLEGAL_Z_PROBE)
|
||||
return false;
|
||||
Printer::moveTo(x1Mirror, y1Mirror, IGNORE_COORDINATE, IGNORE_COORDINATE, EEPROM::zProbeXYSpeed());
|
||||
h4 = Printer::runZProbe(false, false);
|
||||
if(h4 == ILLEGAL_Z_PROBE)
|
||||
return false;
|
||||
t = h2 + (h3 - h2) * t; // theoretical height for crossing point for symmetric axis
|
||||
h1 = t - (h4 - h1) * 0.5; // remove bending part
|
||||
builder.addPoint(EEPROM::zProbeX1(), EEPROM::zProbeY1(), h1);
|
||||
builder.addPoint(EEPROM::zProbeX2(), EEPROM::zProbeY2(), h2);
|
||||
builder.addPoint(EEPROM::zProbeX3(), EEPROM::zProbeY3(), h3);
|
||||
#else
|
||||
#error Unknown bed leveling method
|
||||
#endif
|
||||
builder.createPlane(plane, false);
|
||||
return true;
|
||||
}
|
||||
|
||||
void correctAutolevel(Plane &plane) {
|
||||
#if BED_CORRECTION_METHOD == 0 // rotation matrix
|
||||
//Printer::buildTransformationMatrix(plane.z(EEPROM::zProbeX1(),EEPROM::zProbeY1()),plane.z(EEPROM::zProbeX2(),EEPROM::zProbeY2()),plane.z(EEPROM::zProbeX3(),EEPROM::zProbeY3()));
|
||||
Printer::buildTransformationMatrix(plane);
|
||||
#elif BED_CORRECTION_METHOD == 1 // motorized correction
|
||||
#if !defined(NUM_MOTOR_DRIVERS) || NUM_MOTOR_DRIVERS < 2
|
||||
#error You need to define 2 motors for motorized bed correction
|
||||
#endif
|
||||
Commands::waitUntilEndOfAllMoves(); // move steppers might be leveling steppers as well !
|
||||
float h1 = plane.z(BED_MOTOR_1_X, BED_MOTOR_1_Y);
|
||||
float h2 = plane.z(BED_MOTOR_2_X, BED_MOTOR_2_Y);
|
||||
float h3 = plane.z(BED_MOTOR_3_X, BED_MOTOR_3_Y);
|
||||
// h1 is reference heights, h2 => motor 0, h3 => motor 1
|
||||
h2 -= h1;
|
||||
h3 -= h1;
|
||||
#if defined(LIMIT_MOTORIZED_CORRECTION)
|
||||
if(h2 < -LIMIT_MOTORIZED_CORRECTION) h2 = -LIMIT_MOTORIZED_CORRECTION;
|
||||
if(h2 > LIMIT_MOTORIZED_CORRECTION) h2 = LIMIT_MOTORIZED_CORRECTION;
|
||||
if(h3 < -LIMIT_MOTORIZED_CORRECTION) h3 = -LIMIT_MOTORIZED_CORRECTION;
|
||||
if(h3 > LIMIT_MOTORIZED_CORRECTION) h3 = LIMIT_MOTORIZED_CORRECTION;
|
||||
#endif
|
||||
MotorDriverInterface *motor2 = getMotorDriver(0);
|
||||
MotorDriverInterface *motor3 = getMotorDriver(1);
|
||||
motor2->setCurrentAs(0);
|
||||
motor3->setCurrentAs(0);
|
||||
motor2->gotoPosition(h2);
|
||||
motor3->gotoPosition(h3);
|
||||
motor2->disable();
|
||||
motor3->disable(); // now bed is even
|
||||
Printer::currentPositionSteps[Z_AXIS] = h1 * Printer::axisStepsPerMM[Z_AXIS];
|
||||
#if NONLINEAR_SYSTEM
|
||||
transformCartesianStepsToDeltaSteps(Printer::currentPositionSteps, Printer::currentNonlinearPositionSteps);
|
||||
#endif
|
||||
#else
|
||||
#error Unknown bed correction method set
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
Implementation of the G32 command
|
||||
G32 S<0..2> - Autolevel print bed. S = 1 measure zLength, S = 2 Measure and store new zLength
|
||||
S = 0 : Do not update length - use this if you have not homed before or you mess up zLength!
|
||||
S = 1 : Measure zLength so homing works
|
||||
S = 2 : Like s = 1 plus store results in EEPROM for next connection.
|
||||
*/
|
||||
bool runBedLeveling(int s) {
|
||||
bool success = true;
|
||||
Printer::prepareForProbing();
|
||||
#if defined(Z_PROBE_MIN_TEMPERATURE) && Z_PROBE_MIN_TEMPERATURE && Z_PROBE_REQUIRES_HEATING
|
||||
float actTemp[NUM_EXTRUDER];
|
||||
for(int i = 0; i < NUM_EXTRUDER; i++)
|
||||
actTemp[i] = extruder[i].tempControl.targetTemperatureC;
|
||||
Printer::moveToReal(IGNORE_COORDINATE, IGNORE_COORDINATE, RMath::max(EEPROM::zProbeBedDistance() + (EEPROM::zProbeHeight() > 0 ? EEPROM::zProbeHeight() : 0), static_cast<float>(ZHOME_HEAT_HEIGHT)), IGNORE_COORDINATE, Printer::homingFeedrate[Z_AXIS]);
|
||||
Commands::waitUntilEndOfAllMoves();
|
||||
#if ZHOME_HEAT_ALL
|
||||
for(int i = 0; i < NUM_EXTRUDER; i++) {
|
||||
Extruder::setTemperatureForExtruder(RMath::max(actTemp[i], static_cast<float>(ZPROBE_MIN_TEMPERATURE)), i, false, false);
|
||||
}
|
||||
for(int i = 0; i < NUM_EXTRUDER; i++) {
|
||||
if(extruder[i].tempControl.currentTemperatureC < ZPROBE_MIN_TEMPERATURE)
|
||||
Extruder::setTemperatureForExtruder(RMath::max(actTemp[i], static_cast<float>(ZPROBE_MIN_TEMPERATURE)), i, false, true);
|
||||
}
|
||||
#else
|
||||
if(extruder[Extruder::current->id].tempControl.currentTemperatureC < ZPROBE_MIN_TEMPERATURE)
|
||||
Extruder::setTemperatureForExtruder(RMath::max(actTemp[Extruder::current->id], static_cast<float>(ZPROBE_MIN_TEMPERATURE)), Extruder::current->id, false, true);
|
||||
#endif
|
||||
#endif // defined(Z_PROBE_MIN_TEMPERATURE) && Z_PROBE_MIN_TEMPERATURE && Z_PROBE_REQUIRES_HEATING
|
||||
|
||||
|
||||
float h1, h2, h3, hc, oldFeedrate = Printer::feedrate;
|
||||
#if DISTORTION_CORRECTION
|
||||
bool distEnabled = Printer::distortion.isEnabled();
|
||||
Printer::distortion.disable(false); // if level has changed, distortion is also invalid
|
||||
#endif
|
||||
Printer::setAutolevelActive(false); // iterate
|
||||
Printer::resetTransformationMatrix(true); // in case we switch from matrix to motorized!
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
// It is not possible to go to the edges at the top, also users try
|
||||
// it often and wonder why the coordinate system is then wrong.
|
||||
// For that reason we ensure a correct behavior by code.
|
||||
Printer::homeAxis(true, true, true);
|
||||
Printer::moveTo(IGNORE_COORDINATE, IGNORE_COORDINATE, EEPROM::zProbeBedDistance() + (EEPROM::zProbeHeight() > 0 ? EEPROM::zProbeHeight() : 0), IGNORE_COORDINATE, Printer::homingFeedrate[Z_AXIS]);
|
||||
#else
|
||||
if(!Printer::isXHomed() || !Printer::isYHomed())
|
||||
Printer::homeAxis(true, true, false);
|
||||
Printer::updateCurrentPosition(true);
|
||||
Printer::moveTo(EEPROM::zProbeX1(), EEPROM::zProbeY1(), IGNORE_COORDINATE, IGNORE_COORDINATE, EEPROM::zProbeXYSpeed());
|
||||
#endif
|
||||
Printer::coordinateOffset[X_AXIS] = Printer::coordinateOffset[Y_AXIS] = Printer::coordinateOffset[Z_AXIS] = 0;
|
||||
Printer::startProbing(true);
|
||||
//GCode::executeFString(Com::tZProbeStartScript);
|
||||
Plane plane;
|
||||
#if BED_CORRECTION_METHOD == 1
|
||||
success = false;
|
||||
for(int r = 0; r < BED_LEVELING_REPETITIONS; r++) {
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
if(r > 0) {
|
||||
Printer::finishProbing();
|
||||
Printer::homeAxis(true, true, true);
|
||||
Printer::moveTo(IGNORE_COORDINATE, IGNORE_COORDINATE, EEPROM::zProbeBedDistance() + (EEPROM::zProbeHeight() > 0 ? EEPROM::zProbeHeight() : 0), IGNORE_COORDINATE, Printer::homingFeedrate[Z_AXIS]);
|
||||
Printer::startProbing(true);
|
||||
}
|
||||
#endif // DELTA
|
||||
#endif // BED_CORRECTION_METHOD == 1
|
||||
if(!measureAutolevelPlane(plane)) {
|
||||
Com::printErrorFLN(PSTR("Probing had returned errors - autoleveling canceled."));
|
||||
UI_MESSAGE(1);
|
||||
return false;
|
||||
}
|
||||
correctAutolevel(plane);
|
||||
|
||||
// Leveling is finished now update own positions and store leveling data if needed
|
||||
//float currentZ = plane.z((float)Printer::currentPositionSteps[X_AXIS] * Printer::invAxisStepsPerMM[X_AXIS],(float)Printer::currentPositionSteps[Y_AXIS] * Printer::invAxisStepsPerMM[Y_AXIS]);
|
||||
float currentZ = plane.z(0.0, 0.0); // we rotated around this point, so that is now z height
|
||||
// With max z end stop we adjust z length so after next homing we have also a calibrated printer
|
||||
Printer::zMin = 0;
|
||||
#if MAX_HARDWARE_ENDSTOP_Z
|
||||
//float xRot,yRot,zRot;
|
||||
//Printer::transformFromPrinter(Printer::currentPosition[X_AXIS],Printer::currentPosition[Y_AXIS],Printer::currentPosition[Z_AXIS],xRot,yRot,zRot);
|
||||
//Com::printFLN(PSTR("Z after rotation:"),zRot);
|
||||
// With max z end stop we adjust z length so after next homing we have also a calibrated printer
|
||||
if(s != 0) {
|
||||
// at origin rotations have no influence so use values there to update
|
||||
Printer::zLength += currentZ - Printer::currentPosition[Z_AXIS];
|
||||
//Printer::zLength += /*currentZ*/ plane.z((float)Printer::currentPositionSteps[X_AXIS] * Printer::invAxisStepsPerMM[X_AXIS],(float)Printer::currentPositionSteps[Y_AXIS] * Printer::invAxisStepsPerMM[Y_AXIS]) - zRot;
|
||||
Com::printFLN(Com::tZProbePrinterHeight, Printer::zLength);
|
||||
}
|
||||
#endif
|
||||
#if Z_PROBE_Z_OFFSET_MODE == 1
|
||||
currentZ -= EEPROM::zProbeZOffset();
|
||||
#endif
|
||||
Com::printF(PSTR("CurrentZ:"), currentZ);
|
||||
Com::printFLN(PSTR(" atZ:"), Printer::currentPosition[Z_AXIS]);
|
||||
Printer::currentPositionSteps[Z_AXIS] = currentZ * Printer::axisStepsPerMM[Z_AXIS];
|
||||
Printer::updateCurrentPosition(true); // set position based on steps position
|
||||
#if BED_CORRECTION_METHOD == 1
|
||||
if(fabsf(plane.a) < 0.00025 && fabsf(plane.b) < 0.00025 ) {
|
||||
success = true;
|
||||
break; // we reached achievable precision so we can stop
|
||||
}
|
||||
} // for BED_LEVELING_REPETITIONS
|
||||
#if Z_HOME_DIR > 0 && MAX_HARDWARE_ENDSTOP_Z
|
||||
float zall = Printer::runZProbe(false, false, 1, false);
|
||||
if(zall == ILLEGAL_Z_PROBE)
|
||||
return false;
|
||||
Printer::currentPosition[Z_AXIS] = zall;
|
||||
Printer::currentPositionSteps[Z_AXIS] = zall * Printer::axisStepsPerMM[Z_AXIS];
|
||||
#if NONLINEAR_SYSTEM
|
||||
transformCartesianStepsToDeltaSteps(Printer::currentPositionSteps, Printer::currentNonlinearPositionSteps);
|
||||
#endif
|
||||
if(s >= 1) {
|
||||
float zMax = Printer::runZMaxProbe();
|
||||
if(zMax == ILLEGAL_Z_PROBE)
|
||||
return false;
|
||||
zall += zMax - ENDSTOP_Z_BACK_ON_HOME;
|
||||
Printer::zLength = zall;
|
||||
}
|
||||
#endif
|
||||
#endif // BED_CORRECTION_METHOD == 1
|
||||
Printer::updateDerivedParameter();
|
||||
Printer::finishProbing();
|
||||
#if BED_CORRECTION_METHOD != 1
|
||||
Printer::setAutolevelActive(true); // only for software correction or we can spare the comp. time
|
||||
#endif
|
||||
if(s >= 2) {
|
||||
EEPROM::storeDataIntoEEPROM();
|
||||
}
|
||||
Printer::updateCurrentPosition(true);
|
||||
Commands::printCurrentPosition();
|
||||
#if DISTORTION_CORRECTION
|
||||
if(distEnabled)
|
||||
Printer::distortion.enable(false); // if level has changed, distortion is also invalid
|
||||
#endif
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
Printer::homeAxis(true, true, true); // shifting z makes positioning invalid, need to recalibrate
|
||||
#endif
|
||||
Printer::feedrate = oldFeedrate;
|
||||
|
||||
#if defined(Z_PROBE_MIN_TEMPERATURE) && Z_PROBE_MIN_TEMPERATURE && Z_PROBE_REQUIRES_HEATING
|
||||
#if ZHOME_HEAT_ALL
|
||||
for(int i = 0; i < NUM_EXTRUDER; i++) {
|
||||
Extruder::setTemperatureForExtruder(RMath::max(actTemp[i], static_cast<float>(ZPROBE_MIN_TEMPERATURE)), i, false, false);
|
||||
}
|
||||
for(int i = 0; i < NUM_EXTRUDER; i++) {
|
||||
if(extruder[i].tempControl.currentTemperatureC < ZPROBE_MIN_TEMPERATURE)
|
||||
Extruder::setTemperatureForExtruder(RMath::max(actTemp[i], static_cast<float>(ZPROBE_MIN_TEMPERATURE)), i, false, true);
|
||||
}
|
||||
#else
|
||||
if(extruder[Extruder::current->id].tempControl.currentTemperatureC < ZPROBE_MIN_TEMPERATURE)
|
||||
Extruder::setTemperatureForExtruder(RMath::max(actTemp[Extruder::current->id], static_cast<float>(ZPROBE_MIN_TEMPERATURE)), Extruder::current->id, false, true);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
return success;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/** \brief Activate or deactivate rotation correction.
|
||||
|
||||
\param on True if Rotation correction should be enabled.
|
||||
*/
|
||||
void Printer::setAutolevelActive(bool on) {
|
||||
#if FEATURE_AUTOLEVEL
|
||||
if(on == isAutolevelActive()) return;
|
||||
flag0 = (on ? flag0 | PRINTER_FLAG0_AUTOLEVEL_ACTIVE : flag0 & ~PRINTER_FLAG0_AUTOLEVEL_ACTIVE);
|
||||
if(on)
|
||||
Com::printInfoFLN(Com::tAutolevelEnabled);
|
||||
else
|
||||
Com::printInfoFLN(Com::tAutolevelDisabled);
|
||||
updateCurrentPosition(false);
|
||||
#endif // FEATURE_AUTOLEVEL
|
||||
}
|
||||
#if MAX_HARDWARE_ENDSTOP_Z
|
||||
/** \brief Measure distance from current position until triggering z max endstop.
|
||||
|
||||
\return Distance until triggering in mm. */
|
||||
float Printer::runZMaxProbe() {
|
||||
#if NONLINEAR_SYSTEM
|
||||
long startZ = realDeltaPositionSteps[Z_AXIS] = currentNonlinearPositionSteps[Z_AXIS]; // update real
|
||||
#endif
|
||||
Commands::waitUntilEndOfAllMoves();
|
||||
long probeDepth = 2 * (Printer::zMaxSteps - Printer::zMinSteps);
|
||||
stepsRemainingAtZHit = -1;
|
||||
setZProbingActive(true);
|
||||
PrintLine::moveRelativeDistanceInSteps(0, 0, probeDepth, 0, homingFeedrate[Z_AXIS] / ENDSTOP_Z_RETEST_REDUCTION_FACTOR, true, true);
|
||||
if(stepsRemainingAtZHit < 0) {
|
||||
Com::printErrorFLN(PSTR("z-max homing failed"));
|
||||
return ILLEGAL_Z_PROBE;
|
||||
}
|
||||
setZProbingActive(false);
|
||||
currentPositionSteps[Z_AXIS] -= stepsRemainingAtZHit;
|
||||
#if NONLINEAR_SYSTEM
|
||||
transformCartesianStepsToDeltaSteps(Printer::currentPositionSteps, Printer::currentNonlinearPositionSteps);
|
||||
probeDepth = (realDeltaPositionSteps[Z_AXIS] - startZ);
|
||||
#else
|
||||
probeDepth -= stepsRemainingAtZHit;
|
||||
#endif
|
||||
float distance = (float)probeDepth * invAxisStepsPerMM[Z_AXIS];
|
||||
Com::printF(Com::tZProbeMax, distance);
|
||||
Com::printF(Com::tSpaceXColon, realXPosition());
|
||||
Com::printFLN(Com::tSpaceYColon, realYPosition());
|
||||
PrintLine::moveRelativeDistanceInSteps(0, 0, -probeDepth, 0, homingFeedrate[Z_AXIS], true, true);
|
||||
return distance;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if FEATURE_Z_PROBE
|
||||
/** \brief Activate z-probe
|
||||
|
||||
Tests if switching from active tool to z-probe is possible at current position. If not the operation is aborted.
|
||||
If ok, it runs start script, checks z position and applies the z-probe offset.
|
||||
|
||||
\param runScript Run start z-probe script from configuration.
|
||||
\param enforceStartHeight If true moves z to EEPROM::zProbeBedDistance() + (EEPROM::zProbeHeight() > 0 ? EEPROM::zProbeHeight() : 0) + 0.1 if current position is higher.
|
||||
\return True if activation was successful. */
|
||||
bool Printer::startProbing(bool runScript, bool enforceStartHeight) {
|
||||
float cx, cy, cz;
|
||||
realPosition(cx, cy, cz);
|
||||
// Fix position to be inside print area when probe is enabled
|
||||
#if EXTRUDER_IS_Z_PROBE == 0
|
||||
float ZPOffsetX = EEPROM::zProbeXOffset();
|
||||
float ZPOffsetY = EEPROM::zProbeYOffset();
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
float rad = EEPROM::deltaMaxRadius();
|
||||
float dx = Printer::currentPosition[X_AXIS] - ZPOffsetX;
|
||||
float dy = Printer::currentPosition[Y_AXIS] - ZPOffsetY;
|
||||
if(sqrt(dx * dx + dy * dy) > rad)
|
||||
#else
|
||||
if((ZPOffsetX > 0 && Printer::currentPosition[X_AXIS] - ZPOffsetX < Printer::xMin) ||
|
||||
(ZPOffsetY > 0 && Printer::currentPosition[Y_AXIS] - ZPOffsetY < Printer::yMin) ||
|
||||
(ZPOffsetX < 0 && Printer::currentPosition[X_AXIS] - ZPOffsetX > Printer::xMin + Printer::xLength) ||
|
||||
(ZPOffsetY < 0 && Printer::currentPosition[Y_AXIS] - ZPOffsetY > Printer::yMin + Printer::yLength))
|
||||
#endif
|
||||
{
|
||||
Com::printErrorF(PSTR("Activating z-probe would lead to forbidden xy position: "));
|
||||
Com::print(Printer::currentPosition[X_AXIS] - ZPOffsetX);
|
||||
Com::printFLN(PSTR(", "), Printer::currentPosition[Y_AXIS] - ZPOffsetY);
|
||||
GCode::fatalError(PSTR("Could not activate z-probe offset due to coordinate constraints - result is inaccurate!"));
|
||||
return false;
|
||||
} else {
|
||||
if(runScript) {
|
||||
GCode::executeFString(Com::tZProbeStartScript);
|
||||
}
|
||||
float maxStartHeight = EEPROM::zProbeBedDistance() + (EEPROM::zProbeHeight() > 0 ? EEPROM::zProbeHeight() : 0) + 0.1;
|
||||
if(currentPosition[Z_AXIS] > maxStartHeight && enforceStartHeight) {
|
||||
cz = maxStartHeight;
|
||||
moveTo(IGNORE_COORDINATE, IGNORE_COORDINATE, maxStartHeight, IGNORE_COORDINATE, homingFeedrate[Z_AXIS]);
|
||||
}
|
||||
|
||||
// Update position
|
||||
Printer::offsetX = -ZPOffsetX;
|
||||
Printer::offsetY = -ZPOffsetY;
|
||||
Printer::offsetZ = 0;
|
||||
#if FEATURE_AUTOLEVEL
|
||||
// we must not change z for the probe offset even if we are rotated, so add a correction for z
|
||||
float dx, dy;
|
||||
transformToPrinter(EEPROM::zProbeXOffset(), EEPROM::zProbeYOffset(), 0, dx, dy, offsetZ2);
|
||||
//Com::printFLN(PSTR("ZPOffset2:"),offsetZ2,3);
|
||||
#endif
|
||||
}
|
||||
#else
|
||||
if(runScript) {
|
||||
GCode::executeFString(Com::tZProbeStartScript);
|
||||
}
|
||||
#endif
|
||||
Printer::moveToReal(cx, cy, cz, IGNORE_COORDINATE, EXTRUDER_SWITCH_XY_SPEED);
|
||||
updateCurrentPosition(false);
|
||||
return true;
|
||||
}
|
||||
|
||||
/** \brief Deactivate z-probe. */
|
||||
void Printer::finishProbing() {
|
||||
float cx, cy, cz;
|
||||
realPosition(cx, cy, cz);
|
||||
GCode::executeFString(Com::tZProbeEndScript);
|
||||
if(Extruder::current) {
|
||||
#if DUAL_X_AXIS
|
||||
offsetX = 0; // offsets are parking positions for dual x axis!
|
||||
#else
|
||||
offsetX = -Extruder::current->xOffset * invAxisStepsPerMM[X_AXIS];
|
||||
#endif
|
||||
offsetY = -Extruder::current->yOffset * invAxisStepsPerMM[Y_AXIS];
|
||||
offsetZ = -Extruder::current->zOffset * invAxisStepsPerMM[Z_AXIS];
|
||||
} else {
|
||||
offsetX = offsetY = offsetZ = 0;
|
||||
}
|
||||
offsetZ2 = 0;
|
||||
Printer::moveToReal(cx, cy, cz, IGNORE_COORDINATE, EXTRUDER_SWITCH_XY_SPEED);
|
||||
}
|
||||
|
||||
/** \brief Measure distance to bottom at current position.
|
||||
|
||||
This is the most important function for bed leveling. It does
|
||||
1. Run probe start script if first = true and runStartScript = true
|
||||
2. Position zProbe at current position if first = true. If we are more then maxStartHeight away from bed we also go down to that distance.
|
||||
3. Measure the the steps until probe hits the bed.
|
||||
4. Undo positioning to z probe and run finish script if last = true.
|
||||
|
||||
Now we compute the nozzle height as follows:
|
||||
a) Compute average height from repeated measurements
|
||||
b) Add zProbeHeight to correct difference between triggering point and nozzle height above bed
|
||||
c) If Z_PROBE_Z_OFFSET_MODE == 1 we add zProbeZOffset() that is coating thickness if we measure below coating with indictive sensor.
|
||||
d) Add distortion correction.
|
||||
e) Add bending correction
|
||||
|
||||
Then we return the measured and corrected z distance.
|
||||
|
||||
\param first If true, Printer::startProbing is called.
|
||||
\param last If true, Printer::finishProbing is called at the end.
|
||||
\param repeat Number of repetitions to average measurement errors.
|
||||
\param runStartScript If true tells startProbing to run start script.
|
||||
\param enforceStartHeight Tells start script to enforce a maximum distance to bed.
|
||||
\return ILLEGAL_Z_PROBE on errors or measured distance.
|
||||
*/
|
||||
float Printer::runZProbe(bool first, bool last, uint8_t repeat, bool runStartScript, bool enforceStartHeight) {
|
||||
float oldOffX = Printer::offsetX;
|
||||
float oldOffY = Printer::offsetY;
|
||||
float oldOffZ = Printer::offsetZ;
|
||||
if(first) {
|
||||
if(!startProbing(runStartScript, enforceStartHeight))
|
||||
return ILLEGAL_Z_PROBE;
|
||||
}
|
||||
Commands::waitUntilEndOfAllMoves();
|
||||
#if defined(Z_PROBE_USE_MEDIAN) && Z_PROBE_USE_MEDIAN
|
||||
int32_t measurements[Z_PROBE_REPETITIONS];
|
||||
repeat = RMath::min(repeat, Z_PROBE_REPETITIONS);
|
||||
#else
|
||||
int32_t sum = 0;
|
||||
#endif
|
||||
int32_t probeDepth;
|
||||
int32_t shortMove = static_cast<int32_t>((float)Z_PROBE_SWITCHING_DISTANCE * axisStepsPerMM[Z_AXIS]); // distance to go up for repeated moves
|
||||
int32_t lastCorrection = currentPositionSteps[Z_AXIS]; // starting position
|
||||
#if NONLINEAR_SYSTEM
|
||||
realDeltaPositionSteps[Z_AXIS] = currentNonlinearPositionSteps[Z_AXIS]; // update real
|
||||
#endif
|
||||
//int32_t updateZ = 0;
|
||||
waitForZProbeStart();
|
||||
#if defined(Z_PROBE_DELAY) && Z_PROBE_DELAY > 0
|
||||
HAL::delayMilliseconds(Z_PROBE_DELAY);
|
||||
#endif
|
||||
Endstops::update();
|
||||
Endstops::update(); // need to call twice for full update!
|
||||
if(Endstops::zProbe()) {
|
||||
Com::printErrorFLN(PSTR("z-probe triggered before starting probing."));
|
||||
return ILLEGAL_Z_PROBE;
|
||||
}
|
||||
#if Z_PROBE_DISABLE_HEATERS
|
||||
Extruder::pauseExtruders(true);
|
||||
HAL::delayMilliseconds(70);
|
||||
#endif
|
||||
for(int8_t r = 0; r < repeat; r++) {
|
||||
probeDepth = 2 * (Printer::zMaxSteps - Printer::zMinSteps); // probe should always hit within this distance
|
||||
stepsRemainingAtZHit = -1; // Marker that we did not hit z probe
|
||||
setZProbingActive(true);
|
||||
#if defined(Z_PROBE_DELAY) && Z_PROBE_DELAY > 0
|
||||
HAL::delayMilliseconds(Z_PROBE_DELAY);
|
||||
#endif
|
||||
PrintLine::moveRelativeDistanceInSteps(0, 0, -probeDepth, 0, EEPROM::zProbeSpeed(), true, true);
|
||||
setZProbingActive(false);
|
||||
if(stepsRemainingAtZHit < 0) {
|
||||
Com::printErrorFLN(Com::tZProbeFailed);
|
||||
return ILLEGAL_Z_PROBE;
|
||||
}
|
||||
#if NONLINEAR_SYSTEM
|
||||
stepsRemainingAtZHit = realDeltaPositionSteps[C_TOWER] - currentNonlinearPositionSteps[C_TOWER]; // nonlinear moves may split z so stepsRemainingAtZHit is only what is left from last segment not total move. This corrects the problem.
|
||||
#endif
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
currentNonlinearPositionSteps[A_TOWER] += stepsRemainingAtZHit; // Update difference
|
||||
currentNonlinearPositionSteps[B_TOWER] += stepsRemainingAtZHit;
|
||||
currentNonlinearPositionSteps[C_TOWER] += stepsRemainingAtZHit;
|
||||
#elif NONLINEAR_SYSTEM
|
||||
currentNonlinearPositionSteps[Z_AXIS] += stepsRemainingAtZHit;
|
||||
#endif
|
||||
currentPositionSteps[Z_AXIS] += stepsRemainingAtZHit; // now current position is correct
|
||||
#if defined(Z_PROBE_USE_MEDIAN) && Z_PROBE_USE_MEDIAN
|
||||
measurements[r] = lastCorrection - currentPositionSteps[Z_AXIS];
|
||||
#else
|
||||
sum += lastCorrection - currentPositionSteps[Z_AXIS];
|
||||
#endif
|
||||
//Com::printFLN(PSTR("ZHSteps:"),lastCorrection - currentPositionSteps[Z_AXIS]);
|
||||
if(r + 1 < repeat) {
|
||||
// go only shortest possible move up for repetitions
|
||||
PrintLine::moveRelativeDistanceInSteps(0, 0, shortMove, 0, HOMING_FEEDRATE_Z, true, true);
|
||||
if(Endstops::zProbe()) {
|
||||
Com::printErrorFLN(PSTR("z-probe did not untrigger on repetitive measurement - maybe you need to increase distance!"));
|
||||
UI_MESSAGE(1);
|
||||
return ILLEGAL_Z_PROBE;
|
||||
}
|
||||
}
|
||||
#ifdef Z_PROBE_RUN_AFTER_EVERY_PROBE
|
||||
GCode::executeFString(PSTR(Z_PROBE_RUN_AFTER_EVERY_PROBE));
|
||||
#endif
|
||||
}
|
||||
#if Z_PROBE_DISABLE_HEATERS
|
||||
Extruder::unpauseExtruders(false);
|
||||
#endif
|
||||
|
||||
// Go back to start position
|
||||
PrintLine::moveRelativeDistanceInSteps(0, 0, lastCorrection - currentPositionSteps[Z_AXIS], 0, HOMING_FEEDRATE_Z, true, true);
|
||||
if(Endstops::zProbe()) { // did we untrigger? If not don't trust result!
|
||||
Com::printErrorFLN(PSTR("z-probe did not untrigger on repetitive measurement - maybe you need to increase distance!"));
|
||||
UI_MESSAGE(1);
|
||||
return ILLEGAL_Z_PROBE;
|
||||
}
|
||||
updateCurrentPosition(false);
|
||||
//Com::printFLN(PSTR("after probe"));
|
||||
//Commands::printCurrentPosition();
|
||||
#if defined(Z_PROBE_USE_MEDIAN) && Z_PROBE_USE_MEDIAN
|
||||
// bubble sort the measurements
|
||||
int32_t tmp;
|
||||
for(fast8_t i = 0 ; i < repeat - 1; i++) { // n numbers require at most n-1 rounds of swapping
|
||||
for(fast8_t j = 0; j < repeat - i - 1; j++) { //
|
||||
if( measurements[j] > measurements[j + 1] ) { // out of order?
|
||||
tmp = measurements[j]; // swap them:
|
||||
measurements[j] = measurements[j + 1];
|
||||
measurements[j + 1] = tmp;
|
||||
}
|
||||
}
|
||||
}
|
||||
// process result
|
||||
float distance = static_cast<float>(measurements[repeat >> 1]) * invAxisStepsPerMM[Z_AXIS] + EEPROM::zProbeHeight();
|
||||
#else
|
||||
float distance = static_cast<float>(sum) * invAxisStepsPerMM[Z_AXIS] / static_cast<float>(repeat) + EEPROM::zProbeHeight();
|
||||
#endif
|
||||
#if FEATURE_AUTOLEVEL
|
||||
// we must change z for the z change from moving in rotated coordinates away from real position
|
||||
float dx, dy, dz;
|
||||
transformToPrinter(0, 0, currentPosition[Z_AXIS], dx, dy, dz); // what is our x,y offset from z position
|
||||
dz -= currentPosition[Z_AXIS];
|
||||
//Com::printF(PSTR("ZXO:"),dx,3);Com::printF(PSTR(" ZYO:"),dy,3);
|
||||
//transformToPrinter(dx,dy,0,dx,dy,dz); // how much changes z from x,y offset?
|
||||
//Com::printFLN(PSTR(" Z from xy off:"), dz,7);
|
||||
distance += dz;
|
||||
#endif
|
||||
//Com::printFLN(PSTR("OrigDistance:"),distance);
|
||||
#if Z_PROBE_Z_OFFSET_MODE == 1
|
||||
distance += EEPROM::zProbeZOffset(); // We measured including coating, so we need to add coating thickness!
|
||||
#endif
|
||||
|
||||
#if DISTORTION_CORRECTION
|
||||
float zCorr = 0;
|
||||
if(Printer::distortion.isEnabled()) {
|
||||
zCorr = distortion.correct(currentPositionSteps[X_AXIS]/* + EEPROM::zProbeXOffset() * axisStepsPerMM[X_AXIS]*/, currentPositionSteps[Y_AXIS]
|
||||
/* + EEPROM::zProbeYOffset() * axisStepsPerMM[Y_AXIS]*/, zMinSteps) * invAxisStepsPerMM[Z_AXIS];
|
||||
distance += zCorr;
|
||||
}
|
||||
#endif
|
||||
|
||||
distance += bendingCorrectionAt(currentPosition[X_AXIS], currentPosition[Y_AXIS]);
|
||||
|
||||
Com::printF(Com::tZProbe, distance, 3);
|
||||
Com::printF(Com::tSpaceXColon, realXPosition());
|
||||
#if DISTORTION_CORRECTION
|
||||
if(Printer::distortion.isEnabled()) {
|
||||
Com::printF(Com::tSpaceYColon, realYPosition());
|
||||
Com::printFLN(PSTR(" zCorr:"), zCorr, 3);
|
||||
} else {
|
||||
Com::printFLN(Com::tSpaceYColon, realYPosition());
|
||||
}
|
||||
#else
|
||||
Com::printFLN(Com::tSpaceYColon, realYPosition());
|
||||
#endif
|
||||
if(Endstops::zProbe()) {
|
||||
Com::printErrorFLN(PSTR("z-probe did not untrigger after going back to start position."));
|
||||
UI_MESSAGE(1);
|
||||
return ILLEGAL_Z_PROBE;
|
||||
}
|
||||
if(last)
|
||||
finishProbing();
|
||||
return distance;
|
||||
}
|
||||
|
||||
/**
|
||||
* Having printer's height set properly (i.e. after calibration of Z=0), one can use this procedure to measure Z-probe height.
|
||||
* It deploys the sensor, takes several probes at center, then updates Z-probe height with average.
|
||||
*/
|
||||
void Printer::measureZProbeHeight(float curHeight) {
|
||||
#if FEATURE_Z_PROBE
|
||||
currentPositionSteps[Z_AXIS] = curHeight * axisStepsPerMM[Z_AXIS];
|
||||
updateCurrentPosition(true);
|
||||
#if NONLINEAR_SYSTEM
|
||||
transformCartesianStepsToDeltaSteps(currentPositionSteps, currentNonlinearPositionSteps);
|
||||
#endif
|
||||
float startHeight = EEPROM::zProbeBedDistance() + (EEPROM::zProbeHeight() > 0 ? EEPROM::zProbeHeight() : 0);
|
||||
moveTo(IGNORE_COORDINATE, IGNORE_COORDINATE, startHeight, IGNORE_COORDINATE, homingFeedrate[Z_AXIS]);
|
||||
float zheight = Printer::runZProbe(true, true, Z_PROBE_REPETITIONS, true);
|
||||
if(zheight == ILLEGAL_Z_PROBE) {
|
||||
return;
|
||||
}
|
||||
float zProbeHeight = EEPROM::zProbeHeight() + startHeight -zheight;
|
||||
|
||||
#if EEPROM_MODE != 0 // Com::tZProbeHeight is not declared when EEPROM_MODE is 0
|
||||
EEPROM::setZProbeHeight(zProbeHeight); // will also report on output
|
||||
#else
|
||||
Com::printFLN(PSTR("Z-probe height [mm]:"), zProbeHeight);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
float Printer::bendingCorrectionAt(float x, float y) {
|
||||
PlaneBuilder builder;
|
||||
builder.addPoint(EEPROM::zProbeX1(), EEPROM::zProbeY1(), EEPROM::bendingCorrectionA());
|
||||
builder.addPoint(EEPROM::zProbeX2(), EEPROM::zProbeY2(), EEPROM::bendingCorrectionB());
|
||||
builder.addPoint(EEPROM::zProbeX3(), EEPROM::zProbeY3(), EEPROM::bendingCorrectionC());
|
||||
Plane plane;
|
||||
builder.createPlane(plane, true);
|
||||
return plane.z(x, y);
|
||||
}
|
||||
|
||||
void Printer::waitForZProbeStart() {
|
||||
#if Z_PROBE_WAIT_BEFORE_TEST
|
||||
Endstops::update();
|
||||
Endstops::update(); // double test to get right signal. Needed for crosstalk protection.
|
||||
if(Endstops::zProbe()) return;
|
||||
#if UI_DISPLAY_TYPE != NO_DISPLAY
|
||||
uid.setStatusP(Com::tHitZProbe);
|
||||
uid.refreshPage();
|
||||
#endif
|
||||
#ifdef DEBUG_PRINT
|
||||
debugWaitLoop = 3;
|
||||
#endif
|
||||
while(!Endstops::zProbe()) {
|
||||
defaultLoopActions();
|
||||
Endstops::update();
|
||||
Endstops::update(); // double test to get right signal. Needed for crosstalk protection.
|
||||
}
|
||||
#ifdef DEBUG_PRINT
|
||||
debugWaitLoop = 4;
|
||||
#endif
|
||||
HAL::delayMilliseconds(30);
|
||||
while(Endstops::zProbe()) {
|
||||
defaultLoopActions();
|
||||
Endstops::update();
|
||||
Endstops::update(); // double test to get right signal. Needed for crosstalk protection.
|
||||
}
|
||||
HAL::delayMilliseconds(30);
|
||||
UI_CLEAR_STATUS;
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
Transforms theoretical correct coordinates to corrected coordinates resulting from bed rotation
|
||||
and shear transformations.
|
||||
|
||||
We have 2 coordinate systems. The printer step position where we want to be. These are the positions
|
||||
we send to printers, the theoretical coordinates. In contrast we have the printer coordinates that
|
||||
we need to be at to get the desired result, the real coordinates.
|
||||
*/
|
||||
void Printer::transformToPrinter(float x, float y, float z, float &transX, float &transY, float &transZ) {
|
||||
#if FEATURE_AXISCOMP
|
||||
// Axis compensation:
|
||||
x = x + y * EEPROM::axisCompTanXY() + z * EEPROM::axisCompTanXZ();
|
||||
y = y + z * EEPROM::axisCompTanYZ();
|
||||
#endif
|
||||
#if BED_CORRECTION_METHOD != 1 && FEATURE_AUTOLEVEL
|
||||
if(isAutolevelActive()) {
|
||||
transX = x * autolevelTransformation[0] + y * autolevelTransformation[3] + z * autolevelTransformation[6];
|
||||
transY = x * autolevelTransformation[1] + y * autolevelTransformation[4] + z * autolevelTransformation[7];
|
||||
transZ = x * autolevelTransformation[2] + y * autolevelTransformation[5] + z * autolevelTransformation[8];
|
||||
} else {
|
||||
transX = x;
|
||||
transY = y;
|
||||
transZ = z;
|
||||
}
|
||||
#else
|
||||
transX = x;
|
||||
transY = y;
|
||||
transZ = z;
|
||||
#endif
|
||||
}
|
||||
|
||||
/* Transform back to real printer coordinates. */
|
||||
void Printer::transformFromPrinter(float x, float y, float z, float &transX, float &transY, float &transZ) {
|
||||
#if BED_CORRECTION_METHOD != 1 && FEATURE_AUTOLEVEL
|
||||
if(isAutolevelActive()) {
|
||||
transX = x * autolevelTransformation[0] + y * autolevelTransformation[1] + z * autolevelTransformation[2];
|
||||
transY = x * autolevelTransformation[3] + y * autolevelTransformation[4] + z * autolevelTransformation[5];
|
||||
transZ = x * autolevelTransformation[6] + y * autolevelTransformation[7] + z * autolevelTransformation[8];
|
||||
} else {
|
||||
transX = x;
|
||||
transY = y;
|
||||
transZ = z;
|
||||
}
|
||||
#else
|
||||
transX = x;
|
||||
transY = y;
|
||||
transZ = z;
|
||||
#endif
|
||||
#if FEATURE_AXISCOMP
|
||||
// Axis compensation:
|
||||
transY = transY - transZ * EEPROM::axisCompTanYZ();
|
||||
transX = transX - transY * EEPROM::axisCompTanXY() - transZ * EEPROM::axisCompTanXZ();
|
||||
#endif
|
||||
}
|
||||
#if FEATURE_AUTOLEVEL
|
||||
void Printer::resetTransformationMatrix(bool silent) {
|
||||
autolevelTransformation[0] = autolevelTransformation[4] = autolevelTransformation[8] = 1;
|
||||
autolevelTransformation[1] = autolevelTransformation[2] = autolevelTransformation[3] =
|
||||
autolevelTransformation[5] = autolevelTransformation[6] = autolevelTransformation[7] = 0;
|
||||
if(!silent)
|
||||
Com::printInfoFLN(Com::tAutolevelReset);
|
||||
}
|
||||
|
||||
void Printer::buildTransformationMatrix(Plane &plane) {
|
||||
float z0 = plane.z(0, 0);
|
||||
float az = z0 - plane.z(1, 0); // ax = 1, ay = 0
|
||||
float bz = z0 - plane.z(0, 1); // bx = 0, by = 1
|
||||
// First z direction
|
||||
autolevelTransformation[6] = -az;
|
||||
autolevelTransformation[7] = -bz;
|
||||
autolevelTransformation[8] = 1;
|
||||
float len = sqrt(az * az + bz * bz + 1);
|
||||
autolevelTransformation[6] /= len;
|
||||
autolevelTransformation[7] /= len;
|
||||
autolevelTransformation[8] /= len;
|
||||
autolevelTransformation[0] = 1;
|
||||
autolevelTransformation[1] = 0;
|
||||
autolevelTransformation[2] = -autolevelTransformation[6] / autolevelTransformation[8];
|
||||
len = sqrt(autolevelTransformation[0] * autolevelTransformation[0] + autolevelTransformation[1] * autolevelTransformation[1] + autolevelTransformation[2] * autolevelTransformation[2]);
|
||||
autolevelTransformation[0] /= len;
|
||||
autolevelTransformation[1] /= len;
|
||||
autolevelTransformation[2] /= len;
|
||||
// cross(z,x) y,z)
|
||||
autolevelTransformation[3] = autolevelTransformation[7] * autolevelTransformation[2] - autolevelTransformation[8] * autolevelTransformation[1];
|
||||
autolevelTransformation[4] = autolevelTransformation[8] * autolevelTransformation[0] - autolevelTransformation[6] * autolevelTransformation[2];
|
||||
autolevelTransformation[5] = autolevelTransformation[6] * autolevelTransformation[1] - autolevelTransformation[7] * autolevelTransformation[0];
|
||||
len = sqrt(autolevelTransformation[3] * autolevelTransformation[3] + autolevelTransformation[4] * autolevelTransformation[4] + autolevelTransformation[5] * autolevelTransformation[5]);
|
||||
autolevelTransformation[3] /= len;
|
||||
autolevelTransformation[4] /= len;
|
||||
autolevelTransformation[5] /= len;
|
||||
|
||||
Com::printArrayFLN(Com::tTransformationMatrix, autolevelTransformation, 9, 6);
|
||||
}
|
||||
/*
|
||||
void Printer::buildTransformationMatrix(float h1,float h2,float h3) {
|
||||
float ax = EEPROM::zProbeX2() - EEPROM::zProbeX1();
|
||||
float ay = EEPROM::zProbeY2() - EEPROM::zProbeY1();
|
||||
float az = h1 - h2;
|
||||
float bx = EEPROM::zProbeX3() - EEPROM::zProbeX1();
|
||||
float by = EEPROM::zProbeY3() - EEPROM::zProbeY1();
|
||||
float bz = h1 - h3;
|
||||
// First z direction
|
||||
autolevelTransformation[6] = ay * bz - az * by;
|
||||
autolevelTransformation[7] = az * bx - ax * bz;
|
||||
autolevelTransformation[8] = ax * by - ay * bx;
|
||||
float len = sqrt(autolevelTransformation[6] * autolevelTransformation[6] + autolevelTransformation[7] * autolevelTransformation[7] + autolevelTransformation[8] * autolevelTransformation[8]);
|
||||
if(autolevelTransformation[8] < 0) len = -len;
|
||||
autolevelTransformation[6] /= len;
|
||||
autolevelTransformation[7] /= len;
|
||||
autolevelTransformation[8] /= len;
|
||||
autolevelTransformation[3] = 0;
|
||||
autolevelTransformation[4] = autolevelTransformation[8];
|
||||
autolevelTransformation[5] = -autolevelTransformation[7];
|
||||
// cross(y,z)
|
||||
autolevelTransformation[0] = autolevelTransformation[4] * autolevelTransformation[8] - autolevelTransformation[5] * autolevelTransformation[7];
|
||||
autolevelTransformation[1] = autolevelTransformation[5] * autolevelTransformation[6];// - autolevelTransformation[3] * autolevelTransformation[8];
|
||||
autolevelTransformation[2] = autolevelTransformation[3] * autolevelTransformation[7] - autolevelTransformation[4] * autolevelTransformation[6];
|
||||
len = sqrt(autolevelTransformation[0] * autolevelTransformation[0] + autolevelTransformation[1] * autolevelTransformation[1] + autolevelTransformation[2] * autolevelTransformation[2]);
|
||||
autolevelTransformation[0] /= len;
|
||||
autolevelTransformation[1] /= len;
|
||||
autolevelTransformation[2] /= len;
|
||||
len = sqrt(autolevelTransformation[4] * autolevelTransformation[4] + autolevelTransformation[5] * autolevelTransformation[5]);
|
||||
autolevelTransformation[4] /= len;
|
||||
autolevelTransformation[5] /= len;
|
||||
Com::printArrayFLN(Com::tTransformationMatrix,autolevelTransformation, 9, 6);
|
||||
}
|
||||
*/
|
||||
#endif
|
3000
Repetier-Firmware 1.0.3/Repetier/Commands.cpp
Normal file
3000
Repetier-Firmware 1.0.3/Repetier/Commands.cpp
Normal file
File diff suppressed because it is too large
Load Diff
53
Repetier-Firmware 1.0.3/Repetier/Commands.h
Normal file
53
Repetier-Firmware 1.0.3/Repetier/Commands.h
Normal file
@ -0,0 +1,53 @@
|
||||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware 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.
|
||||
|
||||
Repetier-Firmware 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 Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
This firmware is a nearly complete rewrite of the sprinter firmware
|
||||
by kliment (https://github.com/kliment/Sprinter)
|
||||
which based on Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
|
||||
|
||||
Functions in this file are used to communicate using ascii or repetier protocol.
|
||||
*/
|
||||
|
||||
#ifndef COMMANDS_H_INCLUDED
|
||||
#define COMMANDS_H_INCLUDED
|
||||
|
||||
class Commands
|
||||
{
|
||||
public:
|
||||
static void commandLoop();
|
||||
static void checkForPeriodicalActions(bool allowNewMoves);
|
||||
static void processArc(GCode *com);
|
||||
static void processGCode(GCode *com);
|
||||
static void processMCode(GCode *com);
|
||||
static void executeGCode(GCode *com);
|
||||
static void waitUntilEndOfAllMoves();
|
||||
static void waitUntilEndOfAllBuffers();
|
||||
static void printCurrentPosition();
|
||||
static void printTemperatures(bool showRaw = false);
|
||||
static void setFanSpeed(int speed, bool immediately = false); /// Set fan speed 0..255
|
||||
static void setFan2Speed(int speed); /// Set fan speed 0..255
|
||||
static void changeFeedrateMultiply(int factorInPercent);
|
||||
static void changeFlowrateMultiply(int factorInPercent);
|
||||
static void reportPrinterUsage();
|
||||
static void emergencyStop();
|
||||
static void checkFreeMemory();
|
||||
static void writeLowestFreeRAM();
|
||||
private:
|
||||
static int lowestRAMValue;
|
||||
static int lowestRAMValueSend;
|
||||
};
|
||||
|
||||
#endif // COMMANDS_H_INCLUDED
|
663
Repetier-Firmware 1.0.3/Repetier/Communication.cpp
Normal file
663
Repetier-Firmware 1.0.3/Repetier/Communication.cpp
Normal file
@ -0,0 +1,663 @@
|
||||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware 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.
|
||||
|
||||
Repetier-Firmware 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 Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
This firmware is a nearly complete rewrite of the sprinter firmware
|
||||
by kliment (https://github.com/kliment/Sprinter)
|
||||
which based on Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
|
||||
*/
|
||||
|
||||
#include "Repetier.h"
|
||||
|
||||
#if FEATURE_CONTROLLER != NO_CONTROLLER
|
||||
uint8_t Com::selectedLanguage;
|
||||
#endif
|
||||
|
||||
#ifndef MACHINE_TYPE
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
#define MACHINE_TYPE "Delta"
|
||||
#elif DRIVE_SYSTEM == CARTESIAN
|
||||
#define MACHINE_TYPE "Mendel"
|
||||
#else
|
||||
#define MACHINE_TYPE "Core_XY"
|
||||
#endif
|
||||
#endif
|
||||
#ifndef FIRMWARE_URL
|
||||
#define FIRMWARE_URL "https://github.com/repetier/Repetier-Firmware/"
|
||||
#endif // FIRMWARE_URL
|
||||
|
||||
FSTRINGVALUE(Com::tFirmware, "FIRMWARE_NAME:Repetier_" REPETIER_VERSION " COMPILED:" __DATE__ " FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:1.0 MACHINE_TYPE:" MACHINE_TYPE " EXTRUDER_COUNT:" XSTR(NUM_EXTRUDER) " REPETIER_PROTOCOL:3")
|
||||
FSTRINGVALUE(Com::tDebug, "Debug:")
|
||||
FSTRINGVALUE(Com::tOk, "ok")
|
||||
FSTRINGVALUE(Com::tNewline, "\r\n")
|
||||
FSTRINGVALUE(Com::tNAN, "NAN")
|
||||
FSTRINGVALUE(Com::tINF, "INF")
|
||||
FSTRINGVALUE(Com::tError, "Error:")
|
||||
FSTRINGVALUE(Com::tInfo, "Info:")
|
||||
FSTRINGVALUE(Com::tWarning, "Warning:")
|
||||
FSTRINGVALUE(Com::tResend, "Resend:")
|
||||
FSTRINGVALUE(Com::tEcho, "Echo:")
|
||||
FSTRINGVALUE(Com::tCap, "Cap:")
|
||||
FSTRINGVALUE(Com::tOkSpace, "ok ")
|
||||
FSTRINGVALUE(Com::tWrongChecksum, "Wrong checksum")
|
||||
FSTRINGVALUE(Com::tMissingChecksum, "Missing checksum")
|
||||
FSTRINGVALUE(Com::tFormatError, "Format error")
|
||||
FSTRINGVALUE(Com::tDonePrinting, "Done printing file")
|
||||
FSTRINGVALUE(Com::tX, " X")
|
||||
FSTRINGVALUE(Com::tY, " Y")
|
||||
FSTRINGVALUE(Com::tZ, " Z")
|
||||
FSTRINGVALUE(Com::tE, " E")
|
||||
FSTRINGVALUE(Com::tF, " F")
|
||||
FSTRINGVALUE(Com::tS, " S")
|
||||
FSTRINGVALUE(Com::tP, " P")
|
||||
FSTRINGVALUE(Com::tI, " I")
|
||||
FSTRINGVALUE(Com::tJ, " J")
|
||||
FSTRINGVALUE(Com::tR, " R")
|
||||
FSTRINGVALUE(Com::tD, " D")
|
||||
FSTRINGVALUE(Com::tC, " C")
|
||||
FSTRINGVALUE(Com::tH, " H")
|
||||
FSTRINGVALUE(Com::tA, " A")
|
||||
FSTRINGVALUE(Com::tB, " B")
|
||||
FSTRINGVALUE(Com::tK, " K")
|
||||
FSTRINGVALUE(Com::tL, " L")
|
||||
FSTRINGVALUE(Com::tO, " O")
|
||||
FSTRINGVALUE(Com::tSDReadError, "SD read error")
|
||||
FSTRINGVALUE(Com::tExpectedLine, "Error:expected line ")
|
||||
FSTRINGVALUE(Com::tGot, " got ")
|
||||
FSTRINGVALUE(Com::tSkip, "skip ")
|
||||
FSTRINGVALUE(Com::tBLK, "BLK ")
|
||||
FSTRINGVALUE(Com::tStart, "start")
|
||||
FSTRINGVALUE(Com::tPowerUp, "PowerUp")
|
||||
FSTRINGVALUE(Com::tExternalReset, "External Reset")
|
||||
FSTRINGVALUE(Com::tBrownOut, "Brown out Reset")
|
||||
FSTRINGVALUE(Com::tWatchdog, "Watchdog Reset")
|
||||
FSTRINGVALUE(Com::tSoftwareReset, "Software Reset")
|
||||
FSTRINGVALUE(Com::tUnknownCommand, "Unknown command:")
|
||||
FSTRINGVALUE(Com::tFreeRAM, "Free RAM:")
|
||||
FSTRINGVALUE(Com::tXColon, "X:")
|
||||
FSTRINGVALUE(Com::tSpaceXColon, " X:")
|
||||
FSTRINGVALUE(Com::tSpaceYColon, " Y:")
|
||||
FSTRINGVALUE(Com::tSpaceZColon, " Z:")
|
||||
FSTRINGVALUE(Com::tSpaceEColon, " E:")
|
||||
FSTRINGVALUE(Com::tTColon, "T:")
|
||||
FSTRINGVALUE(Com::tSpaceBColon, " B:")
|
||||
FSTRINGVALUE(Com::tSpaceAtColon, " @:")
|
||||
FSTRINGVALUE(Com::tSpaceT, " T")
|
||||
FSTRINGVALUE(Com::tSpaceAt, " @")
|
||||
FSTRINGVALUE(Com::tSpaceBAtColon, " B@:")
|
||||
FSTRINGVALUE(Com::tSpaceRaw, " RAW")
|
||||
FSTRINGVALUE(Com::tColon, ":")
|
||||
FSTRINGVALUE(Com::tSlash, "/")
|
||||
FSTRINGVALUE(Com::tSpaceSlash, " /")
|
||||
FSTRINGVALUE(Com::tFatal, "fatal:")
|
||||
FSTRINGVALUE(Com::tDoorOpen, "Door open")
|
||||
#if JSON_OUTPUT
|
||||
FSTRINGVALUE(Com::tJSONDir, "{\"dir\":\"")
|
||||
FSTRINGVALUE(Com::tJSONFiles, "\",\"files\":[")
|
||||
FSTRINGVALUE(Com::tJSONArrayEnd, "]}")
|
||||
FSTRINGVALUE(Com::tJSONErrorStart, "{\"err\":\"")
|
||||
FSTRINGVALUE(Com::tJSONErrorEnd, "\"}")
|
||||
FSTRINGVALUE(Com::tJSONFileInfoStart, "{\"err\":0,\"size\":");
|
||||
FSTRINGVALUE(Com::tJSONFileInfoHeight, ",\"height\":");
|
||||
FSTRINGVALUE(Com::tJSONFileInfoLayerHeight, ",\"layerHeight\":");
|
||||
FSTRINGVALUE(Com::tJSONFileInfoFilament, ",\"filament\":[");
|
||||
FSTRINGVALUE(Com::tJSONFileInfoGeneratedBy, "],\"generatedBy\":\"");
|
||||
FSTRINGVALUE(Com::tJSONFileInfoName, ",\"fileName\":\"");
|
||||
#endif // JSON_OUTPUT
|
||||
FSTRINGVALUE(Com::tSpeedMultiply, "SpeedMultiply:")
|
||||
FSTRINGVALUE(Com::tFlowMultiply, "FlowMultiply:")
|
||||
FSTRINGVALUE(Com::tFanspeed, "Fanspeed:")
|
||||
FSTRINGVALUE(Com::tFan2speed, "Fanspeed2:")
|
||||
FSTRINGVALUE(Com::tPrintedFilament, "Printed filament:")
|
||||
FSTRINGVALUE(Com::tPrintingTime, "Printing time:")
|
||||
FSTRINGVALUE(Com::tSpacem, "m ")
|
||||
FSTRINGVALUE(Com::tSpaceDaysSpace, " days ")
|
||||
FSTRINGVALUE(Com::tSpaceHoursSpace, " hours ")
|
||||
FSTRINGVALUE(Com::tSpaceMin, " min")
|
||||
FSTRINGVALUE(Com::tInvalidArc, "Invalid arc")
|
||||
FSTRINGVALUE(Com::tComma, ",")
|
||||
FSTRINGVALUE(Com::tSpace, " ")
|
||||
FSTRINGVALUE(Com::tYColon, "Y:")
|
||||
FSTRINGVALUE(Com::tZColon, "Z:")
|
||||
FSTRINGVALUE(Com::tE0Colon, "E0:")
|
||||
FSTRINGVALUE(Com::tE1Colon, "E1:")
|
||||
FSTRINGVALUE(Com::tMS1MS2Pins, "MS1,MS2 Pins")
|
||||
FSTRINGVALUE(Com::tSetOutputSpace, "Set output: ")
|
||||
FSTRINGVALUE(Com::tGetInputSpace, "Get Input: ")
|
||||
FSTRINGVALUE(Com::tSpaceToSpace, " to ")
|
||||
FSTRINGVALUE(Com::tSpaceIsSpace, " is ")
|
||||
FSTRINGVALUE(Com::tHSpace, "H ")
|
||||
FSTRINGVALUE(Com::tLSpace, "L ")
|
||||
FSTRINGVALUE(Com::tXMinColon, "x_min:")
|
||||
FSTRINGVALUE(Com::tXMaxColon, "x_max:")
|
||||
FSTRINGVALUE(Com::tYMinColon, "y_min:")
|
||||
FSTRINGVALUE(Com::tYMaxColon, "y_max:")
|
||||
FSTRINGVALUE(Com::tZMinColon, "z_min:")
|
||||
FSTRINGVALUE(Com::tZMaxColon, "z_max:")
|
||||
FSTRINGVALUE(Com::tZ2MinMaxColon, "z2_minmax:")
|
||||
FSTRINGVALUE(Com::tJerkColon, "Jerk:")
|
||||
FSTRINGVALUE(Com::tZJerkColon, " ZJerk:")
|
||||
FSTRINGVALUE(Com::tLinearStepsColon, " linear steps:")
|
||||
FSTRINGVALUE(Com::tQuadraticStepsColon, " quadratic steps:")
|
||||
FSTRINGVALUE(Com::tCommaSpeedEqual, ", speed=")
|
||||
FSTRINGVALUE(Com::tEEPROMUpdated, "EEPROM updated")
|
||||
|
||||
FSTRINGVALUE(Com::tLinearLColon, "linear L:")
|
||||
FSTRINGVALUE(Com::tQuadraticKColon, " quadratic K:")
|
||||
FSTRINGVALUE(Com::tFilamentSlipping, "Filament slipping")
|
||||
FSTRINGVALUE(Com::tPauseCommunication, "// action:pause")
|
||||
FSTRINGVALUE(Com::tContinueCommunication, "// action:resume")
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
FSTRINGVALUE(Com::tMeasurementReset, "Measurement reset.")
|
||||
FSTRINGVALUE(Com::tMeasureDeltaSteps, "Measure/delta (Steps) =")
|
||||
FSTRINGVALUE(Com::tMeasureDelta, "Measure/delta =")
|
||||
FSTRINGVALUE(Com::tMeasureOriginReset, "Measured origin set. Measurement reset.")
|
||||
FSTRINGVALUE(Com::tMeasurementAbortedOrigin, "Origin measurement cannot be set. Use only Z-Cartesian (straight up and down) movements and try again.")
|
||||
FSTRINGVALUE(Com::tLevelingCalc, "Leveling calc:")
|
||||
FSTRINGVALUE(Com::tTower1, "Tower 1:")
|
||||
FSTRINGVALUE(Com::tTower2, "Tower 2:")
|
||||
FSTRINGVALUE(Com::tTower3, "Tower 3:")
|
||||
FSTRINGVALUE(Com::tDeltaAlphaA, "Alpha A(210):")
|
||||
FSTRINGVALUE(Com::tDeltaAlphaB, "Alpha B(330):")
|
||||
FSTRINGVALUE(Com::tDeltaAlphaC, "Alpha C(90):")
|
||||
FSTRINGVALUE(Com::tDeltaRadiusCorrectionA, "Delta Radius A(0):")
|
||||
FSTRINGVALUE(Com::tDeltaRadiusCorrectionB, "Delta Radius B(0):")
|
||||
FSTRINGVALUE(Com::tDeltaRadiusCorrectionC, "Delta Radius C(0):")
|
||||
#endif // DRIVE_SYSTEM
|
||||
#if NONLINEAR_SYSTEM
|
||||
#if DRIVE_SYSTEM == TUGA
|
||||
FSTRINGVALUE(Com::tInvalidDeltaCoordinate, "Invalid coordinate - move ignored")
|
||||
FSTRINGVALUE(Com::tDBGDeltaNoMoveinDSegment, "No move in delta segment with > 1 segment. This should never happen and may cause a problem!")
|
||||
#elif DRIVE_SYSTEM == DELTA
|
||||
FSTRINGVALUE(Com::tInvalidDeltaCoordinate, "Invalid delta coordinate - move ignored")
|
||||
FSTRINGVALUE(Com::tDBGDeltaNoMoveinDSegment, "No move in delta segment with > 1 segment. This should never happen and may cause a problem!")
|
||||
#else
|
||||
FSTRINGVALUE(Com::tInvalidDeltaCoordinate, "Invalid coordinate - move ignored")
|
||||
FSTRINGVALUE(Com::tDBGDeltaNoMoveinDSegment, "No move in segment with > 1 segment. This should never happen and may cause a problem!")
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if DRIVE_SYSTEM==TUGA
|
||||
FSTRINGVALUE(Com::tEPRDiagonalRodLength, "Long arm length [mm]")
|
||||
#endif // DRIVE_SYSTEM
|
||||
#ifdef DEBUG_GENERIC
|
||||
FSTRINGVALUE(Com::tGenTemp, "GenTemp:")
|
||||
#endif // DEBUG_GENERICFSTRINGVALUE(Com::,"")
|
||||
FSTRINGVALUE(Com::tTargetExtr, "TargetExtr")
|
||||
FSTRINGVALUE(Com::tTargetBedColon, "TargetBed:")
|
||||
FSTRINGVALUE(Com::tPIDAutotuneStart, "PID Autotune start")
|
||||
FSTRINGVALUE(Com::tAPIDBias, " bias: ")
|
||||
FSTRINGVALUE(Com::tAPIDD, " d: ")
|
||||
FSTRINGVALUE(Com::tAPIDMin, " min: ")
|
||||
FSTRINGVALUE(Com::tAPIDMax, " max: ")
|
||||
FSTRINGVALUE(Com::tAPIDKu, " Ku: ")
|
||||
FSTRINGVALUE(Com::tAPIDTu, " Tu: ")
|
||||
FSTRINGVALUE(Com::tAPIDClassic, " Classic PID")
|
||||
FSTRINGVALUE(Com::tAPIDSome, " Some Overshoot PID")
|
||||
FSTRINGVALUE(Com::tAPIDNone, " No Overshoot PID")
|
||||
FSTRINGVALUE(Com::tAPIDPessen, " Pessen Integral Rule PID")
|
||||
FSTRINGVALUE(Com::tAPIDTyreusLyben," Tyreus-Lyben PID")
|
||||
FSTRINGVALUE(Com::tAPIDKp, " Kp: ")
|
||||
FSTRINGVALUE(Com::tAPIDKi, " Ki: ")
|
||||
FSTRINGVALUE(Com::tAPIDKd, " Kd: ")
|
||||
FSTRINGVALUE(Com::tAPIDFailedHigh, "PID Autotune failed! Temperature too high")
|
||||
FSTRINGVALUE(Com::tAPIDFailedTimeout, "PID Autotune failed! timeout")
|
||||
FSTRINGVALUE(Com::tAPIDFinished, "PID Autotune finished ! Place the Kp, Ki and Kd constants in the Configuration.h or EEPROM")
|
||||
FSTRINGVALUE(Com::tMTEMPColon, "MTEMP:")
|
||||
FSTRINGVALUE(Com::tHeatedBed, "heated bed")
|
||||
FSTRINGVALUE(Com::tExtruderSpace, "extruder ")
|
||||
FSTRINGVALUE(Com::tTempSensorDefect, ": temp sensor defect")
|
||||
FSTRINGVALUE(Com::tTempSensorWorking, ": working")
|
||||
FSTRINGVALUE(Com::tDryModeUntilRestart, "Printer set into dry run mode until restart!")
|
||||
#ifdef DEBUG_QUEUE_MOVE
|
||||
FSTRINGVALUE(Com::tDBGId, "ID:")
|
||||
FSTRINGVALUE(Com::tDBGVStartEnd, "vStart/End:")
|
||||
FSTRINGVALUE(Com::tDBAccelSteps, "accel/decel steps:")
|
||||
FSTRINGVALUE(Com::tDBGStartEndSpeed, "st./end speed:")
|
||||
FSTRINGVALUE(Com::tDBGFlags, "Flags:")
|
||||
FSTRINGVALUE(Com::tDBGJoinFlags, "joinFlags:")
|
||||
FSTRINGVALUE(Com::tDBGDelta, "Delta")
|
||||
FSTRINGVALUE(Com::tDBGDir, "Dir:")
|
||||
FSTRINGVALUE(Com::tDBGFullSpeed, "fullSpeed:")
|
||||
FSTRINGVALUE(Com::tDBGVMax, "vMax:")
|
||||
FSTRINGVALUE(Com::tDBGAcceleration, "Acceleration:")
|
||||
FSTRINGVALUE(Com::tDBGAccelerationPrim, "Acceleration Prim:")
|
||||
FSTRINGVALUE(Com::tDBGRemainingSteps, "Remaining steps:")
|
||||
FSTRINGVALUE(Com::tDBGAdvanceFull, "advanceFull:")
|
||||
FSTRINGVALUE(Com::tDBGAdvanceRate, "advanceRate:")
|
||||
FSTRINGVALUE(Com::tDBGLimitInterval, "LimitInterval:")
|
||||
FSTRINGVALUE(Com::tDBGMoveDistance, "Move distance on the XYZ space:")
|
||||
FSTRINGVALUE(Com::tDBGCommandedFeedrate, "Commanded feedrate:")
|
||||
FSTRINGVALUE(Com::tDBGConstFullSpeedMoveTime, "Constant full speed move time:")
|
||||
#endif // DEBUG_QUEUE_MOVEFSTRINGVALUE(Com::,"")
|
||||
#ifdef DEBUG_DELTA_OVERFLOW
|
||||
FSTRINGVALUE(Com::tDBGDeltaOverflow, "Delta overflow:")
|
||||
#endif // DEBUG_DELTA_OVERFLOW
|
||||
#ifdef DEBUG_SPLIT
|
||||
FSTRINGVALUE(Com::tDBGDeltaSeconds, "Seconds:")
|
||||
FSTRINGVALUE(Com::tDBGDeltaZDelta, "Z delta:")
|
||||
FSTRINGVALUE(Com::tDBGDeltaSegments, "Segments:")
|
||||
FSTRINGVALUE(Com::tDBGDeltaNumLines, "Num lines:")
|
||||
FSTRINGVALUE(Com::tDBGDeltaSegmentsPerLine, "segments_per_line:")
|
||||
FSTRINGVALUE(Com::tDBGDeltaMaxDS, "Max DS:")
|
||||
FSTRINGVALUE(Com::tDBGDeltaStepsPerSegment, "Steps Per Segment:")
|
||||
FSTRINGVALUE(Com::tDBGDeltaVirtualAxisSteps, "Virtual axis steps:")
|
||||
#endif
|
||||
#ifdef DEBUG_STEPCOUNT
|
||||
FSTRINGVALUE(Com::tDBGMissedSteps, "Missed steps:")
|
||||
#endif // DEBUG_STEPCOUNT
|
||||
#if FEATURE_Z_PROBE
|
||||
FSTRINGVALUE(Com::tZProbe, "Z-probe:")
|
||||
FSTRINGVALUE(Com::tZProbeAverage, "Z-probe average height:")
|
||||
FSTRINGVALUE(Com::tZProbeZReset, "Reset Z height")
|
||||
FSTRINGVALUE(Com::tZProbeState, "Z-probe state:")
|
||||
FSTRINGVALUE(Com::tZProbeStartScript, Z_PROBE_START_SCRIPT)
|
||||
FSTRINGVALUE(Com::tZProbeEndScript, Z_PROBE_FINISHED_SCRIPT)
|
||||
FSTRINGVALUE(Com::tHitZProbe, "Hit z-probe")
|
||||
#endif
|
||||
FSTRINGVALUE(Com::tAutolevelReset, "Autolevel matrix reset")
|
||||
FSTRINGVALUE(Com::tAutolevelEnabled, "Autoleveling enabled")
|
||||
FSTRINGVALUE(Com::tAutolevelDisabled, "Autoleveling disabled")
|
||||
FSTRINGVALUE(Com::tTransformationMatrix, "Transformation matrix:")
|
||||
FSTRINGVALUE(Com::tZProbeFailed, "Z-probe failed")
|
||||
FSTRINGVALUE(Com::tZProbeMax, "Z-probe max:")
|
||||
FSTRINGVALUE(Com::tZProbePrinterHeight, "Printer height:")
|
||||
//FSTRINGVALUE(Com::,"")
|
||||
#ifdef WAITING_IDENTIFIER
|
||||
FSTRINGVALUE(Com::tWait, WAITING_IDENTIFIER)
|
||||
#endif // WAITING_IDENTIFIER
|
||||
#if EEPROM_MODE == 0
|
||||
FSTRINGVALUE(Com::tNoEEPROMSupport, "No EEPROM support compiled.\r\n")
|
||||
#else
|
||||
FSTRINGVALUE(Com::tZProbeOffsetZ, "Coating thickness [mm]")
|
||||
#if FEATURE_Z_PROBE
|
||||
FSTRINGVALUE(Com::tZProbeHeight, "Z-probe height [mm]")
|
||||
FSTRINGVALUE(Com::tZProbeBedDitance, "Max. z-probe - bed dist. [mm]")
|
||||
FSTRINGVALUE(Com::tZProbeOffsetX, "Z-probe offset x [mm]")
|
||||
FSTRINGVALUE(Com::tZProbeOffsetY, "Z-probe offset y [mm]")
|
||||
FSTRINGVALUE(Com::tZProbeSpeed, "Z-probe speed [mm/s]")
|
||||
FSTRINGVALUE(Com::tZProbeSpeedXY, "Z-probe x-y-speed [mm/s]")
|
||||
FSTRINGVALUE(Com::tZProbeX1, "Z-probe X1 [mm]")
|
||||
FSTRINGVALUE(Com::tZProbeY1, "Z-probe Y1 [mm]")
|
||||
FSTRINGVALUE(Com::tZProbeX2, "Z-probe X2 [mm]")
|
||||
FSTRINGVALUE(Com::tZProbeY2, "Z-probe Y2 [mm]")
|
||||
FSTRINGVALUE(Com::tZProbeX3, "Z-probe X3 [mm]")
|
||||
FSTRINGVALUE(Com::tZProbeY3, "Z-probe Y3 [mm]")
|
||||
FSTRINGVALUE(Com::zZProbeBendingCorA, "Z-probe bending correction A [mm]")
|
||||
FSTRINGVALUE(Com::zZProbeBendingCorB, "Z-probe bending correction B [mm]")
|
||||
FSTRINGVALUE(Com::zZProbeBendingCorC, "Z-probe bending correction C [mm]")
|
||||
#endif
|
||||
#if FEATURE_AXISCOMP
|
||||
FSTRINGVALUE(Com::tAxisCompTanXY, "tanXY Axis Compensation")
|
||||
FSTRINGVALUE(Com::tAxisCompTanYZ, "tanYZ Axis Compensation")
|
||||
FSTRINGVALUE(Com::tAxisCompTanXZ, "tanXZ Axis Compensation")
|
||||
#endif
|
||||
|
||||
#if FEATURE_AUTOLEVEL
|
||||
FSTRINGVALUE(Com::tAutolevelActive, "Autolevel active (1/0)")
|
||||
#endif
|
||||
FSTRINGVALUE(Com::tConfigStoredEEPROM, "Configuration stored to EEPROM.")
|
||||
FSTRINGVALUE(Com::tConfigLoadedEEPROM, "Configuration loaded from EEPROM.")
|
||||
FSTRINGVALUE(Com::tEPRConfigResetDefaults, "Configuration reset to defaults.")
|
||||
FSTRINGVALUE(Com::tEPRProtocolChanged, "Protocol version changed, upgrading")
|
||||
FSTRINGVALUE(Com::tEPR0, "EPR:0 ")
|
||||
FSTRINGVALUE(Com::tEPR1, "EPR:1 ")
|
||||
FSTRINGVALUE(Com::tEPR2, "EPR:2 ")
|
||||
FSTRINGVALUE(Com::tEPR3, "EPR:3 ")
|
||||
FSTRINGVALUE(Com::tEPRBaudrate, "Baudrate")
|
||||
FSTRINGVALUE(Com::tLanguage, "Language")
|
||||
FSTRINGVALUE(Com::tEPRFilamentPrinted, "Filament printed [m]")
|
||||
FSTRINGVALUE(Com::tEPRPrinterActive, "Printer active [s]")
|
||||
FSTRINGVALUE(Com::tEPRMaxInactiveTime, "Max. inactive time [ms,0=off]")
|
||||
FSTRINGVALUE(Com::tEPRStopAfterInactivty, "Stop stepper after inactivity [ms,0=off]")
|
||||
FSTRINGVALUE(Com::tEPRXHomePos, "X min pos [mm]")
|
||||
FSTRINGVALUE(Com::tEPRYHomePos, "Y min pos [mm]")
|
||||
FSTRINGVALUE(Com::tEPRZHomePos, "Z min pos [mm]")
|
||||
FSTRINGVALUE(Com::tEPRXMaxLength, "X max length [mm]")
|
||||
FSTRINGVALUE(Com::tEPRYMaxLength, "Y max length [mm]")
|
||||
FSTRINGVALUE(Com::tEPRZMaxLength, "Z max length [mm]")
|
||||
FSTRINGVALUE(Com::tEPRXBacklash, "X backlash [mm]")
|
||||
FSTRINGVALUE(Com::tEPRYBacklash, "Y backlash [mm]")
|
||||
FSTRINGVALUE(Com::tEPRZBacklash, "Z backlash [mm]")
|
||||
FSTRINGVALUE(Com::tEPRMaxJerk, "Max. jerk [mm/s]")
|
||||
FSTRINGVALUE(Com::tEPRAccelerationFactorAtTop, "Acceleration factor at top [%,100=like bottom]")
|
||||
#if NONLINEAR_SYSTEM
|
||||
FSTRINGVALUE(Com::tEPRSegmentsPerSecondPrint, "Segments/s for printing")
|
||||
FSTRINGVALUE(Com::tEPRSegmentsPerSecondTravel, "Segments/s for travel")
|
||||
#endif
|
||||
#if DRIVE_SYSTEM==DELTA
|
||||
FSTRINGVALUE(Com::tEPRZAcceleration, "Acceleration [mm/s^2]")
|
||||
FSTRINGVALUE(Com::tEPRZTravelAcceleration, "Travel acceleration [mm/s^2]")
|
||||
FSTRINGVALUE(Com::tEPRZStepsPerMM, "Steps per mm")
|
||||
FSTRINGVALUE(Com::tEPRZMaxFeedrate, "Max. feedrate [mm/s]")
|
||||
FSTRINGVALUE(Com::tEPRZHomingFeedrate, "Homing feedrate [mm/s]")
|
||||
|
||||
FSTRINGVALUE(Com::tEPRDiagonalRodLength, "Diagonal rod length [mm]")
|
||||
FSTRINGVALUE(Com::tEPRHorizontalRadius, "Horizontal rod radius at 0,0 [mm]")
|
||||
|
||||
FSTRINGVALUE(Com::tEPRTowerXOffset, "Tower X endstop offset [steps]")
|
||||
FSTRINGVALUE(Com::tEPRTowerYOffset, "Tower Y endstop offset [steps]")
|
||||
FSTRINGVALUE(Com::tEPRTowerZOffset, "Tower Z endstop offset [steps]")
|
||||
|
||||
FSTRINGVALUE(Com::tEPRDeltaMaxRadius, "Max printable radius [mm]")
|
||||
FSTRINGVALUE(Com::tDeltaDiagonalCorrectionA, "Corr. diagonal A [mm]")
|
||||
FSTRINGVALUE(Com::tDeltaDiagonalCorrectionB, "Corr. diagonal B [mm]")
|
||||
FSTRINGVALUE(Com::tDeltaDiagonalCorrectionC, "Corr. diagonal C [mm]")
|
||||
|
||||
#else
|
||||
FSTRINGVALUE(Com::tEPRMaxZJerk, "Max. Z-jerk [mm/s]")
|
||||
FSTRINGVALUE(Com::tEPRXStepsPerMM, "X-axis steps per mm")
|
||||
#if DUAL_X_RESOLUTION
|
||||
FSTRINGVALUE(Com::tEPRX2StepsPerMM, "X2-axis steps per mm")
|
||||
#endif
|
||||
FSTRINGVALUE(Com::tEPRYStepsPerMM, "Y-axis steps per mm")
|
||||
FSTRINGVALUE(Com::tEPRZStepsPerMM, "Z-axis steps per mm")
|
||||
FSTRINGVALUE(Com::tEPRXMaxFeedrate, "X-axis max. feedrate [mm/s]")
|
||||
FSTRINGVALUE(Com::tEPRYMaxFeedrate, "Y-axis max. feedrate [mm/s]")
|
||||
FSTRINGVALUE(Com::tEPRZMaxFeedrate, "Z-axis max. feedrate [mm/s]")
|
||||
FSTRINGVALUE(Com::tEPRXHomingFeedrate, "X-axis homing feedrate [mm/s]")
|
||||
FSTRINGVALUE(Com::tEPRYHomingFeedrate, "Y-axis homing feedrate [mm/s]")
|
||||
FSTRINGVALUE(Com::tEPRZHomingFeedrate, "Z-axis homing feedrate [mm/s]")
|
||||
FSTRINGVALUE(Com::tEPRXAcceleration, "X-axis acceleration [mm/s^2]")
|
||||
FSTRINGVALUE(Com::tEPRYAcceleration, "Y-axis acceleration [mm/s^2]")
|
||||
FSTRINGVALUE(Com::tEPRZAcceleration, "Z-axis acceleration [mm/s^2]")
|
||||
FSTRINGVALUE(Com::tEPRXTravelAcceleration, "X-axis travel acceleration [mm/s^2]")
|
||||
FSTRINGVALUE(Com::tEPRYTravelAcceleration, "Y-axis travel acceleration [mm/s^2]")
|
||||
FSTRINGVALUE(Com::tEPRZTravelAcceleration, "Z-axis travel acceleration [mm/s^2]")
|
||||
#endif
|
||||
FSTRINGVALUE(Com::tEPROPSMode, "OPS operation mode [0=Off,1=Classic,2=Fast]")
|
||||
FSTRINGVALUE(Com::tEPROPSMoveAfter, "OPS move after x% retract [%]")
|
||||
FSTRINGVALUE(Com::tEPROPSMinDistance, "OPS min. distance for fil. retraction [mm]")
|
||||
FSTRINGVALUE(Com::tEPROPSRetractionLength, "OPS retraction length [mm]")
|
||||
FSTRINGVALUE(Com::tEPROPSRetractionBacklash, "OPS retraction backlash [mm]")
|
||||
FSTRINGVALUE(Com::tEPRBedHeatManager, "Bed Heat Manager [0-3]")
|
||||
FSTRINGVALUE(Com::tEPRBedPIDDriveMax, "Bed PID drive max")
|
||||
FSTRINGVALUE(Com::tEPRBedPIDDriveMin, "Bed PID drive min")
|
||||
FSTRINGVALUE(Com::tEPRBedPGain, "Bed PID P-gain")
|
||||
FSTRINGVALUE(Com::tEPRBedIGain, "Bed PID I-gain")
|
||||
FSTRINGVALUE(Com::tEPRBedDGain, "Bed PID D-gain")
|
||||
FSTRINGVALUE(Com::tEPRBedPISMaxValue, "Bed PID max value [0-255]")
|
||||
FSTRINGVALUE(Com::tEPRStepsPerMM, "steps per mm")
|
||||
FSTRINGVALUE(Com::tEPRMaxFeedrate, "max. feedrate [mm/s]")
|
||||
FSTRINGVALUE(Com::tEPRStartFeedrate, "start feedrate [mm/s]")
|
||||
FSTRINGVALUE(Com::tEPRAcceleration, "acceleration [mm/s^2]")
|
||||
FSTRINGVALUE(Com::tEPRHeatManager, "heat manager [0-3]")
|
||||
FSTRINGVALUE(Com::tEPRDriveMax, "PID drive max")
|
||||
FSTRINGVALUE(Com::tEPRDriveMin, "PID drive min")
|
||||
FSTRINGVALUE(Com::tEPRPGain, "PID P-gain/dead-time")
|
||||
FSTRINGVALUE(Com::tEPRDead, "Heater dead-time")
|
||||
FSTRINGVALUE(Com::tEPRUnused, "na for dead time ctrl")
|
||||
FSTRINGVALUE(Com::tEPRIGain, "PID I-gain")
|
||||
FSTRINGVALUE(Com::tEPRDGain, "PID D-gain")
|
||||
FSTRINGVALUE(Com::tEPRPIDMaxValue, "PID max value [0-255]")
|
||||
FSTRINGVALUE(Com::tEPRXOffset, "X-offset [steps]")
|
||||
FSTRINGVALUE(Com::tEPRYOffset, "Y-offset [steps]")
|
||||
FSTRINGVALUE(Com::tEPRZOffset, "Z-offset [steps]")
|
||||
FSTRINGVALUE(Com::tEPRStabilizeTime, "temp. stabilize time [s]")
|
||||
FSTRINGVALUE(Com::tEPRRetractionWhenHeating, "temp. for retraction when heating [C]")
|
||||
FSTRINGVALUE(Com::tEPRDistanceRetractHeating, "distance to retract when heating [mm]")
|
||||
FSTRINGVALUE(Com::tEPRExtruderCoolerSpeed, "extruder cooler speed [0-255]")
|
||||
FSTRINGVALUE(Com::tEPRAdvanceK, "advance K [0=off]")
|
||||
FSTRINGVALUE(Com::tEPRAdvanceL, "advance L [0=off]")
|
||||
FSTRINGVALUE(Com::tEPRPreheatTemp, "Preheat temp. [°C]")
|
||||
FSTRINGVALUE(Com::tEPRPreheatBedTemp, "Bed Preheat temp. [°C]")
|
||||
|
||||
#endif
|
||||
#if SDSUPPORT
|
||||
//FSTRINGVALUE(Com::tSDRemoved,UI_TEXT_SD_REMOVED)
|
||||
//FSTRINGVALUE(Com::tSDInserted,UI_TEXT_SD_INSERTED)
|
||||
FSTRINGVALUE(Com::tSDInitFail, "SD init fail")
|
||||
FSTRINGVALUE(Com::tErrorWritingToFile, "error writing to file")
|
||||
FSTRINGVALUE(Com::tBeginFileList, "Begin file list")
|
||||
FSTRINGVALUE(Com::tEndFileList, "End file list")
|
||||
FSTRINGVALUE(Com::tFileOpened, "File opened:")
|
||||
FSTRINGVALUE(Com::tSpaceSizeColon, " Size:")
|
||||
FSTRINGVALUE(Com::tFileSelected, "File selected")
|
||||
FSTRINGVALUE(Com::tFileOpenFailed, "file.open failed")
|
||||
FSTRINGVALUE(Com::tSDPrintingByte, "SD printing byte ")
|
||||
FSTRINGVALUE(Com::tNotSDPrinting, "Not SD printing")
|
||||
FSTRINGVALUE(Com::tOpenFailedFile, "open failed, File: ")
|
||||
FSTRINGVALUE(Com::tWritingToFile, "Writing to file: ")
|
||||
FSTRINGVALUE(Com::tDoneSavingFile, "Done saving file.")
|
||||
FSTRINGVALUE(Com::tFileDeleted, "File deleted")
|
||||
FSTRINGVALUE(Com::tDeletionFailed, "Deletion failed")
|
||||
FSTRINGVALUE(Com::tDirectoryCreated, "Directory created")
|
||||
FSTRINGVALUE(Com::tCreationFailed, "Creation failed")
|
||||
FSTRINGVALUE(Com::tSDErrorCode, "SD errorCode:")
|
||||
#endif // SDSUPPORT
|
||||
FSTRINGVALUE(Com::tHeaterDecoupled, "Heater decoupled")
|
||||
FSTRINGVALUE(Com::tHeaterDecoupledWarning, "One heater seems decoupled from thermistor - disabling all for safety!")
|
||||
#if DISTORTION_CORRECTION
|
||||
FSTRINGVALUE(Com::tZCorrectionEnabled, "Z correction enabled")
|
||||
FSTRINGVALUE(Com::tZCorrectionDisabled, "Z correction disabled")
|
||||
#endif
|
||||
#if FEATURE_RETRACTION
|
||||
FSTRINGVALUE(Com::tEPRAutoretractEnabled, "Enable retraction conversion [0/1]")
|
||||
FSTRINGVALUE(Com::tEPRRetractionLength, "Retraction length [mm]")
|
||||
FSTRINGVALUE(Com::tEPRRetractionLongLength, "Retraction length extruder switch [mm]")
|
||||
FSTRINGVALUE(Com::tEPRRetractionSpeed, "Retraction speed [mm/s]")
|
||||
FSTRINGVALUE(Com::tEPRRetractionZLift, "Retraction z-lift [mm]")
|
||||
FSTRINGVALUE(Com::tEPRRetractionUndoExtraLength, "Extra extrusion on undo retract [mm]")
|
||||
FSTRINGVALUE(Com::tEPRRetractionUndoExtraLongLength, "Extra extrusion on undo switch retract [mm]")
|
||||
FSTRINGVALUE(Com::tEPRRetractionUndoSpeed, "Retraction undo speed")
|
||||
#endif
|
||||
FSTRINGVALUE(Com::tConfig, "Config:")
|
||||
FSTRINGVALUE(Com::tExtrDot, "Extr.")
|
||||
|
||||
#if STEPPER_CURRENT_CONTROL == CURRENT_CONTROL_MCP4728
|
||||
FSTRINGVALUE(Com::tMCPEpromSettings, "MCP4728 DAC EEPROM Settings:")
|
||||
FSTRINGVALUE(Com::tMCPCurrentSettings, "MCP4728 DAC Current Settings:")
|
||||
#endif
|
||||
FSTRINGVALUE(Com::tPrinterModeFFF, "PrinterMode:FFF")
|
||||
FSTRINGVALUE(Com::tPrinterModeLaser, "PrinterMode:Laser")
|
||||
FSTRINGVALUE(Com::tPrinterModeCNC, "PrinterMode:CNC")
|
||||
#ifdef STARTUP_GCODE
|
||||
FSTRINGVALUE(Com::tStartupGCode, STARTUP_GCODE)
|
||||
#endif
|
||||
#ifdef DRV_TMC2130
|
||||
FSTRINGVALUE(Com::tTrinamicMotorCurrent, "Trinamic motor current:")
|
||||
FSTRINGVALUE(Com::tTrinamicMicrostepMode, "Trinamic microstep mode:")
|
||||
#endif
|
||||
bool Com::writeToAll = true; // transmit start messages to all devices!
|
||||
|
||||
void Com::cap(FSTRINGPARAM(text)) {
|
||||
printF(tCap);
|
||||
printFLN(text);
|
||||
}
|
||||
void Com::config(FSTRINGPARAM(text)) {
|
||||
printF(tConfig);
|
||||
printFLN(text);
|
||||
}
|
||||
void Com::config(FSTRINGPARAM(text), int value) {
|
||||
printF(tConfig);
|
||||
printFLN(text, value);
|
||||
}
|
||||
void Com::config(FSTRINGPARAM(text), const char *msg) {
|
||||
printF(tConfig);
|
||||
printF(text);
|
||||
print(msg);
|
||||
println();
|
||||
}
|
||||
void Com::config(FSTRINGPARAM(text), int32_t value) {
|
||||
printF(tConfig);
|
||||
printFLN(text, value);
|
||||
}
|
||||
void Com::config(FSTRINGPARAM(text), uint32_t value) {
|
||||
printF(tConfig);
|
||||
printFLN(text, value);
|
||||
}
|
||||
void Com::config(FSTRINGPARAM(text), float value, uint8_t digits) {
|
||||
printF(tConfig);
|
||||
printFLN(text, value, digits);
|
||||
}
|
||||
void Com::printWarningF(FSTRINGPARAM(text)) {
|
||||
printF(tWarning);
|
||||
printF(text);
|
||||
}
|
||||
void Com::printWarningFLN(FSTRINGPARAM(text)) {
|
||||
printF(tWarning);
|
||||
printFLN(text);
|
||||
}
|
||||
void Com::printInfoF(FSTRINGPARAM(text)) {
|
||||
printF(tInfo);
|
||||
printF(text);
|
||||
}
|
||||
void Com::printInfoFLN(FSTRINGPARAM(text)) {
|
||||
printF(tInfo);
|
||||
printFLN(text);
|
||||
}
|
||||
|
||||
void Com::printErrorF(FSTRINGPARAM(text)) {
|
||||
printF(tError);
|
||||
printF(text);
|
||||
}
|
||||
void Com::printErrorFLN(FSTRINGPARAM(text)) {
|
||||
printF(tError);
|
||||
printFLN(text);
|
||||
}
|
||||
void Com::printFLN(FSTRINGPARAM(text)) {
|
||||
printF(text);
|
||||
println();
|
||||
}
|
||||
void Com::printFLN(FSTRINGPARAM(text), const char *msg) {
|
||||
printF(text);
|
||||
print(msg);
|
||||
println();
|
||||
}
|
||||
|
||||
void Com::printF(FSTRINGPARAM(ptr)) {
|
||||
char c;
|
||||
while ((c = HAL::readFlashByte(ptr++)) != 0)
|
||||
GCodeSource::writeToAll(c);
|
||||
}
|
||||
void Com::printF(FSTRINGPARAM(text), const char *msg) {
|
||||
printF(text);
|
||||
print(msg);
|
||||
}
|
||||
|
||||
void Com::printF(FSTRINGPARAM(text), int value) {
|
||||
printF(text);
|
||||
print(value);
|
||||
}
|
||||
void Com::printF(FSTRINGPARAM(text), int32_t value) {
|
||||
printF(text);
|
||||
print(value);
|
||||
}
|
||||
void Com::printF(FSTRINGPARAM(text), uint32_t value) {
|
||||
printF(text);
|
||||
printNumber(value);
|
||||
}
|
||||
void Com::printFLN(FSTRINGPARAM(text), int value) {
|
||||
printF(text);
|
||||
print(value);
|
||||
println();
|
||||
}
|
||||
void Com::printFLN(FSTRINGPARAM(text), int32_t value) {
|
||||
printF(text);
|
||||
print(value);
|
||||
println();
|
||||
}
|
||||
void Com::printFLN(FSTRINGPARAM(text), uint32_t value) {
|
||||
printF(text);
|
||||
printNumber(value);
|
||||
println();
|
||||
}
|
||||
void Com::printFLN(FSTRINGPARAM(text), float value, uint8_t digits) {
|
||||
printF(text);
|
||||
printFloat(value, digits);
|
||||
println();
|
||||
}
|
||||
void Com::printF(FSTRINGPARAM(text), float value, uint8_t digits) {
|
||||
printF(text);
|
||||
printFloat(value, digits);
|
||||
}
|
||||
|
||||
void Com::print(const char *text) {
|
||||
while(*text) {
|
||||
GCodeSource::writeToAll(*text++);
|
||||
}
|
||||
}
|
||||
void Com::print(long value) {
|
||||
if(value < 0) {
|
||||
GCodeSource::writeToAll('-');
|
||||
value = -value;
|
||||
}
|
||||
printNumber(value);
|
||||
}
|
||||
|
||||
void Com::printNumber(uint32_t n) {
|
||||
char buf[11]; // Assumes 8-bit chars plus zero byte.
|
||||
char *str = &buf[10];
|
||||
*str = '\0';
|
||||
do {
|
||||
unsigned long m = n;
|
||||
n /= 10;
|
||||
*--str = '0' + (m - 10 * n);
|
||||
} while(n);
|
||||
|
||||
print(str);
|
||||
}
|
||||
void Com::printArrayFLN(FSTRINGPARAM(text), float *arr, uint8_t n, uint8_t digits) {
|
||||
printF(text);
|
||||
for(uint8_t i = 0; i < n; i++)
|
||||
printF(Com::tSpace, arr[i], digits);
|
||||
println();
|
||||
}
|
||||
void Com::printArrayFLN(FSTRINGPARAM(text), int32_t *arr, uint8_t n) {
|
||||
printF(text);
|
||||
for(uint8_t i = 0; i < n; i++)
|
||||
printF(Com::tSpace, arr[i]);
|
||||
println();
|
||||
}
|
||||
|
||||
void Com::printFloat(float number, uint8_t digits) {
|
||||
if (isnan(number)) {
|
||||
printF(tNAN);
|
||||
return;
|
||||
}
|
||||
if (isinf(number)) {
|
||||
printF(tINF);
|
||||
return;
|
||||
}
|
||||
// Handle negative numbers
|
||||
if (number < 0.0) {
|
||||
print('-');
|
||||
number = -number;
|
||||
}
|
||||
// Round correctly so that print(1.999, 2) prints as "2.00"
|
||||
float rounding = 0.5;
|
||||
for (uint8_t i = 0; i < digits; ++i)
|
||||
rounding /= 10.0;
|
||||
|
||||
number += rounding;
|
||||
|
||||
// Extract the integer part of the number and print it
|
||||
unsigned long int_part = (unsigned long)number;
|
||||
float remainder = number - (float)int_part;
|
||||
printNumber(int_part);
|
||||
|
||||
// Print the decimal point, but only if there are digits beyond
|
||||
if (digits > 0)
|
||||
print('.');
|
||||
|
||||
// Extract digits from the remainder one at a time
|
||||
while (digits-- > 0) {
|
||||
remainder *= 10.0;
|
||||
int toPrint = int(remainder);
|
||||
print(toPrint);
|
||||
remainder -= toPrint;
|
||||
}
|
||||
}
|
||||
|
548
Repetier-Firmware 1.0.3/Repetier/Communication.h
Normal file
548
Repetier-Firmware 1.0.3/Repetier/Communication.h
Normal file
@ -0,0 +1,548 @@
|
||||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware 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.
|
||||
|
||||
Repetier-Firmware 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 Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
This firmware is a nearly complete rewrite of the sprinter firmware
|
||||
by kliment (https://github.com/kliment/Sprinter)
|
||||
which based on Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
|
||||
*/
|
||||
|
||||
#ifndef COMMUNICATION_H
|
||||
#define COMMUNICATION_H
|
||||
|
||||
#ifndef MAX_DATA_SOURCES
|
||||
#define MAX_DATA_SOURCES 4
|
||||
#endif
|
||||
|
||||
/** This class defines the general interface to handle gcode communication with the firmware. This
|
||||
allows it to connect to different data sources and handle them all inside the same data structure.
|
||||
If several readers are active, the first one sending a byte pauses all other inputs until the command
|
||||
is complete. Only then the next reader will be queried. New queries are started in round robin fashion
|
||||
so every channel gets the same chance to send commands.
|
||||
|
||||
Available source types are:
|
||||
- serial communication port
|
||||
- sd card
|
||||
- flash memory
|
||||
*/
|
||||
class GCodeSource {
|
||||
static fast8_t numSources; ///< Number of data sources available
|
||||
static fast8_t numWriteSources;
|
||||
static GCodeSource *sources[MAX_DATA_SOURCES];
|
||||
static GCodeSource *writeableSources[MAX_DATA_SOURCES];
|
||||
public:
|
||||
static GCodeSource *activeSource;
|
||||
static void registerSource(GCodeSource *newSource);
|
||||
static void removeSource(GCodeSource *delSource);
|
||||
static void rotateSource(); ///< Move active to next source
|
||||
static void writeToAll(uint8_t byte); ///< Write to all listening sources
|
||||
static void printAllFLN(FSTRINGPARAM(text) );
|
||||
static void printAllFLN(FSTRINGPARAM(text), int32_t v);
|
||||
uint32_t lastLineNumber;
|
||||
uint8_t wasLastCommandReceivedAsBinary; ///< Was the last successful command in binary mode?
|
||||
millis_t timeOfLastDataPacket;
|
||||
int8_t waitingForResend; ///< Waiting for line to be resend. -1 = no wait.
|
||||
|
||||
GCodeSource();
|
||||
virtual ~GCodeSource() {}
|
||||
virtual bool isOpen() = 0;
|
||||
virtual bool supportsWrite() = 0; ///< true if write is a non dummy function
|
||||
virtual bool closeOnError() = 0; // return true if the channel can not interactively correct errors.
|
||||
virtual bool dataAvailable() = 0; // would read return a new byte?
|
||||
virtual int readByte() = 0;
|
||||
virtual void close() = 0;
|
||||
virtual void writeByte(uint8_t byte) = 0;
|
||||
};
|
||||
|
||||
class Com
|
||||
{
|
||||
public:
|
||||
FSTRINGVAR(tDebug)
|
||||
FSTRINGVAR(tFirmware)
|
||||
FSTRINGVAR(tOk)
|
||||
FSTRINGVAR(tNewline)
|
||||
FSTRINGVAR(tNAN)
|
||||
FSTRINGVAR(tINF)
|
||||
FSTRINGVAR(tError)
|
||||
FSTRINGVAR(tInfo)
|
||||
FSTRINGVAR(tWarning)
|
||||
FSTRINGVAR(tResend)
|
||||
FSTRINGVAR(tEcho)
|
||||
FSTRINGVAR(tCap)
|
||||
FSTRINGVAR(tOkSpace)
|
||||
FSTRINGVAR(tWrongChecksum)
|
||||
FSTRINGVAR(tMissingChecksum)
|
||||
FSTRINGVAR(tFormatError)
|
||||
FSTRINGVAR(tDonePrinting)
|
||||
FSTRINGVAR(tX)
|
||||
FSTRINGVAR(tY)
|
||||
FSTRINGVAR(tZ)
|
||||
FSTRINGVAR(tE)
|
||||
FSTRINGVAR(tF)
|
||||
FSTRINGVAR(tS)
|
||||
FSTRINGVAR(tP)
|
||||
FSTRINGVAR(tI)
|
||||
FSTRINGVAR(tJ)
|
||||
FSTRINGVAR(tR)
|
||||
FSTRINGVAR(tD)
|
||||
FSTRINGVAR(tC)
|
||||
FSTRINGVAR(tH)
|
||||
FSTRINGVAR(tA)
|
||||
FSTRINGVAR(tB)
|
||||
FSTRINGVAR(tK)
|
||||
FSTRINGVAR(tL)
|
||||
FSTRINGVAR(tO)
|
||||
FSTRINGVAR(tSDReadError)
|
||||
FSTRINGVAR(tExpectedLine)
|
||||
FSTRINGVAR(tGot)
|
||||
FSTRINGVAR(tSkip)
|
||||
FSTRINGVAR(tBLK)
|
||||
FSTRINGVAR(tStart)
|
||||
FSTRINGVAR(tPowerUp)
|
||||
FSTRINGVAR(tExternalReset)
|
||||
FSTRINGVAR(tBrownOut)
|
||||
FSTRINGVAR(tWatchdog)
|
||||
FSTRINGVAR(tSoftwareReset)
|
||||
FSTRINGVAR(tUnknownCommand)
|
||||
FSTRINGVAR(tFreeRAM)
|
||||
FSTRINGVAR(tXColon)
|
||||
FSTRINGVAR(tSlash)
|
||||
FSTRINGVAR(tSpaceSlash)
|
||||
FSTRINGVAR(tFatal)
|
||||
FSTRINGVAR(tDoorOpen)
|
||||
#if JSON_OUTPUT
|
||||
FSTRINGVAR(tJSONDir)
|
||||
FSTRINGVAR(tJSONFiles)
|
||||
FSTRINGVAR(tJSONArrayEnd)
|
||||
FSTRINGVAR(tJSONErrorStart)
|
||||
FSTRINGVAR(tJSONErrorEnd)
|
||||
FSTRINGVAR(tJSONFileInfoStart)
|
||||
FSTRINGVAR(tJSONFileInfoHeight)
|
||||
FSTRINGVAR(tJSONFileInfoLayerHeight)
|
||||
FSTRINGVAR(tJSONFileInfoFilament)
|
||||
FSTRINGVAR(tJSONFileInfoGeneratedBy)
|
||||
FSTRINGVAR(tJSONFileInfoName)
|
||||
#endif
|
||||
FSTRINGVAR(tSpaceXColon)
|
||||
FSTRINGVAR(tSpaceYColon)
|
||||
FSTRINGVAR(tSpaceZColon)
|
||||
FSTRINGVAR(tSpaceEColon)
|
||||
FSTRINGVAR(tTColon)
|
||||
FSTRINGVAR(tSpaceBColon)
|
||||
FSTRINGVAR(tSpaceAtColon)
|
||||
FSTRINGVAR(tSpaceT)
|
||||
FSTRINGVAR(tSpaceRaw)
|
||||
FSTRINGVAR(tSpaceAt)
|
||||
FSTRINGVAR(tSpaceBAtColon)
|
||||
FSTRINGVAR(tColon)
|
||||
FSTRINGVAR(tSpeedMultiply)
|
||||
FSTRINGVAR(tFlowMultiply)
|
||||
FSTRINGVAR(tFanspeed)
|
||||
FSTRINGVAR(tFan2speed)
|
||||
FSTRINGVAR(tPrintedFilament)
|
||||
FSTRINGVAR(tPrintingTime)
|
||||
FSTRINGVAR(tSpacem)
|
||||
FSTRINGVAR(tSpaceDaysSpace)
|
||||
FSTRINGVAR(tSpaceHoursSpace)
|
||||
FSTRINGVAR(tSpaceMin)
|
||||
FSTRINGVAR(tInvalidArc)
|
||||
FSTRINGVAR(tComma)
|
||||
FSTRINGVAR(tSpace)
|
||||
FSTRINGVAR(tYColon)
|
||||
FSTRINGVAR(tZColon)
|
||||
FSTRINGVAR(tE0Colon)
|
||||
FSTRINGVAR(tE1Colon)
|
||||
FSTRINGVAR(tMS1MS2Pins)
|
||||
FSTRINGVAR(tSetOutputSpace)
|
||||
FSTRINGVAR(tGetInputSpace)
|
||||
FSTRINGVAR(tSpaceToSpace)
|
||||
FSTRINGVAR(tSpaceIsSpace)
|
||||
FSTRINGVAR(tHSpace)
|
||||
FSTRINGVAR(tLSpace)
|
||||
FSTRINGVAR(tXMinColon)
|
||||
FSTRINGVAR(tXMaxColon)
|
||||
FSTRINGVAR(tYMinColon)
|
||||
FSTRINGVAR(tYMaxColon)
|
||||
FSTRINGVAR(tZMinColon)
|
||||
FSTRINGVAR(tZ2MinMaxColon)
|
||||
FSTRINGVAR(tZMaxColon)
|
||||
FSTRINGVAR(tJerkColon)
|
||||
FSTRINGVAR(tZJerkColon)
|
||||
FSTRINGVAR(tLinearStepsColon)
|
||||
FSTRINGVAR(tQuadraticStepsColon)
|
||||
FSTRINGVAR(tCommaSpeedEqual)
|
||||
FSTRINGVAR(tLinearLColon)
|
||||
FSTRINGVAR(tQuadraticKColon)
|
||||
FSTRINGVAR(tEEPROMUpdated)
|
||||
FSTRINGVAR(tFilamentSlipping)
|
||||
FSTRINGVAR(tPauseCommunication)
|
||||
FSTRINGVAR(tContinueCommunication)
|
||||
#if NONLINEAR_SYSTEM
|
||||
FSTRINGVAR(tInvalidDeltaCoordinate)
|
||||
FSTRINGVAR(tDBGDeltaNoMoveinDSegment)
|
||||
#endif
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
FSTRINGVAR(tMeasurementReset)
|
||||
FSTRINGVAR(tMeasureDeltaSteps)
|
||||
FSTRINGVAR(tMeasureDelta)
|
||||
FSTRINGVAR(tMeasureOriginReset)
|
||||
FSTRINGVAR(tMeasurementAbortedOrigin)
|
||||
FSTRINGVAR(tLevelingCalc)
|
||||
FSTRINGVAR(tTower1)
|
||||
FSTRINGVAR(tTower2)
|
||||
FSTRINGVAR(tTower3)
|
||||
FSTRINGVAR(tDeltaAlphaA)
|
||||
FSTRINGVAR(tDeltaAlphaB)
|
||||
FSTRINGVAR(tDeltaAlphaC)
|
||||
FSTRINGVAR(tDeltaRadiusCorrectionA)
|
||||
FSTRINGVAR(tDeltaRadiusCorrectionB)
|
||||
FSTRINGVAR(tDeltaRadiusCorrectionC)
|
||||
FSTRINGVAR(tDeltaDiagonalCorrectionA)
|
||||
FSTRINGVAR(tDeltaDiagonalCorrectionB)
|
||||
FSTRINGVAR(tDeltaDiagonalCorrectionC)
|
||||
FSTRINGVAR(tEPRDeltaMaxRadius)
|
||||
#endif // DRIVE_SYSTEM
|
||||
#if DRIVE_SYSTEM==TUGA
|
||||
FSTRINGVAR(tEPRDiagonalRodLength)
|
||||
#endif
|
||||
#ifdef DEBUG_GENERIC
|
||||
FSTRINGVAR(tGenTemp)
|
||||
#endif // DEBUG_GENERICFSTRINGVALUE(Com::,"")
|
||||
FSTRINGVAR(tTargetExtr)
|
||||
FSTRINGVAR(tTargetBedColon)
|
||||
FSTRINGVAR(tPIDAutotuneStart)
|
||||
FSTRINGVAR(tAPIDBias)
|
||||
FSTRINGVAR(tAPIDD)
|
||||
FSTRINGVAR(tAPIDMin)
|
||||
FSTRINGVAR(tAPIDMax)
|
||||
FSTRINGVAR(tAPIDKu)
|
||||
FSTRINGVAR(tAPIDTu)
|
||||
FSTRINGVAR(tAPIDClassic)
|
||||
FSTRINGVAR(tAPIDSome)
|
||||
FSTRINGVAR(tAPIDNone)
|
||||
FSTRINGVAR(tAPIDPessen)
|
||||
FSTRINGVAR(tAPIDTyreusLyben)
|
||||
FSTRINGVAR(tAPIDKp)
|
||||
FSTRINGVAR(tAPIDKi)
|
||||
FSTRINGVAR(tAPIDKd)
|
||||
FSTRINGVAR(tAPIDFailedHigh)
|
||||
FSTRINGVAR(tAPIDFailedTimeout)
|
||||
FSTRINGVAR(tAPIDFinished)
|
||||
FSTRINGVAR(tMTEMPColon)
|
||||
FSTRINGVAR(tHeatedBed)
|
||||
FSTRINGVAR(tExtruderSpace)
|
||||
FSTRINGVAR(tTempSensorDefect)
|
||||
FSTRINGVAR(tTempSensorWorking)
|
||||
FSTRINGVAR(tDryModeUntilRestart)
|
||||
#ifdef DEBUG_QUEUE_MOVE
|
||||
FSTRINGVAR(tDBGId)
|
||||
FSTRINGVAR(tDBGVStartEnd)
|
||||
FSTRINGVAR(tDBAccelSteps)
|
||||
FSTRINGVAR(tDBGStartEndSpeed)
|
||||
FSTRINGVAR(tDBGFlags)
|
||||
FSTRINGVAR(tDBGJoinFlags)
|
||||
FSTRINGVAR(tDBGDelta)
|
||||
FSTRINGVAR(tDBGDir)
|
||||
FSTRINGVAR(tDBGFullSpeed)
|
||||
FSTRINGVAR(tDBGVMax)
|
||||
FSTRINGVAR(tDBGAcceleration)
|
||||
FSTRINGVAR(tDBGAccelerationPrim)
|
||||
FSTRINGVAR(tDBGRemainingSteps)
|
||||
FSTRINGVAR(tDBGAdvanceFull)
|
||||
FSTRINGVAR(tDBGAdvanceRate)
|
||||
FSTRINGVAR(tDBGLimitInterval)
|
||||
FSTRINGVAR(tDBGMoveDistance)
|
||||
FSTRINGVAR(tDBGCommandedFeedrate)
|
||||
FSTRINGVAR(tDBGConstFullSpeedMoveTime)
|
||||
#endif // DEBUG_QUEUE_MOVEFSTRINGVALUE(Com::,"")
|
||||
#ifdef DEBUG_DELTA_OVERFLOW
|
||||
FSTRINGVAR(tDBGDeltaOverflow)
|
||||
#endif // DEBUG_DELTA_OVERFLOW
|
||||
#ifdef DEBUG_SPLIT
|
||||
FSTRINGVAR(tDBGDeltaSeconds)
|
||||
FSTRINGVAR(tDBGDeltaZDelta)
|
||||
FSTRINGVAR(tDBGDeltaSegments)
|
||||
FSTRINGVAR(tDBGDeltaNumLines)
|
||||
FSTRINGVAR(tDBGDeltaSegmentsPerLine)
|
||||
FSTRINGVAR(tDBGDeltaMaxDS)
|
||||
FSTRINGVAR(tDBGDeltaStepsPerSegment)
|
||||
FSTRINGVAR(tDBGDeltaVirtualAxisSteps)
|
||||
#endif
|
||||
#ifdef DEBUG_STEPCOUNT
|
||||
FSTRINGVAR(tDBGMissedSteps)
|
||||
#endif
|
||||
#if FEATURE_Z_PROBE
|
||||
FSTRINGVAR(tZProbe)
|
||||
FSTRINGVAR(tZProbeState)
|
||||
FSTRINGVAR(tZProbeStartScript)
|
||||
FSTRINGVAR(tZProbeEndScript)
|
||||
FSTRINGVAR(tHitZProbe)
|
||||
FSTRINGVAR(tZProbeAverage)
|
||||
FSTRINGVAR(tZProbeZReset)
|
||||
FSTRINGVAR(tZProbeBedDitance)
|
||||
#endif
|
||||
FSTRINGVAR(tAutolevelReset)
|
||||
FSTRINGVAR(tAutolevelEnabled)
|
||||
FSTRINGVAR(tAutolevelDisabled)
|
||||
FSTRINGVAR(tTransformationMatrix)
|
||||
FSTRINGVAR(tZProbeFailed)
|
||||
FSTRINGVAR(tZProbeMax)
|
||||
FSTRINGVAR(tZProbePrinterHeight)
|
||||
|
||||
#ifdef WAITING_IDENTIFIER
|
||||
FSTRINGVAR(tWait)
|
||||
#endif // WAITING_IDENTIFIER
|
||||
|
||||
#if EEPROM_MODE==0
|
||||
FSTRINGVAR(tNoEEPROMSupport)
|
||||
#else
|
||||
FSTRINGVAR(tZProbeOffsetZ)
|
||||
#if FEATURE_Z_PROBE
|
||||
FSTRINGVAR(tZProbeHeight)
|
||||
FSTRINGVAR(tZProbeOffsetX)
|
||||
FSTRINGVAR(tZProbeOffsetY)
|
||||
FSTRINGVAR(tZProbeSpeed)
|
||||
FSTRINGVAR(tZProbeSpeedXY)
|
||||
FSTRINGVAR(tZProbeX1)
|
||||
FSTRINGVAR(tZProbeY1)
|
||||
FSTRINGVAR(tZProbeX2)
|
||||
FSTRINGVAR(tZProbeY2)
|
||||
FSTRINGVAR(tZProbeX3)
|
||||
FSTRINGVAR(tZProbeY3)
|
||||
FSTRINGVAR(zZProbeBendingCorA)
|
||||
FSTRINGVAR(zZProbeBendingCorB)
|
||||
FSTRINGVAR(zZProbeBendingCorC)
|
||||
#endif
|
||||
#if FEATURE_AUTOLEVEL
|
||||
FSTRINGVAR(tAutolevelActive)
|
||||
#endif
|
||||
#if FEATURE_AXISCOMP
|
||||
FSTRINGVAR(tAxisCompTanXY)
|
||||
FSTRINGVAR(tAxisCompTanYZ)
|
||||
FSTRINGVAR(tAxisCompTanXZ)
|
||||
#endif
|
||||
FSTRINGVAR(tConfigStoredEEPROM)
|
||||
FSTRINGVAR(tConfigLoadedEEPROM)
|
||||
FSTRINGVAR(tEPRConfigResetDefaults)
|
||||
FSTRINGVAR(tEPRProtocolChanged)
|
||||
FSTRINGVAR(tEPR0)
|
||||
FSTRINGVAR(tEPR1)
|
||||
FSTRINGVAR(tEPR2)
|
||||
FSTRINGVAR(tEPR3)
|
||||
FSTRINGVAR(tLanguage)
|
||||
FSTRINGVAR(tEPRBaudrate)
|
||||
FSTRINGVAR(tEPRFilamentPrinted)
|
||||
FSTRINGVAR(tEPRPrinterActive)
|
||||
FSTRINGVAR(tEPRMaxInactiveTime)
|
||||
FSTRINGVAR(tEPRStopAfterInactivty)
|
||||
FSTRINGVAR(tEPRMaxJerk)
|
||||
FSTRINGVAR(tEPRXHomePos)
|
||||
FSTRINGVAR(tEPRYHomePos)
|
||||
FSTRINGVAR(tEPRZHomePos)
|
||||
FSTRINGVAR(tEPRXMaxLength)
|
||||
FSTRINGVAR(tEPRYMaxLength)
|
||||
FSTRINGVAR(tEPRZMaxLength)
|
||||
FSTRINGVAR(tEPRXBacklash)
|
||||
FSTRINGVAR(tEPRYBacklash)
|
||||
FSTRINGVAR(tEPRZBacklash)
|
||||
FSTRINGVAR(tEPRZAcceleration)
|
||||
FSTRINGVAR(tEPRZTravelAcceleration)
|
||||
FSTRINGVAR(tEPRAccelerationFactorAtTop)
|
||||
FSTRINGVAR(tEPRZStepsPerMM)
|
||||
FSTRINGVAR(tEPRZMaxFeedrate)
|
||||
FSTRINGVAR(tEPRZHomingFeedrate)
|
||||
#if DRIVE_SYSTEM != DELTA
|
||||
FSTRINGVAR(tEPRMaxZJerk)
|
||||
FSTRINGVAR(tEPRXStepsPerMM)
|
||||
#if DUAL_X_RESOLUTION
|
||||
FSTRINGVAR(tEPRX2StepsPerMM)
|
||||
#endif
|
||||
FSTRINGVAR(tEPRYStepsPerMM)
|
||||
FSTRINGVAR(tEPRXMaxFeedrate)
|
||||
FSTRINGVAR(tEPRYMaxFeedrate)
|
||||
FSTRINGVAR(tEPRXHomingFeedrate)
|
||||
FSTRINGVAR(tEPRYHomingFeedrate)
|
||||
FSTRINGVAR(tEPRXAcceleration)
|
||||
FSTRINGVAR(tEPRYAcceleration)
|
||||
FSTRINGVAR(tEPRXTravelAcceleration)
|
||||
FSTRINGVAR(tEPRYTravelAcceleration)
|
||||
#else
|
||||
FSTRINGVAR(tEPRDiagonalRodLength)
|
||||
FSTRINGVAR(tEPRHorizontalRadius)
|
||||
FSTRINGVAR(tEPRTowerXOffset)
|
||||
FSTRINGVAR(tEPRTowerYOffset)
|
||||
FSTRINGVAR(tEPRTowerZOffset)
|
||||
#endif
|
||||
FSTRINGVAR(tEPROPSMode)
|
||||
FSTRINGVAR(tEPROPSMoveAfter)
|
||||
FSTRINGVAR(tEPROPSMinDistance)
|
||||
FSTRINGVAR(tEPROPSRetractionLength)
|
||||
FSTRINGVAR(tEPROPSRetractionBacklash)
|
||||
FSTRINGVAR(tEPRBedHeatManager)
|
||||
FSTRINGVAR(tEPRBedPIDDriveMax)
|
||||
FSTRINGVAR(tEPRBedPIDDriveMin)
|
||||
FSTRINGVAR(tEPRBedPGain)
|
||||
FSTRINGVAR(tEPRBedIGain)
|
||||
FSTRINGVAR(tEPRBedDGain)
|
||||
FSTRINGVAR(tEPRBedPISMaxValue)
|
||||
FSTRINGVAR(tEPRStepsPerMM)
|
||||
FSTRINGVAR(tEPRMaxFeedrate)
|
||||
FSTRINGVAR(tEPRStartFeedrate)
|
||||
FSTRINGVAR(tEPRAcceleration)
|
||||
FSTRINGVAR(tEPRHeatManager)
|
||||
FSTRINGVAR(tEPRDriveMax)
|
||||
FSTRINGVAR(tEPRDriveMin)
|
||||
FSTRINGVAR(tEPRPGain)
|
||||
FSTRINGVAR(tEPRDead)
|
||||
FSTRINGVAR(tEPRUnused)
|
||||
FSTRINGVAR(tEPRIGain)
|
||||
FSTRINGVAR(tEPRDGain)
|
||||
FSTRINGVAR(tEPRPIDMaxValue)
|
||||
FSTRINGVAR(tEPRXOffset)
|
||||
FSTRINGVAR(tEPRYOffset)
|
||||
FSTRINGVAR(tEPRZOffset)
|
||||
FSTRINGVAR(tEPRStabilizeTime)
|
||||
FSTRINGVAR(tEPRRetractionWhenHeating)
|
||||
FSTRINGVAR(tEPRDistanceRetractHeating)
|
||||
FSTRINGVAR(tEPRExtruderCoolerSpeed)
|
||||
FSTRINGVAR(tEPRAdvanceK)
|
||||
FSTRINGVAR(tEPRAdvanceL)
|
||||
FSTRINGVAR(tEPRPreheatTemp)
|
||||
FSTRINGVAR(tEPRPreheatBedTemp)
|
||||
#endif
|
||||
#if SDSUPPORT
|
||||
//FSTRINGVAR(tSDRemoved)
|
||||
//FSTRINGVAR(tSDInserted)
|
||||
FSTRINGVAR(tSDInitFail)
|
||||
FSTRINGVAR(tErrorWritingToFile)
|
||||
FSTRINGVAR(tBeginFileList)
|
||||
FSTRINGVAR(tEndFileList)
|
||||
FSTRINGVAR(tFileOpened)
|
||||
FSTRINGVAR(tSpaceSizeColon)
|
||||
FSTRINGVAR(tFileSelected)
|
||||
FSTRINGVAR(tFileOpenFailed)
|
||||
FSTRINGVAR(tSDPrintingByte)
|
||||
FSTRINGVAR(tNotSDPrinting)
|
||||
FSTRINGVAR(tOpenFailedFile)
|
||||
FSTRINGVAR(tWritingToFile)
|
||||
FSTRINGVAR(tDoneSavingFile)
|
||||
FSTRINGVAR(tFileDeleted)
|
||||
FSTRINGVAR(tDeletionFailed)
|
||||
FSTRINGVAR(tDirectoryCreated)
|
||||
FSTRINGVAR(tCreationFailed)
|
||||
FSTRINGVAR(tSDErrorCode)
|
||||
#endif // SDSUPPORT
|
||||
FSTRINGVAR(tHeaterDecoupled)
|
||||
FSTRINGVAR(tHeaterDecoupledWarning)
|
||||
#if DISTORTION_CORRECTION
|
||||
FSTRINGVAR(tZCorrectionEnabled)
|
||||
FSTRINGVAR(tZCorrectionDisabled)
|
||||
#endif
|
||||
#if FEATURE_RETRACTION
|
||||
FSTRINGVAR(tEPRAutoretractEnabled)
|
||||
FSTRINGVAR(tEPRRetractionLength)
|
||||
FSTRINGVAR(tEPRRetractionLongLength)
|
||||
FSTRINGVAR(tEPRRetractionSpeed)
|
||||
FSTRINGVAR(tEPRRetractionZLift)
|
||||
FSTRINGVAR(tEPRRetractionUndoExtraLength)
|
||||
FSTRINGVAR(tEPRRetractionUndoExtraLongLength)
|
||||
FSTRINGVAR(tEPRRetractionUndoSpeed)
|
||||
#endif
|
||||
FSTRINGVAR(tConfig)
|
||||
FSTRINGVAR(tExtrDot)
|
||||
|
||||
#if STEPPER_CURRENT_CONTROL == CURRENT_CONTROL_MCP4728
|
||||
FSTRINGVAR(tMCPEpromSettings)
|
||||
FSTRINGVAR(tMCPCurrentSettings)
|
||||
#endif
|
||||
FSTRINGVAR(tPrinterModeFFF)
|
||||
FSTRINGVAR(tPrinterModeLaser)
|
||||
FSTRINGVAR(tPrinterModeCNC)
|
||||
#ifdef STARTUP_GCODE
|
||||
FSTRINGVAR(tStartupGCode)
|
||||
#endif
|
||||
#if NONLINEAR_SYSTEM
|
||||
FSTRINGVAR(tEPRSegmentsPerSecondPrint)
|
||||
FSTRINGVAR(tEPRSegmentsPerSecondTravel)
|
||||
#endif
|
||||
#ifdef DRV_TMC2130
|
||||
FSTRINGVAR(tTrinamicMotorCurrent)
|
||||
FSTRINGVAR(tTrinamicMicrostepMode)
|
||||
#endif
|
||||
|
||||
static void cap(FSTRINGPARAM(text));
|
||||
static void config(FSTRINGPARAM(text));
|
||||
static void config(FSTRINGPARAM(text),int value);
|
||||
static void config(FSTRINGPARAM(text),const char *msg);
|
||||
static void config(FSTRINGPARAM(text),int32_t value);
|
||||
static void config(FSTRINGPARAM(text),uint32_t value);
|
||||
static void config(FSTRINGPARAM(text),float value,uint8_t digits=2);
|
||||
static void printNumber(uint32_t n);
|
||||
static void printWarningF(FSTRINGPARAM(text));
|
||||
static void printInfoF(FSTRINGPARAM(text));
|
||||
static void printErrorF(FSTRINGPARAM(text));
|
||||
static void printWarningFLN(FSTRINGPARAM(text));
|
||||
static void printInfoFLN(FSTRINGPARAM(text));
|
||||
static void printErrorFLN(FSTRINGPARAM(text));
|
||||
static void printFLN(FSTRINGPARAM(text));
|
||||
static void printF(FSTRINGPARAM(text));
|
||||
static void printF(FSTRINGPARAM(text),int value);
|
||||
static void printF(FSTRINGPARAM(text),const char *msg);
|
||||
static void printF(FSTRINGPARAM(text),int32_t value);
|
||||
static void printF(FSTRINGPARAM(text),uint32_t value);
|
||||
static void printF(FSTRINGPARAM(text),float value,uint8_t digits=2);
|
||||
static void printFLN(FSTRINGPARAM(text),int value);
|
||||
static void printFLN(FSTRINGPARAM(text),int32_t value);
|
||||
static void printFLN(FSTRINGPARAM(text),uint32_t value);
|
||||
static void printFLN(FSTRINGPARAM(text),const char *msg);
|
||||
static void printFLN(FSTRINGPARAM(text),float value,uint8_t digits=2);
|
||||
static void printArrayFLN(FSTRINGPARAM(text),float *arr,uint8_t n=4,uint8_t digits=2);
|
||||
static void printArrayFLN(FSTRINGPARAM(text),long *arr,uint8_t n=4);
|
||||
static void print(long value);
|
||||
static inline void print(uint32_t value) {printNumber(value);}
|
||||
static inline void print(int value) {print((int32_t)value);}
|
||||
static void print(const char *text);
|
||||
static inline void print(char c) {GCodeSource::writeToAll(c);}
|
||||
static void printFloat(float number, uint8_t digits);
|
||||
static inline void print(float number) {printFloat(number, 6);}
|
||||
static inline void println() {GCodeSource::writeToAll('\r');GCodeSource::writeToAll('\n');}
|
||||
static bool writeToAll;
|
||||
#if FEATURE_CONTROLLER != NO_CONTROLLER
|
||||
static const char* translatedF(int textId);
|
||||
static void selectLanguage(fast8_t lang);
|
||||
static uint8_t selectedLanguage;
|
||||
#endif
|
||||
protected:
|
||||
private:
|
||||
};
|
||||
|
||||
#ifdef DEBUG
|
||||
#define SHOW(x) {Com::printF(PSTR(" " #x "=")); Com::print(x); Com::println();}
|
||||
#define SHOWS(x) {Com::printF(PSTR(" " #x "=")); Com::print(x); Com::print(" steps "); Com::print(x/80); Com::printFLN(PSTR(" mm"));}
|
||||
#define SHOWM(x) {Com::printF(PSTR(" " #x "=")); Com::print((long)x*80); Com::print(" steps "); Com::print(x); Com::printFLN(PSTR(" mm"));}
|
||||
#define SHOT(x) Com::printF(PSTR(x " "))
|
||||
#define SHOWA(t,a,n) {SHOT(t); for (int i=0;i<n;i++) SHOWS(a[i]);}
|
||||
#define SHOWAM(t,a,n) {SHOT(t); for (int i=0;i<n;i++) SHOWM(a[i]);}
|
||||
|
||||
#else
|
||||
#define SHOW(x)
|
||||
#define SHOT(x)
|
||||
#define SHOWS(x)
|
||||
#define SHOWM(x)
|
||||
#define SHOWA(t,a,n)
|
||||
#define SHOWAM(t,a,n)
|
||||
#endif
|
||||
|
||||
#endif // COMMUNICATION_H
|
1269
Repetier-Firmware 1.0.3/Repetier/Configuration.h
Normal file
1269
Repetier-Firmware 1.0.3/Repetier/Configuration.h
Normal file
File diff suppressed because it is too large
Load Diff
1874
Repetier-Firmware 1.0.3/Repetier/DisplayList.h
Normal file
1874
Repetier-Firmware 1.0.3/Repetier/DisplayList.h
Normal file
File diff suppressed because it is too large
Load Diff
440
Repetier-Firmware 1.0.3/Repetier/Distortion.cpp
Normal file
440
Repetier-Firmware 1.0.3/Repetier/Distortion.cpp
Normal file
@ -0,0 +1,440 @@
|
||||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware 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.
|
||||
|
||||
Repetier-Firmware 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 Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
This firmware is a nearly complete rewrite of the sprinter firmware
|
||||
by kliment (https://github.com/kliment/Sprinter)
|
||||
which based on Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
|
||||
|
||||
Functions in this file are used to communicate using ascii or repetier protocol.
|
||||
*/
|
||||
|
||||
#include "Repetier.h"
|
||||
|
||||
#if DISTORTION_CORRECTION
|
||||
|
||||
Distortion Printer::distortion;
|
||||
|
||||
void Printer::measureDistortion(void) {
|
||||
prepareForProbing();
|
||||
#if defined(Z_PROBE_MIN_TEMPERATURE) && Z_PROBE_MIN_TEMPERATURE && Z_PROBE_REQUIRES_HEATING
|
||||
float actTemp[NUM_EXTRUDER];
|
||||
for(int i = 0; i < NUM_EXTRUDER; i++)
|
||||
actTemp[i] = extruder[i].tempControl.targetTemperatureC;
|
||||
Printer::moveToReal(IGNORE_COORDINATE, IGNORE_COORDINATE, RMath::max(EEPROM::zProbeHeight(), static_cast<float>(ZHOME_HEAT_HEIGHT)), IGNORE_COORDINATE, Printer::homingFeedrate[Z_AXIS]);
|
||||
Commands::waitUntilEndOfAllMoves();
|
||||
#if ZHOME_HEAT_ALL
|
||||
for(int i = 0; i < NUM_EXTRUDER; i++) {
|
||||
Extruder::setTemperatureForExtruder(RMath::max(actTemp[i], static_cast<float>(ZPROBE_MIN_TEMPERATURE)), i, false, false);
|
||||
}
|
||||
for(int i = 0; i < NUM_EXTRUDER; i++) {
|
||||
if(extruder[i].tempControl.currentTemperatureC < ZPROBE_MIN_TEMPERATURE)
|
||||
Extruder::setTemperatureForExtruder(RMath::max(actTemp[i], static_cast<float>(ZPROBE_MIN_TEMPERATURE)), i, false, true);
|
||||
}
|
||||
#else
|
||||
if(extruder[Extruder::current->id].tempControl.currentTemperatureC < ZPROBE_MIN_TEMPERATURE)
|
||||
Extruder::setTemperatureForExtruder(RMath::max(actTemp[Extruder::current->id], static_cast<float>(ZPROBE_MIN_TEMPERATURE)), Extruder::current->id, false, true);
|
||||
#endif
|
||||
#endif
|
||||
float oldFeedrate = Printer::feedrate;
|
||||
|
||||
|
||||
Printer::coordinateOffset[X_AXIS] = Printer::coordinateOffset[Y_AXIS] = Printer::coordinateOffset[Z_AXIS] = 0;
|
||||
|
||||
if(!distortion.measure()) {
|
||||
GCode::fatalError(PSTR("G33 failed!"));
|
||||
return;
|
||||
}
|
||||
Printer::feedrate = oldFeedrate;
|
||||
#if defined(Z_PROBE_MIN_TEMPERATURE) && Z_PROBE_MIN_TEMPERATURE && Z_PROBE_REQUIRES_HEATING
|
||||
#if ZHOME_HEAT_ALL
|
||||
for(int i = 0; i < NUM_EXTRUDER; i++)
|
||||
Extruder::setTemperatureForExtruder(actTemp[i], i, false, false);
|
||||
for(int i = 0; i < NUM_EXTRUDER; i++)
|
||||
Extruder::setTemperatureForExtruder(actTemp[i], i, false, actTemp[i] > MAX_ROOM_TEMPERATURE);
|
||||
#else
|
||||
Extruder::setTemperatureForExtruder(actTemp[Extruder::current->id], Extruder::current->id, false, actTemp[Extruder::current->id] > MAX_ROOM_TEMPERATURE);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
Distortion::Distortion() {
|
||||
}
|
||||
|
||||
void Distortion::init() {
|
||||
updateDerived();
|
||||
#if !DISTORTION_PERMANENT
|
||||
resetCorrection();
|
||||
#endif
|
||||
#if EEPROM_MODE != 0
|
||||
enabled = EEPROM::isZCorrectionEnabled();
|
||||
Com::printFLN(PSTR("zDistortionCorrection:"), (int)enabled);
|
||||
#else
|
||||
enabled = false;
|
||||
#endif
|
||||
}
|
||||
|
||||
void Distortion::updateDerived() {
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
step = (2 * Printer::axisStepsPerMM[Z_AXIS] * DISTORTION_CORRECTION_R) / (DISTORTION_CORRECTION_POINTS - 1.0f);
|
||||
radiusCorrectionSteps = DISTORTION_CORRECTION_R * Printer::axisStepsPerMM[Z_AXIS];
|
||||
#else
|
||||
xCorrectionSteps = (DISTORTION_XMAX - DISTORTION_XMIN) * Printer::axisStepsPerMM[X_AXIS] / (DISTORTION_CORRECTION_POINTS - 1);
|
||||
xOffsetSteps = DISTORTION_XMIN * Printer::axisStepsPerMM[X_AXIS];
|
||||
yCorrectionSteps = (DISTORTION_YMAX - DISTORTION_YMIN) * Printer::axisStepsPerMM[Y_AXIS] / (DISTORTION_CORRECTION_POINTS - 1);
|
||||
yOffsetSteps = DISTORTION_YMIN * Printer::axisStepsPerMM[Y_AXIS];
|
||||
|
||||
#endif
|
||||
zStart = DISTORTION_START_DEGRADE * Printer::axisStepsPerMM[Z_AXIS] + Printer::zMinSteps;
|
||||
zEnd = DISTORTION_END_HEIGHT * Printer::axisStepsPerMM[Z_AXIS] + Printer::zMinSteps;
|
||||
}
|
||||
|
||||
void Distortion::enable(bool permanent) {
|
||||
enabled = true;
|
||||
#if DISTORTION_PERMANENT && EEPROM_MODE != 0
|
||||
if(permanent)
|
||||
EEPROM::setZCorrectionEnabled(enabled);
|
||||
#endif
|
||||
Com::printFLN(Com::tZCorrectionEnabled);
|
||||
}
|
||||
|
||||
void Distortion::disable(bool permanent) {
|
||||
enabled = false;
|
||||
#if DISTORTION_PERMANENT && EEPROM_MODE != 0
|
||||
if(permanent)
|
||||
EEPROM::setZCorrectionEnabled(enabled);
|
||||
#endif
|
||||
#if DRIVE_SYSTEM != DELTA
|
||||
Printer::zCorrectionStepsIncluded = 0;
|
||||
#endif
|
||||
Printer::updateCurrentPosition(false);
|
||||
Com::printFLN(Com::tZCorrectionDisabled);
|
||||
}
|
||||
|
||||
void Distortion::reportStatus() {
|
||||
Com::printFLN(enabled ? Com::tZCorrectionEnabled : Com::tZCorrectionDisabled);
|
||||
}
|
||||
|
||||
void Distortion::resetCorrection(void) {
|
||||
Com::printInfoFLN(PSTR("Resetting Z correction"));
|
||||
for(int i = 0; i < DISTORTION_CORRECTION_POINTS * DISTORTION_CORRECTION_POINTS; i++)
|
||||
setMatrix(0, i);
|
||||
}
|
||||
|
||||
int Distortion::matrixIndex(fast8_t x, fast8_t y) const {
|
||||
return static_cast<int>(y) * DISTORTION_CORRECTION_POINTS + x;
|
||||
}
|
||||
|
||||
int32_t Distortion::getMatrix(int index) const {
|
||||
#if DISTORTION_PERMANENT
|
||||
return EEPROM::getZCorrection(index);
|
||||
#else
|
||||
return matrix[index];
|
||||
#endif
|
||||
}
|
||||
void Distortion::setMatrix(int32_t val, int index) {
|
||||
#if DISTORTION_PERMANENT
|
||||
#if EEPROM_MODE != 0
|
||||
EEPROM::setZCorrection(val, index);
|
||||
#endif
|
||||
#else
|
||||
matrix[index] = val;
|
||||
#endif
|
||||
}
|
||||
|
||||
bool Distortion::isCorner(fast8_t i, fast8_t j) const {
|
||||
return (i == 0 || i == DISTORTION_CORRECTION_POINTS - 1)
|
||||
&& (j == 0 || j == DISTORTION_CORRECTION_POINTS - 1);
|
||||
}
|
||||
|
||||
/**
|
||||
Extrapolates the changes from p1 to p2 to p3 which has the same distance as p1-p2.
|
||||
*/
|
||||
inline int32_t Distortion::extrapolatePoint(fast8_t x1, fast8_t y1, fast8_t x2, fast8_t y2) const {
|
||||
return 2 * getMatrix(matrixIndex(x2, y2)) - getMatrix(matrixIndex(x1, y1));
|
||||
}
|
||||
|
||||
void Distortion::extrapolateCorner(fast8_t x, fast8_t y, fast8_t dx, fast8_t dy) {
|
||||
setMatrix((extrapolatePoint(x + 2 * dx, y, x + dx, y) + extrapolatePoint(x, y + 2 * dy, x, y + dy)) / 2.0,
|
||||
matrixIndex(x, y));
|
||||
}
|
||||
|
||||
void Distortion::extrapolateCorners() {
|
||||
const fast8_t m = DISTORTION_CORRECTION_POINTS - 1;
|
||||
extrapolateCorner(0, 0, 1, 1);
|
||||
extrapolateCorner(0, m, 1, -1);
|
||||
extrapolateCorner(m, 0, -1, 1);
|
||||
extrapolateCorner(m, m, -1, -1);
|
||||
}
|
||||
|
||||
bool Distortion::measure(void) {
|
||||
fast8_t ix, iy;
|
||||
|
||||
disable(false);
|
||||
Printer::prepareForProbing();
|
||||
float z = RMath::max(EEPROM::zProbeBedDistance() + (EEPROM::zProbeHeight() > 0 ? EEPROM::zProbeHeight() : 0), static_cast<float>(ZHOME_HEAT_HEIGHT)); //EEPROM::zProbeBedDistance() + (EEPROM::zProbeHeight() > 0 ? EEPROM::zProbeHeight() : 0);
|
||||
Com::printFLN(PSTR("Reference Z for measurement:"), z, 3);
|
||||
updateDerived();
|
||||
/*
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
// It is not possible to go to the edges at the top, also users try
|
||||
// it often and wonder why the coordinate system is then wrong.
|
||||
// For that reason we ensure a correct behavior by code.
|
||||
Printer::homeAxis(true, true, true);
|
||||
Printer::moveTo(IGNORE_COORDINATE, IGNORE_COORDINATE, EEPROM::zProbeBedDistance() + (EEPROM::zProbeHeight() > 0 ? EEPROM::zProbeHeight() : 0), IGNORE_COORDINATE, Printer::homingFeedrate[Z_AXIS]);
|
||||
#else
|
||||
if(!Printer::isXHomed() || !Printer::isYHomed())
|
||||
Printer::homeAxis(true, true, false);
|
||||
Printer::updateCurrentPosition(true);
|
||||
Printer::moveTo(Printer::invAxisStepsPerMM[X_AXIS] * ((isCorner(0, 0) ? 1 : 0) * xCorrectionSteps + xOffsetSteps), Printer::invAxisStepsPerMM[Y_AXIS] * ((DISTORTION_CORRECTION_POINTS - 1) * yCorrectionSteps + yOffsetSteps), IGNORE_COORDINATE, IGNORE_COORDINATE, EEPROM::zProbeXYSpeed());
|
||||
#endif
|
||||
*/
|
||||
//Com::printFLN(PSTR("radiusCorr:"), radiusCorrectionSteps);
|
||||
//Com::printFLN(PSTR("steps:"), step);
|
||||
int32_t zCorrection = 0;
|
||||
#if Z_PROBE_Z_OFFSET_MODE == 1
|
||||
zCorrection -= Printer::zBedOffset * Printer::axisStepsPerMM[Z_AXIS];
|
||||
#endif
|
||||
|
||||
Printer::startProbing(true);
|
||||
Printer::moveToReal(IGNORE_COORDINATE, IGNORE_COORDINATE, z, IGNORE_COORDINATE, Printer::homingFeedrate[Z_AXIS]);
|
||||
for (iy = DISTORTION_CORRECTION_POINTS - 1; iy >= 0; iy--)
|
||||
for (ix = 0; ix < DISTORTION_CORRECTION_POINTS; ix++) {
|
||||
#if (DRIVE_SYSTEM == DELTA) && DISTORTION_EXTRAPOLATE_CORNERS
|
||||
if (isCorner(ix, iy)) continue;
|
||||
#endif
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
float mtx = Printer::invAxisStepsPerMM[X_AXIS] * (ix * step - radiusCorrectionSteps);
|
||||
float mty = Printer::invAxisStepsPerMM[Y_AXIS] * (iy * step - radiusCorrectionSteps);
|
||||
#else
|
||||
float mtx = Printer::invAxisStepsPerMM[X_AXIS] * (ix * xCorrectionSteps + xOffsetSteps);
|
||||
float mty = Printer::invAxisStepsPerMM[Y_AXIS] * (iy * yCorrectionSteps + yOffsetSteps);
|
||||
#endif
|
||||
//Com::printF(PSTR("mx "),mtx);
|
||||
//Com::printF(PSTR("my "),mty);
|
||||
//Com::printF(PSTR("ix "),(int)ix);
|
||||
//Com::printFLN(PSTR("iy "),(int)iy);
|
||||
Printer::moveToReal(mtx, mty, z, IGNORE_COORDINATE, EEPROM::zProbeXYSpeed());
|
||||
float zp = Printer::runZProbe(false, false, Z_PROBE_REPETITIONS);
|
||||
#if defined(DISTORTION_LIMIT_TO) && DISTORTION_LIMIT_TO != 0
|
||||
if(zp == ILLEGAL_Z_PROBE || fabs(z - zp + zCorrection * Printer::invAxisStepsPerMM[Z_AXIS]) > DISTORTION_LIMIT_TO) {
|
||||
#else
|
||||
if(zp == ILLEGAL_Z_PROBE) {
|
||||
#endif
|
||||
Com::printErrorFLN(PSTR("Stopping distortion measurement due to errors."));
|
||||
Printer::finishProbing();
|
||||
return false;
|
||||
}
|
||||
setMatrix(floor(0.5f + Printer::axisStepsPerMM[Z_AXIS] * (z - zp)) + zCorrection,
|
||||
matrixIndex(ix, iy));
|
||||
}
|
||||
Printer::finishProbing();
|
||||
#if (DRIVE_SYSTEM == DELTA) && DISTORTION_EXTRAPOLATE_CORNERS
|
||||
extrapolateCorners();
|
||||
#endif
|
||||
// make average center
|
||||
// Disabled since we can use grid measurement to get average plane if that is what we want.
|
||||
// Shifting z with each measuring is a pain and can result in unexpected behavior.
|
||||
/*
|
||||
float sum = 0;
|
||||
for(int k = 0;k < DISTORTION_CORRECTION_POINTS * DISTORTION_CORRECTION_POINTS; k++)
|
||||
sum += getMatrix(k);
|
||||
sum /= static_cast<float>(DISTORTION_CORRECTION_POINTS * DISTORTION_CORRECTION_POINTS);
|
||||
for(int k = 0;k < DISTORTION_CORRECTION_POINTS * DISTORTION_CORRECTION_POINTS; k++)
|
||||
setMatrix(getMatrix(k) - sum, k);
|
||||
Printer::zLength -= sum * Printer::invAxisStepsPerMM[Z_AXIS];
|
||||
*/
|
||||
#if EEPROM_MODE
|
||||
EEPROM::storeDataIntoEEPROM();
|
||||
#endif
|
||||
// print matrix
|
||||
Com::printInfoFLN(PSTR("Distortion correction matrix:"));
|
||||
for (iy = DISTORTION_CORRECTION_POINTS - 1; iy >= 0 ; iy--) {
|
||||
for(ix = 0; ix < DISTORTION_CORRECTION_POINTS; ix++)
|
||||
Com::printF(ix ? PSTR(", ") : PSTR(""), getMatrix(matrixIndex(ix, iy)));
|
||||
Com::println();
|
||||
}
|
||||
showMatrix();
|
||||
enable(true);
|
||||
return true;
|
||||
//Printer::homeAxis(false, false, true);
|
||||
}
|
||||
|
||||
|
||||
int32_t Distortion::correct(int32_t x, int32_t y, int32_t z) const {
|
||||
if (!enabled || Printer::isZProbingActive()) {
|
||||
return 0;
|
||||
}
|
||||
z += Printer::offsetZ * Printer::axisStepsPerMM[Z_AXIS] - Printer::zMinSteps;
|
||||
if (z > zEnd) {
|
||||
/* Com::printF(PSTR("NoCor z:"),z);
|
||||
Com::printF(PSTR(" zEnd:"),zEnd);
|
||||
Com::printF(PSTR(" en:"),(int)enabled);
|
||||
Com::printFLN(PSTR(" zp:"),(int)Printer::isZProbingActive());*/
|
||||
return 0;
|
||||
}
|
||||
x -= Printer::offsetX * Printer::axisStepsPerMM[X_AXIS]; // correct active tool offset
|
||||
y -= Printer::offsetY * Printer::axisStepsPerMM[Y_AXIS];
|
||||
if(false) {
|
||||
Com::printF(PSTR("correcting ("), x);
|
||||
Com::printF(PSTR(","), y);
|
||||
}
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
x += radiusCorrectionSteps;
|
||||
y += radiusCorrectionSteps;
|
||||
int32_t fxFloor = (x - (x < 0 ? step - 1 : 0)) / step; // special case floor for negative integers!
|
||||
int32_t fyFloor = (y - (y < 0 ? step - 1 : 0)) / step;
|
||||
#else
|
||||
x -= xOffsetSteps;
|
||||
y -= yOffsetSteps;
|
||||
int32_t fxFloor = (x - (x < 0 ? xCorrectionSteps - 1 : 0)) / xCorrectionSteps; // special case floor for negative integers!
|
||||
int32_t fyFloor = (y - (y < 0 ? yCorrectionSteps - 1 : 0)) / yCorrectionSteps;
|
||||
#endif
|
||||
// indexes to the matrix
|
||||
|
||||
// position between cells of matrix, range=0 to 1 - outside of the matrix the value will be outside this range and the value will be extrapolated
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
int32_t fx = x - fxFloor * step; // Grid normalized coordinates
|
||||
int32_t fy = y - fyFloor * step;
|
||||
if (fxFloor < 0) {
|
||||
fxFloor = 0;
|
||||
fx = 0;
|
||||
} else if (fxFloor >= DISTORTION_CORRECTION_POINTS - 1) {
|
||||
fxFloor = DISTORTION_CORRECTION_POINTS - 2;
|
||||
fx = step;
|
||||
}
|
||||
if (fyFloor < 0) {
|
||||
fyFloor = 0;
|
||||
fy = 0;
|
||||
} else if (fyFloor >= DISTORTION_CORRECTION_POINTS - 1) {
|
||||
fyFloor = DISTORTION_CORRECTION_POINTS - 2;
|
||||
fy = step;
|
||||
}
|
||||
|
||||
int32_t idx11 = matrixIndex(fxFloor, fyFloor);
|
||||
int32_t m11 = getMatrix(idx11), m12 = getMatrix(idx11 + 1);
|
||||
int32_t m21 = getMatrix(idx11 + DISTORTION_CORRECTION_POINTS);
|
||||
int32_t m22 = getMatrix(idx11 + DISTORTION_CORRECTION_POINTS + 1);
|
||||
int32_t zx1 = m11 + ((m12 - m11) * fx) / step;
|
||||
int32_t zx2 = m21 + ((m22 - m21) * fx) / step;
|
||||
int32_t correction_z = zx1 + ((zx2 - zx1) * fy) / step;
|
||||
/*if(z == Printer::zMinSteps) {
|
||||
Com::printF(PSTR("DT M11:"),m11);
|
||||
Com::printF(PSTR(" M12:"),m12);
|
||||
Com::printF(PSTR(" M21:"),m21);
|
||||
Com::printF(PSTR(" M22:"),m22);
|
||||
Com::printF(PSTR(" FX:"),fx);
|
||||
Com::printF(PSTR(" FY:"),fy);
|
||||
Com::printF(PSTR(" FFX:"),fxFloor);
|
||||
Com::printF(PSTR(" FFY:"),fyFloor);
|
||||
Com::printF(PSTR(" XP:"),x-radiusCorrectionSteps);
|
||||
Com::printF(PSTR(" Yp:"),y-radiusCorrectionSteps);
|
||||
Com::printF(PSTR(" STEP:"),step);
|
||||
Com::printFLN(PSTR(" ZCOR:"),correction_z);
|
||||
}*/
|
||||
#else
|
||||
int32_t fx = x - fxFloor * xCorrectionSteps; // Grid normalized coordinates
|
||||
int32_t fy = y - fyFloor * yCorrectionSteps;
|
||||
if (fxFloor < 0) {
|
||||
fxFloor = 0;
|
||||
fx = 0;
|
||||
} else if (fxFloor >= DISTORTION_CORRECTION_POINTS - 1) {
|
||||
fxFloor = DISTORTION_CORRECTION_POINTS - 2;
|
||||
fx = xCorrectionSteps;
|
||||
}
|
||||
if (fyFloor < 0) {
|
||||
fyFloor = 0;
|
||||
fy = 0;
|
||||
} else if (fyFloor >= DISTORTION_CORRECTION_POINTS - 1) {
|
||||
fyFloor = DISTORTION_CORRECTION_POINTS - 2;
|
||||
fy = yCorrectionSteps;
|
||||
}
|
||||
|
||||
int32_t idx11 = matrixIndex(fxFloor, fyFloor);
|
||||
int32_t m11 = getMatrix(idx11), m12 = getMatrix(idx11 + 1);
|
||||
int32_t m21 = getMatrix(idx11 + DISTORTION_CORRECTION_POINTS);
|
||||
int32_t m22 = getMatrix(idx11 + DISTORTION_CORRECTION_POINTS + 1);
|
||||
int32_t zx1 = m11 + ((m12 - m11) * fx) / xCorrectionSteps;
|
||||
int32_t zx2 = m21 + ((m22 - m21) * fx) / xCorrectionSteps;
|
||||
int32_t correction_z = zx1 + ((zx2 - zx1) * fy) / yCorrectionSteps;
|
||||
#endif
|
||||
/* if(false) {
|
||||
Com::printF(PSTR(") by "), correction_z);
|
||||
Com::printF(PSTR(" ix= "), fxFloor); Com::printF(PSTR(" fx= "), (float)fx/(float)xCorrectionSteps,3);
|
||||
Com::printF(PSTR(" iy= "), fyFloor); Com::printFLN(PSTR(" fy= "), (float)fy/(float)yCorrectionSteps,3);
|
||||
}*/
|
||||
if (z > zStart && z > Printer::zMinSteps)
|
||||
//All variables are type int. For calculation we need float values
|
||||
correction_z = (correction_z * static_cast<float>(zEnd - z) / (zEnd - zStart));
|
||||
/* if(correction_z > 20 || correction_z < -20) {
|
||||
Com::printFLN(PSTR("Corr. error too big:"),correction_z);
|
||||
Com::printF(PSTR("fxf"),(int)fxFloor);
|
||||
Com::printF(PSTR(" fyf"),(int)fyFloor);
|
||||
Com::printF(PSTR(" fx"),fx);
|
||||
Com::printF(PSTR(" fy"),fy);
|
||||
Com::printF(PSTR(" x"),x);
|
||||
Com::printFLN(PSTR(" y"),y);
|
||||
Com::printF(PSTR(" m11:"),m11);
|
||||
Com::printF(PSTR(" m12:"),m12);
|
||||
Com::printF(PSTR(" m21:"),m21);
|
||||
Com::printF(PSTR(" m22:"),m22);
|
||||
Com::printFLN(PSTR(" step:"),step);
|
||||
correction_z = 0;
|
||||
}*/
|
||||
return correction_z;
|
||||
}
|
||||
|
||||
void Distortion::set(float x, float y, float z) {
|
||||
#if defined(DISTORTION_LIMIT_TO) && DISTORTION_LIMIT_TO != 0
|
||||
if(fabs(z) > DISTORTION_LIMIT_TO) {
|
||||
Com::printWarningFLN(PSTR("Max. distortion value exceeded - not setting this value."));
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
int ix = (x * Printer::axisStepsPerMM[Z_AXIS] + radiusCorrectionSteps + step / 2) / step;
|
||||
int iy = (y * Printer::axisStepsPerMM[Z_AXIS] + radiusCorrectionSteps + step / 2) / step;
|
||||
#else
|
||||
int ix = (x * Printer::axisStepsPerMM[X_AXIS] - xOffsetSteps + xCorrectionSteps / 2) / xCorrectionSteps;
|
||||
int iy = (y * Printer::axisStepsPerMM[Y_AXIS] - yOffsetSteps + yCorrectionSteps / 2) / yCorrectionSteps;
|
||||
#endif
|
||||
if(ix < 0) ix = 0;
|
||||
if(iy < 0) iy = 0;
|
||||
if(ix >= DISTORTION_CORRECTION_POINTS - 1) ix = DISTORTION_CORRECTION_POINTS - 1;
|
||||
if(iy >= DISTORTION_CORRECTION_POINTS - 1) iy = DISTORTION_CORRECTION_POINTS - 1;
|
||||
int32_t idx = matrixIndex(ix, iy);
|
||||
setMatrix(z * Printer::axisStepsPerMM[Z_AXIS], idx);
|
||||
}
|
||||
|
||||
void Distortion::showMatrix() {
|
||||
for(int ix = 0; ix < DISTORTION_CORRECTION_POINTS; ix++) {
|
||||
for(int iy = 0; iy < DISTORTION_CORRECTION_POINTS; iy++) {
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
float x = (-radiusCorrectionSteps + ix * step) * Printer::invAxisStepsPerMM[Z_AXIS];
|
||||
float y = (-radiusCorrectionSteps + iy * step) * Printer::invAxisStepsPerMM[Z_AXIS];
|
||||
#else
|
||||
float x = (xOffsetSteps + ix * xCorrectionSteps) * Printer::invAxisStepsPerMM[X_AXIS];
|
||||
float y = (yOffsetSteps + iy * yCorrectionSteps) * Printer::invAxisStepsPerMM[Y_AXIS];
|
||||
#endif
|
||||
int32_t idx = matrixIndex(ix, iy);
|
||||
float z = getMatrix(idx) * Printer::invAxisStepsPerMM[Z_AXIS];
|
||||
Com::printF(PSTR("G33 X"), x, 2);
|
||||
Com::printF(PSTR(" Y"), y, 2);
|
||||
Com::printFLN(PSTR(" Z"), z, 3);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif // DISTORTION_CORRECTION
|
86
Repetier-Firmware 1.0.3/Repetier/Distortion.h
Normal file
86
Repetier-Firmware 1.0.3/Repetier/Distortion.h
Normal file
@ -0,0 +1,86 @@
|
||||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware 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.
|
||||
|
||||
Repetier-Firmware 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 Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
|
||||
#ifndef _DISTORTION_H
|
||||
#define _DISTORTION_H
|
||||
|
||||
#if DISTORTION_CORRECTION || defined(DOXYGEN)
|
||||
/** \brief Handle distortion related stuff.
|
||||
|
||||
Distortion correction can be used to solve problems resulting from an uneven build plate.
|
||||
It allows measuring a nxn grid with a z-probe and add these correction to all moves.
|
||||
Normally you start at the bottom with 100% correction and at 0.5mm you start reducing correction
|
||||
until it vanishes completely at 1-3 mm.
|
||||
|
||||
The stored values are steps required to reach the bumped level assuming you are at zMin. So if you have a 1mm indentation
|
||||
it contains -steps per mm.
|
||||
*/
|
||||
class Distortion {
|
||||
public:
|
||||
Distortion();
|
||||
void init();
|
||||
void enable(bool permanent = true);
|
||||
void disable(bool permanent = true);
|
||||
bool measure(void);
|
||||
/** \brief Compute distortion correction at given position.
|
||||
|
||||
The current tool offset is added to the CNC position to reference the right distortion point.
|
||||
|
||||
\param x coordinate in CMC steps.
|
||||
\param y coordinate in CMC steps.
|
||||
\param z coordinate in CMC steps.
|
||||
\return Correction required in z steps.
|
||||
*/
|
||||
int32_t correct(int32_t x, int32_t y, int32_t z) const;
|
||||
void updateDerived();
|
||||
void reportStatus();
|
||||
bool isEnabled() {
|
||||
return enabled;
|
||||
}
|
||||
int32_t zMaxSteps() {
|
||||
return zEnd;
|
||||
}
|
||||
void set(float x, float y, float z);
|
||||
void showMatrix();
|
||||
void resetCorrection();
|
||||
private:
|
||||
int matrixIndex(fast8_t x, fast8_t y) const;
|
||||
int32_t getMatrix(int index) const;
|
||||
void setMatrix(int32_t val, int index);
|
||||
bool isCorner(fast8_t i, fast8_t j) const;
|
||||
INLINE int32_t extrapolatePoint(fast8_t x1, fast8_t y1, fast8_t x2, fast8_t y2) const;
|
||||
void extrapolateCorner(fast8_t x, fast8_t y, fast8_t dx, fast8_t dy);
|
||||
void extrapolateCorners();
|
||||
|
||||
// attributes
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
int32_t step;
|
||||
int32_t radiusCorrectionSteps;
|
||||
#else
|
||||
int32_t xCorrectionSteps, xOffsetSteps;
|
||||
int32_t yCorrectionSteps, yOffsetSteps;
|
||||
#endif
|
||||
int32_t zStart, zEnd;
|
||||
#if !DISTORTION_PERMANENT
|
||||
int32_t matrix[DISTORTION_CORRECTION_POINTS * DISTORTION_CORRECTION_POINTS];
|
||||
#endif
|
||||
bool enabled;
|
||||
};
|
||||
#endif //DISTORTION_CORRECTION
|
||||
|
||||
#endif
|
253
Repetier-Firmware 1.0.3/Repetier/Drivers.cpp
Normal file
253
Repetier-Firmware 1.0.3/Repetier/Drivers.cpp
Normal file
@ -0,0 +1,253 @@
|
||||
#include "Repetier.h"
|
||||
|
||||
#if defined(NUM_MOTOR_DRIVERS) && NUM_MOTOR_DRIVERS > 0
|
||||
MOTOR_DRIVER_1(motorDriver1);
|
||||
#if NUM_MOTOR_DRIVERS > 1
|
||||
MOTOR_DRIVER_2(motorDriver2);
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 2
|
||||
MOTOR_DRIVER_3(motorDriver3);
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 3
|
||||
MOTOR_DRIVER_4(motorDriver4);
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 4
|
||||
MOTOR_DRIVER_5(motorDriver5);
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 5
|
||||
MOTOR_DRIVER_6(motorDriver6);
|
||||
#endif
|
||||
|
||||
MotorDriverInterface *motorDrivers[NUM_MOTOR_DRIVERS] =
|
||||
{
|
||||
&motorDriver1
|
||||
#if NUM_MOTOR_DRIVERS > 1
|
||||
, &motorDriver2
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 2
|
||||
, &motorDriver3
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 3
|
||||
, &motorDriver4
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 4
|
||||
, &motorDriver5
|
||||
#endif
|
||||
#if NUM_MOTOR_DRIVERS > 5
|
||||
, &motorDriver6
|
||||
#endif
|
||||
};
|
||||
|
||||
MotorDriverInterface *getMotorDriver(int idx)
|
||||
{
|
||||
return motorDrivers[idx];
|
||||
}
|
||||
|
||||
/**
|
||||
Run motor P until it is at position X
|
||||
*/
|
||||
void commandG201(GCode &code)
|
||||
{
|
||||
int id = 0;
|
||||
if(code.hasP())
|
||||
id = code.P;
|
||||
if(id < 0) id = 0;
|
||||
if(id >= NUM_MOTOR_DRIVERS) id = 0;
|
||||
if(!code.hasX()) return;
|
||||
motorDrivers[id]->gotoPosition(code.X);
|
||||
}
|
||||
|
||||
//G202 P<motorId> X<setpos> - Mark current position as X
|
||||
void commandG202(GCode &code)
|
||||
{
|
||||
int id = 0;
|
||||
if(code.hasP())
|
||||
id = code.P;
|
||||
if(id < 0) id = 0;
|
||||
if(id >= NUM_MOTOR_DRIVERS) id = 0;
|
||||
if(!code.hasX()) return;
|
||||
motorDrivers[id]->setCurrentAs(code.X);
|
||||
}
|
||||
//G203 P<motorId> - Report current motor position
|
||||
void commandG203(GCode &code)
|
||||
{
|
||||
int id = 0;
|
||||
if(code.hasP())
|
||||
id = code.P;
|
||||
if(id < 0) id = 0;
|
||||
if(id >= NUM_MOTOR_DRIVERS) id = 0;
|
||||
Com::printF(PSTR("Motor"),id);
|
||||
Com::printFLN(PSTR(" Pos:"),motorDrivers[id]->getPosition());
|
||||
}
|
||||
//G204 P<motorId> S<0/1> - Enable/disable motor
|
||||
void commandG204(GCode &code)
|
||||
{
|
||||
int id = 0;
|
||||
if(code.hasP())
|
||||
id = code.P;
|
||||
if(id < 0) id = 0;
|
||||
if(id >= NUM_MOTOR_DRIVERS) id = 0;
|
||||
if(!code.hasS()) return;
|
||||
if(code.S)
|
||||
motorDrivers[id]->enable();
|
||||
else
|
||||
motorDrivers[id]->disable();
|
||||
}
|
||||
// G205 P<motorId> S<0/1> E<0/1> - Home motor, S1 = go back to stored position, E1 = home only if endstop was never met, meaning it was never homed with motor.
|
||||
void commandG205(GCode &code)
|
||||
{
|
||||
int id = 0;
|
||||
if(code.hasP())
|
||||
id = code.P;
|
||||
if(id < 0) id = 0;
|
||||
if(id >= NUM_MOTOR_DRIVERS) id = 0;
|
||||
motorDrivers[id]->home(code.hasS() && code.S != 0, code.hasE() && code.E != 0);
|
||||
}
|
||||
|
||||
void disableAllMotorDrivers()
|
||||
{
|
||||
for(int i = 0; i < NUM_MOTOR_DRIVERS; i++)
|
||||
motorDrivers[i]->disable();
|
||||
}
|
||||
void initializeAllMotorDrivers()
|
||||
{
|
||||
for(int i = 0; i < NUM_MOTOR_DRIVERS; i++)
|
||||
motorDrivers[i]->initialize();
|
||||
}
|
||||
|
||||
#endif // NUM_MOTOR_DRIVERS
|
||||
|
||||
#if defined(SUPPORT_LASER) && SUPPORT_LASER
|
||||
|
||||
secondspeed_t LaserDriver::intensity = LASER_PWM_MAX; // Intensity to use for next move queued if we want lasers. This is NOT the current value!
|
||||
secondspeed_t LaserDriver::intens = 0;
|
||||
|
||||
bool LaserDriver::laserOn = false;
|
||||
bool LaserDriver::firstMove = true;
|
||||
|
||||
void LaserDriver::initialize()
|
||||
{
|
||||
if(EVENT_INITIALIZE_LASER)
|
||||
{
|
||||
#if LASER_PIN > -1
|
||||
SET_OUTPUT(LASER_PIN);
|
||||
#endif
|
||||
}
|
||||
changeIntensity(0);
|
||||
}
|
||||
|
||||
void LaserDriver::changeIntensity(secondspeed_t newIntensity)
|
||||
{
|
||||
#if defined(DOOR_PIN) && DOOR_PIN > -1
|
||||
if(Printer::isDoorOpen()) {
|
||||
newIntensity = 0; // force laser off if door is open
|
||||
}
|
||||
#endif
|
||||
if(EVENT_SET_LASER(newIntensity))
|
||||
{
|
||||
// Default implementation
|
||||
#if LASER_PIN > -1
|
||||
WRITE(LASER_PIN,(LASER_ON_HIGH ? newIntensity > 199 : newIntensity < 200));
|
||||
#endif
|
||||
}
|
||||
intens=newIntensity;//for "Transfer" Status Page
|
||||
}
|
||||
#endif // SUPPORT_LASER
|
||||
|
||||
#if defined(SUPPORT_CNC) && SUPPORT_CNC
|
||||
/**
|
||||
The CNC driver differs a bit from laser driver. Here only M3,M4,M5 have an influence on the spindle.
|
||||
The motor also keeps running for G0 moves. M3 and M4 wait for old moves to be finished and then enables
|
||||
the motor. It then waits CNC_WAIT_ON_ENABLE milliseconds for the spindle to reach target speed.
|
||||
*/
|
||||
|
||||
int8_t CNCDriver::direction = 0;
|
||||
secondspeed_t CNCDriver::spindleSpeed= 0;
|
||||
uint16_t CNCDriver::spindleRpm= 0;
|
||||
|
||||
|
||||
/** Initialize cnc pins. EVENT_INITIALIZE_CNC should return false to prevent default initialization.*/
|
||||
void CNCDriver::initialize()
|
||||
{
|
||||
if(EVENT_INITIALIZE_CNC)
|
||||
{
|
||||
#if CNC_ENABLE_PIN > -1
|
||||
SET_OUTPUT(CNC_ENABLE_PIN);
|
||||
WRITE(CNC_ENABLE_PIN,!CNC_ENABLE_WITH);
|
||||
#endif
|
||||
#if CNC_DIRECTION_PIN > -1
|
||||
SET_OUTPUT(CNC_DIRECTION_PIN);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
/** Turns off spindle. For event override implement
|
||||
EVENT_SPINDLE_OFF
|
||||
returning false.
|
||||
*/
|
||||
void CNCDriver::spindleOff()
|
||||
{
|
||||
spindleRpm=0;
|
||||
if(direction == 0) return; // already off
|
||||
if(EVENT_SPINDLE_OFF)
|
||||
{
|
||||
#if CNC_ENABLE_PIN > -1
|
||||
WRITE(CNC_ENABLE_PIN,!CNC_ENABLE_WITH);
|
||||
#endif
|
||||
}
|
||||
HAL::delayMilliseconds(CNC_WAIT_ON_DISABLE);
|
||||
direction = 0;
|
||||
}
|
||||
/** Turns spindle on. Default implementation uses a enable pin CNC_ENABLE_PIN. If
|
||||
CNC_DIRECTION_PIN is not -1 it sets direction to CNC_DIRECTION_CW. rpm is ignored.
|
||||
To override with event system, return false for the event
|
||||
EVENT_SPINDLE_CW(rpm)
|
||||
*/
|
||||
void CNCDriver::spindleOnCW(int32_t rpm)
|
||||
{
|
||||
spindleSpeed=map(rpm,0,CNC_RPM_MAX,0,CNC_PWM_MAX);// linear interpolation
|
||||
|
||||
|
||||
if(direction == 1 && spindleRpm == rpm)
|
||||
return;
|
||||
if(direction == -1) {
|
||||
spindleOff();
|
||||
}
|
||||
spindleRpm = rpm;// for display
|
||||
direction = 1;
|
||||
if(EVENT_SPINDLE_CW(rpm)) {
|
||||
#if CNC_DIRECTION_PIN > -1
|
||||
WRITE(CNC_DIRECTION_PIN, CNC_DIRECTION_CW);
|
||||
#endif
|
||||
#if CNC_ENABLE_PIN > -1
|
||||
WRITE(CNC_ENABLE_PIN, CNC_ENABLE_WITH);
|
||||
#endif
|
||||
}
|
||||
HAL::delayMilliseconds(CNC_WAIT_ON_ENABLE);
|
||||
}
|
||||
/** Turns spindle on. Default implementation uses a enable pin CNC_ENABLE_PIN. If
|
||||
CNC_DIRECTION_PIN is not -1 it sets direction to !CNC_DIRECTION_CW. rpm is ignored.
|
||||
To override with event system, return false for the event
|
||||
EVENT_SPINDLE_CCW(rpm)
|
||||
*/
|
||||
void CNCDriver::spindleOnCCW(int32_t rpm)
|
||||
{
|
||||
spindleSpeed=map(rpm,0,CNC_RPM_MAX,0,CNC_PWM_MAX);// linear interpolation
|
||||
|
||||
if(direction == -1 && spindleRpm == rpm)
|
||||
return;
|
||||
if(direction == 1) {
|
||||
spindleOff();
|
||||
}
|
||||
spindleRpm = rpm;// for display
|
||||
direction = -1;
|
||||
if(EVENT_SPINDLE_CCW(rpm)) {
|
||||
#if CNC_DIRECTION_PIN > -1
|
||||
WRITE(CNC_DIRECTION_PIN, !CNC_DIRECTION_CW);
|
||||
#endif
|
||||
#if CNC_ENABLE_PIN > -1
|
||||
WRITE(CNC_ENABLE_PIN, CNC_ENABLE_WITH);
|
||||
#endif
|
||||
}
|
||||
HAL::delayMilliseconds(CNC_WAIT_ON_ENABLE);
|
||||
}
|
||||
#endif
|
268
Repetier-Firmware 1.0.3/Repetier/Drivers.h
Normal file
268
Repetier-Firmware 1.0.3/Repetier/Drivers.h
Normal file
@ -0,0 +1,268 @@
|
||||
#ifndef DRIVERS_H_INCLUDED
|
||||
#define DRIVERS_H_INCLUDED
|
||||
|
||||
/**
|
||||
For some special printers you need to control extra motors. Possible reasons are
|
||||
- Extruder switches
|
||||
- Clearing surface
|
||||
- Leveling
|
||||
|
||||
Repetier-Firmware supports up to 4 extra motors that can be controlled by
|
||||
G201 P<motorId> X<pos> - Go to position X with motor motorId
|
||||
G202 P<motorId> X<setpos> - Mark current position as X
|
||||
G203 P<motorId> - Report current motor position
|
||||
G204 P<motorId> S<0/1> - Enable/disable motor
|
||||
G205 P<motorId> S<0/1> E<0/1> - Home motor, S1 = go back to stored position, E1 = home only if endstop was never met, meaning it was never homed with motor.
|
||||
|
||||
These motors are already special and there might be different types, so we can not assume
|
||||
one class fits all needs. So to keep it simple, the firmware defines this general
|
||||
interface which a motor must implement. That way we can handle any type without changing
|
||||
the main code.
|
||||
*/
|
||||
class MotorDriverInterface
|
||||
{
|
||||
public:
|
||||
virtual void initialize() = 0;
|
||||
virtual float getPosition() = 0;
|
||||
virtual void setCurrentAs(float newPos) = 0;
|
||||
virtual void gotoPosition(float newPos) = 0;
|
||||
virtual void enable() = 0;
|
||||
virtual void disable() = 0;
|
||||
virtual void home(bool goToCurrent, bool onlyIfNotHomed) = 0;
|
||||
};
|
||||
|
||||
/**
|
||||
Simple class to drive a stepper motor with fixed speed.
|
||||
*/
|
||||
template<int stepPin, int dirPin, int enablePin,bool invertDir, bool invertEnable>
|
||||
class StepperDriver : public MotorDriverInterface
|
||||
{
|
||||
int32_t position;
|
||||
int32_t delayUS;
|
||||
float stepsPerMM;
|
||||
public:
|
||||
StepperDriver(float _stepsPerMM,float speed)
|
||||
{
|
||||
stepsPerMM = _stepsPerMM;
|
||||
position = 0;
|
||||
delayUS = 500000 / (speed * stepsPerMM);
|
||||
}
|
||||
void initialize() {
|
||||
HAL::pinMode(enablePin, OUTPUT);
|
||||
HAL::pinMode(stepPin, OUTPUT);
|
||||
HAL::pinMode(dirPin, OUTPUT);
|
||||
HAL::digitalWrite(enablePin, !invertEnable);
|
||||
}
|
||||
float getPosition()
|
||||
{
|
||||
return position / stepsPerMM;
|
||||
}
|
||||
void setCurrentAs(float newPos)
|
||||
{
|
||||
position = floor(newPos * stepsPerMM + 0.5f);
|
||||
}
|
||||
void gotoPosition(float newPos)
|
||||
{
|
||||
enable();
|
||||
int32_t target = floor(newPos * stepsPerMM + 0.5f) - position;
|
||||
position += target;
|
||||
if(target > 0) {
|
||||
HAL::digitalWrite(dirPin, !invertDir);
|
||||
} else {
|
||||
target = -target;
|
||||
HAL::digitalWrite(dirPin, invertDir);
|
||||
}
|
||||
while(target) {
|
||||
HAL::digitalWrite(stepPin, HIGH);
|
||||
HAL::delayMicroseconds(delayUS);
|
||||
HAL::digitalWrite(stepPin, LOW);
|
||||
HAL::delayMicroseconds(delayUS);
|
||||
target--;
|
||||
HAL::pingWatchdog();
|
||||
if((target & 127) == 0) {
|
||||
Commands::checkForPeriodicalActions(false);
|
||||
GCode::keepAlive(Processing);
|
||||
}
|
||||
}
|
||||
}
|
||||
void enable()
|
||||
{
|
||||
HAL::digitalWrite(enablePin, invertEnable);
|
||||
}
|
||||
void disable()
|
||||
{
|
||||
HAL::digitalWrite(enablePin, !invertEnable);
|
||||
}
|
||||
void home(bool goToCurrent, bool onlyIfNotHomed) {}
|
||||
};
|
||||
|
||||
/**
|
||||
Simple class to drive a stepper motor with fixed speed with additional endstop.
|
||||
Min position is 0 and max. position maxDistance.
|
||||
*/
|
||||
template<int stepPin, int dirPin, int enablePin,bool invertDir, bool invertEnable, int endstopPin, bool invertEndstop, bool minEndstop, bool endstopPullup>
|
||||
class StepperDriverWithEndstop : public MotorDriverInterface
|
||||
{
|
||||
int32_t position;
|
||||
int32_t delayUS;
|
||||
float stepsPerMM;
|
||||
float maxDistance;
|
||||
bool isHomed;
|
||||
public:
|
||||
StepperDriverWithEndstop(float _stepsPerMM,float speed,float maxDist)
|
||||
{
|
||||
stepsPerMM = _stepsPerMM;
|
||||
maxDistance = maxDist;
|
||||
isHomed = false;
|
||||
position = 0;
|
||||
delayUS = 500000 / (speed * stepsPerMM);
|
||||
}
|
||||
void initialize() {
|
||||
HAL::pinMode(enablePin, OUTPUT);
|
||||
HAL::pinMode(stepPin, OUTPUT);
|
||||
HAL::pinMode(dirPin, OUTPUT);
|
||||
HAL::pinMode(endstopPin, endstopPullup ? INPUT_PULLUP : INPUT);
|
||||
HAL::digitalWrite(enablePin, !invertEnable);
|
||||
}
|
||||
bool endstopHit() {
|
||||
return invertEndstop ? !HAL::digitalRead(endstopPin) : HAL::digitalRead(endstopPin);
|
||||
}
|
||||
float getPosition()
|
||||
{
|
||||
return position / stepsPerMM;
|
||||
}
|
||||
void setCurrentAs(float newPos)
|
||||
{
|
||||
position = floor(newPos * stepsPerMM + 0.5f);
|
||||
}
|
||||
void gotoPosition(float newPos)
|
||||
{
|
||||
bool up = true;
|
||||
if(newPos < 0)
|
||||
newPos = 0;
|
||||
if(newPos > maxDistance)
|
||||
newPos = maxDistance;
|
||||
enable();
|
||||
int32_t target = floor(newPos * stepsPerMM + 0.5f) - position;
|
||||
position += target;
|
||||
if(target > 0) {
|
||||
HAL::digitalWrite(dirPin, !invertDir);
|
||||
} else {
|
||||
target = -target;
|
||||
up = false;
|
||||
HAL::digitalWrite(dirPin, invertDir);
|
||||
}
|
||||
while(target) {
|
||||
HAL::digitalWrite(stepPin, HIGH);
|
||||
HAL::delayMicroseconds(delayUS);
|
||||
HAL::digitalWrite(stepPin, LOW);
|
||||
HAL::delayMicroseconds(delayUS);
|
||||
target--;
|
||||
HAL::pingWatchdog();
|
||||
if((target & 127) == 0) {
|
||||
Commands::checkForPeriodicalActions(false);
|
||||
GCode::keepAlive(Processing);
|
||||
}
|
||||
if(up != minEndstop) {
|
||||
if(endstopHit()) {
|
||||
isHomed = true;
|
||||
if(minEndstop)
|
||||
position = 0;
|
||||
else
|
||||
setCurrentAs(maxDistance);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
void home(bool goToCurrent, bool onlyIfNotHomed) {
|
||||
if(onlyIfNotHomed && isHomed)
|
||||
return;
|
||||
float origPosition = getPosition();
|
||||
if(minEndstop) {
|
||||
setCurrentAs(maxDistance);
|
||||
gotoPosition(0);
|
||||
} else {
|
||||
position = 0;
|
||||
gotoPosition(maxDistance);
|
||||
}
|
||||
if(goToCurrent)
|
||||
gotoPosition(origPosition);
|
||||
}
|
||||
void enable()
|
||||
{
|
||||
HAL::digitalWrite(enablePin, invertEnable);
|
||||
}
|
||||
void disable()
|
||||
{
|
||||
HAL::digitalWrite(enablePin, !invertEnable);
|
||||
}
|
||||
};
|
||||
|
||||
#if defined(NUM_MOTOR_DRIVERS) && NUM_MOTOR_DRIVERS > 0
|
||||
class GCode;
|
||||
extern void commandG201(GCode &code);
|
||||
extern void commandG202(GCode &code);
|
||||
extern void commandG203(GCode &code);
|
||||
extern void commandG204(GCode &code);
|
||||
extern void commandG205(GCode &code);
|
||||
extern void disableAllMotorDrivers();
|
||||
extern MotorDriverInterface *getMotorDriver(int idx);
|
||||
extern void initializeAllMotorDrivers();
|
||||
#endif
|
||||
|
||||
|
||||
#if defined(SUPPORT_LASER) && SUPPORT_LASER
|
||||
/**
|
||||
With laser support you can exchange a extruder by a laser. A laser gets controlled by a digital pin.
|
||||
By default all intensities > 200 are always on, and lower values are always off. You can overwrite
|
||||
this with a programmed event EVENT_SET_LASER(intensity) that return false to signal the default
|
||||
implementation that it has set it's value already.
|
||||
EVENT_INITIALIZE_LASER should return false to prevent default initialization.
|
||||
*/
|
||||
class LaserDriver {
|
||||
public:
|
||||
static secondspeed_t intensity; // Intensity to use for next move queued. This is NOT the current value!
|
||||
static secondspeed_t intens;
|
||||
static bool laserOn; // Enabled by M3?
|
||||
static bool firstMove ;
|
||||
static void initialize();
|
||||
static void changeIntensity(secondspeed_t newIntensity);
|
||||
};
|
||||
#endif
|
||||
|
||||
#if defined(SUPPORT_CNC) && SUPPORT_CNC
|
||||
/**
|
||||
The CNC driver differs a bit from laser driver. Here only M3,M4,M5 have an influence on the spindle.
|
||||
The motor also keeps running for G0 moves. M3 and M4 wait for old moves to be finished and then enables
|
||||
the motor. It then waits CNC_WAIT_ON_ENABLE milliseconds for the spindle to reach target speed.
|
||||
*/
|
||||
class CNCDriver {
|
||||
public:
|
||||
static int8_t direction;
|
||||
static secondspeed_t spindleSpeed;
|
||||
static uint16_t spindleRpm;
|
||||
|
||||
/** Initialize cnc pins. EVENT_INITIALIZE_CNC should return false to prevent default initialization.*/
|
||||
static void initialize();
|
||||
/** Turns off spindle. For event override implement
|
||||
EVENT_SPINDLE_OFF
|
||||
returning false.
|
||||
*/
|
||||
static void spindleOff();
|
||||
/** Turns spindle on. Default implementation uses a enable pin CNC_ENABLE_PIN. If
|
||||
CNC_DIRECTION_PIN is not -1 it sets direction to CNC_DIRECTION_CW. rpm is ignored.
|
||||
To override with event system, return false for the event
|
||||
EVENT_SPINDLE_CW(rpm)
|
||||
*/
|
||||
static void spindleOnCW(int32_t rpm);
|
||||
/** Turns spindle on. Default implementation uses a enable pin CNC_ENABLE_PIN. If
|
||||
CNC_DIRECTION_PIN is not -1 it sets direction to !CNC_DIRECTION_CW. rpm is ignored.
|
||||
To override with event system, return false for the event
|
||||
EVENT_SPINDLE_CCW(rpm)
|
||||
*/
|
||||
static void spindleOnCCW(int32_t rpm);
|
||||
};
|
||||
#endif
|
||||
|
||||
#endif // DRIVERS_H_INCLUDED
|
1199
Repetier-Firmware 1.0.3/Repetier/Eeprom.cpp
Normal file
1199
Repetier-Firmware 1.0.3/Repetier/Eeprom.cpp
Normal file
File diff suppressed because it is too large
Load Diff
596
Repetier-Firmware 1.0.3/Repetier/Eeprom.h
Normal file
596
Repetier-Firmware 1.0.3/Repetier/Eeprom.h
Normal file
@ -0,0 +1,596 @@
|
||||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware 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.
|
||||
|
||||
Repetier-Firmware 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 Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
|
||||
#ifndef _EEPROM_H
|
||||
#define _EEPROM_H
|
||||
|
||||
// Id to distinguish version changes
|
||||
#define EEPROM_PROTOCOL_VERSION 19
|
||||
|
||||
/** Where to start with our data block in memory. Can be moved if you
|
||||
have problems with other modules using the eeprom */
|
||||
|
||||
#define EPR_MAGIC_BYTE 0
|
||||
#define EPR_ACCELERATION_TYPE 1
|
||||
#define EPR_XAXIS_STEPS_PER_MM 3
|
||||
#define EPR_YAXIS_STEPS_PER_MM 7
|
||||
#define EPR_ZAXIS_STEPS_PER_MM 11
|
||||
#define EPR_X_MAX_FEEDRATE 15
|
||||
#define EPR_Y_MAX_FEEDRATE 19
|
||||
#define EPR_Z_MAX_FEEDRATE 23
|
||||
#define EPR_X_HOMING_FEEDRATE 27
|
||||
#define EPR_Y_HOMING_FEEDRATE 31
|
||||
#define EPR_Z_HOMING_FEEDRATE 35
|
||||
#define EPR_MAX_JERK 39
|
||||
//#define EPR_OPS_MIN_DISTANCE 43
|
||||
#define EPR_MAX_ZJERK 47
|
||||
#define EPR_X_MAX_ACCEL 51
|
||||
#define EPR_Y_MAX_ACCEL 55
|
||||
#define EPR_Z_MAX_ACCEL 59
|
||||
#define EPR_X_MAX_TRAVEL_ACCEL 63
|
||||
#define EPR_Y_MAX_TRAVEL_ACCEL 67
|
||||
#define EPR_Z_MAX_TRAVEL_ACCEL 71
|
||||
#define EPR_BAUDRATE 75
|
||||
#define EPR_MAX_INACTIVE_TIME 79
|
||||
#define EPR_STEPPER_INACTIVE_TIME 83
|
||||
//#define EPR_OPS_RETRACT_DISTANCE 87
|
||||
//#define EPR_OPS_RETRACT_BACKLASH 91
|
||||
#define EPR_EXTRUDER_SPEED 95
|
||||
//#define EPR_OPS_MOVE_AFTER 99
|
||||
//#define EPR_OPS_MODE 103
|
||||
#define EPR_INTEGRITY_BYTE 104 // Here the xored sum over eeprom is stored
|
||||
#define EPR_VERSION 105 // Version id for updates in EEPROM storage
|
||||
#define EPR_BED_HEAT_MANAGER 106
|
||||
#define EPR_BED_DRIVE_MAX 107
|
||||
#define EPR_BED_PID_PGAIN 108
|
||||
#define EPR_BED_PID_IGAIN 112
|
||||
#define EPR_BED_PID_DGAIN 116
|
||||
#define EPR_BED_PID_MAX 120
|
||||
#define EPR_BED_DRIVE_MIN 124
|
||||
#define EPR_PRINTING_TIME 125 // Time in seconds printing
|
||||
#define EPR_PRINTING_DISTANCE 129 // Filament length printed
|
||||
#define EPR_X_HOME_OFFSET 133
|
||||
#define EPR_Y_HOME_OFFSET 137
|
||||
#define EPR_Z_HOME_OFFSET 141
|
||||
#define EPR_X_LENGTH 145
|
||||
#define EPR_Y_LENGTH 149
|
||||
#define EPR_Z_LENGTH 153
|
||||
#define EPR_BACKLASH_X 157
|
||||
#define EPR_BACKLASH_Y 161
|
||||
#define EPR_BACKLASH_Z 165
|
||||
|
||||
#define EPR_Z_PROBE_X_OFFSET 800
|
||||
#define EPR_Z_PROBE_Y_OFFSET 804
|
||||
#define EPR_Z_PROBE_HEIGHT 808
|
||||
#define EPR_Z_PROBE_SPEED 812
|
||||
#define EPR_Z_PROBE_X1 816
|
||||
#define EPR_Z_PROBE_Y1 820
|
||||
#define EPR_Z_PROBE_X2 824
|
||||
#define EPR_Z_PROBE_Y2 828
|
||||
#define EPR_Z_PROBE_X3 832
|
||||
#define EPR_Z_PROBE_Y3 836
|
||||
#define EPR_Z_PROBE_XY_SPEED 840
|
||||
#define EPR_AUTOLEVEL_MATRIX 844
|
||||
#define EPR_AUTOLEVEL_ACTIVE 880
|
||||
#define EPR_DELTA_DIAGONAL_ROD_LENGTH 881
|
||||
#define EPR_DELTA_HORIZONTAL_RADIUS 885
|
||||
#define EPR_DELTA_SEGMENTS_PER_SECOND_PRINT 889
|
||||
#define EPR_DELTA_SEGMENTS_PER_SECOND_MOVE 891
|
||||
#define EPR_DELTA_TOWERX_OFFSET_STEPS 893
|
||||
#define EPR_DELTA_TOWERY_OFFSET_STEPS 895
|
||||
#define EPR_DELTA_TOWERZ_OFFSET_STEPS 897
|
||||
#define EPR_DELTA_ALPHA_A 901
|
||||
#define EPR_DELTA_ALPHA_B 905
|
||||
#define EPR_DELTA_ALPHA_C 909
|
||||
#define EPR_DELTA_RADIUS_CORR_A 913
|
||||
#define EPR_DELTA_RADIUS_CORR_B 917
|
||||
#define EPR_DELTA_RADIUS_CORR_C 921
|
||||
#define EPR_DELTA_MAX_RADIUS 925
|
||||
#define EPR_Z_PROBE_BED_DISTANCE 929
|
||||
#define EPR_DELTA_DIAGONAL_CORRECTION_A 933
|
||||
#define EPR_DELTA_DIAGONAL_CORRECTION_B 937
|
||||
#define EPR_DELTA_DIAGONAL_CORRECTION_C 941
|
||||
#define EPR_TOUCHSCREEN 946 // - 975 = 30 byte for touchscreen calibration data
|
||||
|
||||
// Axis compensation
|
||||
#define EPR_AXISCOMP_TANXY 976
|
||||
#define EPR_AXISCOMP_TANYZ 980
|
||||
#define EPR_AXISCOMP_TANXZ 984
|
||||
|
||||
#define EPR_DISTORTION_CORRECTION_ENABLED 988
|
||||
#define EPR_RETRACTION_LENGTH 992
|
||||
#define EPR_RETRACTION_LONG_LENGTH 996
|
||||
#define EPR_RETRACTION_SPEED 1000
|
||||
#define EPR_RETRACTION_Z_LIFT 1004
|
||||
#define EPR_RETRACTION_UNDO_EXTRA_LENGTH 1008
|
||||
#define EPR_RETRACTION_UNDO_EXTRA_LONG_LENGTH 1012
|
||||
#define EPR_RETRACTION_UNDO_SPEED 1016
|
||||
#define EPR_AUTORETRACT_ENABLED 1020
|
||||
#define EPR_Z_PROBE_Z_OFFSET 1024
|
||||
#define EPR_SELECTED_LANGUAGE 1028
|
||||
#define EPR_ACCELERATION_FACTOR_TOP 1032
|
||||
#define EPR_BENDING_CORRECTION_A 1036
|
||||
#define EPR_BENDING_CORRECTION_B 1040
|
||||
#define EPR_BENDING_CORRECTION_C 1044
|
||||
#define EPR_BED_PREHEAT_TEMP 1048
|
||||
#define EPR_X2AXIS_STEPS_PER_MM 1052
|
||||
#define EPR_PARK_X 1056
|
||||
#define EPR_PARK_Y 1060
|
||||
#define EPR_PARK_Z 1064
|
||||
|
||||
|
||||
|
||||
#if EEPROM_MODE != 0
|
||||
#define EEPROM_FLOAT(x) HAL::eprGetFloat(EPR_##x)
|
||||
#define EEPROM_INT32(x) HAL::eprGetInt32(EPR_##x)
|
||||
#define EEPROM_BYTE(x) HAL::eprGetByte(EPR_##x)
|
||||
#define EEPROM_SET_BYTE(x,val) HAL::eprSetByte(EPR_##x,val)
|
||||
#else
|
||||
#define EEPROM_FLOAT(x) (float)(x)
|
||||
#define EEPROM_INT32(x) (int32_t)(x)
|
||||
#define EEPROM_BYTE(x) (uint8_t)(x)
|
||||
#define EEPROM_SET_BYTE(x,val)
|
||||
#endif
|
||||
|
||||
#define EEPROM_EXTRUDER_OFFSET 200
|
||||
// bytes per extruder needed, leave some space for future development
|
||||
#define EEPROM_EXTRUDER_LENGTH 100
|
||||
// Extruder positions relative to extruder start
|
||||
#define EPR_EXTRUDER_STEPS_PER_MM 0
|
||||
#define EPR_EXTRUDER_MAX_FEEDRATE 4
|
||||
// Feedrate from halted extruder in mm/s
|
||||
#define EPR_EXTRUDER_MAX_START_FEEDRATE 8
|
||||
// Acceleration in mm/s^2
|
||||
#define EPR_EXTRUDER_MAX_ACCELERATION 12
|
||||
#define EPR_EXTRUDER_HEAT_MANAGER 16
|
||||
#define EPR_EXTRUDER_DRIVE_MAX 17
|
||||
#define EPR_EXTRUDER_PID_PGAIN 18
|
||||
#define EPR_EXTRUDER_PID_IGAIN 22
|
||||
#define EPR_EXTRUDER_PID_DGAIN 26
|
||||
#define EPR_EXTRUDER_DEADTIME EPR_EXTRUDER_PID_PGAIN
|
||||
#define EPR_EXTRUDER_PID_MAX 30
|
||||
#define EPR_EXTRUDER_X_OFFSET 31
|
||||
#define EPR_EXTRUDER_Y_OFFSET 35
|
||||
#define EPR_EXTRUDER_WATCH_PERIOD 39
|
||||
#define EPR_EXTRUDER_ADVANCE_K 41
|
||||
#define EPR_EXTRUDER_DRIVE_MIN 45
|
||||
#define EPR_EXTRUDER_ADVANCE_L 46
|
||||
#define EPR_EXTRUDER_WAIT_RETRACT_TEMP 50
|
||||
#define EPR_EXTRUDER_WAIT_RETRACT_UNITS 52
|
||||
#define EPR_EXTRUDER_COOLER_SPEED 54
|
||||
// 55-57 free for byte sized parameter
|
||||
#define EPR_EXTRUDER_MIXING_RATIOS 58 // 16*2 byte ratios = 32 byte -> end = 89
|
||||
#define EPR_EXTRUDER_Z_OFFSET 90
|
||||
#define EPR_EXTRUDER_PREHEAT 94 // maybe better temperature
|
||||
#ifndef Z_PROBE_BED_DISTANCE
|
||||
#define Z_PROBE_BED_DISTANCE 5.0
|
||||
#endif
|
||||
|
||||
class EEPROM
|
||||
{
|
||||
#if EEPROM_MODE != 0
|
||||
static void writeExtruderPrefix(uint pos);
|
||||
static void writeFloat(uint pos,PGM_P text,uint8_t digits = 3);
|
||||
static void writeLong(uint pos,PGM_P text);
|
||||
static void writeInt(uint pos,PGM_P text);
|
||||
static void writeByte(uint pos,PGM_P text);
|
||||
public:
|
||||
static uint8_t computeChecksum();
|
||||
static void updateChecksum();
|
||||
#endif
|
||||
public:
|
||||
|
||||
static void init();
|
||||
static void initBaudrate();
|
||||
static void storeDataIntoEEPROM(uint8_t corrupted = 0);
|
||||
static void readDataFromEEPROM(bool includeExtruder);
|
||||
static void restoreEEPROMSettingsFromConfiguration();
|
||||
static void writeSettings();
|
||||
static void update(GCode *com);
|
||||
static void updatePrinterUsage();
|
||||
static inline void setVersion(uint8_t v) {
|
||||
#if EEPROM_MODE != 0
|
||||
HAL::eprSetByte(EPR_VERSION,v);
|
||||
HAL::eprSetByte(EPR_INTEGRITY_BYTE,computeChecksum());
|
||||
#endif
|
||||
}
|
||||
static inline uint8_t getStoredLanguage() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetByte(EPR_SELECTED_LANGUAGE);
|
||||
#else
|
||||
return 0;
|
||||
#endif
|
||||
}
|
||||
#if FEATURE_Z_PROBE
|
||||
static inline void setZProbeHeight(float mm) {
|
||||
#if EEPROM_MODE != 0
|
||||
HAL::eprSetFloat(EPR_Z_PROBE_HEIGHT, mm);
|
||||
Com::printFLN(PSTR("Z-Probe height set to: "),mm,3);
|
||||
EEPROM::updateChecksum();
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
static inline float zProbeZOffset() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_Z_PROBE_Z_OFFSET);
|
||||
#else
|
||||
return Z_PROBE_Z_OFFSET;
|
||||
#endif
|
||||
}
|
||||
static inline float zProbeSpeed() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_Z_PROBE_SPEED);
|
||||
#else
|
||||
return Z_PROBE_SPEED;
|
||||
#endif
|
||||
}
|
||||
static inline float zProbeXYSpeed() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_Z_PROBE_XY_SPEED);
|
||||
#else
|
||||
return Z_PROBE_XY_SPEED;
|
||||
#endif
|
||||
}
|
||||
static inline float zProbeXOffset() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_Z_PROBE_X_OFFSET);
|
||||
#else
|
||||
return Z_PROBE_X_OFFSET;
|
||||
#endif
|
||||
}
|
||||
static inline float zProbeYOffset() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_Z_PROBE_Y_OFFSET);
|
||||
#else
|
||||
return Z_PROBE_Y_OFFSET;
|
||||
#endif
|
||||
}
|
||||
static inline float zProbeHeight() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_Z_PROBE_HEIGHT);
|
||||
#else
|
||||
return Z_PROBE_HEIGHT;
|
||||
#endif
|
||||
}
|
||||
static inline float zProbeX1() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_Z_PROBE_X1);
|
||||
#else
|
||||
return Z_PROBE_X1;
|
||||
#endif
|
||||
}
|
||||
static inline float zProbeY1() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_Z_PROBE_Y1);
|
||||
#else
|
||||
return Z_PROBE_Y1;
|
||||
#endif
|
||||
}
|
||||
static inline float zProbeX2() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_Z_PROBE_X2);
|
||||
#else
|
||||
return Z_PROBE_X2;
|
||||
#endif
|
||||
}
|
||||
static inline float zProbeY2() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_Z_PROBE_Y2);
|
||||
#else
|
||||
return Z_PROBE_Y2;
|
||||
#endif
|
||||
}
|
||||
static inline float zProbeX3() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_Z_PROBE_X3);
|
||||
#else
|
||||
return Z_PROBE_X3;
|
||||
#endif
|
||||
}
|
||||
static inline float zProbeY3() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_Z_PROBE_Y3);
|
||||
#else
|
||||
return Z_PROBE_Y3;
|
||||
#endif
|
||||
}
|
||||
static inline float zProbeBedDistance() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_Z_PROBE_BED_DISTANCE);
|
||||
#else
|
||||
return Z_PROBE_BED_DISTANCE;
|
||||
#endif
|
||||
}
|
||||
|
||||
static inline float axisCompTanXY() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_AXISCOMP_TANXY);
|
||||
#else
|
||||
return AXISCOMP_TANXY;
|
||||
#endif
|
||||
}
|
||||
static inline float axisCompTanYZ() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_AXISCOMP_TANYZ);
|
||||
#else
|
||||
return AXISCOMP_TANYZ;
|
||||
#endif
|
||||
}
|
||||
static inline float axisCompTanXZ() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_AXISCOMP_TANXZ);
|
||||
#else
|
||||
return AXISCOMP_TANXZ;
|
||||
#endif
|
||||
}
|
||||
|
||||
#if NONLINEAR_SYSTEM
|
||||
static inline int16_t deltaSegmentsPerSecondMove() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetInt16(EPR_DELTA_SEGMENTS_PER_SECOND_MOVE);
|
||||
#else
|
||||
return DELTA_SEGMENTS_PER_SECOND_MOVE;
|
||||
#endif
|
||||
}
|
||||
static inline float deltaDiagonalRodLength() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_DELTA_DIAGONAL_ROD_LENGTH);
|
||||
#else
|
||||
return DELTA_DIAGONAL_ROD;
|
||||
#endif
|
||||
}
|
||||
static inline int16_t deltaSegmentsPerSecondPrint() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetInt16(EPR_DELTA_SEGMENTS_PER_SECOND_PRINT);
|
||||
#else
|
||||
return DELTA_SEGMENTS_PER_SECOND_PRINT;
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
static inline float deltaHorizontalRadius() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_DELTA_HORIZONTAL_RADIUS);
|
||||
#else
|
||||
return ROD_RADIUS;
|
||||
#endif
|
||||
}
|
||||
static inline int16_t deltaTowerXOffsetSteps() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetInt16(EPR_DELTA_TOWERX_OFFSET_STEPS);
|
||||
#else
|
||||
return DELTA_X_ENDSTOP_OFFSET_STEPS;
|
||||
#endif
|
||||
}
|
||||
static inline int16_t deltaTowerYOffsetSteps() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetInt16(EPR_DELTA_TOWERY_OFFSET_STEPS);
|
||||
#else
|
||||
return DELTA_Y_ENDSTOP_OFFSET_STEPS;
|
||||
#endif
|
||||
}
|
||||
static inline int16_t deltaTowerZOffsetSteps() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetInt16(EPR_DELTA_TOWERZ_OFFSET_STEPS);
|
||||
#else
|
||||
return DELTA_Z_ENDSTOP_OFFSET_STEPS;
|
||||
#endif
|
||||
}
|
||||
|
||||
static inline void setRodRadius(float mm) {
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
Printer::radius0=mm;
|
||||
Printer::updateDerivedParameter();
|
||||
#if EEPROM_MODE != 0
|
||||
//This is an odd situation, the radius can only be changed if eeprom is on.
|
||||
// The radius is not saved to printer variable now, it is all derived parameters of
|
||||
// fetching the radius, which if EEProm is off returns the Configuration constant.
|
||||
HAL::eprSetFloat(EPR_DELTA_HORIZONTAL_RADIUS, mm);
|
||||
EEPROM::updateChecksum();
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
static inline void incrementRodRadius(float mm) {
|
||||
setRodRadius(mm + deltaHorizontalRadius());
|
||||
}
|
||||
static inline void setTowerXFloor(float newZ) {
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
Printer::xMin = newZ;
|
||||
Printer::updateDerivedParameter();
|
||||
Com::printFLN(PSTR("X (A) tower floor set to: "),Printer::xMin,3);
|
||||
#if EEPROM_MODE != 0
|
||||
HAL::eprSetFloat(EPR_X_HOME_OFFSET,Printer::xMin);
|
||||
EEPROM::updateChecksum();
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
static inline void setTowerYFloor(float newZ) {
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
Printer::yMin = newZ;
|
||||
Printer::updateDerivedParameter();
|
||||
Com::printFLN(PSTR("Y (B) tower floor set to: "), Printer::yMin, 3);
|
||||
#if EEPROM_MODE != 0
|
||||
|
||||
HAL::eprSetFloat(EPR_Y_HOME_OFFSET,Printer::yMin);
|
||||
EEPROM::updateChecksum();
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
static inline void setTowerZFloor(float newZ) {
|
||||
#if DRIVE_SYSTEM == DELTA
|
||||
Printer::zMin = newZ;
|
||||
Printer::updateDerivedParameter();
|
||||
Com::printFLN(PSTR("Z (C) tower floor set to: "), Printer::zMin, 3);
|
||||
#if EEPROM_MODE != 0
|
||||
HAL::eprSetFloat(EPR_Z_HOME_OFFSET,Printer::zMin);
|
||||
EEPROM::updateChecksum();
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
static inline void setDeltaTowerXOffsetSteps(int16_t steps) {
|
||||
#if EEPROM_MODE != 0
|
||||
HAL::eprSetInt16(EPR_DELTA_TOWERX_OFFSET_STEPS,steps);
|
||||
EEPROM::updateChecksum();
|
||||
#endif
|
||||
}
|
||||
static inline void setDeltaTowerYOffsetSteps(int16_t steps) {
|
||||
#if EEPROM_MODE != 0
|
||||
HAL::eprSetInt16(EPR_DELTA_TOWERY_OFFSET_STEPS,steps);
|
||||
EEPROM::updateChecksum();
|
||||
#endif
|
||||
}
|
||||
static inline void setDeltaTowerZOffsetSteps(int16_t steps) {
|
||||
#if EEPROM_MODE != 0
|
||||
HAL::eprSetInt16(EPR_DELTA_TOWERZ_OFFSET_STEPS,steps);
|
||||
EEPROM::updateChecksum();
|
||||
#endif
|
||||
}
|
||||
static inline float deltaAlphaA() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_DELTA_ALPHA_A);
|
||||
#else
|
||||
return DELTA_ALPHA_A;
|
||||
#endif
|
||||
}
|
||||
static inline float deltaAlphaB() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_DELTA_ALPHA_B);
|
||||
#else
|
||||
return DELTA_ALPHA_B;
|
||||
#endif
|
||||
}
|
||||
static inline float deltaAlphaC() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_DELTA_ALPHA_C);
|
||||
#else
|
||||
return DELTA_ALPHA_C;
|
||||
#endif
|
||||
}
|
||||
static inline float deltaRadiusCorrectionA() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_DELTA_RADIUS_CORR_A);
|
||||
#else
|
||||
return DELTA_RADIUS_CORRECTION_A;
|
||||
#endif
|
||||
}
|
||||
static inline float deltaRadiusCorrectionB() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_DELTA_RADIUS_CORR_B);
|
||||
#else
|
||||
return DELTA_RADIUS_CORRECTION_B;
|
||||
#endif
|
||||
}
|
||||
static inline float deltaRadiusCorrectionC() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_DELTA_RADIUS_CORR_C);
|
||||
#else
|
||||
return DELTA_RADIUS_CORRECTION_C;
|
||||
#endif
|
||||
}
|
||||
static inline float deltaDiagonalCorrectionA() {
|
||||
return EEPROM_FLOAT(DELTA_DIAGONAL_CORRECTION_A);
|
||||
}
|
||||
static inline float deltaDiagonalCorrectionB() {
|
||||
return EEPROM_FLOAT(DELTA_DIAGONAL_CORRECTION_B);
|
||||
}
|
||||
static inline float deltaDiagonalCorrectionC() {
|
||||
return EEPROM_FLOAT(DELTA_DIAGONAL_CORRECTION_C);
|
||||
}
|
||||
static inline float deltaMaxRadius() {
|
||||
return EEPROM_FLOAT(DELTA_MAX_RADIUS);
|
||||
}
|
||||
|
||||
#endif
|
||||
static void initalizeUncached();
|
||||
#if MIXING_EXTRUDER
|
||||
static void storeMixingRatios(bool updateChecksums = true);
|
||||
static void readMixingRatios();
|
||||
static void restoreMixingRatios();
|
||||
#endif
|
||||
|
||||
static void setZCorrection(int32_t c,int index);
|
||||
static inline int32_t getZCorrection(int index) {
|
||||
return HAL::eprGetInt32(2048 + (index << 2));
|
||||
}
|
||||
static inline void setZCorrectionEnabled(int8_t on) {
|
||||
#if EEPROM_MODE != 0
|
||||
if(isZCorrectionEnabled() == on) return;
|
||||
HAL::eprSetInt16(EPR_DISTORTION_CORRECTION_ENABLED, on);
|
||||
EEPROM::updateChecksum();
|
||||
#endif
|
||||
}
|
||||
static inline int8_t isZCorrectionEnabled() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetByte(EPR_DISTORTION_CORRECTION_ENABLED);
|
||||
#else
|
||||
return 0;
|
||||
#endif
|
||||
}
|
||||
static inline float bendingCorrectionA() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_BENDING_CORRECTION_A);
|
||||
#else
|
||||
return BENDING_CORRECTION_A;
|
||||
#endif
|
||||
}
|
||||
static inline float bendingCorrectionB() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_BENDING_CORRECTION_B);
|
||||
#else
|
||||
return BENDING_CORRECTION_B;
|
||||
#endif
|
||||
}
|
||||
static inline float bendingCorrectionC() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_BENDING_CORRECTION_C);
|
||||
#else
|
||||
return BENDING_CORRECTION_C;
|
||||
#endif
|
||||
}
|
||||
static inline float accelarationFactorTop() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_ACCELERATION_FACTOR_TOP);
|
||||
#else
|
||||
return ACCELERATION_FACTOR_TOP;
|
||||
#endif
|
||||
}
|
||||
static inline float parkX() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_PARK_X);
|
||||
#else
|
||||
return PARK_POSITION_X;
|
||||
#endif
|
||||
}
|
||||
static inline float parkY() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_PARK_Y);
|
||||
#else
|
||||
return PARK_POSITION_Y;
|
||||
#endif
|
||||
}
|
||||
static inline float parkZ() {
|
||||
#if EEPROM_MODE != 0
|
||||
return HAL::eprGetFloat(EPR_PARK_Z);
|
||||
#else
|
||||
return PARK_POSITION_Z_RAISE;
|
||||
#endif
|
||||
}
|
||||
|
||||
};
|
||||
#endif
|
316
Repetier-Firmware 1.0.3/Repetier/Endstops.cpp
Normal file
316
Repetier-Firmware 1.0.3/Repetier/Endstops.cpp
Normal file
@ -0,0 +1,316 @@
|
||||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware 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.
|
||||
|
||||
Repetier-Firmware 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 Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
This firmware is a nearly complete rewrite of the sprinter firmware
|
||||
by kliment (https://github.com/kliment/Sprinter)
|
||||
which based on Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
|
||||
|
||||
Functions in this file are used to communicate using ascii or repetier protocol.
|
||||
*/
|
||||
|
||||
#include "Repetier.h"
|
||||
|
||||
flag8_t Endstops::lastState = 0;
|
||||
flag8_t Endstops::lastRead = 0;
|
||||
flag8_t Endstops::accumulator = 0;
|
||||
#ifdef EXTENDED_ENDSTOPS
|
||||
flag8_t Endstops::lastState2 = 0;
|
||||
flag8_t Endstops::lastRead2 = 0;
|
||||
flag8_t Endstops::accumulator2 = 0;
|
||||
#endif
|
||||
|
||||
void Endstops::update() {
|
||||
flag8_t newRead = 0;
|
||||
#ifdef EXTENDED_ENDSTOPS
|
||||
flag8_t newRead2 = 0;
|
||||
#endif
|
||||
#if (Y_MIN_PIN > -1) && MIN_HARDWARE_ENDSTOP_Y
|
||||
if(READ(Y_MIN_PIN) != ENDSTOP_Y_MIN_INVERTING)
|
||||
newRead |= ENDSTOP_Y_MIN_ID;
|
||||
#endif
|
||||
#if (Y_MAX_PIN > -1) && MAX_HARDWARE_ENDSTOP_Y
|
||||
if(READ(Y_MAX_PIN) != ENDSTOP_Y_MAX_INVERTING)
|
||||
newRead |= ENDSTOP_Y_MAX_ID;
|
||||
#endif
|
||||
#if (X_MIN_PIN > -1) && MIN_HARDWARE_ENDSTOP_X
|
||||
if(READ(X_MIN_PIN) != ENDSTOP_X_MIN_INVERTING) {
|
||||
newRead |= ENDSTOP_X_MIN_ID;
|
||||
}
|
||||
#endif
|
||||
#if (X_MAX_PIN > -1) && MAX_HARDWARE_ENDSTOP_X
|
||||
if(READ(X_MAX_PIN) != ENDSTOP_X_MAX_INVERTING)
|
||||
newRead |= ENDSTOP_X_MAX_ID;
|
||||
#endif
|
||||
#if (Z_MIN_PIN > -1) && MIN_HARDWARE_ENDSTOP_Z
|
||||
if(READ(Z_MIN_PIN) != ENDSTOP_Z_MIN_INVERTING)
|
||||
newRead |= ENDSTOP_Z_MIN_ID;
|
||||
#endif
|
||||
#if (Z_MAX_PIN > -1) && MAX_HARDWARE_ENDSTOP_Z
|
||||
if(READ(Z_MAX_PIN) != ENDSTOP_Z_MAX_INVERTING)
|
||||
newRead |= ENDSTOP_Z_MAX_ID;
|
||||
#endif
|
||||
#if (Z2_MINMAX_PIN > -1) && MINMAX_HARDWARE_ENDSTOP_Z2
|
||||
if(READ(Z2_MINMAX_PIN) != ENDSTOP_Z2_MINMAX_INVERTING)
|
||||
newRead |= ENDSTOP_Z2_MINMAX_ID;
|
||||
#endif
|
||||
#if FEATURE_Z_PROBE
|
||||
#if Z_PROBE_PIN == Z_MIN_PIN && MIN_HARDWARE_ENDSTOP_Z
|
||||
if(newRead & ENDSTOP_Z_MIN_ID) // prevent different results causing confusion
|
||||
newRead |= ENDSTOP_Z_PROBE_ID;
|
||||
if(!Printer::isHoming())
|
||||
newRead &= ~ENDSTOP_Z_MIN_ID; // could cause wrong signals depending on probe position
|
||||
#else
|
||||
if(Z_PROBE_ON_HIGH ? READ(Z_PROBE_PIN) : !READ(Z_PROBE_PIN))
|
||||
newRead |= ENDSTOP_Z_PROBE_ID;
|
||||
#endif
|
||||
#endif
|
||||
#ifdef EXTENDED_ENDSTOPS
|
||||
#if HAS_PIN(Y2_MIN) && MIN_HARDWARE_ENDSTOP_Y2
|
||||
if(READ(Y2_MIN_PIN) != ENDSTOP_Y2_MIN_INVERTING)
|
||||
newRead2 |= ENDSTOP_Y2_MIN_ID;
|
||||
#endif
|
||||
#if HAS_PIN(Y2_MAX) && MAX_HARDWARE_ENDSTOP_Y2
|
||||
if(READ(Y2_MAX_PIN) != ENDSTOP_Y2_MAX_INVERTING)
|
||||
newRead2 |= ENDSTOP_Y2_MAX_ID;
|
||||
#endif
|
||||
#if HAS_PIN(X2_MIN) && MIN_HARDWARE_ENDSTOP_X2
|
||||
if(READ(X2_MIN_PIN) != ENDSTOP_X2_MIN_INVERTING) {
|
||||
newRead2 |= ENDSTOP_X2_MIN_ID;
|
||||
}
|
||||
#endif
|
||||
#if HAS_PIN(X2_MAX) && MAX_HARDWARE_ENDSTOP_X2
|
||||
if(READ(X2_MAX_PIN) != ENDSTOP_X2_MAX_INVERTING)
|
||||
newRead2 |= ENDSTOP_X2_MAX_ID;
|
||||
#endif
|
||||
#if HAS_PIN(Z2_MAX) && MAX_HARDWARE_ENDSTOP_Z2
|
||||
if(READ(Z2_MAX_PIN) != ENDSTOP_Z2_MAX_INVERTING)
|
||||
newRead2 |= ENDSTOP_Z2_MAX_ID;
|
||||
#endif
|
||||
#if HAS_PIN(Z3_MAX) && MAX_HARDWARE_ENDSTOP_Z3
|
||||
if(READ(Z3_MAX_PIN) != ENDSTOP_Z3_MAX_INVERTING)
|
||||
newRead2 |= ENDSTOP_Z3_MAX_ID;
|
||||
#endif
|
||||
#if HAS_PIN(Z3_MIN) && MIN_HARDWARE_ENDSTOP_Z3
|
||||
if(READ(Z3_MIN_PIN) != ENDSTOP_Z3_MIN_INVERTING)
|
||||
newRead2 |= ENDSTOP_Z3_MIN_ID;
|
||||
#endif
|
||||
|
||||
#endif
|
||||
InterruptProtectedBlock noInts; // bad idea to run this from different interrupts at once!
|
||||
lastRead &= newRead;
|
||||
#ifdef EXTENDED_ENDSTOPS
|
||||
lastRead2 &= newRead2;
|
||||
#endif // EXTENDED_ENDSTOPS
|
||||
if(lastRead != lastState
|
||||
#ifdef EXTENDED_ENDSTOPS
|
||||
|| (lastState2 != lastRead2)
|
||||
#endif
|
||||
) { // Report endstop hit changes
|
||||
lastState = lastRead;
|
||||
accumulator |= lastState;
|
||||
#ifdef EXTENDED_ENDSTOPS
|
||||
lastState2 = lastRead2;
|
||||
accumulator2 |= lastState2;
|
||||
#endif
|
||||
if (Printer::debugEndStop()) Endstops::report();
|
||||
} else {
|
||||
lastState = lastRead;
|
||||
#ifdef EXTENDED_ENDSTOPS
|
||||
lastState2 = lastRead2;
|
||||
#endif
|
||||
}
|
||||
lastRead = newRead;
|
||||
#ifdef EXTENDED_ENDSTOPS
|
||||
lastRead2 = newRead2;
|
||||
#endif
|
||||
}
|
||||
|
||||
void Endstops::report() {
|
||||
Com::printF(PSTR("endstops hit: "));
|
||||
#if (X_MIN_PIN > -1) && MIN_HARDWARE_ENDSTOP_X
|
||||
Com::printF(Com::tXMinColon);
|
||||
Com::printF(xMin() ? Com::tHSpace : Com::tLSpace);
|
||||
#endif
|
||||
#if HAS_PIN(X2_MIN) && IS_MAC_TRUE(MIN_HARDWARE_ENDSTOP_X2)
|
||||
Com::printF(PSTR("x2_min:"));
|
||||
Com::printF(x2Min() ? Com::tHSpace : Com::tLSpace);
|
||||
#endif
|
||||
#if (X_MAX_PIN > -1) && MAX_HARDWARE_ENDSTOP_X
|
||||
Com::printF(Com::tXMaxColon);
|
||||
Com::printF(xMax() ? Com::tHSpace : Com::tLSpace);
|
||||
#endif
|
||||
#if HAS_PIN(X2_MAX) && IS_MAC_TRUE(MAX_HARDWARE_ENDSTOP_X2)
|
||||
Com::printF(PSTR("x2_max:"));
|
||||
Com::printF(x2Max() ? Com::tHSpace : Com::tLSpace);
|
||||
#endif
|
||||
#if (Y_MIN_PIN > -1) && MIN_HARDWARE_ENDSTOP_Y
|
||||
Com::printF(Com::tYMinColon);
|
||||
Com::printF(yMin() ? Com::tHSpace : Com::tLSpace);
|
||||
#endif
|
||||
#if HAS_PIN(Y2_MIN) && IS_MAC_TRUE(MIN_HARDWARE_ENDSTOP_Y2)
|
||||
Com::printF(PSTR("y2_min:"));
|
||||
Com::printF(y2Min() ? Com::tHSpace : Com::tLSpace);
|
||||
#endif
|
||||
#if (Y_MAX_PIN > -1) && MAX_HARDWARE_ENDSTOP_Y
|
||||
Com::printF(Com::tYMaxColon);
|
||||
Com::printF(yMax() ? Com::tHSpace : Com::tLSpace);
|
||||
#endif
|
||||
#if HAS_PIN(Y2_MAX) && IS_MAC_TRUE(MAX_HARDWARE_ENDSTOP_Y2)
|
||||
Com::printF(PSTR("y2_max:"));
|
||||
Com::printF(y2Max() ? Com::tHSpace : Com::tLSpace);
|
||||
#endif
|
||||
#if (Z_MIN_PIN > -1) && MIN_HARDWARE_ENDSTOP_Z
|
||||
Com::printF(Com::tZMinColon);
|
||||
Com::printF(zMin() ? Com::tHSpace : Com::tLSpace);
|
||||
#endif
|
||||
#if (Z_MAX_PIN > -1) && MAX_HARDWARE_ENDSTOP_Z
|
||||
Com::printF(Com::tZMaxColon);
|
||||
Com::printF(zMax() ? Com::tHSpace : Com::tLSpace);
|
||||
#endif
|
||||
#if (Z2_MINMAX_PIN > -1) && MINMAX_HARDWARE_ENDSTOP_Z2
|
||||
Com::printF(PSTR("z2_minmax:"));
|
||||
Com::printF(z2MinMax() ? Com::tHSpace : Com::tLSpace);
|
||||
#endif
|
||||
#if FEATURE_Z_PROBE
|
||||
Com::printF(Com::tZProbeState);
|
||||
Com::printF(zProbe() ? Com::tHSpace : Com::tLSpace);
|
||||
#endif
|
||||
Com::println();
|
||||
}
|
||||
|
||||
void Endstops::setup() {
|
||||
// Set end stops to input and enable pullup if required
|
||||
#if MIN_HARDWARE_ENDSTOP_X
|
||||
#if X_MIN_PIN > -1
|
||||
SET_INPUT(X_MIN_PIN);
|
||||
#if ENDSTOP_PULLUP_X_MIN
|
||||
PULLUP(X_MIN_PIN, HIGH);
|
||||
#endif
|
||||
#else
|
||||
#error You have defined hardware x min endstop without pin assignment. Set pin number for X_MIN_PIN
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if MIN_HARDWARE_ENDSTOP_X2
|
||||
#if X2_MIN_PIN > -1
|
||||
SET_INPUT(X2_MIN_PIN);
|
||||
#if ENDSTOP_PULLUP_X2_MIN
|
||||
PULLUP(X2_MIN_PIN, HIGH);
|
||||
#endif
|
||||
#else
|
||||
#error You have defined hardware 2 min endstop without pin assignment. Set pin number for X2_MIN_PIN
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if MIN_HARDWARE_ENDSTOP_Y
|
||||
#if Y_MIN_PIN > -1
|
||||
SET_INPUT(Y_MIN_PIN);
|
||||
#if ENDSTOP_PULLUP_Y_MIN
|
||||
PULLUP(Y_MIN_PIN, HIGH);
|
||||
#endif
|
||||
#else
|
||||
#error You have defined hardware y min endstop without pin assignment. Set pin number for Y_MIN_PIN
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if MIN_HARDWARE_ENDSTOP_Y2
|
||||
#if Y2_MIN_PIN > -1
|
||||
SET_INPUT(Y2_MIN_PIN);
|
||||
#if ENDSTOP_PULLUP_Y2_MIN
|
||||
PULLUP(Y2_MIN_PIN, HIGH);
|
||||
#endif
|
||||
#else
|
||||
#error You have defined hardware y2 min endstop without pin assignment. Set pin number for Y2_MIN_PIN
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if MIN_HARDWARE_ENDSTOP_Z
|
||||
#if Z_MIN_PIN > -1
|
||||
SET_INPUT(Z_MIN_PIN);
|
||||
#if ENDSTOP_PULLUP_Z_MIN
|
||||
PULLUP(Z_MIN_PIN, HIGH);
|
||||
#endif
|
||||
#else
|
||||
#error You have defined hardware z min endstop without pin assignment. Set pin number for Z_MIN_PIN
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if MINMAX_HARDWARE_ENDSTOP_Z2
|
||||
#if Z2_MINMAX_PIN > -1
|
||||
SET_INPUT(Z2_MINMAX_PIN);
|
||||
#if ENDSTOP_PULLUP_Z2_MINMAX
|
||||
PULLUP(Z2_MINMAX_PIN, HIGH);
|
||||
#endif
|
||||
#else
|
||||
#error You have defined hardware z2 minmax endstop without pin assignment. Set pin number for Z2_MINMAX_PIN
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if MAX_HARDWARE_ENDSTOP_X
|
||||
#if X_MAX_PIN > -1
|
||||
SET_INPUT(X_MAX_PIN);
|
||||
#if ENDSTOP_PULLUP_X_MAX
|
||||
PULLUP(X_MAX_PIN, HIGH);
|
||||
#endif
|
||||
#else
|
||||
#error You have defined hardware x max endstop without pin assignment. Set pin number for X_MAX_PIN
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if MAX_HARDWARE_ENDSTOP_X2
|
||||
#if X2_MAX_PIN > -1
|
||||
SET_INPUT(X2_MAX_PIN);
|
||||
#if ENDSTOP_PULLUP_X2_MAX
|
||||
PULLUP(X2_MAX_PIN, HIGH);
|
||||
#endif
|
||||
#else
|
||||
#error You have defined hardware x2 max endstop without pin assignment. Set pin number for X2_MAX_PIN
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if MAX_HARDWARE_ENDSTOP_Y
|
||||
#if Y_MAX_PIN > -1
|
||||
SET_INPUT(Y_MAX_PIN);
|
||||
#if ENDSTOP_PULLUP_Y_MAX
|
||||
PULLUP(Y_MAX_PIN, HIGH);
|
||||
#endif
|
||||
#else
|
||||
#error You have defined hardware y max endstop without pin assignment. Set pin number for Y_MAX_PIN
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if MAX_HARDWARE_ENDSTOP_Y2
|
||||
#if Y2_MAX_PIN > -1
|
||||
SET_INPUT(Y2_MAX_PIN);
|
||||
#if ENDSTOP_PULLUP_Y2_MAX
|
||||
PULLUP(Y2_MAX_PIN, HIGH);
|
||||
#endif
|
||||
#else
|
||||
#error You have defined hardware y2 max endstop without pin assignment. Set pin number for Y2_MAX_PIN
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if MAX_HARDWARE_ENDSTOP_Z
|
||||
#if Z_MAX_PIN>-1
|
||||
SET_INPUT(Z_MAX_PIN);
|
||||
#if ENDSTOP_PULLUP_Z_MAX
|
||||
PULLUP(Z_MAX_PIN, HIGH);
|
||||
#endif
|
||||
#else
|
||||
#error You have defined hardware z max endstop without pin assignment. Set pin number for Z_MAX_PIN
|
||||
#endif
|
||||
#endif
|
||||
}
|
197
Repetier-Firmware 1.0.3/Repetier/Endstops.h
Normal file
197
Repetier-Firmware 1.0.3/Repetier/Endstops.h
Normal file
@ -0,0 +1,197 @@
|
||||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware 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.
|
||||
|
||||
Repetier-Firmware 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 Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
|
||||
#ifndef _ENDSTOPS_H
|
||||
#define _ENDSTOPS_H
|
||||
|
||||
#define ENDSTOP_X_MIN_ID 1
|
||||
#define ENDSTOP_X_MAX_ID 2
|
||||
#define ENDSTOP_Y_MIN_ID 4
|
||||
#define ENDSTOP_Y_MAX_ID 8
|
||||
#define ENDSTOP_Z_MIN_ID 16
|
||||
#define ENDSTOP_Z_MAX_ID 32
|
||||
#define ENDSTOP_Z2_MIN_ID 64
|
||||
#define ENDSTOP_Z2_MINMAX_ID 64
|
||||
#define ENDSTOP_Z_PROBE_ID 128
|
||||
|
||||
// These endstops are only used with EXTENDED_ENDSTOPS
|
||||
#define ENDSTOP_X2_MIN_ID 1
|
||||
#define ENDSTOP_X2_MAX_ID 2
|
||||
#define ENDSTOP_Y2_MIN_ID 4
|
||||
#define ENDSTOP_Y2_MAX_ID 8
|
||||
#define ENDSTOP_Z2_MAX_ID 16
|
||||
#define ENDSTOP_Z3_MIN_ID 32
|
||||
#define ENDSTOP_Z3_MAX_ID 64
|
||||
|
||||
#if IS_MAC_TRUE(MIN_HARDWARE_ENDSTOP_X2) || IS_MAC_TRUE(MAX_HARDWARE_ENDSTOP_X2) || IS_MAC_TRUE(MIN_HARDWARE_ENDSTOP_Y2) || IS_MAC_TRUE(MAX_HARDWARE_ENDSTOP_Y2) || IS_MAC_TRUE(MAX_HARDWARE_ENDSTOP_Z2) || IS_MAC_TRUE(MAX_HARDWARE_ENDSTOP_Z3) || IS_MAC_TRUE(MIN_HARDWARE_ENDSTOP_Z3)
|
||||
#define EXTENDED_ENDSTOPS 1
|
||||
#endif
|
||||
|
||||
class Endstops {
|
||||
static flag8_t lastState;
|
||||
static flag8_t lastRead;
|
||||
static flag8_t accumulator;
|
||||
#ifdef EXTENDED_ENDSTOPS
|
||||
static flag8_t lastState2;
|
||||
static flag8_t lastRead2;
|
||||
static flag8_t accumulator2;
|
||||
#endif
|
||||
public:
|
||||
static void update();
|
||||
static void report();
|
||||
static void setup();
|
||||
static INLINE bool anyXYZMax() {
|
||||
return (lastState & (ENDSTOP_X_MAX_ID | ENDSTOP_Y_MAX_ID | ENDSTOP_Z_MAX_ID)) != 0;
|
||||
}
|
||||
static INLINE bool anyXYZ() {
|
||||
#ifdef EXTENDED_ENDSTOPS
|
||||
return (lastState & (ENDSTOP_X_MAX_ID | ENDSTOP_Y_MAX_ID | ENDSTOP_Z_MAX_ID | ENDSTOP_X_MIN_ID | ENDSTOP_Y_MIN_ID | ENDSTOP_Z_MIN_ID | ENDSTOP_Z2_MIN_ID)) != 0 ||
|
||||
lastState2 != 0;
|
||||
#else
|
||||
return (lastState & (ENDSTOP_X_MAX_ID | ENDSTOP_Y_MAX_ID | ENDSTOP_Z_MAX_ID | ENDSTOP_X_MIN_ID | ENDSTOP_Y_MIN_ID | ENDSTOP_Z_MIN_ID | ENDSTOP_Z2_MIN_ID)) != 0;
|
||||
#endif
|
||||
}
|
||||
static INLINE bool anyEndstopHit() {
|
||||
#ifdef EXTENDED_ENDSTOPS
|
||||
return lastState != 0 || lastState2 != 0;
|
||||
#else
|
||||
return lastState != 0;
|
||||
#endif
|
||||
}
|
||||
static INLINE void resetAccumulator() {
|
||||
accumulator = 0;
|
||||
#ifdef EXTENDED_ENDSTOPS
|
||||
accumulator2 = 0;
|
||||
#endif
|
||||
}
|
||||
static INLINE void fillFromAccumulator() {
|
||||
lastState = accumulator;
|
||||
#ifdef EXTENDED_ENDSTOPS
|
||||
lastState2 = accumulator2;
|
||||
#endif
|
||||
}
|
||||
static INLINE bool xMin() {
|
||||
#if (X_MIN_PIN > -1) && MIN_HARDWARE_ENDSTOP_X
|
||||
return (lastState & ENDSTOP_X_MIN_ID) != 0;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
static INLINE bool xMax() {
|
||||
#if (X_MAX_PIN > -1) && MAX_HARDWARE_ENDSTOP_X
|
||||
return (lastState & ENDSTOP_X_MAX_ID) != 0;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
static INLINE bool yMin() {
|
||||
#if (Y_MIN_PIN > -1) && MIN_HARDWARE_ENDSTOP_Y
|
||||
return (lastState & ENDSTOP_Y_MIN_ID) != 0;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
static INLINE bool yMax() {
|
||||
#if (Y_MAX_PIN > -1) && MAX_HARDWARE_ENDSTOP_Y
|
||||
return (lastState & ENDSTOP_Y_MAX_ID) != 0;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
static INLINE bool zMin() {
|
||||
#if (Z_MIN_PIN > -1) && MIN_HARDWARE_ENDSTOP_Z
|
||||
return (lastState & ENDSTOP_Z_MIN_ID) != 0;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
static INLINE bool zMax() {
|
||||
#if (Z_MAX_PIN > -1) && MAX_HARDWARE_ENDSTOP_Z
|
||||
return (lastState & ENDSTOP_Z_MAX_ID) != 0;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
static INLINE bool z2MinMax() {
|
||||
#if (Z2_MINMAX_PIN > -1) && MINMAX_HARDWARE_ENDSTOP_Z2
|
||||
return (lastState & ENDSTOP_Z2_MIN_ID) != 0;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
static INLINE bool zProbe() {
|
||||
#if FEATURE_Z_PROBE
|
||||
return (lastState & ENDSTOP_Z_PROBE_ID) != 0;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
#ifdef EXTENDED_ENDSTOPS
|
||||
static INLINE bool x2Min() {
|
||||
#if HAS_PIN(X2_MIN) && MIN_HARDWARE_ENDSTOP_X2
|
||||
return (lastState2 & ENDSTOP_X2_MIN_ID) != 0;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
static INLINE bool x2Max() {
|
||||
#if HAS_PIN(X2_MAX) && MAX_HARDWARE_ENDSTOP_X2
|
||||
return (lastState2 & ENDSTOP_X2_MAX_ID) != 0;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
static INLINE bool y2Min() {
|
||||
#if HAS_PIN(Y2_MIN) && MIN_HARDWARE_ENDSTOP_Y2
|
||||
return (lastState2 & ENDSTOP_Y2_MIN_ID) != 0;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
static INLINE bool y2Max() {
|
||||
#if HAS_PIN(Y2_MAX) && MAX_HARDWARE_ENDSTOP_Y2
|
||||
return (lastState2 & ENDSTOP_Y2_MAX_ID) != 0;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
static INLINE bool z2Max() {
|
||||
#if HAS_PIN(Z2_MAX) && MAX_HARDWARE_ENDSTOP_Z2
|
||||
return (lastState2 & ENDSTOP_Z2_MAX_ID) != 0;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
static INLINE bool z3Max() {
|
||||
#if HAS_PIN(Z3_MAX) && MAX_HARDWARE_ENDSTOP_Z3
|
||||
return (lastState2 & ENDSTOP_Z3_MAX_ID) != 0;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
static INLINE bool z3Min() {
|
||||
#if HAS_PIN(Z3_MIN) && MIN_HARDWARE_ENDSTOP_Z3
|
||||
return (lastState2 & ENDSTOP_Z3_MIN_ID) != 0;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
};
|
||||
|
||||
#endif
|
130
Repetier-Firmware 1.0.3/Repetier/Events.h
Normal file
130
Repetier-Firmware 1.0.3/Repetier/Events.h
Normal file
@ -0,0 +1,130 @@
|
||||
#ifndef EVENTS_H_INCLUDED
|
||||
#define EVENTS_H_INCLUDED
|
||||
|
||||
/*
|
||||
Event system in a nutshell:
|
||||
|
||||
All printers are different and my need additions in the one or other place.
|
||||
It is not very convenient to add these code parts across the firmware. For this
|
||||
reason repetier-firmware uses a simple event system that comes at no cost if
|
||||
a event is not used.
|
||||
|
||||
- simple: Only one subscriber is possible
|
||||
- cost effective: Macros work as event caller. By default all macros are empty
|
||||
|
||||
How to use the system:
|
||||
|
||||
1. In Configuration.h add
|
||||
#define CUSTOM_EVENTS
|
||||
2. Add a file "CustomEvents.h" which overrides all event macros you need.
|
||||
It should also include the function declarations used.
|
||||
3. Add a file "CustomEventsImpl.h" which includes all function definitions.
|
||||
Also it is named .h it will be included inside a cpp file only once.
|
||||
This is to compile only when selected and still keep ArduinoIDE happy.
|
||||
|
||||
Each of the following events describe the parameter and when it is called.
|
||||
*/
|
||||
|
||||
// Catch heating events. id is extruder id or -1 for heated bed.
|
||||
#define EVENT_WAITING_HEATER(id) {}
|
||||
#define EVENT_HEATING_FINISHED(id) {}
|
||||
|
||||
// This gets called every 0.1 second
|
||||
#define EVENT_TIMER_100MS {}
|
||||
// This gets called every 0.5 second
|
||||
#define EVENT_TIMER_500MS {}
|
||||
// Gets called on a regular basis as time allows
|
||||
#define EVENT_PERIODICAL {}
|
||||
// Gets called when kill gets called. only_steppes = true -> we only want to disable steppers, not everything.
|
||||
#define EVENT_KILL(only_steppers) {}
|
||||
// Gets called when a jam was detected.
|
||||
#define EVENT_JAM_DETECTED {}
|
||||
// Gets called at the end of the detection routine.
|
||||
#define EVENT_JAM_DETECTED_END {}
|
||||
// Gets called every time the jam detection signal switches. Steps are the extruder steps since last change.
|
||||
#define EVENT_JAM_SIGNAL_CHANGED(extruderId,steps) {}
|
||||
// Gets called if a heater decoupling is detected.
|
||||
#define EVENT_HEATER_DECOUPLED(id) {}
|
||||
// Gets called if a missing/shorted thermistor is detected.
|
||||
#define EVENT_HEATER_DEFECT(id) {}
|
||||
// Gets called if a action in ui.cpp okAction gets executed.
|
||||
#define EVENT_START_UI_ACTION(shortAction) {}
|
||||
// Gets called if a nextPrevius actions gets executed.
|
||||
#define EVENT_START_NEXTPREVIOUS(action,increment) {}
|
||||
// Gets called before a move is queued. Gives the ability to limit moves.
|
||||
#define EVENT_CONTRAIN_DESTINATION_COORDINATES
|
||||
// Gets called when a fatal error occurs and all actions should be stopped
|
||||
#define EVENT_FATAL_ERROR_OCCURED
|
||||
// Gets called after a M999 to continue from fatal errors
|
||||
#define EVENT_CONTINUE_FROM_FATAL_ERROR
|
||||
|
||||
// Called to initialize laser pins. Return false to prevent default initialization.
|
||||
#define EVENT_INITIALIZE_LASER true
|
||||
// Set laser to intensity level 0 = off, 255 = full. Return false if you have overridden the setting routine.
|
||||
// with true the default solution will set it as digital value.
|
||||
#define EVENT_SET_LASER(intensity) true
|
||||
|
||||
// Called to initialize CNC pins. Return false to prevent default initialization.
|
||||
#define EVENT_INITIALIZE_CNC true
|
||||
// Turn off spindle
|
||||
#define EVENT_SPINDLE_OFF true
|
||||
// Turn spindle clockwise
|
||||
#define EVENT_SPINDLE_CW(rpm) true
|
||||
// Turn spindle counter clockwise
|
||||
#define EVENT_SPINDLE_CCW(rpm) true
|
||||
|
||||
// Allow adding new G and M codes. To implement it create a function
|
||||
// bool eventUnhandledGCode(GCode *com)
|
||||
// that returns true if it handled the code, otherwise false.
|
||||
// Event define would then be
|
||||
// #define EVENT_UNHANDLED_G_CODE(c) eventUnhandledGCode(c)
|
||||
#define EVENT_UNHANDLED_G_CODE(c) false
|
||||
#define EVENT_UNHANDLED_M_CODE(c) false
|
||||
|
||||
// Called when bed temperature is set
|
||||
#define EVENT_SET_BED_TEMP(temp,boop)
|
||||
|
||||
// This gets called every time the user has saved a value to eeprom
|
||||
// or any other reason why dependent values may need recomputation.
|
||||
#define EVENT_UPDATE_DERIVED {}
|
||||
|
||||
// Gets called after HAL is initialized, but before the regular pin settings is defined.
|
||||
#define EVENT_INITIALIZE_EARLY {}
|
||||
// This gets called after the basic firmware functions have initialized.
|
||||
// Use this to initialize your hardware etc.
|
||||
#define EVENT_INITIALIZE {}
|
||||
|
||||
// Allows adding custom symbols in strings that get parsed. Return false if not replaced so defaults can trigger.
|
||||
// override function signature: bool parser(uint8_t c1,uint8_t c2)
|
||||
#define EVENT_CUSTOM_TEXT_PARSER(c1,c2) false
|
||||
|
||||
// User interface actions
|
||||
// These get only executed if there was no hot, so they are ideal to add new actions
|
||||
|
||||
// ok button in wizard page is called
|
||||
#define EVENT_UI_OK_WIZARD(action) {}
|
||||
#define EVENT_UI_FINISH_ACTION(action) false
|
||||
#define EVENT_UI_EXECUTE(action,allowMoves) {}
|
||||
// Returns false if no function was executed
|
||||
#define EVENT_UI_OVERRIDE_EXECUTE(action,allowMoves) false
|
||||
#define EVENT_UI_NEXTPREVIOUS(action,allowMoves,increment) {}
|
||||
// replace by function call returning true if it handled refresh page it self.
|
||||
#define EVENT_UI_REFRESH_PAGE false
|
||||
|
||||
// the following 2 events are equivalent to slow and fast key function and allow adding extra keys in event system.
|
||||
// make sure action is called by reference so it can be changed and returned.
|
||||
// Set action only if key is hit
|
||||
#define EVENT_CHECK_FAST_KEYS(action) {}
|
||||
#define EVENT_CHECK_SLOW_KEYS(action) {}
|
||||
|
||||
// Events on sd pause
|
||||
#define EVENT_SD_PAUSE_START(intern) true
|
||||
#define EVENT_SD_PAUSE_END(intern) {}
|
||||
#define EVENT_SD_CONTINUE_START(intern) true
|
||||
#define EVENT_SD_CONTINUE_END(intern) {}
|
||||
#define EVENT_SD_STOP_START true
|
||||
#define EVENT_SD_STOP_END {}
|
||||
|
||||
#define EVENT_BEFORE_Z_HOME {}
|
||||
|
||||
#endif // EVENTS_H_INCLUDED
|
2906
Repetier-Firmware 1.0.3/Repetier/Extruder.cpp
Normal file
2906
Repetier-Firmware 1.0.3/Repetier/Extruder.cpp
Normal file
File diff suppressed because it is too large
Load Diff
359
Repetier-Firmware 1.0.3/Repetier/Extruder.h
Normal file
359
Repetier-Firmware 1.0.3/Repetier/Extruder.h
Normal file
@ -0,0 +1,359 @@
|
||||
#ifndef EXTRUDER_H_INCLUDED
|
||||
#define EXTRUDER_H_INCLUDED
|
||||
|
||||
#define CELSIUS_EXTRA_BITS 3
|
||||
#define VIRTUAL_EXTRUDER 16 // don't change this to more then 16 without modifying the eeprom positions
|
||||
|
||||
// Updates the temperature of all extruders and heated bed if it's time.
|
||||
// Toggles the heater power if necessary.
|
||||
extern bool reportTempsensorError(); ///< Report defect sensors
|
||||
extern uint8_t manageMonitor;
|
||||
#define HTR_OFF 0
|
||||
#define HTR_PID 1
|
||||
#define HTR_SLOWBANG 2
|
||||
#define HTR_DEADTIME 3
|
||||
|
||||
#define TEMPERATURE_CONTROLLER_FLAG_ALARM 1
|
||||
#define TEMPERATURE_CONTROLLER_FLAG_DECOUPLE_FULL 2 ///< Full heating enabled
|
||||
#define TEMPERATURE_CONTROLLER_FLAG_DECOUPLE_HOLD 4 ///< Holding target temperature
|
||||
#define TEMPERATURE_CONTROLLER_FLAG_SENSDEFECT 8 ///< Indicating sensor defect
|
||||
#define TEMPERATURE_CONTROLLER_FLAG_SENSDECOUPLED 16 ///< Indicating sensor decoupling
|
||||
#define TEMPERATURE_CONTROLLER_FLAG_JAM 32 ///< Indicates a jammed filament
|
||||
#define TEMPERATURE_CONTROLLER_FLAG_SLOWDOWN 64 ///< Indicates a slowed down extruder
|
||||
#define TEMPERATURE_CONTROLLER_FLAG_FILAMENTCHANGE 128 ///< Indicates we are switching filament
|
||||
|
||||
#ifndef PID_TEMP_CORRECTION
|
||||
#define PID_TEMP_CORRECTION 2.0
|
||||
#endif
|
||||
|
||||
/** TemperatureController manages one heater-temperature sensor loop. You can have up to
|
||||
4 loops allowing pid/bang bang for up to 3 extruder and the heated bed.
|
||||
|
||||
*/
|
||||
class TemperatureController
|
||||
{
|
||||
public:
|
||||
uint8_t pwmIndex; ///< pwm index for output control. 0-2 = Extruder, 3 = Fan, 4 = Heated Bed
|
||||
uint8_t sensorType; ///< Type of temperature sensor.
|
||||
uint8_t sensorPin; ///< Pin to read extruder temperature.
|
||||
int8_t heatManager; ///< How is temperature controlled. 0 = on/off, 1 = PID-Control, 3 = dead time control
|
||||
int16_t currentTemperature; ///< Current temperature value read from sensor.
|
||||
//int16_t targetTemperature; ///< Target temperature value in units of sensor.
|
||||
float currentTemperatureC; ///< Current temperature in degC.
|
||||
float targetTemperatureC; ///< Target temperature in degC.
|
||||
float temperatureC; ///< For 1s updates temperature and last build a short time history
|
||||
float lastTemperatureC; ///< Used to compute D errors.
|
||||
uint32_t lastTemperatureUpdate; ///< Time in millis of the last temperature update.
|
||||
float tempIState; ///< Temp. var. for PID computation.
|
||||
uint8_t pidDriveMax; ///< Used for windup in PID calculation.
|
||||
uint8_t pidDriveMin; ///< Used for windup in PID calculation.
|
||||
#define deadTime pidPGain
|
||||
// deadTime is logically different value but physically overlays pidPGain for saving space
|
||||
float pidPGain; ///< Pgain (proportional gain) for PID temperature control [0,01 Units].
|
||||
float pidIGain; ///< Igain (integral) for PID temperature control [0,01 Units].
|
||||
float pidDGain; ///< Dgain (damping) for PID temperature control [0,01 Units].
|
||||
uint8_t pidMax; ///< Maximum PWM value, the heater should be set.
|
||||
float tempIStateLimitMax;
|
||||
float tempIStateLimitMin;
|
||||
uint8_t flags;
|
||||
millis_t lastDecoupleTest; ///< Last time of decoupling sensor-heater test
|
||||
float lastDecoupleTemp; ///< Temperature on last test
|
||||
millis_t decoupleTestPeriod; ///< Time between setting and testing decoupling.
|
||||
millis_t preheatStartTime; ///< Time (in milliseconds) when heat up was started
|
||||
int16_t preheatTemperature;
|
||||
|
||||
void setTargetTemperature(float target);
|
||||
void updateCurrentTemperature();
|
||||
void updateTempControlVars();
|
||||
inline bool isAlarm()
|
||||
{
|
||||
return flags & TEMPERATURE_CONTROLLER_FLAG_ALARM;
|
||||
}
|
||||
inline void setAlarm(bool on)
|
||||
{
|
||||
if(on) flags |= TEMPERATURE_CONTROLLER_FLAG_ALARM;
|
||||
else flags &= ~TEMPERATURE_CONTROLLER_FLAG_ALARM;
|
||||
}
|
||||
inline bool isDecoupleFull()
|
||||
{
|
||||
return flags & TEMPERATURE_CONTROLLER_FLAG_DECOUPLE_FULL;
|
||||
}
|
||||
inline void removeErrorStates() {
|
||||
flags &= ~(TEMPERATURE_CONTROLLER_FLAG_ALARM | TEMPERATURE_CONTROLLER_FLAG_SENSDEFECT | TEMPERATURE_CONTROLLER_FLAG_SENSDECOUPLED);
|
||||
}
|
||||
inline bool isDecoupleFullOrHold()
|
||||
{
|
||||
return flags & (TEMPERATURE_CONTROLLER_FLAG_DECOUPLE_FULL | TEMPERATURE_CONTROLLER_FLAG_DECOUPLE_HOLD);
|
||||
}
|
||||
inline void setDecoupleFull(bool on)
|
||||
{
|
||||
flags &= ~(TEMPERATURE_CONTROLLER_FLAG_DECOUPLE_FULL | TEMPERATURE_CONTROLLER_FLAG_DECOUPLE_HOLD);
|
||||
if(on) flags |= TEMPERATURE_CONTROLLER_FLAG_DECOUPLE_FULL;
|
||||
}
|
||||
inline bool isDecoupleHold()
|
||||
{
|
||||
return flags & TEMPERATURE_CONTROLLER_FLAG_DECOUPLE_HOLD;
|
||||
}
|
||||
inline void setDecoupleHold(bool on)
|
||||
{
|
||||
flags &= ~(TEMPERATURE_CONTROLLER_FLAG_DECOUPLE_FULL | TEMPERATURE_CONTROLLER_FLAG_DECOUPLE_HOLD);
|
||||
if(on) flags |= TEMPERATURE_CONTROLLER_FLAG_DECOUPLE_HOLD;
|
||||
}
|
||||
inline void startFullDecouple(millis_t &t)
|
||||
{
|
||||
if(isDecoupleFull()) return;
|
||||
lastDecoupleTest = t;
|
||||
lastDecoupleTemp = currentTemperatureC;
|
||||
setDecoupleFull(true);
|
||||
}
|
||||
inline void startHoldDecouple(millis_t &t)
|
||||
{
|
||||
if(isDecoupleHold()) return;
|
||||
if(fabs(currentTemperatureC - targetTemperatureC) + 1 > DECOUPLING_TEST_MAX_HOLD_VARIANCE) return;
|
||||
lastDecoupleTest = t;
|
||||
lastDecoupleTemp = targetTemperatureC;
|
||||
setDecoupleHold(true);
|
||||
}
|
||||
inline void stopDecouple()
|
||||
{
|
||||
setDecoupleFull(false);
|
||||
}
|
||||
inline bool isSensorDefect()
|
||||
{
|
||||
return flags & TEMPERATURE_CONTROLLER_FLAG_SENSDEFECT;
|
||||
}
|
||||
inline bool isSensorDecoupled()
|
||||
{
|
||||
return flags & TEMPERATURE_CONTROLLER_FLAG_SENSDECOUPLED;
|
||||
}
|
||||
static void resetAllErrorStates();
|
||||
fast8_t errorState();
|
||||
inline bool isFilamentChange()
|
||||
{
|
||||
return flags & TEMPERATURE_CONTROLLER_FLAG_FILAMENTCHANGE;
|
||||
}
|
||||
inline bool isJammed()
|
||||
{
|
||||
return flags & TEMPERATURE_CONTROLLER_FLAG_JAM;
|
||||
}
|
||||
inline bool isSlowedDown()
|
||||
{
|
||||
return flags & TEMPERATURE_CONTROLLER_FLAG_SLOWDOWN;
|
||||
}
|
||||
#if EXTRUDER_JAM_CONTROL
|
||||
inline void setFilamentChange(bool on)
|
||||
{
|
||||
flags &= ~TEMPERATURE_CONTROLLER_FLAG_FILAMENTCHANGE;
|
||||
if(on) flags |= TEMPERATURE_CONTROLLER_FLAG_FILAMENTCHANGE;
|
||||
}
|
||||
void setJammed(bool on);
|
||||
inline void setSlowedDown(bool on)
|
||||
{
|
||||
flags &= ~TEMPERATURE_CONTROLLER_FLAG_SLOWDOWN;
|
||||
if(on) flags |= TEMPERATURE_CONTROLLER_FLAG_SLOWDOWN;
|
||||
}
|
||||
|
||||
#endif
|
||||
void waitForTargetTemperature();
|
||||
void autotunePID(float temp,uint8_t controllerId,int maxCycles,bool storeResult, int method);
|
||||
inline void startPreheatTime()
|
||||
{
|
||||
preheatStartTime = HAL::timeInMilliseconds();
|
||||
}
|
||||
inline void resetPreheatTime()
|
||||
{
|
||||
preheatStartTime = 0;
|
||||
}
|
||||
inline millis_t preheatTime()
|
||||
{
|
||||
return preheatStartTime == 0 ? 0 : HAL::timeInMilliseconds() - preheatStartTime;
|
||||
}
|
||||
};
|
||||
class Extruder;
|
||||
extern Extruder extruder[];
|
||||
|
||||
#if EXTRUDER_JAM_CONTROL
|
||||
#if JAM_METHOD == 1
|
||||
#define _TEST_EXTRUDER_JAM(x,pin) {\
|
||||
uint8_t sig = READ(pin);extruder[x].jamStepsSinceLastSignal += extruder[x].jamLastDir;\
|
||||
if(extruder[x].jamLastSignal != sig && abs(extruder[x].jamStepsSinceLastSignal - extruder[x].jamLastChangeAt) > JAM_MIN_STEPS) {\
|
||||
if(sig) {extruder[x].resetJamSteps();} \
|
||||
extruder[x].jamLastSignal = sig;extruder[x].jamLastChangeAt = extruder[x].jamStepsSinceLastSignal;\
|
||||
} else if(abs(extruder[x].jamStepsSinceLastSignal) > extruder[x].jamErrorSteps && !Printer::isDebugJamOrDisabled() && !extruder[x].tempControl.isJammed() && !extruder[x].tempControl.isFilamentChange()) {\
|
||||
if(extruder[x].jamLastDir > 0) {\
|
||||
extruder[x].tempControl.setJammed(true);\
|
||||
} else {\
|
||||
extruder[x].tempControl.setFilamentChange(true);}} \
|
||||
}
|
||||
#define RESET_EXTRUDER_JAM(x,dir) extruder[x].jamLastDir = dir ? 1 : -1;
|
||||
#elif JAM_METHOD == 2
|
||||
#define _TEST_EXTRUDER_JAM(x,pin) {\
|
||||
uint8_t sig = READ(pin);\
|
||||
if(sig != extruder[x].jamLastSignal) {\
|
||||
extruder[x].jamLastSignal = sig;\
|
||||
if(sig)\
|
||||
{extruder[x].tempControl.setFilamentChange(true);extruder[x].tempControl.setJammed(true);} \
|
||||
else if(!Printer::isDebugJamOrDisabled() && extruder[x].tempControl.isJammed()) \
|
||||
{extruder[x].resetJamSteps();}}\
|
||||
}
|
||||
#define RESET_EXTRUDER_JAM(x,dir)
|
||||
#elif JAM_METHOD == 3
|
||||
#define _TEST_EXTRUDER_JAM(x,pin) {\
|
||||
uint8_t sig = !READ(pin);\
|
||||
if(sig != extruder[x].jamLastSignal) {\
|
||||
extruder[x].jamLastSignal = sig;\
|
||||
if(sig)\
|
||||
{extruder[x].tempControl.setFilamentChange(true);extruder[x].tempControl.setJammed(true);} \
|
||||
else if(!Printer::isDebugJamOrDisabled() && extruder[x].tempControl.isJammed()) \
|
||||
{extruder[x].resetJamSteps();}}\
|
||||
}
|
||||
#define RESET_EXTRUDER_JAM(x,dir)
|
||||
#else
|
||||
#error Unknown value for JAM_METHOD
|
||||
#endif
|
||||
#define ___TEST_EXTRUDER_JAM(x,y) _TEST_EXTRUDER_JAM(x,y)
|
||||
#define __TEST_EXTRUDER_JAM(x) ___TEST_EXTRUDER_JAM(x,EXT ## x ## _JAM_PIN)
|
||||
#define TEST_EXTRUDER_JAM(x) __TEST_EXTRUDER_JAM(x)
|
||||
#else
|
||||
#define TEST_EXTRUDER_JAM(x)
|
||||
#define RESET_EXTRUDER_JAM(x,dir)
|
||||
#endif
|
||||
|
||||
#define EXTRUDER_FLAG_RETRACTED 1
|
||||
#define EXTRUDER_FLAG_WAIT_JAM_STARTCOUNT 2 ///< Waiting for the first signal to start counting
|
||||
|
||||
/** \brief Data to drive one extruder.
|
||||
|
||||
This structure contains all definitions for an extruder and all
|
||||
current state variables, like current temperature, feeder position etc.
|
||||
*/
|
||||
class Extruder // Size: 12*1 Byte+12*4 Byte+4*2Byte = 68 Byte
|
||||
{
|
||||
public:
|
||||
static Extruder *current;
|
||||
#if FEATURE_DITTO_PRINTING
|
||||
static uint8_t dittoMode;
|
||||
#endif
|
||||
#if MIXING_EXTRUDER > 0
|
||||
static int mixingS; ///< Sum of all weights
|
||||
static uint8_t mixingDir; ///< Direction flag
|
||||
static uint8_t activeMixingExtruder;
|
||||
static void recomputeMixingExtruderSteps();
|
||||
#endif
|
||||
uint8_t id;
|
||||
int32_t xOffset;
|
||||
int32_t yOffset;
|
||||
int32_t zOffset;
|
||||
float stepsPerMM; ///< Steps per mm.
|
||||
int8_t enablePin; ///< Pin to enable extruder stepper motor.
|
||||
// uint8_t directionPin; ///< Pin number to assign the direction.
|
||||
// uint8_t stepPin; ///< Pin number for a step.
|
||||
uint8_t enableOn;
|
||||
// uint8_t invertDir; ///< 1 if the direction of the extruder should be inverted.
|
||||
float maxFeedrate; ///< Maximum feedrate in mm/s.
|
||||
float maxAcceleration; ///< Maximum acceleration in mm/s^2.
|
||||
float maxStartFeedrate; ///< Maximum start feedrate in mm/s.
|
||||
int32_t extrudePosition; ///< Current extruder position in steps.
|
||||
int16_t watchPeriod; ///< Time in seconds, a M109 command will wait to stabilize temperature
|
||||
int16_t waitRetractTemperature; ///< Temperature to retract the filament when waiting for heat up
|
||||
int16_t waitRetractUnits; ///< Units to retract the filament when waiting for heat up
|
||||
#if USE_ADVANCE
|
||||
#if ENABLE_QUADRATIC_ADVANCE
|
||||
float advanceK; ///< Coefficient for advance algorithm. 0 = off
|
||||
#endif
|
||||
float advanceL;
|
||||
int16_t advanceBacklash;
|
||||
#endif // USE_ADVANCE
|
||||
#if MIXING_EXTRUDER > 0
|
||||
int mixingW; ///< Weight for this extruder when mixing steps
|
||||
int mixingWB; ///< Weight after balancing extruder steps per mm
|
||||
int mixingE; ///< Cumulated error for this step.
|
||||
int virtualWeights[VIRTUAL_EXTRUDER]; // Virtual extruder weights
|
||||
#endif // MIXING_EXTRUDER > 0
|
||||
TemperatureController tempControl;
|
||||
const char * PROGMEM selectCommands;
|
||||
const char * PROGMEM deselectCommands;
|
||||
uint8_t coolerSpeed; ///< Speed to use when enabled
|
||||
uint8_t coolerPWM; ///< current PWM setting
|
||||
float diameter;
|
||||
uint8_t flags;
|
||||
#if EXTRUDER_JAM_CONTROL
|
||||
int32_t jamStepsSinceLastSignal; // when was the last signal
|
||||
uint8_t jamLastSignal; // what was the last signal
|
||||
int8_t jamLastDir;
|
||||
int32_t jamStepsOnSignal;
|
||||
int32_t jamLastChangeAt;
|
||||
int32_t jamSlowdownSteps;
|
||||
int32_t jamErrorSteps;
|
||||
uint8_t jamSlowdownTo;
|
||||
#endif
|
||||
|
||||
// Methods here
|
||||
|
||||
#if EXTRUDER_JAM_CONTROL
|
||||
inline bool isWaitJamStartcount()
|
||||
{
|
||||
return flags & EXTRUDER_FLAG_WAIT_JAM_STARTCOUNT;
|
||||
}
|
||||
inline void setWaitJamStartcount(bool on)
|
||||
{
|
||||
if(on) flags |= EXTRUDER_FLAG_WAIT_JAM_STARTCOUNT;
|
||||
else flags &= ~(EXTRUDER_FLAG_WAIT_JAM_STARTCOUNT);
|
||||
}
|
||||
static void markAllUnjammed();
|
||||
void resetJamSteps();
|
||||
#endif
|
||||
#if MIXING_EXTRUDER > 0
|
||||
static void setMixingWeight(uint8_t extr,int weight);
|
||||
#endif
|
||||
static void step();
|
||||
static void unstep();
|
||||
static void setDirection(uint8_t dir);
|
||||
static void enable();
|
||||
#if FEATURE_RETRACTION
|
||||
inline bool isRetracted() {return (flags & EXTRUDER_FLAG_RETRACTED) != 0;}
|
||||
inline void setRetracted(bool on) {
|
||||
flags = (flags & (255 - EXTRUDER_FLAG_RETRACTED)) | (on ? EXTRUDER_FLAG_RETRACTED : 0);
|
||||
}
|
||||
void retract(bool isRetract,bool isLong);
|
||||
void retractDistance(float dist,bool extraLength = false);
|
||||
#endif
|
||||
static void manageTemperatures();
|
||||
static void disableCurrentExtruderMotor();
|
||||
static void disableAllExtruderMotors();
|
||||
static void selectExtruderById(uint8_t extruderId);
|
||||
static void disableAllHeater();
|
||||
static void initExtruder();
|
||||
static void initHeatedBed();
|
||||
static void setHeatedBedTemperature(float temp_celsius,bool beep = false);
|
||||
static float getHeatedBedTemperature();
|
||||
static void setTemperatureForExtruder(float temp_celsius,uint8_t extr,bool beep = false,bool wait = false);
|
||||
static void pauseExtruders(bool bed = false);
|
||||
static void unpauseExtruders(bool wait = true);
|
||||
};
|
||||
|
||||
#if HAVE_HEATED_BED
|
||||
#define HEATED_BED_INDEX NUM_EXTRUDER
|
||||
extern TemperatureController heatedBedController;
|
||||
#else
|
||||
#define HEATED_BED_INDEX NUM_EXTRUDER-1
|
||||
#endif
|
||||
#if FAN_THERMO_PIN > -1
|
||||
#define THERMO_CONTROLLER_INDEX HEATED_BED_INDEX+1
|
||||
extern TemperatureController thermoController;
|
||||
#else
|
||||
#define THERMO_CONTROLLER_INDEX HEATED_BED_INDEX
|
||||
#endif
|
||||
#define NUM_TEMPERATURE_LOOPS THERMO_CONTROLLER_INDEX+1
|
||||
|
||||
#define TEMP_INT_TO_FLOAT(temp) ((float)(temp)/(float)(1<<CELSIUS_EXTRA_BITS))
|
||||
#define TEMP_FLOAT_TO_INT(temp) ((int)((temp)*(1<<CELSIUS_EXTRA_BITS)))
|
||||
|
||||
//extern Extruder *Extruder::current;
|
||||
#if NUM_TEMPERATURE_LOOPS > 0
|
||||
extern TemperatureController *tempController[NUM_TEMPERATURE_LOOPS];
|
||||
#endif
|
||||
extern uint8_t autotuneIndex;
|
||||
|
||||
|
||||
#endif // EXTRUDER_H_INCLUDED
|
1427
Repetier-Firmware 1.0.3/Repetier/HAL.cpp
Normal file
1427
Repetier-Firmware 1.0.3/Repetier/HAL.cpp
Normal file
File diff suppressed because it is too large
Load Diff
785
Repetier-Firmware 1.0.3/Repetier/HAL.h
Normal file
785
Repetier-Firmware 1.0.3/Repetier/HAL.h
Normal file
@ -0,0 +1,785 @@
|
||||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware 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.
|
||||
|
||||
Repetier-Firmware 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 Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
This firmware is a nearly complete rewrite of the sprinter firmware
|
||||
by kliment (https://github.com/kliment/Sprinter)
|
||||
which based on Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
|
||||
|
||||
Functions in this file are used to communicate using ascii or repetier protocol.
|
||||
*/
|
||||
|
||||
#ifndef HAL_H
|
||||
#define HAL_H
|
||||
|
||||
/**
|
||||
This is the main Hardware Abstraction Layer (HAL).
|
||||
To make the firmware work with different processors and tool chains,
|
||||
all hardware related code should be packed into the hal files.
|
||||
*/
|
||||
|
||||
#include <avr/pgmspace.h>
|
||||
#include <avr/io.h>
|
||||
|
||||
|
||||
#define INLINE __attribute__((always_inline))
|
||||
|
||||
#if CPU_ARCH == ARCH_AVR
|
||||
#include <avr/io.h>
|
||||
#else
|
||||
#define PROGMEM
|
||||
#define PGM_P const char *
|
||||
#define PSTR(s) s
|
||||
#define pgm_read_byte_near(x) (*(uint8_t*)x)
|
||||
#define pgm_read_byte(x) (*(uint8_t*)x)
|
||||
#endif
|
||||
|
||||
#define PACK
|
||||
|
||||
#define FSTRINGVALUE(var,value) const char var[] PROGMEM = value;
|
||||
#define FSTRINGVAR(var) static const char var[] PROGMEM;
|
||||
#define FSTRINGPARAM(var) PGM_P var
|
||||
|
||||
#include <avr/eeprom.h>
|
||||
#include <avr/wdt.h>
|
||||
/** \brief Prescale factor, timer0 runs at.
|
||||
|
||||
All known Arduino boards use 64. This value is needed for the extruder timing. */
|
||||
#define TIMER0_PRESCALE 64
|
||||
|
||||
#define ANALOG_PRESCALER _BV(ADPS0)|_BV(ADPS1)|_BV(ADPS2)
|
||||
|
||||
#if MOTHERBOARD==8 || MOTHERBOARD==88 || MOTHERBOARD==9 || MOTHERBOARD==92 || CPU_ARCH!=ARCH_AVR
|
||||
#define EXTERNALSERIAL
|
||||
#endif
|
||||
#if NEW_COMMUNICATION && defined(BLUETOOTH_SERIAL) && BLUETOOTH_SERIAL > 0
|
||||
#undef EXTERNALSERIAL
|
||||
#define EXTERNALSERIAL
|
||||
#endif
|
||||
|
||||
//#define EXTERNALSERIAL // Force using Arduino serial
|
||||
#ifndef EXTERNALSERIAL
|
||||
#undef HardwareSerial_h
|
||||
#define HardwareSerial_h // Don't use standard serial console
|
||||
#endif
|
||||
#include <inttypes.h>
|
||||
#include "Stream.h"
|
||||
#ifdef EXTERNALSERIAL
|
||||
// Can not change buffer size here, need add build flag -D SERIAL_RX_BUFFER_SIZE=128
|
||||
//#define SERIAL_RX_BUFFER_SIZE 128
|
||||
#endif
|
||||
#if defined(ARDUINO) && ARDUINO >= 100
|
||||
#include "Arduino.h"
|
||||
#else
|
||||
#include "WProgram.h"
|
||||
#define COMPAT_PRE1
|
||||
#endif
|
||||
#if CPU_ARCH==ARCH_AVR
|
||||
#include "fastio.h"
|
||||
#else
|
||||
#define READ(IO) digitalRead(IO)
|
||||
#define WRITE(IO, v) digitalWrite(IO, v)
|
||||
#define SET_INPUT(IO) pinMode(IO, INPUT)
|
||||
#define SET_OUTPUT(IO) pinMode(IO, OUTPUT)
|
||||
#endif
|
||||
#ifndef cbi
|
||||
#define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
|
||||
#endif
|
||||
#ifndef sbi
|
||||
#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
|
||||
#endif
|
||||
|
||||
class InterruptProtectedBlock
|
||||
{
|
||||
uint8_t sreg;
|
||||
public:
|
||||
inline void protect()
|
||||
{
|
||||
cli();
|
||||
}
|
||||
|
||||
inline void unprotect()
|
||||
{
|
||||
SREG = sreg;
|
||||
}
|
||||
|
||||
inline InterruptProtectedBlock(bool later = false)
|
||||
{
|
||||
sreg = SREG;
|
||||
if(!later)
|
||||
cli();
|
||||
}
|
||||
|
||||
inline ~InterruptProtectedBlock()
|
||||
{
|
||||
SREG = sreg;
|
||||
}
|
||||
};
|
||||
|
||||
#define EEPROM_OFFSET 0
|
||||
#define SECONDS_TO_TICKS(s) (unsigned long)(s*(float)F_CPU)
|
||||
#define ANALOG_INPUT_SAMPLE 5
|
||||
// Bits of the ADC converter
|
||||
#define ANALOG_INPUT_BITS 10
|
||||
#define ANALOG_REDUCE_BITS 0
|
||||
#define ANALOG_REDUCE_FACTOR 1
|
||||
|
||||
#define MAX_RAM 32767
|
||||
|
||||
#define bit_clear(x,y) x&= ~(1<<y) //cbi(x,y)
|
||||
#define bit_set(x,y) x|= (1<<y)//sbi(x,y)
|
||||
|
||||
/** defines the data direction (reading from I2C device) in i2cStart(),i2cRepStart() */
|
||||
#define I2C_READ 1
|
||||
/** defines the data direction (writing to I2C device) in i2cStart(),i2cRepStart() */
|
||||
#define I2C_WRITE 0
|
||||
|
||||
#if NONLINEAR_SYSTEM
|
||||
// Maximum speed with 100% interrupt utilization is 27000 Hz at 16MHz cpu
|
||||
// leave some margin for all the extra transformations. So we keep inside clean timings.
|
||||
#define LIMIT_INTERVAL ((F_CPU/30000)+1)
|
||||
#else
|
||||
#define LIMIT_INTERVAL ((F_CPU/40000)+1)
|
||||
#endif
|
||||
|
||||
typedef uint16_t speed_t;
|
||||
typedef uint32_t ticks_t;
|
||||
typedef uint32_t millis_t;
|
||||
typedef uint8_t flag8_t;
|
||||
typedef int8_t fast8_t;
|
||||
typedef uint8_t ufast8_t;
|
||||
|
||||
#define FAST_INTEGER_SQRT
|
||||
|
||||
#ifndef EXTERNALSERIAL
|
||||
// Implement serial communication for one stream only!
|
||||
/*
|
||||
HardwareSerial.h - Hardware serial library for Wiring
|
||||
Copyright (c) 2006 Nicholas Zambetti. All right reserved.
|
||||
|
||||
This library is free software; you can redistribute it and/or
|
||||
modify it under the terms of the GNU Lesser General Public
|
||||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
|
||||
This library 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
|
||||
Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General Public
|
||||
License along with this library; if not, write to the Free Software
|
||||
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
|
||||
Modified 28 September 2010 by Mark Sproul
|
||||
|
||||
Modified to use only 1 queue with fixed length by Repetier
|
||||
*/
|
||||
|
||||
#define SERIAL_BUFFER_SIZE 128
|
||||
#define SERIAL_BUFFER_MASK 127
|
||||
#undef SERIAL_TX_BUFFER_SIZE
|
||||
#undef SERIAL_TX_BUFFER_MASK
|
||||
#ifdef BIG_OUTPUT_BUFFER
|
||||
#define SERIAL_TX_BUFFER_SIZE 128
|
||||
#define SERIAL_TX_BUFFER_MASK 127
|
||||
#else
|
||||
#define SERIAL_TX_BUFFER_SIZE 64
|
||||
#define SERIAL_TX_BUFFER_MASK 63
|
||||
#endif
|
||||
|
||||
struct ring_buffer
|
||||
{
|
||||
uint8_t buffer[SERIAL_BUFFER_SIZE];
|
||||
volatile uint8_t head;
|
||||
volatile uint8_t tail;
|
||||
};
|
||||
struct ring_buffer_tx
|
||||
{
|
||||
uint8_t buffer[SERIAL_TX_BUFFER_SIZE];
|
||||
volatile uint8_t head;
|
||||
volatile uint8_t tail;
|
||||
};
|
||||
|
||||
class RFHardwareSerial : public Stream
|
||||
{
|
||||
public:
|
||||
ring_buffer *_rx_buffer;
|
||||
ring_buffer_tx *_tx_buffer;
|
||||
volatile uint8_t *_ubrrh;
|
||||
volatile uint8_t *_ubrrl;
|
||||
volatile uint8_t *_ucsra;
|
||||
volatile uint8_t *_ucsrb;
|
||||
volatile uint8_t *_udr;
|
||||
uint8_t _rxen;
|
||||
uint8_t _txen;
|
||||
uint8_t _rxcie;
|
||||
uint8_t _udrie;
|
||||
uint8_t _u2x;
|
||||
public:
|
||||
RFHardwareSerial(ring_buffer *rx_buffer, ring_buffer_tx *tx_buffer,
|
||||
volatile uint8_t *ubrrh, volatile uint8_t *ubrrl,
|
||||
volatile uint8_t *ucsra, volatile uint8_t *ucsrb,
|
||||
volatile uint8_t *udr,
|
||||
uint8_t rxen, uint8_t txen, uint8_t rxcie, uint8_t udrie, uint8_t u2x);
|
||||
void begin(unsigned long);
|
||||
void end();
|
||||
virtual int available(void);
|
||||
virtual int peek(void);
|
||||
virtual int read(void);
|
||||
virtual void flush(void);
|
||||
#ifdef COMPAT_PRE1
|
||||
virtual void write(uint8_t);
|
||||
#else
|
||||
virtual size_t write(uint8_t);
|
||||
#endif
|
||||
using Print::write; // pull in write(str) and write(buf, size) from Print
|
||||
operator bool();
|
||||
int outputUnused(void); // Used for output in interrupts
|
||||
};
|
||||
extern RFHardwareSerial RFSerial;
|
||||
#define RFSERIAL RFSerial
|
||||
//extern ring_buffer tx_buffer;
|
||||
#define WAIT_OUT_EMPTY while(tx_buffer.head != tx_buffer.tail) {}
|
||||
#else
|
||||
#define RFSERIAL Serial
|
||||
#if defined(BLUETOOTH_SERIAL) && BLUETOOTH_SERIAL > 0
|
||||
#if BLUETOOTH_SERIAL == 1
|
||||
#define RFSERIAL2 Serial1
|
||||
#elif BLUETOOTH_SERIAL == 2
|
||||
#define RFSERIAL2 Serial2
|
||||
#elif BLUETOOTH_SERIAL == 3
|
||||
#define RFSERIAL2 Serial3
|
||||
#elif BLUETOOTH_SERIAL == 4
|
||||
#define RFSERIAL2 Serial4
|
||||
#elif BLUETOOTH_SERIAL == 5
|
||||
#define RFSERIAL2 Serial5
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
class HAL
|
||||
{
|
||||
public:
|
||||
#if FEATURE_WATCHDOG
|
||||
static bool wdPinged;
|
||||
#endif
|
||||
HAL();
|
||||
virtual ~HAL();
|
||||
static inline void hwSetup(void)
|
||||
{}
|
||||
// return val*val
|
||||
static uint16_t integerSqrt(uint32_t a);
|
||||
/** \brief Optimized division
|
||||
|
||||
Normally the C compiler will compute a long/long division, which takes ~670 Ticks.
|
||||
This version is optimized for a 16 bit dividend and recognizes the special cases
|
||||
of a 24 bit and 16 bit dividend, which often, but not always occur in updating the
|
||||
interval.
|
||||
*/
|
||||
static inline int32_t Div4U2U(uint32_t a,uint16_t b)
|
||||
{
|
||||
#if CPU_ARCH==ARCH_AVR
|
||||
// r14/r15 remainder
|
||||
// r16 counter
|
||||
__asm__ __volatile__ (
|
||||
"clr r14 \n\t"
|
||||
"sub r15,r15 \n\t"
|
||||
"tst %D0 \n\t"
|
||||
"brne do32%= \n\t"
|
||||
"tst %C0 \n\t"
|
||||
"breq donot24%= \n\t"
|
||||
"rjmp do24%= \n\t"
|
||||
"donot24%=:" "ldi r16,17 \n\t" // 16 Bit divide
|
||||
"d16u_1%=:" "rol %A0 \n\t"
|
||||
"rol %B0 \n\t"
|
||||
"dec r16 \n\t"
|
||||
"brne d16u_2%= \n\t"
|
||||
"rjmp end%= \n\t"
|
||||
"d16u_2%=:" "rol r14 \n\t"
|
||||
"rol r15 \n\t"
|
||||
"sub r14,%A2 \n\t"
|
||||
"sbc r15,%B2 \n\t"
|
||||
"brcc d16u_3%= \n\t"
|
||||
"add r14,%A2 \n\t"
|
||||
"adc r15,%B2 \n\t"
|
||||
"clc \n\t"
|
||||
"rjmp d16u_1%= \n\t"
|
||||
"d16u_3%=:" "sec \n\t"
|
||||
"rjmp d16u_1%= \n\t"
|
||||
"do32%=:" // divide full 32 bit
|
||||
"rjmp do32B%= \n\t"
|
||||
"do24%=:" // divide 24 bit
|
||||
|
||||
"ldi r16,25 \n\t" // 24 Bit divide
|
||||
"d24u_1%=:" "rol %A0 \n\t"
|
||||
"rol %B0 \n\t"
|
||||
"rol %C0 \n\t"
|
||||
"dec r16 \n\t"
|
||||
"brne d24u_2%= \n\t"
|
||||
"rjmp end%= \n\t"
|
||||
"d24u_2%=:" "rol r14 \n\t"
|
||||
"rol r15 \n\t"
|
||||
"sub r14,%A2 \n\t"
|
||||
"sbc r15,%B2 \n\t"
|
||||
"brcc d24u_3%= \n\t"
|
||||
"add r14,%A2 \n\t"
|
||||
"adc r15,%B2 \n\t"
|
||||
"clc \n\t"
|
||||
"rjmp d24u_1%= \n\t"
|
||||
"d24u_3%=:" "sec \n\t"
|
||||
"rjmp d24u_1%= \n\t"
|
||||
|
||||
"do32B%=:" // divide full 32 bit
|
||||
|
||||
"ldi r16,33 \n\t" // 32 Bit divide
|
||||
"d32u_1%=:" "rol %A0 \n\t"
|
||||
"rol %B0 \n\t"
|
||||
"rol %C0 \n\t"
|
||||
"rol %D0 \n\t"
|
||||
"dec r16 \n\t"
|
||||
"brne d32u_2%= \n\t"
|
||||
"rjmp end%= \n\t"
|
||||
"d32u_2%=:" "rol r14 \n\t"
|
||||
"rol r15 \n\t"
|
||||
"sub r14,%A2 \n\t"
|
||||
"sbc r15,%B2 \n\t"
|
||||
"brcc d32u_3%= \n\t"
|
||||
"add r14,%A2 \n\t"
|
||||
"adc r15,%B2 \n\t"
|
||||
"clc \n\t"
|
||||
"rjmp d32u_1%= \n\t"
|
||||
"d32u_3%=:" "sec \n\t"
|
||||
"rjmp d32u_1%= \n\t"
|
||||
|
||||
"end%=:" // end
|
||||
:"=&r"(a)
|
||||
:"0"(a),"r"(b)
|
||||
:"r14","r15","r16"
|
||||
);
|
||||
return a;
|
||||
#else
|
||||
return a/b;
|
||||
#endif
|
||||
}
|
||||
static inline unsigned long U16SquaredToU32(unsigned int val)
|
||||
{
|
||||
long res;
|
||||
__asm__ __volatile__ ( // 15 Ticks
|
||||
"mul %A1,%A1 \n\t"
|
||||
"movw %A0,r0 \n\t"
|
||||
"mul %B1,%B1 \n\t"
|
||||
"movw %C0,r0 \n\t"
|
||||
"mul %A1,%B1 \n\t"
|
||||
"clr %A1 \n\t"
|
||||
"add %B0,r0 \n\t"
|
||||
"adc %C0,r1 \n\t"
|
||||
"adc %D0,%A1 \n\t"
|
||||
"add %B0,r0 \n\t"
|
||||
"adc %C0,r1 \n\t"
|
||||
"adc %D0,%A1 \n\t"
|
||||
"clr r1 \n\t"
|
||||
: "=&r"(res),"=r"(val)
|
||||
: "1"(val)
|
||||
);
|
||||
return res;
|
||||
}
|
||||
static inline unsigned int ComputeV(long timer,long accel)
|
||||
{
|
||||
#if CPU_ARCH==ARCH_AVR
|
||||
unsigned int res;
|
||||
// 38 Ticks
|
||||
__asm__ __volatile__ ( // 0 = res, 1 = timer, 2 = accel %D2=0 ,%A1 are unused is free
|
||||
// Result LSB first: %A0, %B0, %A1
|
||||
"mul %B1,%A2 \n\t"
|
||||
"mov %A0,r1 \n\t"
|
||||
"mul %B1,%C2 \n\t"
|
||||
"mov %B0,r0 \n\t"
|
||||
"mov %A1,r1 \n\t"
|
||||
"mul %B1,%B2 \n\t"
|
||||
"add %A0,r0 \n\t"
|
||||
"adc %B0,r1 \n\t"
|
||||
"adc %A1,%D2 \n\t"
|
||||
"mul %C1,%A2 \n\t"
|
||||
"add %A0,r0 \n\t"
|
||||
"adc %B0,r1 \n\t"
|
||||
"adc %A1,%D2 \n\t"
|
||||
"mul %C1,%B2 \n\t"
|
||||
"add %B0,r0 \n\t"
|
||||
"adc %A1,r1 \n\t"
|
||||
"mul %D1,%A2 \n\t"
|
||||
"add %B0,r0 \n\t"
|
||||
"adc %A1,r1 \n\t"
|
||||
"mul %C1,%C2 \n\t"
|
||||
"add %A1,r0 \n\t"
|
||||
"mul %D1,%B2 \n\t"
|
||||
"add %A1,r0 \n\t"
|
||||
"lsr %A1 \n\t"
|
||||
"ror %B0 \n\t"
|
||||
"ror %A0 \n\t"
|
||||
"lsr %A1 \n\t"
|
||||
"ror %B0 \n\t"
|
||||
"ror %A0 \n\t"
|
||||
"clr r1 \n\t"
|
||||
:"=&r"(res),"=r"(timer),"=r"(accel)
|
||||
:"1"(timer),"2"(accel)
|
||||
: );
|
||||
// unsigned int v = ((timer>>8)*cur->accel)>>10;
|
||||
return res;
|
||||
#else
|
||||
return ((timer >> 8) * accel) >> 10;
|
||||
#endif
|
||||
}
|
||||
// Multiply two 16 bit values and return 32 bit result
|
||||
static inline uint32_t mulu16xu16to32(unsigned int a,unsigned int b)
|
||||
{
|
||||
uint32_t res;
|
||||
// 18 Ticks = 1.125 us
|
||||
__asm__ __volatile__ ( // 0 = res, 1 = timer, 2 = accel %D2=0 ,%A1 are unused is free
|
||||
// Result LSB first: %A0, %B0, %A1
|
||||
"clr r18 \n\t"
|
||||
"mul %B2,%B1 \n\t" // mul hig bytes
|
||||
"movw %C0,r0 \n\t"
|
||||
"mul %A1,%A2 \n\t" // mul low bytes
|
||||
"movw %A0,r0 \n\t"
|
||||
"mul %A1,%B2 \n\t"
|
||||
"add %B0,r0 \n\t"
|
||||
"adc %C0,r1 \n\t"
|
||||
"adc %D0,r18 \n\t"
|
||||
"mul %B1,%A2 \n\t"
|
||||
"add %B0,r0 \n\t"
|
||||
"adc %C0,r1 \n\t"
|
||||
"adc %D0,r18 \n\t"
|
||||
"clr r1 \n\t"
|
||||
:"=&r"(res),"=r"(a),"=r"(b)
|
||||
:"1"(a),"2"(b)
|
||||
:"r18" );
|
||||
// return (long)a*b;
|
||||
return res;
|
||||
}
|
||||
// Multiply two 16 bit values and return 32 bit result
|
||||
static inline unsigned int mulu6xu16shift16(unsigned int a,unsigned int b)
|
||||
{
|
||||
#if CPU_ARCH == ARCH_AVR
|
||||
unsigned int res;
|
||||
// 18 Ticks = 1.125 us
|
||||
__asm__ __volatile__ ( // 0 = res, 1 = timer, 2 = accel %D2=0 ,%A1 are unused is free
|
||||
// Result LSB first: %A0, %B0, %A1
|
||||
"clr r18 \n\t"
|
||||
"mul %B2,%B1 \n\t" // mul hig bytes
|
||||
"movw %A0,r0 \n\t"
|
||||
"mul %A1,%A2 \n\t" // mul low bytes
|
||||
"mov r19,r1 \n\t"
|
||||
"mul %A1,%B2 \n\t"
|
||||
"add r19,r0 \n\t"
|
||||
"adc %A0,r1 \n\t"
|
||||
"adc %B0,r18 \n\t"
|
||||
"mul %B1,%A2 \n\t"
|
||||
"add r19,r0 \n\t"
|
||||
"adc %A0,r1 \n\t"
|
||||
"adc %B0,r18 \n\t"
|
||||
"clr r1 \n\t"
|
||||
:"=&r"(res),"=r"(a),"=r"(b)
|
||||
:"1"(a),"2"(b)
|
||||
:"r18","r19" );
|
||||
return res;
|
||||
#else
|
||||
return ((int32_t)a * b) >> 16;
|
||||
#endif
|
||||
}
|
||||
static inline void digitalWrite(uint8_t pin,uint8_t value)
|
||||
{
|
||||
::digitalWrite(pin,value);
|
||||
}
|
||||
static inline uint8_t digitalRead(uint8_t pin)
|
||||
{
|
||||
return ::digitalRead(pin);
|
||||
}
|
||||
static inline void pinMode(uint8_t pin,uint8_t mode)
|
||||
{
|
||||
::pinMode(pin,mode);
|
||||
}
|
||||
static int32_t CPUDivU2(unsigned int divisor);
|
||||
static inline void delayMicroseconds(unsigned int delayUs)
|
||||
{
|
||||
::delayMicroseconds(delayUs);
|
||||
}
|
||||
static inline void delayMilliseconds(unsigned int delayMs)
|
||||
{
|
||||
::delay(delayMs);
|
||||
}
|
||||
static inline void tone(uint8_t pin,int duration)
|
||||
{
|
||||
::tone(pin,duration);
|
||||
}
|
||||
static inline void noTone(uint8_t pin)
|
||||
{
|
||||
::noTone(pin);
|
||||
}
|
||||
static inline void eprSetByte(unsigned int pos,uint8_t value)
|
||||
{
|
||||
eeprom_write_byte((unsigned char *)(EEPROM_OFFSET + pos), value);
|
||||
}
|
||||
static inline void eprSetInt16(unsigned int pos,int16_t value)
|
||||
{
|
||||
eeprom_write_word((unsigned int*)(EEPROM_OFFSET + pos),value);
|
||||
}
|
||||
static inline void eprSetInt32(unsigned int pos,int32_t value)
|
||||
{
|
||||
eeprom_write_dword((uint32_t*)(EEPROM_OFFSET + pos),value);
|
||||
}
|
||||
static inline void eprSetFloat(unsigned int pos,float value)
|
||||
{
|
||||
eeprom_write_block(&value,(void*)(EEPROM_OFFSET + pos), 4);
|
||||
}
|
||||
static inline uint8_t eprGetByte(unsigned int pos)
|
||||
{
|
||||
return eeprom_read_byte ((unsigned char *)(EEPROM_OFFSET + pos));
|
||||
}
|
||||
static inline int16_t eprGetInt16(unsigned int pos)
|
||||
{
|
||||
return eeprom_read_word((uint16_t *)(EEPROM_OFFSET + pos));
|
||||
}
|
||||
static inline int32_t eprGetInt32(unsigned int pos)
|
||||
{
|
||||
return eeprom_read_dword((uint32_t*)(EEPROM_OFFSET + pos));
|
||||
}
|
||||
static inline float eprGetFloat(unsigned int pos)
|
||||
{
|
||||
float v;
|
||||
eeprom_read_block(&v,(void *)(EEPROM_OFFSET + pos),4); // newer gcc have eeprom_read_block but not arduino 22
|
||||
return v;
|
||||
}
|
||||
|
||||
// Faster version of InterruptProtectedBlock.
|
||||
// For safety it may only be called from within an
|
||||
// interrupt handler.
|
||||
static inline void allowInterrupts()
|
||||
{
|
||||
sei();
|
||||
}
|
||||
|
||||
// Faster version of InterruptProtectedBlock.
|
||||
// For safety it may only be called from within an
|
||||
// interrupt handler.
|
||||
static inline void forbidInterrupts()
|
||||
{
|
||||
cli();
|
||||
}
|
||||
static inline millis_t timeInMilliseconds()
|
||||
{
|
||||
return millis();
|
||||
}
|
||||
static inline char readFlashByte(PGM_P ptr)
|
||||
{
|
||||
return pgm_read_byte(ptr);
|
||||
}
|
||||
static inline int16_t readFlashWord(PGM_P ptr)
|
||||
{
|
||||
return pgm_read_word(ptr);
|
||||
}
|
||||
static inline void serialSetBaudrate(long baud)
|
||||
{
|
||||
RFSERIAL.begin(baud);
|
||||
}
|
||||
static inline bool serialByteAvailable()
|
||||
{
|
||||
return RFSERIAL.available() > 0;
|
||||
}
|
||||
static inline uint8_t serialReadByte()
|
||||
{
|
||||
return RFSERIAL.read();
|
||||
}
|
||||
static inline void serialWriteByte(char b)
|
||||
{
|
||||
RFSERIAL.write(b);
|
||||
}
|
||||
static inline void serialFlush()
|
||||
{
|
||||
RFSERIAL.flush();
|
||||
}
|
||||
static void setupTimer();
|
||||
static void showStartReason();
|
||||
static int getFreeRam();
|
||||
static void resetHardware();
|
||||
|
||||
// SPI related functions
|
||||
static void spiBegin(uint8_t ssPin = 0)
|
||||
{
|
||||
#if SDSS >= 0
|
||||
SET_INPUT(MISO_PIN);
|
||||
SET_OUTPUT(MOSI_PIN);
|
||||
SET_OUTPUT(SCK_PIN);
|
||||
// SS must be in output mode even it is not chip select
|
||||
SET_OUTPUT(SDSS);
|
||||
#if SDSSORIG >- 1
|
||||
SET_OUTPUT(SDSSORIG);
|
||||
#endif
|
||||
// set SS high - may be chip select for another SPI device
|
||||
#if defined(SET_SPI_SS_HIGH) && SET_SPI_SS_HIGH
|
||||
WRITE(SDSS, HIGH);
|
||||
#endif // SET_SPI_SS_HIGH
|
||||
#endif
|
||||
}
|
||||
static inline void spiInit(uint8_t spiRate)
|
||||
{
|
||||
uint8_t r = 0;
|
||||
for (uint8_t b = 2; spiRate > b && r < 6; b <<= 1, r++);
|
||||
SET_OUTPUT(SS);
|
||||
WRITE(SS,HIGH);
|
||||
SET_OUTPUT(SCK);
|
||||
SET_OUTPUT(MOSI_PIN);
|
||||
SET_INPUT(MISO_PIN);
|
||||
#ifdef PRR
|
||||
PRR &= ~(1<<PRSPI);
|
||||
#elif defined PRR0
|
||||
PRR0 &= ~(1<<PRSPI);
|
||||
#endif
|
||||
// See avr processor documentation
|
||||
SPCR = (1 << SPE) | (1 << MSTR) | (r >> 1);
|
||||
SPSR = (r & 1 || r == 6 ? 0 : 1) << SPI2X;
|
||||
|
||||
}
|
||||
static inline uint8_t spiReceive(uint8_t send=0xff)
|
||||
{
|
||||
SPDR = send;
|
||||
while (!(SPSR & (1 << SPIF))) {}
|
||||
return SPDR;
|
||||
}
|
||||
static inline void spiReadBlock(uint8_t*buf,size_t nbyte)
|
||||
{
|
||||
if (nbyte-- == 0) return;
|
||||
SPDR = 0XFF;
|
||||
for (size_t i = 0; i < nbyte; i++)
|
||||
{
|
||||
while (!(SPSR & (1 << SPIF))) {}
|
||||
buf[i] = SPDR;
|
||||
SPDR = 0XFF;
|
||||
}
|
||||
while (!(SPSR & (1 << SPIF))) {}
|
||||
buf[nbyte] = SPDR;
|
||||
}
|
||||
static inline void spiSend(uint8_t b)
|
||||
{
|
||||
SPDR = b;
|
||||
while (!(SPSR & (1 << SPIF))) {}
|
||||
}
|
||||
static inline void spiSend(const uint8_t* buf , size_t n)
|
||||
{
|
||||
if (n == 0) return;
|
||||
SPDR = buf[0];
|
||||
if (n > 1)
|
||||
{
|
||||
uint8_t b = buf[1];
|
||||
size_t i = 2;
|
||||
while (1)
|
||||
{
|
||||
while (!(SPSR & (1 << SPIF))) {}
|
||||
SPDR = b;
|
||||
if (i == n) break;
|
||||
b = buf[i++];
|
||||
}
|
||||
}
|
||||
while (!(SPSR & (1 << SPIF))) {}
|
||||
}
|
||||
|
||||
static inline __attribute__((always_inline))
|
||||
void spiSendBlock(uint8_t token, const uint8_t* buf)
|
||||
{
|
||||
SPDR = token;
|
||||
for (uint16_t i = 0; i < 512; i += 2)
|
||||
{
|
||||
while (!(SPSR & (1 << SPIF))) {}
|
||||
SPDR = buf[i];
|
||||
while (!(SPSR & (1 << SPIF))) {}
|
||||
SPDR = buf[i + 1];
|
||||
}
|
||||
while (!(SPSR & (1 << SPIF))) {}
|
||||
}
|
||||
|
||||
// I2C Support
|
||||
|
||||
static void i2cSetClockspeed(uint32_t clockSpeedHz);
|
||||
static void i2cInit(uint32_t clockSpeedHz);
|
||||
static unsigned char i2cStart(uint8_t address);
|
||||
static void i2cStartWait(uint8_t address);
|
||||
static void i2cStop(void);
|
||||
static void i2cWrite( uint8_t data );
|
||||
static uint8_t i2cReadAck(void);
|
||||
static uint8_t i2cReadNak(void);
|
||||
|
||||
// Watchdog support
|
||||
|
||||
inline static void startWatchdog()
|
||||
{
|
||||
#if defined (__AVR_ATmega1280__) || defined (__AVR_ATmega2560__)
|
||||
WDTCSR = (1<<WDCE) | (1<<WDE); // wdt FIX for arduino mega boards
|
||||
WDTCSR = (1<<WDIE) | (1<<WDP3);
|
||||
#else
|
||||
wdt_enable(WDTO_4S);
|
||||
#endif
|
||||
};
|
||||
inline static void stopWatchdog()
|
||||
{
|
||||
wdt_disable();
|
||||
}
|
||||
inline static void pingWatchdog()
|
||||
{
|
||||
#if FEATURE_WATCHDOG
|
||||
wdPinged = true;
|
||||
#endif
|
||||
};
|
||||
inline static float maxExtruderTimerFrequency()
|
||||
{
|
||||
return (float)F_CPU/TIMER0_PRESCALE;
|
||||
}
|
||||
#if FEATURE_SERVO
|
||||
static unsigned int servoTimings[4];
|
||||
static void servoMicroseconds(uint8_t servo,int ms, uint16_t autoOff);
|
||||
#endif
|
||||
static void analogStart();
|
||||
#if USE_ADVANCE
|
||||
static void resetExtruderDirection();
|
||||
#endif
|
||||
protected:
|
||||
private:
|
||||
};
|
||||
/*#if MOTHERBOARD==6 || MOTHERBOARD==62 || MOTHERBOARD==7
|
||||
#if MOTHERBOARD!=7
|
||||
#define SIMULATE_PWM
|
||||
#endif
|
||||
#define EXTRUDER_TIMER_VECTOR TIMER2_COMPA_vect
|
||||
#define EXTRUDER_OCR OCR2A
|
||||
#define EXTRUDER_TCCR TCCR2A
|
||||
#define EXTRUDER_TIMSK TIMSK2
|
||||
#define EXTRUDER_OCIE OCIE2A
|
||||
#define PWM_TIMER_VECTOR TIMER2_COMPB_vect
|
||||
#define PWM_OCR OCR2B
|
||||
#define PWM_TCCR TCCR2B
|
||||
#define PWM_TIMSK TIMSK2
|
||||
#define PWM_OCIE OCIE2B
|
||||
#else*/
|
||||
#define EXTRUDER_TIMER_VECTOR TIMER0_COMPA_vect
|
||||
#define EXTRUDER_OCR OCR0A
|
||||
#define EXTRUDER_TCCR TCCR0A
|
||||
#define EXTRUDER_TIMSK TIMSK0
|
||||
#define EXTRUDER_OCIE OCIE0A
|
||||
#define PWM_TIMER_VECTOR TIMER0_COMPB_vect
|
||||
#define PWM_OCR OCR0B
|
||||
#define PWM_TCCR TCCR0A
|
||||
#define PWM_TIMSK TIMSK0
|
||||
#define PWM_OCIE OCIE0B
|
||||
//#endif
|
||||
#endif // HAL_H
|
2673
Repetier-Firmware 1.0.3/Repetier/Printer.cpp
Normal file
2673
Repetier-Firmware 1.0.3/Repetier/Printer.cpp
Normal file
File diff suppressed because it is too large
Load Diff
1271
Repetier-Firmware 1.0.3/Repetier/Printer.h
Normal file
1271
Repetier-Firmware 1.0.3/Repetier/Printer.h
Normal file
File diff suppressed because it is too large
Load Diff
1123
Repetier-Firmware 1.0.3/Repetier/Repetier.h
Normal file
1123
Repetier-Firmware 1.0.3/Repetier/Repetier.h
Normal file
File diff suppressed because it is too large
Load Diff
208
Repetier-Firmware 1.0.3/Repetier/Repetier.ino
Normal file
208
Repetier-Firmware 1.0.3/Repetier/Repetier.ino
Normal file
@ -0,0 +1,208 @@
|
||||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware 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.
|
||||
|
||||
Repetier-Firmware 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 Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
This firmware is a nearly complete rewrite of the sprinter firmware
|
||||
by kliment (https://github.com/kliment/Sprinter)
|
||||
which based on Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
|
||||
|
||||
Main author: repetier
|
||||
|
||||
*/
|
||||
/**
|
||||
\mainpage Repetier-Firmware for Arduino based RepRaps
|
||||
<CENTER>Copyright © 2011-2013 by repetier
|
||||
</CENTER>
|
||||
|
||||
\section Intro Introduction
|
||||
|
||||
|
||||
\section GCodes Implemented GCodes
|
||||
|
||||
look here for descriptions of gcodes: http://linuxcnc.org/handbook/gcode/g-code.html
|
||||
and http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes
|
||||
|
||||
Implemented Codes
|
||||
|
||||
- G0 -> G1
|
||||
- G1 - Coordinated Movement X Y Z E, S1 disables boundary check, S0 enables it
|
||||
- G2 - Clockwise arc X,Y,E = end position, R = Radius or I,J = center
|
||||
- G3 - Counterclockwise arc X,Y,E = end position, R = Radius or I,J = center
|
||||
- G4 - Dwell S<seconds> or P<milliseconds>
|
||||
- G10 S<1 = long retract, 0 = short retract = default> retracts filament according to stored setting
|
||||
- G11 S<1 = long retract, 0 = short retract = default> = Undo retraction according to stored setting
|
||||
- G20 - Units for G0/G1 are inches.
|
||||
- G21 - Units for G0/G1 are mm.
|
||||
- G28 - Home all axis or named axis.
|
||||
- G29 S<0..2> - Z-Probe at the 3 defined probe points. S = 1 measure avg. zHeight, S = 2 store avg zHeight
|
||||
- G30 P<0..3> - Single z-probe at current position P = 1 first measurement, P = 2 Last measurement P = 0 or 3 first and last measurement
|
||||
- G30 H<height> R<offset> Make probe define new Z and z offset (R) at trigger point assuming z-probe measured an object of H height.
|
||||
- G31 - Write signal of probe sensor
|
||||
- G32 S<0..2> P<0..1> - Autolevel print bed. S = 1 measure zLength, S = 2 Measure and store new zLength
|
||||
- G33 - Measure distortion map
|
||||
- G33 R0 - delete distortion map
|
||||
- G33 L0 - List distortion map
|
||||
- G33 X<xpos> Y<ypos> Z<newdistortioncorrection> - Set new distortion for nearest distortion point.
|
||||
- G90 - Use absolute coordinates
|
||||
- G91 - Use relative coordinates
|
||||
- G92 - Set current position to coordinates given
|
||||
- G131 - set extruder offset position to 0 - needed for calibration with G132
|
||||
- G132 - calibrate endstop positions. Call this, after calling G131 and after centering the extruder holder.
|
||||
- G133 - measure steps until max endstops for deltas. Can be used to detect lost steps within tolerances of endstops.
|
||||
- G134 Px Sx Zx - Calibrate nozzle height difference (need z probe in nozzle!) Px = reference extruder, Sx = only measure extrude x against reference, Zx = add to measured z distance for Sx for correction.
|
||||
- G201 P<motorId> X<pos> - Go to position X with motor X
|
||||
- G202 P<motorId> X<setpos> - Mark current position as X
|
||||
- G203 P<motorId> - Report current motor position
|
||||
- G204 P<motorId> S<0/1> - Enable/disable motor
|
||||
- G205 P<motorId> S<0/1> E<0/1> - Home motor, S1 = go back to stored position, E1 = home only if endstop was never met, meaning it was never homed with motor.
|
||||
|
||||
RepRap M Codes
|
||||
|
||||
- M104 - Set extruder target temp
|
||||
- M105 - Read current temp
|
||||
- M106 S<speed> P<fan> I<ignore> - Fan on speed = 0..255, P = 0 or 1, 0 is default and can be omitted, I1 = Ignore M106/M107 from now on, I0 = disable ignore
|
||||
- M107 P<fan> - Fan off, P = 0 or 1, 0 is default and can be omitted
|
||||
- M109 - Wait for extruder current temp to reach target temp. Same params as M104
|
||||
- M114 S1 - Display current position, S1 = also write position in steps
|
||||
|
||||
Custom M Codes
|
||||
|
||||
- M3 Sx - Spindle on, Clockwise or Laser on during G1 moves. Sx = laser intensity 0-255 if driver supports this (default ignores it)
|
||||
- M4 - Spindle on, Counterclockwise.
|
||||
- M5 - Spindle off, Laser off.
|
||||
- M20 - List SD card
|
||||
- M21 - Initialize SD card
|
||||
- M22 - Release SD card
|
||||
- M23 - Select SD file (M23 filename.g)
|
||||
- M24 - Start/resume SD print
|
||||
- M25 - Pause SD print
|
||||
- M26 - Set SD position in bytes (M26 S12345)
|
||||
- M27 - Report SD print status
|
||||
- M28 - Start SD write (M28 filename.g)
|
||||
- M29 - Stop SD write
|
||||
- M30 <filename> - Delete file on sd card
|
||||
- M32 <dirname> create subdirectory
|
||||
- M42 P<pin number> S<value 0..255> - Change output of pin P to S. Does not work on most important pins.
|
||||
- M80 - Turn on power supply
|
||||
- M81 - Turn off power supply
|
||||
- M82 - Set E codes absolute (default)
|
||||
- M83 - Set E codes relative while in Absolute Coordinates (G90) mode
|
||||
- M84 - Disable steppers until next move,
|
||||
or use S<seconds> to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout.
|
||||
- M85 - Set inactivity shutdown timer with parameter S<seconds>. To disable set zero (default)
|
||||
- M92 - Set axisStepsPerMM - same syntax as G92
|
||||
- M99 S<delayInSec> X0 Y0 Z0 - Disable motors for S seconds (default 10) for given axis.
|
||||
- M104 S<temp> T<extruder> P1 F1 H1 O<offset>- Set temperature without wait. P1 = wait for moves to finish, F1 = beep when temp. reached first time
|
||||
O add offset to temperature in S, H1 use preheat temperature instead of S value.
|
||||
- M105 X0 - Get temperatures. If X0 is added, the raw analog values are also written.
|
||||
- M111 S<debugflags> - Set debugging option. Add values for wanted options:
|
||||
1 = echo commands, 2 = info, 4 = errors, 8 = dry run mode, 16 = only communication, no actions
|
||||
- M112 - Emergency kill
|
||||
- M115- Capabilities string
|
||||
- M116 - Wait for all temperatures in a +/- 1 degree range
|
||||
- M117 <message> - Write message in status row on lcd
|
||||
- M119 - Report endstop status
|
||||
- M140 S<temp> H1 O<offset> F1 - Set bed target temp, F1 makes a beep when temperature is reached the first time
|
||||
- M155 S<1/0> Enable/disable auto report temperatures. When enabled firmware will emit temperatures every second.
|
||||
- M163 S<extruderNum> P<weight> - Set weight for this mixing extruder drive
|
||||
- M164 S<virtNum> P<0 = dont store eeprom,1 = store to eeprom> - Store weights as virtual extruder S
|
||||
- M170 B<bedtemp> T<extruderid> S<extrudertemp> L0 - Set preset temperatures for extruder (T+S) or bed (B) or list settings (L0)
|
||||
- M190 - Wait for bed current temp to reach target temp. Same params as M109
|
||||
- M200 T<extruder> D<diameter> - Use volumetric extrusion. Set D0 or omit D to disable volumetric extr. Omit T for current extruder.
|
||||
- M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000)
|
||||
- M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000)
|
||||
- M203 - Set temperature monitor to Sx
|
||||
- M204 - Set PID parameter X => Kp Y => Ki Z => Kd S<extruder> Default is current extruder. NUM_EXTRUDER=Heated bed
|
||||
- M205 - Output EEPROM settings
|
||||
- M206 - Set EEPROM value
|
||||
- M207 X<XY jerk> Z<Z Jerk> E<ExtruderJerk> - Changes current jerk values, but do not store them in eeprom.
|
||||
- M209 S<0/1> - Enable/disable auto retraction
|
||||
- M218 T<extruderId> X<offset> Y<offset> Z<offset> S<0/1> - Set extruder offset. S1 = Save to eeprom.
|
||||
- M220 S<Feedrate multiplier in percent> - Increase/decrease given feedrate
|
||||
- M221 S<Extrusion flow multiplier in percent> - Increase/decrease given flow rate
|
||||
- M226 P<pin> S<state 0/1> - Wait for pin getting state S. Add X0 to init as input without pull-up and X1 for input with pull-up.
|
||||
- M231 S<OPS_MODE> X<Min_Distance> Y<Retract> Z<Backlash> F<ReatrctMove> - Set OPS parameter
|
||||
- M232 - Read and reset max. advance values
|
||||
- M233 X<AdvanceK> Y<AdvanceL> - Set temporary advance K-value to X and linear term advanceL to Y
|
||||
- M251 Measure Z steps from homing stop (Delta printers). S0 - Reset, S1 - Print, S2 - Store to Z length (also EEPROM if enabled)
|
||||
- M280 S<mode> - Set ditto printing mode. mode: 0 = off, 1 = 1 extra extruder, 2 = 2 extra extruder, 3 = 3 extra extruders
|
||||
- M281 Test if watchdog is running and working. Use M281 X0 to disable watchdog on AVR boards. Sometimes needed for boards with old bootloaders to allow reflashing.
|
||||
- M290 Z<babysteps> - Correct by adding baby steps for Z mm
|
||||
- M300 S<Frequency> P<DurationMillis> play frequency
|
||||
- M302 S<0 or 1> - allow cold extrusion. Without S parameter it will allow. S1 will allow, S0 will disallow.
|
||||
- M303 P<extruder/bed> S<printTemerature> X0 R<Repetitions> C<method>- Auto detect pid values. Use P<NUM_EXTRUDER> for heated bed. X0 saves result in EEPROM. R is number of cycles.
|
||||
method 0 = classic, 1 = some overshoot, 2 = no overshoot, 3 = pessen, 4 = Tyreus-Lyben
|
||||
- M320 S<0/1> - Activate auto level, S1 stores it in eeprom
|
||||
- M321 S<0/1> - Deactivate auto level, S1 stores it in eeprom
|
||||
- M322 - Reset auto level matrix
|
||||
- M323 S0/S1 enable disable distortion correction P0 = not permanent, P1 = permanent = default
|
||||
- M340 P<servoId> S<pulseInUS> R<autoOffIn ms>: servoID = 0..3, Servos are controlled by a pulse with normally between 500 and 2500 with 1500ms in center position. 0 turns servo off. R allows automatic disabling after a while.
|
||||
- M350 S<mstepsAll> X<mstepsX> Y<mstepsY> Z<mstepsZ> E<mstepsE0> P<mstespE1> : Set micro stepping on RAMBO board
|
||||
- M355 S<0/1> - Turn case light on/off, no S = report status
|
||||
- M360 - show configuration
|
||||
- M400 - Wait until move buffers empty.
|
||||
- M401 - Store x, y and z position.
|
||||
- M402 - Go to stored position. If X, Y or Z is specified, only these coordinates are used. F changes feedrate for that move.
|
||||
- M408 S<0-5> - Return status as json string (requires matching feature) for PanelDue
|
||||
- M450 - Reports printer mode
|
||||
- M451 - Set printer mode to FFF
|
||||
- M452 - Set printer mode to laser
|
||||
- M453 - Set printer mode to CNC
|
||||
- M460 X<minTemp> Y<maxTemp> : Set temperature range for thermistor controlled fan
|
||||
- M500 Store settings to EEPROM
|
||||
- M501 Load settings from EEPROM
|
||||
- M502 Reset settings to the one in configuration.h. Does not store values in EEPROM!
|
||||
- M513 - Clear all jam marker.
|
||||
- M530 S<printing> L<layer> - Enables explicit printing mode (S1) or disables it (S0). L can set layer count
|
||||
- M531 filename - Define filename being printed
|
||||
- M532 X<percent> L<curLayer> - update current print state progress (X=0..100) and layer L
|
||||
- M600 Change filament
|
||||
- M601 S<1/0> B<1/0> P<1/0> - Pause extruders. B1 also pauses heated bed. Paused extrudes disable heaters and motor. Continue (S0) reheats extruder to old temp. P0 does not wait for target temperature.
|
||||
- M602 S<1/0> P<1/0>- Debug jam control (S) Disable jam control (P). If enabled it will log signal changes and will not trigger jam errors!
|
||||
- M603 - Simulate a jam
|
||||
- M604 X<slowdownSteps> Y<errorSteps> Z<slowdownTo> T<extruderId> - Set jam detection values on a per extruder basis. If not set it uses defaults from Configuration.h
|
||||
- M666 - force communication error, required DEBUG_COM_ERRORS
|
||||
- M668 - set line number 0 without notice to simulate error
|
||||
- M670 S<version> - Set eeprom version to a value for testing eeprom upgrade path.
|
||||
- M908 P<address> S<value> : Set stepper current for digipot (RAMBO board)
|
||||
- M999 - Continue from fatal error. M999 S1 will create a fatal error for testing.
|
||||
- M914 X<sg_value> Y<sg_value> Z<sg_value> Stall detection sensitivity for Trinamic stepper drivers.
|
||||
- M915 X<0/1> Y<0/1> Z<0/1> Turn StealthChop mode ON or OFF on Trinamic stepper drivers.
|
||||
*/
|
||||
|
||||
#include "Repetier.h"
|
||||
#include <SPI.h>
|
||||
|
||||
#if UI_DISPLAY_TYPE == DISPLAY_ARDUINO_LIB
|
||||
//#include <LiquidCrystal.h> // Uncomment this if you are using liquid crystal library
|
||||
#endif
|
||||
|
||||
void setup()
|
||||
{
|
||||
Printer::setup();
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
Commands::commandLoop();
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
815
Repetier-Firmware 1.0.3/Repetier/SDCard.cpp
Normal file
815
Repetier-Firmware 1.0.3/Repetier/SDCard.cpp
Normal file
@ -0,0 +1,815 @@
|
||||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware 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.
|
||||
|
||||
Repetier-Firmware 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 Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
This firmware is a nearly complete rewrite of the sprinter firmware
|
||||
by kliment (https://github.com/kliment/Sprinter)
|
||||
which based on Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
|
||||
*/
|
||||
|
||||
#include "Repetier.h"
|
||||
|
||||
#if SDSUPPORT
|
||||
|
||||
char tempLongFilename[LONG_FILENAME_LENGTH + 1];
|
||||
char fullName[LONG_FILENAME_LENGTH * SD_MAX_FOLDER_DEPTH + SD_MAX_FOLDER_DEPTH + 1];
|
||||
#if NEW_COMMUNICATION
|
||||
SDCardGCodeSource sdSource;
|
||||
#endif
|
||||
SDCard sd;
|
||||
|
||||
SDCard::SDCard() {
|
||||
sdmode = 0;
|
||||
sdactive = false;
|
||||
savetosd = false;
|
||||
Printer::setAutomount(false);
|
||||
}
|
||||
|
||||
void SDCard::automount() {
|
||||
#if SDCARDDETECT > -1
|
||||
if(READ(SDCARDDETECT) != SDCARDDETECTINVERTED) {
|
||||
if(sdactive || sdmode == 100) { // Card removed
|
||||
Com::printFLN(PSTR("SD card removed"));
|
||||
#if UI_DISPLAY_TYPE != NO_DISPLAY
|
||||
uid.executeAction(UI_ACTION_TOP_MENU, true);
|
||||
#endif
|
||||
unmount();
|
||||
UI_STATUS_UPD_F(Com::translatedF(UI_TEXT_SD_REMOVED_ID));
|
||||
}
|
||||
} else {
|
||||
if(!sdactive && sdmode != 100) {
|
||||
UI_STATUS_UPD_F(Com::translatedF(UI_TEXT_SD_INSERTED_ID));
|
||||
mount();
|
||||
if(sdmode != 100) // send message only if we have success
|
||||
Com::printFLN(PSTR("SD card inserted")); // Not translatable or host will not understand signal
|
||||
#if UI_DISPLAY_TYPE != NO_DISPLAY
|
||||
if(sdactive && !uid.isWizardActive()) { // Wizards have priority
|
||||
Printer::setAutomount(true);
|
||||
uid.executeAction(UI_ACTION_SD_PRINT + UI_ACTION_TOPMENU, true);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void SDCard::initsd() {
|
||||
sdactive = false;
|
||||
#if SDSS > -1
|
||||
#if SDCARDDETECT > -1
|
||||
if(READ(SDCARDDETECT) != SDCARDDETECTINVERTED)
|
||||
return;
|
||||
#endif
|
||||
HAL::pingWatchdog();
|
||||
HAL::delayMilliseconds(50); // wait for stabilization of contacts, bootup ...
|
||||
#if defined(ENABLE_SOFTWARE_SPI_CLASS) && ENABLE_SOFTWARE_SPI_CLASS
|
||||
fat.begin(SDSS);
|
||||
#else
|
||||
fat.begin(SDSS, SD_SCK_MHZ(4)); // dummy init of SD_CARD
|
||||
#endif
|
||||
HAL::delayMilliseconds(50); // wait for init end
|
||||
HAL::pingWatchdog();
|
||||
/*if(dir[0].isOpen())
|
||||
dir[0].close();*/
|
||||
if (!fat.begin(SDSS, SD_SCK_MHZ(4))) {
|
||||
Com::printFLN(Com::tSDInitFail);
|
||||
sdmode = 100; // prevent automount loop!
|
||||
if (fat.card()->errorCode()) {
|
||||
Com::printFLN(PSTR(
|
||||
"\nSD initialization failed.\n"
|
||||
"Do not reformat the card!\n"
|
||||
"Is the card correctly inserted?\n"
|
||||
"Is chipSelect set to the correct value?\n"
|
||||
"Does another SPI device need to be disabled?\n"
|
||||
"Is there a wiring/soldering problem?"));
|
||||
Com::printFLN(PSTR("errorCode: "), int(fat.card()->errorCode()));
|
||||
return;
|
||||
}
|
||||
if (fat.vol()->fatType() == 0) {
|
||||
Com::printFLN(PSTR("Can't find a valid FAT16/FAT32 partition.\n"));
|
||||
return;
|
||||
}
|
||||
if (!fat.vwd()->isOpen()) {
|
||||
Com::printFLN(PSTR("Can't open root directory.\n"));
|
||||
return;
|
||||
}
|
||||
return;
|
||||
}
|
||||
Com::printFLN(PSTR("Card successfully initialized."));
|
||||
sdactive = true;
|
||||
Printer::setMenuMode(MENU_MODE_SD_MOUNTED, true);
|
||||
HAL::pingWatchdog();
|
||||
|
||||
fat.chdir();
|
||||
|
||||
#if defined(EEPROM_AVAILABLE) && EEPROM_AVAILABLE == EEPROM_SDCARD
|
||||
HAL::importEEPROM();
|
||||
#endif
|
||||
if(selectFile("init.g", true)) {
|
||||
startPrint();
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void SDCard::mount() {
|
||||
sdmode = 0;
|
||||
initsd();
|
||||
}
|
||||
|
||||
void SDCard::unmount() {
|
||||
sdmode = 0;
|
||||
sdactive = false;
|
||||
savetosd = false;
|
||||
Printer::setAutomount(false);
|
||||
Printer::setMenuMode(MENU_MODE_SD_MOUNTED + MENU_MODE_PAUSED + MENU_MODE_SD_PRINTING, false);
|
||||
#if UI_DISPLAY_TYPE != NO_DISPLAY && SDSUPPORT
|
||||
uid.cwd[0] = '/';
|
||||
uid.cwd[1] = 0;
|
||||
uid.folderLevel = 0;
|
||||
#endif
|
||||
Com::printFLN(PSTR("SD Card unmounted"));
|
||||
}
|
||||
|
||||
void SDCard::startPrint() {
|
||||
if(!sdactive) return;
|
||||
sdmode = 1;
|
||||
Printer::setMenuMode(MENU_MODE_SD_PRINTING, true);
|
||||
Printer::setMenuMode(MENU_MODE_PAUSED, false);
|
||||
Printer::setPrinting(true);
|
||||
Printer::maxLayer = 0;
|
||||
Printer::currentLayer = 0;
|
||||
UI_STATUS_F(PSTR(""));
|
||||
#if NEW_COMMUNICATION
|
||||
GCodeSource::registerSource(&sdSource);
|
||||
#endif
|
||||
}
|
||||
|
||||
void SDCard::pausePrint(bool intern) {
|
||||
if(!sdactive) return;
|
||||
sdmode = 2; // finish running line
|
||||
Printer::setMenuMode(MENU_MODE_PAUSED, true);
|
||||
#if !defined(DISABLE_PRINTMODE_ON_PAUSE) || DISABLE_PRINTMODE_ON_PAUSE==1
|
||||
Printer::setPrinting(false);
|
||||
#endif
|
||||
#if NEW_COMMUNICATION
|
||||
GCodeSource::removeSource(&sdSource);
|
||||
#endif
|
||||
if(EVENT_SD_PAUSE_START(intern)) {
|
||||
if(intern) {
|
||||
Commands::waitUntilEndOfAllBuffers();
|
||||
//sdmode = 0; // why ?
|
||||
Printer::MemoryPosition();
|
||||
Printer::moveToReal(IGNORE_COORDINATE, IGNORE_COORDINATE, IGNORE_COORDINATE,
|
||||
Printer::memoryE - RETRACT_ON_PAUSE,
|
||||
Printer::maxFeedrate[E_AXIS] / 2);
|
||||
Printer::moveToParkPosition();
|
||||
Printer::lastCmdPos[X_AXIS] = Printer::currentPosition[X_AXIS];
|
||||
Printer::lastCmdPos[Y_AXIS] = Printer::currentPosition[Y_AXIS];
|
||||
Printer::lastCmdPos[Z_AXIS] = Printer::currentPosition[Z_AXIS];
|
||||
GCode::executeFString(PSTR(PAUSE_START_COMMANDS));
|
||||
}
|
||||
}
|
||||
EVENT_SD_PAUSE_END(intern);
|
||||
}
|
||||
|
||||
void SDCard::continuePrint(bool intern) {
|
||||
if(!sd.sdactive) return;
|
||||
if(EVENT_SD_CONTINUE_START(intern)) {
|
||||
if(intern) {
|
||||
GCode::executeFString(PSTR(PAUSE_END_COMMANDS));
|
||||
Printer::GoToMemoryPosition(true, true, false, false, Printer::maxFeedrate[X_AXIS]);
|
||||
Printer::GoToMemoryPosition(false, false, true, false, Printer::maxFeedrate[Z_AXIS] / 2.0f);
|
||||
Printer::GoToMemoryPosition(false, false, false, true, Printer::maxFeedrate[E_AXIS] / 2.0f);
|
||||
}
|
||||
}
|
||||
EVENT_SD_CONTINUE_END(intern);
|
||||
#if NEW_COMMUNICATION
|
||||
GCodeSource::registerSource(&sdSource);
|
||||
#endif
|
||||
Printer::setPrinting(true);
|
||||
Printer::setMenuMode(MENU_MODE_PAUSED, false);
|
||||
sdmode = 1;
|
||||
}
|
||||
|
||||
void SDCard::stopPrint() {
|
||||
if(!sd.sdactive) return;
|
||||
if(sdmode)
|
||||
Com::printFLN(PSTR("SD print stopped by user."));
|
||||
sdmode = 0;
|
||||
Printer::setMenuMode(MENU_MODE_SD_PRINTING, false);
|
||||
Printer::setMenuMode(MENU_MODE_PAUSED, false);
|
||||
Printer::setPrinting(0);
|
||||
#if NEW_COMMUNICATION
|
||||
GCodeSource::removeSource(&sdSource);
|
||||
#endif
|
||||
if(EVENT_SD_STOP_START) {
|
||||
GCode::executeFString(PSTR(SD_RUN_ON_STOP));
|
||||
if(SD_STOP_HEATER_AND_MOTORS_ON_STOP) {
|
||||
Commands::waitUntilEndOfAllMoves();
|
||||
Printer::kill(false);
|
||||
}
|
||||
}
|
||||
EVENT_SD_STOP_END;
|
||||
}
|
||||
|
||||
void SDCard::writeCommand(GCode *code) {
|
||||
unsigned int sum1 = 0, sum2 = 0; // for fletcher-16 checksum
|
||||
uint8_t buf[100];
|
||||
uint8_t p = 2;
|
||||
file.clearWriteError();
|
||||
uint16_t params = 128 | (code->params & ~1);
|
||||
memcopy2(buf, ¶ms);
|
||||
//*(int*)buf = params;
|
||||
if(code->isV2()) { // Read G,M as 16 bit value
|
||||
memcopy2(&buf[p], &code->params2);
|
||||
//*(int*)&buf[p] = code->params2;
|
||||
p += 2;
|
||||
if(code->hasString())
|
||||
buf[p++] = strlen(code->text);
|
||||
if(code->hasM()) {
|
||||
memcopy2(&buf[p], &code->M);
|
||||
//*(int*)&buf[p] = code->M;
|
||||
p += 2;
|
||||
}
|
||||
if(code->hasG()) {
|
||||
memcopy2(&buf[p], &code->G);
|
||||
//*(int*)&buf[p]= code->G;
|
||||
p += 2;
|
||||
}
|
||||
} else {
|
||||
if(code->hasM()) {
|
||||
buf[p++] = (uint8_t)code->M;
|
||||
}
|
||||
if(code->hasG()) {
|
||||
buf[p++] = (uint8_t)code->G;
|
||||
}
|
||||
}
|
||||
if(code->hasX()) {
|
||||
memcopy4(&buf[p], &code->X);
|
||||
//*(float*)&buf[p] = code->X;
|
||||
p += 4;
|
||||
}
|
||||
if(code->hasY()) {
|
||||
memcopy4(&buf[p], &code->Y);
|
||||
//*(float*)&buf[p] = code->Y;
|
||||
p += 4;
|
||||
}
|
||||
if(code->hasZ()) {
|
||||
memcopy4(&buf[p], &code->Z);
|
||||
//*(float*)&buf[p] = code->Z;
|
||||
p += 4;
|
||||
}
|
||||
if(code->hasE()) {
|
||||
memcopy4(&buf[p], &code->E);
|
||||
//*(float*)&buf[p] = code->E;
|
||||
p += 4;
|
||||
}
|
||||
if(code->hasF()) {
|
||||
memcopy4(&buf[p], &code->F);
|
||||
//*(float*)&buf[p] = code->F;
|
||||
p += 4;
|
||||
}
|
||||
if(code->hasT()) {
|
||||
buf[p++] = code->T;
|
||||
}
|
||||
if(code->hasS()) {
|
||||
memcopy4(&buf[p], &code->S);
|
||||
//*(int32_t*)&buf[p] = code->S;
|
||||
p += 4;
|
||||
}
|
||||
if(code->hasP()) {
|
||||
memcopy4(&buf[p], &code->P);
|
||||
//*(int32_t*)&buf[p] = code->P;
|
||||
p += 4;
|
||||
}
|
||||
if(code->hasI()) {
|
||||
memcopy4(&buf[p], &code->I);
|
||||
//*(float*)&buf[p] = code->I;
|
||||
p += 4;
|
||||
}
|
||||
if(code->hasJ()) {
|
||||
memcopy4(&buf[p], &code->J);
|
||||
//*(float*)&buf[p] = code->J;
|
||||
p += 4;
|
||||
}
|
||||
if(code->hasR()) {
|
||||
memcopy4(&buf[p], &code->R);
|
||||
//*(float*)&buf[p] = code->R;
|
||||
p += 4;
|
||||
}
|
||||
if(code->hasD()) {
|
||||
memcopy4(&buf[p], &code->D);
|
||||
//*(float*)&buf[p] = code->D;
|
||||
p += 4;
|
||||
}
|
||||
if(code->hasC()) {
|
||||
memcopy4(&buf[p], &code->C);
|
||||
//*(float*)&buf[p] = code->C;
|
||||
p += 4;
|
||||
}
|
||||
if(code->hasH()) {
|
||||
memcopy4(&buf[p], &code->H);
|
||||
//*(float*)&buf[p] = code->H;
|
||||
p += 4;
|
||||
}
|
||||
if(code->hasA()) {
|
||||
memcopy4(&buf[p], &code->A);
|
||||
//*(float*)&buf[p] = code->A;
|
||||
p += 4;
|
||||
}
|
||||
if(code->hasB()) {
|
||||
memcopy4(&buf[p], &code->B);
|
||||
//*(float*)&buf[p] = code->B;
|
||||
p += 4;
|
||||
}
|
||||
if(code->hasK()) {
|
||||
memcopy4(&buf[p], &code->K);
|
||||
//*(float*)&buf[p] = code->K;
|
||||
p += 4;
|
||||
}
|
||||
if(code->hasL()) {
|
||||
memcopy4(&buf[p], &code->L);
|
||||
//*(float*)&buf[p] = code->L;
|
||||
p += 4;
|
||||
}
|
||||
if(code->hasO()) {
|
||||
memcopy4(&buf[p], &code->O);
|
||||
//*(float*)&buf[p] = code->O;
|
||||
p += 4;
|
||||
}
|
||||
if(code->hasString()) { // read 16 uint8_t into string
|
||||
char *sp = code->text;
|
||||
if(code->isV2()) {
|
||||
uint8_t i = strlen(code->text);
|
||||
for(; i; i--) buf[p++] = *sp++;
|
||||
} else {
|
||||
for(uint8_t i = 0; i < 16; ++i) buf[p++] = *sp++;
|
||||
}
|
||||
}
|
||||
uint8_t *ptr = buf;
|
||||
uint8_t len = p;
|
||||
while (len) {
|
||||
uint8_t tlen = len > 21 ? 21 : len;
|
||||
len -= tlen;
|
||||
do {
|
||||
sum1 += *ptr++;
|
||||
if(sum1 >= 255) sum1 -= 255;
|
||||
sum2 += sum1;
|
||||
if(sum2 >= 255) sum2 -= 255;
|
||||
} while (--tlen);
|
||||
}
|
||||
buf[p++] = sum1;
|
||||
buf[p++] = sum2;
|
||||
// Debug
|
||||
/*Com::printF(PSTR("Buf: "));
|
||||
for(int i=0;i<p;i++)
|
||||
Com::printF(PSTR(" "),(int)buf[i]);
|
||||
Com::println();*/
|
||||
if(params == 128) {
|
||||
Com::printErrorFLN(Com::tAPIDFinished);
|
||||
} else
|
||||
file.write(buf, p);
|
||||
if (file.getWriteError()) {
|
||||
Com::printFLN(Com::tErrorWritingToFile);
|
||||
}
|
||||
}
|
||||
|
||||
char *SDCard::createFilename(char *buffer, const dir_t &p) {
|
||||
char *pos = buffer, *src = (char*)p.name;
|
||||
for (uint8_t i = 0; i < 11; i++, src++) {
|
||||
if (*src == ' ') continue;
|
||||
if (i == 8)
|
||||
*pos++ = '.';
|
||||
*pos++ = *src;
|
||||
}
|
||||
*pos = 0;
|
||||
return pos;
|
||||
}
|
||||
|
||||
bool SDCard::showFilename(const uint8_t *name) {
|
||||
if (*name == DIR_NAME_DELETED || *name == '.') return false;
|
||||
return true;
|
||||
}
|
||||
|
||||
int8_t RFstricmp(const char* s1, const char* s2) {
|
||||
while(*s1 && (tolower(*s1) == tolower(*s2)))
|
||||
s1++, s2++;
|
||||
return (const uint8_t)tolower(*s1) - (const uint8_t)tolower(*s2);
|
||||
}
|
||||
|
||||
int8_t RFstrnicmp(const char* s1, const char* s2, size_t n) {
|
||||
while(n--) {
|
||||
if(tolower(*s1) != tolower(*s2))
|
||||
return (uint8_t)tolower(*s1) - (uint8_t)tolower(*s2);
|
||||
s1++;
|
||||
s2++;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
void SDCard::ls() {
|
||||
SdBaseFile file;
|
||||
|
||||
Com::printFLN(Com::tBeginFileList);
|
||||
fat.chdir();
|
||||
|
||||
file.openRoot(fat.vol());
|
||||
file.ls(0, 0);
|
||||
Com::printFLN(Com::tEndFileList);
|
||||
}
|
||||
|
||||
#if JSON_OUTPUT
|
||||
void SDCard::lsJSON(const char *filename) {
|
||||
SdBaseFile dir;
|
||||
fat.chdir();
|
||||
if (*filename == 0) {
|
||||
dir.openRoot(fat.vol());
|
||||
} else {
|
||||
if (!dir.open(fat.vwd(), filename, O_READ) || !dir.isDir()) {
|
||||
Com::printF(Com::tJSONErrorStart);
|
||||
Com::printF(Com::tFileOpenFailed);
|
||||
Com::printFLN(Com::tJSONErrorEnd);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
Com::printF(Com::tJSONDir);
|
||||
SDCard::printEscapeChars(filename);
|
||||
Com::printF(Com::tJSONFiles);
|
||||
dir.lsJSON();
|
||||
Com::printFLN(Com::tJSONArrayEnd);
|
||||
}
|
||||
|
||||
void SDCard::printEscapeChars(const char *s) {
|
||||
for (unsigned int i = 0; i < strlen(s); ++i) {
|
||||
switch (s[i]) {
|
||||
case '"':
|
||||
case '/':
|
||||
case '\b':
|
||||
case '\f':
|
||||
case '\n':
|
||||
case '\r':
|
||||
case '\t':
|
||||
case '\\':
|
||||
Com::print('\\');
|
||||
break;
|
||||
}
|
||||
Com::print(s[i]);
|
||||
}
|
||||
}
|
||||
|
||||
void SDCard::JSONFileInfo(const char* filename) {
|
||||
SdFile targetFile;
|
||||
GCodeFileInfo *info, tmpInfo;
|
||||
if (strlen(filename) == 0) {
|
||||
targetFile = file;
|
||||
info = &fileInfo;
|
||||
} else {
|
||||
if (!targetFile.open(fat.vwd(), filename, O_READ) || targetFile.isDir()) {
|
||||
Com::printF(Com::tJSONErrorStart);
|
||||
Com::printF(Com::tFileOpenFailed);
|
||||
Com::printFLN(Com::tJSONErrorEnd);
|
||||
return;
|
||||
}
|
||||
info = &tmpInfo;
|
||||
info->init(targetFile);
|
||||
}
|
||||
if (!targetFile.isOpen()) {
|
||||
Com::printF(Com::tJSONErrorStart);
|
||||
Com::printF(Com::tNotSDPrinting);
|
||||
Com::printFLN(Com::tJSONErrorEnd);
|
||||
return;
|
||||
}
|
||||
|
||||
// {"err":0,"size":457574,"height":4.00,"layerHeight":0.25,"filament":[6556.3],"generatedBy":"Slic3r 1.1.7 on 2014-11-09 at 17:11:32"}
|
||||
Com::printF(Com::tJSONFileInfoStart);
|
||||
Com::print(info->fileSize);
|
||||
Com::printF(Com::tJSONFileInfoHeight);
|
||||
Com::print(info->objectHeight);
|
||||
Com::printF(Com::tJSONFileInfoLayerHeight);
|
||||
Com::print(info->layerHeight);
|
||||
Com::printF(Com::tJSONFileInfoFilament);
|
||||
Com::print(info->filamentNeeded);
|
||||
Com::printF(Com::tJSONFileInfoGeneratedBy);
|
||||
Com::print(info->generatedBy);
|
||||
Com::print('"');
|
||||
if (strlen(filename) == 0) {
|
||||
Com::printF(Com::tJSONFileInfoName);
|
||||
file.printName();
|
||||
Com::print('"');
|
||||
}
|
||||
Com::print('}');
|
||||
Com::println();
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
bool SDCard::selectFile(const char* filename, bool silent) {
|
||||
const char* oldP = filename;
|
||||
|
||||
if (!sdactive)
|
||||
return false;
|
||||
sdmode = 0;
|
||||
|
||||
file.close();
|
||||
// Filename for progress view
|
||||
strncpy(Printer::printName, filename, 20);
|
||||
Printer::printName[20] = 0;
|
||||
if (file.open(fat.vwd(), filename, O_READ)) {
|
||||
if ((oldP = strrchr(filename, '/')) != NULL)
|
||||
oldP++;
|
||||
else
|
||||
oldP = filename;
|
||||
|
||||
if (!silent) {
|
||||
Com::printF(Com::tFileOpened, oldP);
|
||||
Com::printFLN(Com::tSpaceSizeColon, file.fileSize());
|
||||
}
|
||||
#if JSON_OUTPUT
|
||||
fileInfo.init(file);
|
||||
#endif
|
||||
sdpos = 0;
|
||||
filesize = file.fileSize();
|
||||
Com::printFLN(Com::tFileSelected);
|
||||
return true;
|
||||
} else {
|
||||
if (!silent)
|
||||
Com::printFLN(Com::tFileOpenFailed);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
void SDCard::printStatus() {
|
||||
if(sdactive) {
|
||||
Com::printF(Com::tSDPrintingByte, sdpos);
|
||||
Com::printFLN(Com::tSlash, filesize);
|
||||
} else {
|
||||
Com::printFLN(Com::tNotSDPrinting);
|
||||
}
|
||||
}
|
||||
|
||||
void SDCard::startWrite(char *filename) {
|
||||
if(!sdactive) return;
|
||||
file.close();
|
||||
sdmode = 0;
|
||||
fat.chdir();
|
||||
if(!file.open(filename, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) {
|
||||
Com::printFLN(Com::tOpenFailedFile, filename);
|
||||
} else {
|
||||
UI_STATUS_F(Com::translatedF(UI_TEXT_UPLOADING_ID));
|
||||
savetosd = true;
|
||||
Com::printFLN(Com::tWritingToFile, filename);
|
||||
}
|
||||
}
|
||||
|
||||
void SDCard::finishWrite() {
|
||||
if(!savetosd) return; // already closed or never opened
|
||||
file.sync();
|
||||
file.close();
|
||||
savetosd = false;
|
||||
Com::printFLN(Com::tDoneSavingFile);
|
||||
UI_CLEAR_STATUS;
|
||||
}
|
||||
|
||||
void SDCard::deleteFile(char *filename) {
|
||||
if(!sdactive) return;
|
||||
sdmode = 0;
|
||||
file.close();
|
||||
if(fat.remove(filename)) {
|
||||
Com::printFLN(Com::tFileDeleted);
|
||||
} else {
|
||||
if(fat.rmdir(filename))
|
||||
Com::printFLN(Com::tFileDeleted);
|
||||
else
|
||||
Com::printFLN(Com::tDeletionFailed);
|
||||
}
|
||||
}
|
||||
|
||||
void SDCard::makeDirectory(char *filename) {
|
||||
if(!sdactive) return;
|
||||
sdmode = 0;
|
||||
file.close();
|
||||
if(fat.mkdir(filename)) {
|
||||
Com::printFLN(Com::tDirectoryCreated);
|
||||
} else {
|
||||
Com::printFLN(Com::tCreationFailed);
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef GLENN_DEBUG
|
||||
void SDCard::writeToFile() {
|
||||
size_t nbyte;
|
||||
char szName[10];
|
||||
|
||||
strcpy(szName, "Testing\r\n");
|
||||
nbyte = file.write(szName, strlen(szName));
|
||||
Com::print("L=");
|
||||
Com::print((long)nbyte);
|
||||
Com::println();
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#if JSON_OUTPUT
|
||||
|
||||
// --------------------------------------------------------------- //
|
||||
// Code that gets gcode information is adapted from RepRapFirmware //
|
||||
// Originally licensed under GPL //
|
||||
// Authors: reprappro, dc42, dcnewman, others //
|
||||
// Source: https://github.com/dcnewman/RepRapFirmware //
|
||||
// Copy date: 15 Nov 2015 //
|
||||
// --------------------------------------------------------------- //
|
||||
|
||||
void GCodeFileInfo::init(SdFile &file) {
|
||||
this->fileSize = file.fileSize();
|
||||
this->filamentNeeded = 0.0;
|
||||
this->objectHeight = 0.0;
|
||||
this->layerHeight = 0.0;
|
||||
if (!file.isOpen()) return;
|
||||
bool genByFound = false, layerHeightFound = false, filamentNeedFound = false;
|
||||
#if CPU_ARCH==ARCH_AVR
|
||||
#define GCI_BUF_SIZE 120
|
||||
#else
|
||||
#define GCI_BUF_SIZE 1024
|
||||
#endif
|
||||
// READ 4KB FROM THE BEGINNING
|
||||
char buf[GCI_BUF_SIZE];
|
||||
for (int i = 0; i < 4096; i += GCI_BUF_SIZE - 50) {
|
||||
if(!file.seekSet(i)) break;
|
||||
file.read(buf, GCI_BUF_SIZE);
|
||||
if (!genByFound && findGeneratedBy(buf, this->generatedBy)) genByFound = true;
|
||||
if (!layerHeightFound && findLayerHeight(buf, this->layerHeight)) layerHeightFound = true;
|
||||
if (!filamentNeedFound && findFilamentNeed(buf, this->filamentNeeded)) filamentNeedFound = true;
|
||||
if(genByFound && layerHeightFound && filamentNeedFound) goto get_objectHeight;
|
||||
}
|
||||
|
||||
// READ 4KB FROM END
|
||||
for (int i = 0; i < 4096; i += GCI_BUF_SIZE - 50) {
|
||||
if(!file.seekEnd(-4096 + i)) break;
|
||||
file.read(buf, GCI_BUF_SIZE);
|
||||
if (!genByFound && findGeneratedBy(buf, this->generatedBy)) genByFound = true;
|
||||
if (!layerHeightFound && findLayerHeight(buf, this->layerHeight)) layerHeightFound = true;
|
||||
if (!filamentNeedFound && findFilamentNeed(buf, this->filamentNeeded)) filamentNeedFound = true;
|
||||
if(genByFound && layerHeightFound && filamentNeedFound) goto get_objectHeight;
|
||||
}
|
||||
|
||||
get_objectHeight:
|
||||
// MOVE FROM END UP IN 1KB BLOCKS UP TO 30KB
|
||||
for (int i = GCI_BUF_SIZE; i < 30000; i += GCI_BUF_SIZE - 50) {
|
||||
if(!file.seekEnd(-i)) break;
|
||||
file.read(buf, GCI_BUF_SIZE);
|
||||
if (findTotalHeight(buf, this->objectHeight)) break;
|
||||
}
|
||||
file.seekSet(0);
|
||||
}
|
||||
|
||||
bool GCodeFileInfo::findGeneratedBy(char *buf, char *genBy) {
|
||||
// Slic3r & S3D
|
||||
const char* generatedByString = PSTR("generated by ");
|
||||
char* pos = strstr_P(buf, generatedByString);
|
||||
if (pos) {
|
||||
pos += strlen_P(generatedByString);
|
||||
size_t i = 0;
|
||||
while (i < GENBY_SIZE - 1 && *pos >= ' ') {
|
||||
char c = *pos++;
|
||||
if (c == '"' || c == '\\') {
|
||||
// Need to escape the quote-mark for JSON
|
||||
if (i > GENBY_SIZE - 3) break;
|
||||
genBy[i++] = '\\';
|
||||
}
|
||||
genBy[i++] = c;
|
||||
}
|
||||
genBy[i] = 0;
|
||||
return true;
|
||||
}
|
||||
|
||||
// CURA
|
||||
const char* slicedAtString = PSTR(";Sliced at: ");
|
||||
pos = strstr_P(buf, slicedAtString);
|
||||
if (pos) {
|
||||
strcpy_P(genBy, PSTR("Cura"));
|
||||
return true;
|
||||
}
|
||||
|
||||
// UNKNOWN
|
||||
strcpy_P(genBy, PSTR("Unknown"));
|
||||
return false;
|
||||
}
|
||||
|
||||
bool GCodeFileInfo::findLayerHeight(char *buf, float &layerHeight) {
|
||||
// SLIC3R
|
||||
layerHeight = 0;
|
||||
const char* layerHeightSlic3r = PSTR("; layer_height ");
|
||||
char *pos = strstr_P(buf, layerHeightSlic3r);
|
||||
if (pos) {
|
||||
pos += strlen_P(layerHeightSlic3r);
|
||||
while (*pos == ' ' || *pos == 't' || *pos == '=' || *pos == ':') {
|
||||
++pos;
|
||||
}
|
||||
layerHeight = strtod(pos, NULL);
|
||||
return true;
|
||||
}
|
||||
|
||||
// CURA
|
||||
const char* layerHeightCura = PSTR("Layer height: ");
|
||||
pos = strstr_P(buf, layerHeightCura);
|
||||
if (pos) {
|
||||
pos += strlen_P(layerHeightCura);
|
||||
while (*pos == ' ' || *pos == 't' || *pos == '=' || *pos == ':') {
|
||||
++pos;
|
||||
}
|
||||
layerHeight = strtod(pos, NULL);
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool GCodeFileInfo::findFilamentNeed(char *buf, float &filament) {
|
||||
const char* filamentUsedStr = PSTR("filament used");
|
||||
const char* pos = strstr_P(buf, filamentUsedStr);
|
||||
filament = 0;
|
||||
if (pos != NULL) {
|
||||
pos += strlen_P(filamentUsedStr);
|
||||
while (*pos == ' ' || *pos == 't' || *pos == '=' || *pos == ':') {
|
||||
++pos; // this allows for " = " from default slic3r comment and ": " from default Cura comment
|
||||
}
|
||||
if (isDigit(*pos)) {
|
||||
char *q;
|
||||
filament += strtod(pos, &q);
|
||||
if (*q == 'm' && *(q + 1) != 'm') {
|
||||
filament *= 1000.0; // Cura outputs filament used in metres not mm
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool GCodeFileInfo::findTotalHeight(char *buf, float &height) {
|
||||
int len = 1024;
|
||||
bool inComment, inRelativeMode = false;
|
||||
unsigned int zPos;
|
||||
for (int i = len - 5; i > 0; i--) {
|
||||
if (inRelativeMode) {
|
||||
inRelativeMode = !(buf[i] == 'G' && buf[i + 1] == '9' && buf[i + 2] == '1' && buf[i + 3] <= ' ');
|
||||
} else if (buf[i] == 'G') {
|
||||
// Ignore G0/G1 codes if absolute mode was switched back using G90 (typical for Cura files)
|
||||
if (buf[i + 1] == '9' && buf[i + 2] == '0' && buf[i + 3] <= ' ') {
|
||||
inRelativeMode = true;
|
||||
} else if ((buf[i + 1] == '0' || buf[i + 1] == '1') && buf[i + 2] == ' ') {
|
||||
// Look for last "G0/G1 ... Z#HEIGHT#" command as generated by common slicers
|
||||
// Looks like we found a controlled move, however it could be in a comment, especially when using slic3r 1.1.1
|
||||
inComment = false;
|
||||
size_t j = i;
|
||||
while (j != 0) {
|
||||
--j;
|
||||
char c = buf[j];
|
||||
if (c == '\n' || c == '\r') break;
|
||||
if (c == ';') {
|
||||
// It is in a comment, so give up on this one
|
||||
inComment = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (inComment) continue;
|
||||
|
||||
// Find 'Z' position and grab that value
|
||||
zPos = 0;
|
||||
for (int j = i + 3; j < len - 2; j++) {
|
||||
char c = buf[j];
|
||||
if (c < ' ') {
|
||||
// Skip all white spaces...
|
||||
while (j < len - 2 && c <= ' ') {
|
||||
c = buf[++j];
|
||||
}
|
||||
// ...to make sure ";End" doesn't follow G0 .. Z#HEIGHT#
|
||||
if (zPos != 0) {
|
||||
//debugPrintf("Found at offset %u text: %.100s\n", zPos, &buf[zPos + 1]);
|
||||
height = strtod(&buf[zPos + 1], NULL);
|
||||
return true;
|
||||
}
|
||||
break;
|
||||
} else if (c == ';') break;
|
||||
else if (c == 'Z') zPos = j;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
#endif // JSON_OUTPUT
|
167
Repetier-Firmware 1.0.3/Repetier/Trinamic.h
Normal file
167
Repetier-Firmware 1.0.3/Repetier/Trinamic.h
Normal file
@ -0,0 +1,167 @@
|
||||
#include <TMC2130Stepper.h>
|
||||
|
||||
#define TMC2130_ON_X (TMC2130_X_CS_PIN > 0)
|
||||
#define TMC2130_ON_Y (TMC2130_Y_CS_PIN > 0)
|
||||
#define TMC2130_ON_Z (TMC2130_Z_CS_PIN > 0)
|
||||
#define TMC2130_ON_EXT0 (TMC2130_EXT0_CS_PIN > 0)
|
||||
#define TMC2130_ON_EXT1 (TMC2130_EXT1_CS_PIN > 0)
|
||||
#define TMC2130_ON_EXT2 (TMC2130_EXT2_CS_PIN > 0)
|
||||
/*
|
||||
_TMC_COUNT determines the number of Trinamic chips to configure.
|
||||
It counts how many ChipSelect pins were configured by the user.
|
||||
*/
|
||||
#define _TMC_COUNT ( TMC2130_ON_X + \
|
||||
TMC2130_ON_Y + \
|
||||
TMC2130_ON_Z + \
|
||||
TMC2130_ON_EXT0 + \
|
||||
TMC2130_ON_EXT1 + \
|
||||
TMC2130_ON_EXT2 )
|
||||
#if _TMC_COUNT < 1
|
||||
#error "Trinamic TMC2130 support enabled but no CS pins defined."
|
||||
#endif
|
||||
|
||||
#if STEPPER_CURRENT_CONTROL == CURRENT_CONTROL_MANUAL
|
||||
#undef STEPPER_CURRENT_CONTROL
|
||||
#else
|
||||
#error "When using Trinamic drivers you can't enable another STEPPER_CURRENT_CONTROL method."
|
||||
#endif
|
||||
#define STEPPER_CURRENT_CONTROL CURRENT_CONTROL_TMC2130
|
||||
|
||||
#if !defined(MOTOR_CURRENT)
|
||||
#error "When using Trinamic drivers you have to define MOTOR_CURRENT parameter."
|
||||
#endif
|
||||
|
||||
/*
|
||||
If user did not define axis specific values we use the global ones.
|
||||
*/
|
||||
#if !defined(TMC2130_STEALTHCHOP_X) && TMC2130_ON_X
|
||||
#define TMC2130_STEALTHCHOP_X TMC2130_STEALTHCHOP
|
||||
#endif
|
||||
#if !defined(TMC2130_INTERPOLATE_256_X) && TMC2130_ON_X
|
||||
#define TMC2130_INTERPOLATE_256_X TMC2130_INTERPOLATE_256
|
||||
#endif
|
||||
#if !defined(TMC2130_STALLGUARD_X) && TMC2130_ON_X
|
||||
#define TMC2130_STALLGUARD_X TMC2130_STALLGUARD
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_AMPL_X) && TMC2130_ON_X
|
||||
#define TMC2130_PWM_AMPL_X TMC2130_PWM_AMPL
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_GRAD_X) && TMC2130_ON_X
|
||||
#define TMC2130_PWM_GRAD_X TMC2130_PWM_GRAD
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_AUTOSCALE_X) && TMC2130_ON_X
|
||||
#define TMC2130_PWM_AUTOSCALE_X TMC2130_PWM_AUTOSCALE
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_FREQ_X) && TMC2130_ON_X
|
||||
#define TMC2130_PWM_FREQ_X TMC2130_PWM_FREQ
|
||||
#endif
|
||||
|
||||
#if !defined(TMC2130_STEALTHCHOP_Y) && TMC2130_ON_Y
|
||||
#define TMC2130_STEALTHCHOP_Y TMC2130_STEALTHCHOP
|
||||
#endif
|
||||
#if !defined(TMC2130_INTERPOLATE_256_Y) && TMC2130_ON_Y
|
||||
#define TMC2130_INTERPOLATE_256_Y TMC2130_INTERPOLATE_256
|
||||
#endif
|
||||
#if !defined(TMC2130_STALLGUARD_Y) && TMC2130_ON_Y
|
||||
#define TMC2130_STALLGUARD_Y TMC2130_STALLGUARD
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_AMPL_Y) && TMC2130_ON_Y
|
||||
#define TMC2130_PWM_AMPL_Y TMC2130_PWM_AMPL
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_GRAD_Y) && TMC2130_ON_Y
|
||||
#define TMC2130_PWM_GRAD_Y TMC2130_PWM_GRAD
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_AUTOSCALE_Y) && TMC2130_ON_Y
|
||||
#define TMC2130_PWM_AUTOSCALE_Y TMC2130_PWM_AUTOSCALE
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_FREQ_Y) && TMC2130_ON_Y
|
||||
#define TMC2130_PWM_FREQ_Y TMC2130_PWM_FREQ
|
||||
#endif
|
||||
|
||||
#if !defined(TMC2130_STEALTHCHOP_Z) && TMC2130_ON_Z
|
||||
#define TMC2130_STEALTHCHOP_Z TMC2130_STEALTHCHOP
|
||||
#endif
|
||||
#if !defined(TMC2130_INTERPOLATE_256_Z) && TMC2130_ON_Z
|
||||
#define TMC2130_INTERPOLATE_256_Z TMC2130_INTERPOLATE_256
|
||||
#endif
|
||||
#if !defined(TMC2130_STALLGUARD_Z) && TMC2130_ON_Z
|
||||
#define TMC2130_STALLGUARD_Z TMC2130_STALLGUARD
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_AMPL_Z) && TMC2130_ON_Z
|
||||
#define TMC2130_PWM_AMPL_Z TMC2130_PWM_AMPL
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_GRAD_Z) && TMC2130_ON_Z
|
||||
#define TMC2130_PWM_GRAD_Z TMC2130_PWM_GRAD
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_AUTOSCALE_Z) && TMC2130_ON_Z
|
||||
#define TMC2130_PWM_AUTOSCALE_Z TMC2130_PWM_AUTOSCALE
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_FREQ_Z) && TMC2130_ON_Z
|
||||
#define TMC2130_PWM_FREQ_Z TMC2130_PWM_FREQ
|
||||
#endif
|
||||
|
||||
#if !defined(TMC2130_STEALTHCHOP_EXT0) && TMC2130_ON_EXT0
|
||||
#define TMC2130_STEALTHCHOP_EXT0 TMC2130_STEALTHCHOP
|
||||
#endif
|
||||
#if !defined(TMC2130_INTERPOLATE_256_EXT0) && TMC2130_ON_EXT0
|
||||
#define TMC2130_INTERPOLATE_256_EXT0 TMC2130_INTERPOLATE_256
|
||||
#endif
|
||||
#if !defined(TMC2130_STALLGUARD_EXT0) && TMC2130_ON_EXT0
|
||||
#define TMC2130_STALLGUARD_EXT0 TMC2130_STALLGUARD
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_AMPL_EXT0) && TMC2130_ON_EXT0
|
||||
#define TMC2130_PWM_AMPL_EXT0 TMC2130_PWM_AMPL
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_GRAD_EXT0) && TMC2130_ON_EXT0
|
||||
#define TMC2130_PWM_GRAD_EXT0 TMC2130_PWM_GRAD
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_AUTOSCALE_EXT0) && TMC2130_ON_EXT0
|
||||
#define TMC2130_PWM_AUTOSCALE_EXT0 TMC2130_PWM_AUTOSCALE
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_FREQ_EXT0) && TMC2130_ON_EXT0
|
||||
#define TMC2130_PWM_FREQ_EXT0 TMC2130_PWM_FREQ
|
||||
#endif
|
||||
|
||||
#if !defined(TMC2130_STEALTHCHOP_EXT1) && TMC2130_ON_EXT1
|
||||
#define TMC2130_STEALTHCHOP_EXT1 TMC2130_STEALTHCHOP
|
||||
#endif
|
||||
#if !defined(TMC2130_INTERPOLATE_256_EXT1) && TMC2130_ON_EXT1
|
||||
#define TMC2130_INTERPOLATE_256_EXT1 TMC2130_INTERPOLATE_256
|
||||
#endif
|
||||
#if !defined(TMC2130_STALLGUARD_EXT1) && TMC2130_ON_EXT1
|
||||
#define TMC2130_STALLGUARD_EXT1 TMC2130_STALLGUARD
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_AMPL_EXT1) && TMC2130_ON_EXT1
|
||||
#define TMC2130_PWM_AMPL_EXT1 TMC2130_PWM_AMPL
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_GRAD_EXT1) && TMC2130_ON_EXT1
|
||||
#define TMC2130_PWM_GRAD_EXT1 TMC2130_PWM_GRAD
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_AUTOSCALE_EXT1) && TMC2130_ON_EXT1
|
||||
#define TMC2130_PWM_AUTOSCALE_EXT1 TMC2130_PWM_AUTOSCALE
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_FREQ_EXT1) && TMC2130_ON_EXT1
|
||||
#define TMC2130_PWM_FREQ_EXT1 TMC2130_PWM_FREQ
|
||||
#endif
|
||||
|
||||
#if !defined(TMC2130_STEALTHCHOP_EXT2) && TMC2130_ON_EXT2
|
||||
#define TMC2130_STEALTHCHOP_EXT2 TMC2130_STEALTHCHOP
|
||||
#endif
|
||||
#if !defined(TMC2130_INTERPOLATE_256_EXT2) && TMC2130_ON_EXT2
|
||||
#define TMC2130_INTERPOLATE_256_EXT2 TMC2130_INTERPOLATE_256
|
||||
#endif
|
||||
#if !defined(TMC2130_STALLGUARD_EXT2) && TMC2130_ON_EXT2
|
||||
#define TMC2130_STALLGUARD_EXT2 TMC2130_STALLGUARD
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_AMPL_EXT2) && TMC2130_ON_EXT2
|
||||
#define TMC2130_PWM_AMPL_EXT2 TMC2130_PWM_AMPL
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_GRAD_EXT2) && TMC2130_ON_EXT2
|
||||
#define TMC2130_PWM_GRAD_EXT2 TMC2130_PWM_GRAD
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_AUTOSCALE_EXT2) && TMC2130_ON_EXT2
|
||||
#define TMC2130_PWM_AUTOSCALE_EXT2 TMC2130_PWM_AUTOSCALE
|
||||
#endif
|
||||
#if !defined(TMC2130_PWM_FREQ_EXT2) && TMC2130_ON_EXT2
|
||||
#define TMC2130_PWM_FREQ_EXT2 TMC2130_PWM_FREQ
|
||||
#endif
|
3737
Repetier-Firmware 1.0.3/Repetier/fastio.h
Normal file
3737
Repetier-Firmware 1.0.3/Repetier/fastio.h
Normal file
File diff suppressed because it is too large
Load Diff
1562
Repetier-Firmware 1.0.3/Repetier/gcode.cpp
Normal file
1562
Repetier-Firmware 1.0.3/Repetier/gcode.cpp
Normal file
File diff suppressed because it is too large
Load Diff
341
Repetier-Firmware 1.0.3/Repetier/gcode.h
Normal file
341
Repetier-Firmware 1.0.3/Repetier/gcode.h
Normal file
@ -0,0 +1,341 @@
|
||||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware 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.
|
||||
|
||||
Repetier-Firmware 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 Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
#ifndef _GCODE_H
|
||||
#define _GCODE_H
|
||||
|
||||
#define MAX_CMD_SIZE 96
|
||||
#define ARRAY_SIZE(_x) (sizeof(_x)/sizeof(_x[0]))
|
||||
|
||||
enum FirmwareState {NotBusy=0,Processing,Paused,WaitHeater,DoorOpen};
|
||||
|
||||
class SDCard;
|
||||
class Commands;
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
class SerialGCodeSource: public GCodeSource {
|
||||
Stream *stream;
|
||||
public:
|
||||
SerialGCodeSource(Stream *p);
|
||||
virtual bool isOpen();
|
||||
virtual bool supportsWrite(); ///< true if write is a non dummy function
|
||||
virtual bool closeOnError(); // return true if the channel can not interactively correct errors.
|
||||
virtual bool dataAvailable(); // would read return a new byte?
|
||||
virtual int readByte();
|
||||
virtual void writeByte(uint8_t byte);
|
||||
virtual void close();
|
||||
};
|
||||
//#pragma message "Sd support: " XSTR(SDSUPPORT)
|
||||
#if SDSUPPORT
|
||||
class SDCardGCodeSource: public GCodeSource {
|
||||
public:
|
||||
virtual bool isOpen();
|
||||
virtual bool supportsWrite(); ///< true if write is a non dummy function
|
||||
virtual bool closeOnError(); // return true if the channel can not interactively correct errors.
|
||||
virtual bool dataAvailable(); // would read return a new byte?
|
||||
virtual int readByte();
|
||||
virtual void writeByte(uint8_t byte);
|
||||
virtual void close();
|
||||
};
|
||||
#endif
|
||||
|
||||
class FlashGCodeSource: public GCodeSource {
|
||||
public:
|
||||
FSTRINGPARAM(pointer);
|
||||
volatile bool finished;
|
||||
int actionOnFinish;
|
||||
|
||||
FlashGCodeSource();
|
||||
virtual bool isOpen();
|
||||
virtual bool supportsWrite(); ///< true if write is a non dummy function
|
||||
virtual bool closeOnError(); // return true if the channel can not interactively correct errors.
|
||||
virtual bool dataAvailable(); // would read return a new byte?
|
||||
virtual int readByte();
|
||||
virtual void writeByte(uint8_t byte);
|
||||
virtual void close();
|
||||
|
||||
/** Execute the commands at the given memory. If already an other string is
|
||||
running, the command will wait until that command finishes. If wait is true it
|
||||
will also wait for given command to be enqueued completely. */
|
||||
void executeCommands(FSTRINGPARAM(data),bool waitFinish,int action);
|
||||
};
|
||||
|
||||
#if NEW_COMMUNICATION
|
||||
extern FlashGCodeSource flashSource;
|
||||
extern SerialGCodeSource serial0Source;
|
||||
#if BLUETOOTH_SERIAL > 0
|
||||
extern SerialGCodeSource serial1Source;
|
||||
#endif
|
||||
#if SDSUPPORT
|
||||
extern SDCardGCodeSource sdSource;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
class GCode // 52 uint8_ts per command needed
|
||||
{
|
||||
uint16_t params;
|
||||
uint16_t params2;
|
||||
public:
|
||||
uint16_t N; ///< Line number reduced to 16 bit
|
||||
uint16_t M; ///< G-code M value if set
|
||||
uint16_t G; ///< G-code G value if set
|
||||
float X; ///< G-code X value if set
|
||||
float Y; ///< G-code Y value if set
|
||||
float Z; ///< G-code Z value if set
|
||||
float E; ///< G-code E value if set
|
||||
float F; ///< G-code F value if set
|
||||
int32_t S; ///< G-code S value if set
|
||||
int32_t P; ///< G-code P value if set
|
||||
float I; ///< G-code I value if set
|
||||
float J; ///< G-code J value if set
|
||||
float R; ///< G-code R value if set
|
||||
float D; ///< G-code D value if set
|
||||
float C; ///< G-code C value if set
|
||||
float H; ///< G-code H value if set
|
||||
float A; ///< G-code A value if set
|
||||
float B; ///< G-code B value if set
|
||||
float K; ///< G-code K value if set
|
||||
float L; ///< G-code L value if set
|
||||
float O; ///< G-code O value if set
|
||||
|
||||
char *text; ///< Text message of g-code if present.
|
||||
//moved the byte to the end and aligned ints on short boundary
|
||||
// Old habit from PC, which require alignments for data types such as int and long to be on 2 or 4 byte boundary
|
||||
// Otherwise, the compiler adds padding, wasted space.
|
||||
uint8_t T; // This may not matter on any of these controllers, but it can't hurt
|
||||
// True if origin did not come from serial console. That way we can send status messages to
|
||||
// a host only if he would normally not know about the mode switch.
|
||||
bool internalCommand;
|
||||
inline bool hasM()
|
||||
{
|
||||
return ((params & 2)!=0);
|
||||
}
|
||||
inline bool hasN()
|
||||
{
|
||||
return ((params & 1)!=0);
|
||||
}
|
||||
inline bool hasG()
|
||||
{
|
||||
return ((params & 4)!=0);
|
||||
}
|
||||
inline bool hasX()
|
||||
{
|
||||
return ((params & 8)!=0);
|
||||
}
|
||||
inline void unsetX() {
|
||||
params &= ~8;
|
||||
}
|
||||
inline bool hasY()
|
||||
{
|
||||
return ((params & 16)!=0);
|
||||
}
|
||||
inline void unsetY() {
|
||||
params &= ~16;
|
||||
}
|
||||
inline bool hasZ()
|
||||
{
|
||||
return ((params & 32)!=0);
|
||||
}
|
||||
inline void unsetZ() {
|
||||
params &= ~32;
|
||||
}
|
||||
inline bool hasNoXYZ()
|
||||
{
|
||||
return ((params & 56)==0);
|
||||
}
|
||||
inline bool hasE()
|
||||
{
|
||||
return ((params & 64)!=0);
|
||||
}
|
||||
inline bool hasF()
|
||||
{
|
||||
return ((params & 256)!=0);
|
||||
}
|
||||
inline bool hasT()
|
||||
{
|
||||
return ((params & 512)!=0);
|
||||
}
|
||||
inline bool hasS()
|
||||
{
|
||||
return ((params & 1024)!=0);
|
||||
}
|
||||
inline bool hasP()
|
||||
{
|
||||
return ((params & 2048)!=0);
|
||||
}
|
||||
inline bool isV2()
|
||||
{
|
||||
return ((params & 4096)!=0);
|
||||
}
|
||||
inline bool hasString()
|
||||
{
|
||||
return ((params & 32768)!=0);
|
||||
}
|
||||
inline bool hasI()
|
||||
{
|
||||
return ((params2 & 1)!=0);
|
||||
}
|
||||
inline bool hasJ()
|
||||
{
|
||||
return ((params2 & 2)!=0);
|
||||
}
|
||||
inline bool hasR()
|
||||
{
|
||||
return ((params2 & 4)!=0);
|
||||
}
|
||||
inline bool hasD()
|
||||
{
|
||||
return ((params2 & 8)!=0);
|
||||
}
|
||||
inline bool hasC()
|
||||
{
|
||||
return ((params2 & 16)!=0);
|
||||
}
|
||||
inline bool hasH()
|
||||
{
|
||||
return ((params2 & 32)!=0);
|
||||
}
|
||||
inline bool hasA()
|
||||
{
|
||||
return ((params2 & 64)!=0);
|
||||
}
|
||||
inline bool hasB()
|
||||
{
|
||||
return ((params2 & 128)!=0);
|
||||
}
|
||||
inline bool hasK()
|
||||
{
|
||||
return ((params2 & 256)!=0);
|
||||
}
|
||||
inline bool hasL()
|
||||
{
|
||||
return ((params2 & 512)!=0);
|
||||
}
|
||||
inline bool hasO()
|
||||
{
|
||||
return ((params2 & 1024)!=0);
|
||||
}
|
||||
inline long getS(long def)
|
||||
{
|
||||
return (hasS() ? S : def);
|
||||
}
|
||||
inline long getP(long def)
|
||||
{
|
||||
return (hasP() ? P : def);
|
||||
}
|
||||
inline void setFormatError() {
|
||||
params2 |= 32768;
|
||||
}
|
||||
inline bool hasFormatError() {
|
||||
return ((params2 & 32768)!=0);
|
||||
}
|
||||
void printCommand();
|
||||
bool parseBinary(uint8_t *buffer,bool fromSerial);
|
||||
bool parseAscii(char *line,bool fromSerial);
|
||||
void popCurrentCommand();
|
||||
void echoCommand();
|
||||
/** Get next command in command buffer. After the command is processed, call gcode_command_finished() */
|
||||
static GCode *peekCurrentCommand();
|
||||
/** Frees the cache used by the last command fetched. */
|
||||
static void readFromSerial();
|
||||
static void pushCommand();
|
||||
static void executeFString(FSTRINGPARAM(cmd));
|
||||
static uint8_t computeBinarySize(char *ptr);
|
||||
static void fatalError(FSTRINGPARAM(message));
|
||||
static void reportFatalError();
|
||||
static void resetFatalError();
|
||||
inline static bool hasFatalError() {
|
||||
return fatalErrorMsg != NULL;
|
||||
}
|
||||
static void keepAlive(enum FirmwareState state);
|
||||
static uint32_t keepAliveInterval;
|
||||
friend class SDCard;
|
||||
friend class UIDisplay;
|
||||
static FSTRINGPARAM(fatalErrorMsg);
|
||||
friend class GCodeSource;
|
||||
protected:
|
||||
void debugCommandBuffer();
|
||||
void checkAndPushCommand();
|
||||
static void requestResend();
|
||||
inline float parseFloatValue(char *s)
|
||||
{
|
||||
char *endPtr;
|
||||
while(*s == 32) s++; // skip spaces
|
||||
float f = (strtod(s, &endPtr));
|
||||
if(s == endPtr) f=0.0; // treat empty string "x " as "x0"
|
||||
return f;
|
||||
}
|
||||
inline long parseLongValue(char *s)
|
||||
{
|
||||
char *endPtr;
|
||||
while(*s == 32) s++; // skip spaces
|
||||
long l = (strtol(s, &endPtr, 10));
|
||||
if(s == endPtr) l=0; // treat empty string argument "p " as "p0"
|
||||
return l;
|
||||
}
|
||||
|
||||
static GCode commandsBuffered[GCODE_BUFFER_SIZE]; ///< Buffer for received commands.
|
||||
static uint8_t bufferReadIndex; ///< Read position in gcode_buffer.
|
||||
static uint8_t bufferWriteIndex; ///< Write position in gcode_buffer.
|
||||
static uint8_t commandReceiving[MAX_CMD_SIZE]; ///< Current received command.
|
||||
static uint8_t commandsReceivingWritePosition; ///< Writing position in gcode_transbuffer.
|
||||
static uint8_t sendAsBinary; ///< Flags the command as binary input.
|
||||
static uint8_t commentDetected; ///< Flags true if we are reading the comment part of a command.
|
||||
static uint8_t binaryCommandSize; ///< Expected size of the incoming binary command.
|
||||
static bool waitUntilAllCommandsAreParsed; ///< Don't read until all commands are parsed. Needed if gcode_buffer is misused as storage for strings.
|
||||
static uint32_t actLineNumber; ///< Line number of current command.
|
||||
static volatile uint8_t bufferLength; ///< Number of commands stored in gcode_buffer
|
||||
static uint8_t formatErrors; ///< Number of sequential format errors
|
||||
static millis_t lastBusySignal; ///< When was the last busy signal
|
||||
#if NEW_COMMUNICATION == 0
|
||||
static int8_t waitingForResend; ///< Waiting for line to be resend. -1 = no wait.
|
||||
static uint32_t lastLineNumber; ///< Last line number received.
|
||||
static millis_t timeOfLastDataPacket; ///< Time, when we got the last data packet. Used to detect missing uint8_ts.
|
||||
static uint8_t wasLastCommandReceivedAsBinary; ///< Was the last successful command in binary mode?
|
||||
#else
|
||||
public:
|
||||
GCodeSource *source;
|
||||
#endif
|
||||
};
|
||||
|
||||
|
||||
#if JSON_OUTPUT
|
||||
#include "src/SdFat/SdFat.h"
|
||||
// Struct to hold Gcode file information 32 bytes
|
||||
#define GENBY_SIZE 16
|
||||
class GCodeFileInfo {
|
||||
public:
|
||||
void init(SdFile &file);
|
||||
|
||||
unsigned long fileSize;
|
||||
float objectHeight;
|
||||
float layerHeight;
|
||||
float filamentNeeded;
|
||||
char generatedBy[GENBY_SIZE];
|
||||
|
||||
bool findGeneratedBy(char *buf, char *genBy);
|
||||
bool findLayerHeight(char *buf, float &layerHeight);
|
||||
bool findFilamentNeed(char *buf, float &filament);
|
||||
bool findTotalHeight(char *buf, float &objectHeight);
|
||||
};
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
46
Repetier-Firmware 1.0.3/Repetier/logo.h
Normal file
46
Repetier-Firmware 1.0.3/Repetier/logo.h
Normal file
@ -0,0 +1,46 @@
|
||||
//------------------------------------------------------------------------------
|
||||
// File generated by LCD Assistant
|
||||
// http://en.radzio.dxp.pl/bitmap_converter/
|
||||
//------------------------------------------------------------------------------
|
||||
|
||||
#ifndef CUSTOM_LOGO
|
||||
#define LOGO_WIDTH 60
|
||||
#define LOGO_HEIGHT 64
|
||||
|
||||
const unsigned char logo[] PROGMEM = { //AVR-GCC, WinAVR
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x01, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x80, 0x00, 0xFF, 0xFE, 0x00,
|
||||
0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0xC3, 0xE1, 0xF0, 0x7F, 0x0F, 0xC0,
|
||||
0x00, 0x07, 0x1F, 0x87, 0xC1, 0xFC, 0x3F, 0xC0, 0x00, 0x38, 0xFF, 0xFF, 0xFF, 0xF0, 0xFE, 0x40,
|
||||
0x01, 0xC3, 0xFF, 0xFF, 0xFF, 0xC1, 0xFC, 0x40, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x07, 0xF0, 0x40,
|
||||
0x3F, 0xFF, 0xFF, 0x80, 0x00, 0x1F, 0xE0, 0x40, 0x3F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x40,
|
||||
0x3F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x40, 0x3F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0x40,
|
||||
0x30, 0x00, 0x00, 0x01, 0xFF, 0xFC, 0x04, 0x40, 0x30, 0x00, 0x00, 0x00, 0x00, 0xFC, 0x0C, 0x40,
|
||||
0x30, 0x00, 0x00, 0x00, 0x00, 0x38, 0x1C, 0x40, 0x30, 0x00, 0x00, 0x00, 0x00, 0x38, 0x3E, 0x40,
|
||||
0x30, 0x00, 0x00, 0x00, 0x00, 0x38, 0x7E, 0x40, 0x30, 0xFF, 0xFF, 0x80, 0x00, 0x38, 0xFE, 0x40,
|
||||
0x30, 0xFF, 0xFF, 0xF8, 0x00, 0x38, 0xFE, 0x40, 0x30, 0xFF, 0xFF, 0xFE, 0x00, 0x38, 0xE6, 0x40,
|
||||
0x30, 0xFF, 0xFF, 0xFF, 0x00, 0x38, 0xE6, 0x40, 0x30, 0xFF, 0xFF, 0xFF, 0x80, 0x38, 0xC6, 0x40,
|
||||
0x30, 0xFF, 0xFF, 0xFF, 0x80, 0x38, 0xC6, 0x40, 0x30, 0xFF, 0xBF, 0xFF, 0x80, 0x38, 0xC4, 0x40,
|
||||
0x30, 0xFF, 0x80, 0xFF, 0xC0, 0x38, 0xC4, 0x40, 0x30, 0xFF, 0x80, 0xFF, 0xC0, 0x38, 0xC4, 0x40,
|
||||
0x30, 0xFF, 0x80, 0x7F, 0xC0, 0x38, 0xCC, 0x40, 0x30, 0xFF, 0x80, 0x7F, 0xC0, 0x38, 0xFC, 0x40,
|
||||
0x30, 0xFF, 0x80, 0x7F, 0xC0, 0x38, 0xF8, 0x40, 0x30, 0xFF, 0x80, 0xFF, 0xC0, 0x38, 0xF8, 0x40,
|
||||
0x30, 0xFF, 0xFF, 0xFF, 0xC0, 0x38, 0xF0, 0x40, 0x30, 0xFF, 0xFF, 0xFF, 0x80, 0x38, 0xE0, 0x40,
|
||||
0x30, 0xFF, 0xFF, 0xFF, 0x80, 0x38, 0xE0, 0x40, 0x30, 0xFF, 0xFF, 0xFF, 0x00, 0x38, 0xC0, 0x40,
|
||||
0x30, 0xFF, 0xFF, 0xFE, 0x00, 0x38, 0xC0, 0x40, 0x30, 0xFF, 0xFF, 0xF0, 0x00, 0x38, 0xC0, 0x40,
|
||||
0x30, 0xFF, 0x9F, 0xF0, 0x00, 0x38, 0xC0, 0x40, 0x30, 0xFF, 0x8F, 0xFC, 0x00, 0x38, 0xC0, 0x40,
|
||||
0x30, 0xFF, 0x87, 0xFC, 0x00, 0x38, 0xC0, 0x40, 0x30, 0xFF, 0x87, 0xFE, 0x00, 0x38, 0xC0, 0x40,
|
||||
0x30, 0xFF, 0x83, 0xFF, 0x00, 0x38, 0xC0, 0x80, 0x30, 0xFF, 0x83, 0xFF, 0x00, 0x38, 0xC0, 0x80,
|
||||
0x30, 0xFF, 0x81, 0xFF, 0x80, 0x38, 0xC1, 0x00, 0x30, 0xFF, 0x81, 0xFF, 0x80, 0x38, 0xC2, 0x00,
|
||||
0x30, 0xFF, 0x80, 0xFF, 0xC0, 0x38, 0x82, 0x00, 0x30, 0xFF, 0x80, 0xFF, 0xC0, 0x38, 0x84, 0x00,
|
||||
0x30, 0xFF, 0x80, 0x7F, 0xE0, 0x38, 0x08, 0x00, 0x30, 0x7F, 0x80, 0x7F, 0xE0, 0x38, 0x08, 0x00,
|
||||
0x30, 0x0F, 0x80, 0x3F, 0xE0, 0x38, 0x10, 0x00, 0x30, 0x00, 0x00, 0x3F, 0xF0, 0x38, 0x10, 0x00,
|
||||
0x38, 0x00, 0x00, 0x03, 0xF0, 0x38, 0x20, 0x00, 0x38, 0x00, 0x00, 0x00, 0x00, 0x38, 0x40, 0x00,
|
||||
0x3C, 0x00, 0x00, 0x00, 0x00, 0x38, 0x40, 0x00, 0x3F, 0xF8, 0x00, 0x00, 0x00, 0x39, 0x80, 0x00,
|
||||
0x3F, 0xFF, 0xF8, 0x00, 0x00, 0x3D, 0x00, 0x00, 0x00, 0xFF, 0xFF, 0xF8, 0x00, 0x7F, 0x00, 0x00,
|
||||
0x00, 0x07, 0xFF, 0xFF, 0xF8, 0x7E, 0x00, 0x00, 0x00, 0x00, 0x07, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x03, 0xFF, 0xF8, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0D, 0xF8, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||
};
|
||||
#else
|
||||
LOGO_BITMAP
|
||||
#endif
|
2853
Repetier-Firmware 1.0.3/Repetier/motion.cpp
Normal file
2853
Repetier-Firmware 1.0.3/Repetier/motion.cpp
Normal file
File diff suppressed because it is too large
Load Diff
704
Repetier-Firmware 1.0.3/Repetier/motion.h
Normal file
704
Repetier-Firmware 1.0.3/Repetier/motion.h
Normal file
@ -0,0 +1,704 @@
|
||||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware 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.
|
||||
|
||||
Repetier-Firmware 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 Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
This firmware is a nearly complete rewrite of the sprinter firmware
|
||||
by kliment (https://github.com/kliment/Sprinter)
|
||||
which based on Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
|
||||
#
|
||||
Functions in this file are used to communicate using ascii or repetier protocol.
|
||||
*/
|
||||
|
||||
#ifndef MOTION_H_INCLUDED
|
||||
#define MOTION_H_INCLUDED
|
||||
|
||||
/** Marks the first step of a new move */
|
||||
#define FLAG_WARMUP 1
|
||||
#define FLAG_NOMINAL 2
|
||||
#define FLAG_DECELERATING 4
|
||||
#define FLAG_ACCELERATION_ENABLED 8 // unused
|
||||
#define FLAG_CHECK_ENDSTOPS 16
|
||||
#define FLAG_ALL_E_MOTORS 32 // For mixed extruder move all motors instead of selected motor
|
||||
#define FLAG_SKIP_DEACCELERATING 64 // unused
|
||||
#define FLAG_BLOCKED 128
|
||||
|
||||
/** Are the step parameter computed */
|
||||
#define FLAG_JOIN_STEPPARAMS_COMPUTED 1
|
||||
/** The right speed is fixed. Don't check this block or any block to the left. */
|
||||
#define FLAG_JOIN_END_FIXED 2
|
||||
/** The left speed is fixed. Don't check left block. */
|
||||
#define FLAG_JOIN_START_FIXED 4
|
||||
/** Start filament retraction at move start */
|
||||
#define FLAG_JOIN_START_RETRACT 8
|
||||
/** Wait for filament push back, before ending move */
|
||||
#define FLAG_JOIN_END_RETRACT 16
|
||||
/** Disable retract for this line */
|
||||
#define FLAG_JOIN_NO_RETRACT 32
|
||||
/** Wait for the extruder to finish it's up movement */
|
||||
#define FLAG_JOIN_WAIT_EXTRUDER_UP 64
|
||||
/** Wait for the extruder to finish it's down movement */
|
||||
#define FLAG_JOIN_WAIT_EXTRUDER_DOWN 128
|
||||
// Printing related data
|
||||
#if NONLINEAR_SYSTEM || defined(DOXYGEN)
|
||||
// Allow the delta cache to store segments for every line in line cache. Beware this gets big ... fast.
|
||||
|
||||
class PrintLine;
|
||||
typedef struct {
|
||||
flag8_t dir; ///< Direction of delta movement.
|
||||
uint16_t deltaSteps[TOWER_ARRAY]; ///< Number of steps in move.
|
||||
inline bool checkEndstops(PrintLine *cur, bool checkall);
|
||||
inline void setXMoveFinished() {
|
||||
dir &= ~XSTEP;
|
||||
}
|
||||
inline void setYMoveFinished() {
|
||||
dir &= ~YSTEP;
|
||||
}
|
||||
inline void setZMoveFinished() {
|
||||
dir &= ~ZSTEP;
|
||||
}
|
||||
inline void setXYMoveFinished() {
|
||||
dir &= ~XY_STEP;
|
||||
}
|
||||
inline bool isXPositiveMove() {
|
||||
return (dir & X_STEP_DIRPOS) == X_STEP_DIRPOS;
|
||||
}
|
||||
inline bool isXNegativeMove() {
|
||||
return (dir & X_STEP_DIRPOS) == XSTEP;
|
||||
}
|
||||
inline bool isYPositiveMove() {
|
||||
return (dir & Y_STEP_DIRPOS) == Y_STEP_DIRPOS;
|
||||
}
|
||||
inline bool isYNegativeMove() {
|
||||
return (dir & Y_STEP_DIRPOS) == YSTEP;
|
||||
}
|
||||
inline bool isZPositiveMove() {
|
||||
return (dir & Z_STEP_DIRPOS) == Z_STEP_DIRPOS;
|
||||
}
|
||||
inline bool isZNegativeMove() {
|
||||
return (dir & Z_STEP_DIRPOS) == ZSTEP;
|
||||
}
|
||||
inline bool isEPositiveMove() {
|
||||
return (dir & E_STEP_DIRPOS) == E_STEP_DIRPOS;
|
||||
}
|
||||
inline bool isENegativeMove() {
|
||||
return (dir & E_STEP_DIRPOS) == ESTEP;
|
||||
}
|
||||
inline bool isXMove() {
|
||||
return (dir & XSTEP);
|
||||
}
|
||||
inline bool isYMove() {
|
||||
return (dir & YSTEP);
|
||||
}
|
||||
inline bool isXOrYMove() {
|
||||
return dir & XY_STEP;
|
||||
}
|
||||
inline bool isZMove() {
|
||||
return (dir & ZSTEP);
|
||||
}
|
||||
inline bool isEMove() {
|
||||
return (dir & ESTEP);
|
||||
}
|
||||
inline bool isEOnlyMove() {
|
||||
return (dir & XYZE_STEP) == ESTEP;
|
||||
}
|
||||
inline bool isNoMove() {
|
||||
return (dir & XYZE_STEP) == 0;
|
||||
}
|
||||
inline bool isXYZMove() {
|
||||
return dir & XYZ_STEP;
|
||||
}
|
||||
inline bool isMoveOfAxis(uint8_t axis) {
|
||||
return (dir & (XSTEP << axis));
|
||||
}
|
||||
inline void setMoveOfAxis(uint8_t axis) {
|
||||
dir |= XSTEP << axis;
|
||||
}
|
||||
inline void setPositiveMoveOfAxis(uint8_t axis) {
|
||||
dir |= X_STEP_DIRPOS << axis;
|
||||
}
|
||||
inline void setPositiveDirectionForAxis(uint8_t axis) {
|
||||
dir |= X_DIRPOS << axis;
|
||||
}
|
||||
} NonlinearSegment;
|
||||
extern uint8_t lastMoveID;
|
||||
#endif
|
||||
class UIDisplay;
|
||||
class PrintLine { // RAM usage: 24*4+15 = 113 Byte
|
||||
friend class UIDisplay;
|
||||
#if CPU_ARCH == ARCH_ARM
|
||||
static volatile bool nlFlag;
|
||||
#endif
|
||||
public:
|
||||
static ufast8_t linesPos; // Position for executing line movement
|
||||
static PrintLine lines[];
|
||||
static ufast8_t linesWritePos; // Position where we write the next cached line move
|
||||
ufast8_t joinFlags;
|
||||
volatile ufast8_t flags;
|
||||
secondspeed_t secondSpeed; // for laser intensity or fan control
|
||||
private:
|
||||
fast8_t primaryAxis;
|
||||
ufast8_t dir; ///< Direction of movement. 1 = X+, 2 = Y+, 4= Z+, values can be combined.
|
||||
int32_t timeInTicks;
|
||||
int32_t delta[E_AXIS_ARRAY]; ///< Steps we want to move.
|
||||
int32_t error[E_AXIS_ARRAY]; ///< Error calculation for Bresenham algorithm
|
||||
float speedX; ///< Speed in x direction at fullInterval in mm/s
|
||||
float speedY; ///< Speed in y direction at fullInterval in mm/s
|
||||
float speedZ; ///< Speed in z direction at fullInterval in mm/s
|
||||
float speedE; ///< Speed in E direction at fullInterval in mm/s
|
||||
float fullSpeed; ///< Desired speed mm/s
|
||||
float invFullSpeed; ///< 1.0/fullSpeed for faster computation
|
||||
float accelerationDistance2; ///< Real 2.0*distance*acceleration mm²/s²
|
||||
float maxJunctionSpeed; ///< Max. junction speed between this and next segment
|
||||
float startSpeed; ///< Starting speed in mm/s
|
||||
float endSpeed; ///< Exit speed in mm/s
|
||||
float minSpeed;
|
||||
float distance;
|
||||
#if NONLINEAR_SYSTEM || defined(DOXYGEN)
|
||||
uint8_t numNonlinearSegments; ///< Number of delta segments left in line. Decremented by stepper timer.
|
||||
uint8_t moveID; ///< ID used to identify moves which are all part of the same line
|
||||
int32_t numPrimaryStepPerSegment; ///< Number of primary Bresenham axis steps in each delta segment
|
||||
NonlinearSegment segments[DELTASEGMENTS_PER_PRINTLINE];
|
||||
#endif
|
||||
ticks_t fullInterval; ///< interval at full speed in ticks/step.
|
||||
uint32_t accelSteps; ///< How much steps does it take, to reach the plateau.
|
||||
uint32_t decelSteps; ///< How much steps does it take, to reach the end speed.
|
||||
uint32_t accelerationPrim; ///< Acceleration along primary axis
|
||||
uint32_t fAcceleration; ///< accelerationPrim*262144/F_CPU
|
||||
speed_t vMax; ///< Maximum reached speed in steps/s.
|
||||
speed_t vStart; ///< Starting speed in steps/s.
|
||||
speed_t vEnd; ///< End speed in steps/s
|
||||
#if USE_ADVANCE
|
||||
#if ENABLE_QUADRATIC_ADVANCE
|
||||
int32_t advanceRate; ///< Advance steps at full speed
|
||||
int32_t advanceFull; ///< Maximum advance at fullInterval [steps*65536]
|
||||
int32_t advanceStart;
|
||||
int32_t advanceEnd;
|
||||
#endif
|
||||
uint16_t advanceL; ///< Recomputed L value
|
||||
#endif
|
||||
#ifdef DEBUG_STEPCOUNT
|
||||
int32_t totalStepsRemaining;
|
||||
#endif
|
||||
public:
|
||||
int32_t stepsRemaining; ///< Remaining steps, until move is finished
|
||||
static PrintLine *cur;
|
||||
static volatile ufast8_t linesCount; // Number of lines cached 0 = nothing to do
|
||||
inline bool areParameterUpToDate() {
|
||||
return joinFlags & FLAG_JOIN_STEPPARAMS_COMPUTED;
|
||||
}
|
||||
inline void invalidateParameter() {
|
||||
joinFlags &= ~FLAG_JOIN_STEPPARAMS_COMPUTED;
|
||||
}
|
||||
inline void setParameterUpToDate() {
|
||||
joinFlags |= FLAG_JOIN_STEPPARAMS_COMPUTED;
|
||||
}
|
||||
inline bool isStartSpeedFixed() {
|
||||
return joinFlags & FLAG_JOIN_START_FIXED;
|
||||
}
|
||||
inline void setStartSpeedFixed(bool newState) {
|
||||
joinFlags = (newState ? joinFlags | FLAG_JOIN_START_FIXED : joinFlags & ~FLAG_JOIN_START_FIXED);
|
||||
}
|
||||
inline void fixStartAndEndSpeed() {
|
||||
joinFlags |= FLAG_JOIN_END_FIXED | FLAG_JOIN_START_FIXED;
|
||||
}
|
||||
inline bool isEndSpeedFixed() {
|
||||
return joinFlags & FLAG_JOIN_END_FIXED;
|
||||
}
|
||||
inline void setEndSpeedFixed(bool newState) {
|
||||
joinFlags = (newState ? joinFlags | FLAG_JOIN_END_FIXED : joinFlags & ~FLAG_JOIN_END_FIXED);
|
||||
}
|
||||
inline bool isWarmUp() {
|
||||
return flags & FLAG_WARMUP;
|
||||
}
|
||||
inline uint8_t getWaitForXLinesFilled() {
|
||||
return primaryAxis;
|
||||
}
|
||||
inline void setWaitForXLinesFilled(uint8_t b) {
|
||||
primaryAxis = b;
|
||||
}
|
||||
inline bool isExtruderForwardMove() {
|
||||
return (dir & E_STEP_DIRPOS) == E_STEP_DIRPOS;
|
||||
}
|
||||
inline void block() {
|
||||
flags |= FLAG_BLOCKED;
|
||||
}
|
||||
inline void unblock() {
|
||||
flags &= ~FLAG_BLOCKED;
|
||||
}
|
||||
inline bool isBlocked() {
|
||||
return flags & FLAG_BLOCKED;
|
||||
}
|
||||
inline bool isAllEMotors() {
|
||||
return flags & FLAG_ALL_E_MOTORS;
|
||||
}
|
||||
inline bool isCheckEndstops() {
|
||||
return flags & FLAG_CHECK_ENDSTOPS;
|
||||
}
|
||||
inline bool isNominalMove() {
|
||||
return flags & FLAG_NOMINAL;
|
||||
}
|
||||
inline void setNominalMove() {
|
||||
flags |= FLAG_NOMINAL;
|
||||
}
|
||||
inline void checkEndstops() {
|
||||
if(isCheckEndstops()) {
|
||||
Endstops::update();
|
||||
if(Endstops::anyEndstopHit()) {
|
||||
#if MULTI_XENDSTOP_HOMING
|
||||
{
|
||||
if(Printer::isHoming()) {
|
||||
if(isXNegativeMove()) {
|
||||
if(Endstops::xMin())
|
||||
Printer::multiXHomeFlags &= ~1;
|
||||
if(Endstops::x2Min())
|
||||
Printer::multiXHomeFlags &= ~2;
|
||||
if(Printer::multiXHomeFlags == 0)
|
||||
setXMoveFinished();
|
||||
} else if(isXPositiveMove()) {
|
||||
if(Endstops::xMax())
|
||||
Printer::multiXHomeFlags &= ~1;
|
||||
if(Endstops::x2Max())
|
||||
Printer::multiXHomeFlags &= ~2;
|
||||
if(Printer::multiXHomeFlags == 0) {
|
||||
setXMoveFinished();
|
||||
}
|
||||
}
|
||||
} else {
|
||||
if(isXNegativeMove() && Endstops::xMin()) {
|
||||
setXMoveFinished();
|
||||
} else if(isXPositiveMove() && Endstops::xMax()) {
|
||||
setXMoveFinished();
|
||||
}
|
||||
}
|
||||
}
|
||||
#else // Multi endstop homing
|
||||
if(isXNegativeMove() && Endstops::xMin())
|
||||
setXMoveFinished();
|
||||
else if(isXPositiveMove() && Endstops::xMax())
|
||||
setXMoveFinished();
|
||||
#endif
|
||||
#if MULTI_YENDSTOP_HOMING
|
||||
{
|
||||
if(Printer::isHoming()) {
|
||||
if(isYNegativeMove()) {
|
||||
if(Endstops::yMin())
|
||||
Printer::multiYHomeFlags &= ~1;
|
||||
if(Endstops::y2Min())
|
||||
Printer::multiYHomeFlags &= ~2;
|
||||
if(Printer::multiYHomeFlags == 0)
|
||||
setYMoveFinished();
|
||||
} else if(isYPositiveMove()) {
|
||||
if(Endstops::yMax())
|
||||
Printer::multiYHomeFlags &= ~1;
|
||||
if(Endstops::y2Max())
|
||||
Printer::multiYHomeFlags &= ~2;
|
||||
if(Printer::multiYHomeFlags == 0) {
|
||||
setYMoveFinished();
|
||||
}
|
||||
}
|
||||
} else {
|
||||
if(isYNegativeMove() && Endstops::yMin()) {
|
||||
setYMoveFinished();
|
||||
} else if(isYPositiveMove() && Endstops::yMax()) {
|
||||
setYMoveFinished();
|
||||
}
|
||||
}
|
||||
}
|
||||
#else // Multi endstop homing
|
||||
if(isYNegativeMove() && Endstops::yMin())
|
||||
setYMoveFinished();
|
||||
else if(isYPositiveMove() && Endstops::yMax())
|
||||
setYMoveFinished();
|
||||
#endif
|
||||
#if FEATURE_Z_PROBE
|
||||
if(Printer::isZProbingActive() && isZNegativeMove() && Endstops::zProbe()) {
|
||||
setZMoveFinished();
|
||||
Printer::stepsRemainingAtZHit = stepsRemaining;
|
||||
} else
|
||||
#endif
|
||||
#if MULTI_ZENDSTOP_HOMING
|
||||
{
|
||||
if(Printer::isHoming()) {
|
||||
if(isZNegativeMove()) {
|
||||
if(Endstops::zMin())
|
||||
Printer::multiZHomeFlags &= ~1;
|
||||
if(Endstops::z2MinMax())
|
||||
Printer::multiZHomeFlags &= ~2;
|
||||
if(Printer::multiZHomeFlags == 0)
|
||||
setZMoveFinished();
|
||||
} else if(isZPositiveMove()) {
|
||||
if(Endstops::zMax())
|
||||
Printer::multiZHomeFlags &= ~1;
|
||||
if(Endstops::z2MinMax())
|
||||
Printer::multiZHomeFlags &= ~2;
|
||||
if(Printer::multiZHomeFlags == 0) {
|
||||
#if MAX_HARDWARE_ENDSTOP_Z
|
||||
Printer::stepsRemainingAtZHit = stepsRemaining;
|
||||
#endif
|
||||
setZMoveFinished();
|
||||
}
|
||||
}
|
||||
} else {
|
||||
#if !(Z_MIN_PIN == Z_PROBE_PIN && FEATURE_Z_PROBE)
|
||||
if(isZNegativeMove() && Endstops::zMin()) {
|
||||
setZMoveFinished();
|
||||
} else
|
||||
#endif
|
||||
|
||||
if(isZPositiveMove() && Endstops::zMax()) {
|
||||
#if MAX_HARDWARE_ENDSTOP_Z
|
||||
Printer::stepsRemainingAtZHit = stepsRemaining;
|
||||
#endif
|
||||
setZMoveFinished();
|
||||
}
|
||||
}
|
||||
}
|
||||
#else // Multi endstop homing
|
||||
if(isZNegativeMove() && Endstops::zMin()
|
||||
#if Z_MIN_PIN == Z_PROBE_PIN && FEATURE_Z_PROBE
|
||||
&& Printer::isHoming()
|
||||
#endif
|
||||
) {
|
||||
setZMoveFinished();
|
||||
} else if(isZPositiveMove() && Endstops::zMax()) {
|
||||
#if MAX_HARDWARE_ENDSTOP_Z
|
||||
Printer::stepsRemainingAtZHit = stepsRemaining;
|
||||
#endif
|
||||
setZMoveFinished();
|
||||
}
|
||||
#endif
|
||||
}
|
||||
#if FEATURE_Z_PROBE
|
||||
else if(Printer::isZProbingActive() && isZNegativeMove()) {
|
||||
Endstops::update();
|
||||
if(Endstops::zProbe()) {
|
||||
setZMoveFinished();
|
||||
Printer::stepsRemainingAtZHit = stepsRemaining;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
inline void setXMoveFinished() {
|
||||
#if DRIVE_SYSTEM==XY_GANTRY || DRIVE_SYSTEM==YX_GANTRY
|
||||
dir &= ~48;
|
||||
#elif DRIVE_SYSTEM==XZ_GANTRY || DRIVE_SYSTEM==ZX_GANTRY
|
||||
dir &= ~80;
|
||||
#else
|
||||
dir &= ~16;
|
||||
#endif
|
||||
}
|
||||
inline void setYMoveFinished() {
|
||||
#if DRIVE_SYSTEM==XY_GANTRY || DRIVE_SYSTEM==YX_GANTRY
|
||||
dir &= ~48;
|
||||
#else
|
||||
dir &= ~32;
|
||||
#endif
|
||||
}
|
||||
inline void setZMoveFinished() {
|
||||
#if DRIVE_SYSTEM==XZ_GANTRY || DRIVE_SYSTEM==ZX_GANTRY
|
||||
dir &= ~80;
|
||||
#else
|
||||
dir &= ~64;
|
||||
#endif
|
||||
}
|
||||
inline void setXYMoveFinished() {
|
||||
dir &= ~48;
|
||||
}
|
||||
inline bool isXPositiveMove() {
|
||||
return (dir & X_STEP_DIRPOS) == X_STEP_DIRPOS;
|
||||
}
|
||||
inline bool isXNegativeMove() {
|
||||
return (dir & X_STEP_DIRPOS) == XSTEP;
|
||||
}
|
||||
inline bool isYPositiveMove() {
|
||||
return (dir & Y_STEP_DIRPOS) == Y_STEP_DIRPOS;
|
||||
}
|
||||
inline bool isYNegativeMove() {
|
||||
return (dir & Y_STEP_DIRPOS) == YSTEP;
|
||||
}
|
||||
inline bool isZPositiveMove() {
|
||||
return (dir & Z_STEP_DIRPOS) == Z_STEP_DIRPOS;
|
||||
}
|
||||
inline bool isZNegativeMove() {
|
||||
return (dir & Z_STEP_DIRPOS) == ZSTEP;
|
||||
}
|
||||
inline bool isEPositiveMove() {
|
||||
return (dir & E_STEP_DIRPOS) == E_STEP_DIRPOS;
|
||||
}
|
||||
inline bool isENegativeMove() {
|
||||
return (dir & E_STEP_DIRPOS) == ESTEP;
|
||||
}
|
||||
inline bool isXMove() {
|
||||
return (dir & XSTEP);
|
||||
}
|
||||
inline bool isYMove() {
|
||||
return (dir & YSTEP);
|
||||
}
|
||||
inline bool isXOrYMove() {
|
||||
return dir & XY_STEP;
|
||||
}
|
||||
inline bool isXOrZMove() {
|
||||
return dir & (XSTEP | ZSTEP);
|
||||
}
|
||||
inline bool isZMove() {
|
||||
return (dir & ZSTEP);
|
||||
}
|
||||
inline bool isEMove() {
|
||||
return (dir & ESTEP);
|
||||
}
|
||||
inline bool isEOnlyMove() {
|
||||
return (dir & XYZE_STEP) == ESTEP;
|
||||
}
|
||||
inline bool isNoMove() {
|
||||
return (dir & XYZE_STEP) == 0;
|
||||
}
|
||||
inline bool isXYZMove() {
|
||||
return dir & XYZ_STEP;
|
||||
}
|
||||
inline bool isMoveOfAxis(uint8_t axis) {
|
||||
return (dir & (XSTEP << axis));
|
||||
}
|
||||
inline void setMoveOfAxis(uint8_t axis) {
|
||||
dir |= XSTEP << axis;
|
||||
}
|
||||
inline void setPositiveDirectionForAxis(uint8_t axis) {
|
||||
dir |= X_DIRPOS << axis;
|
||||
}
|
||||
inline static void resetPathPlanner() {
|
||||
linesCount = 0;
|
||||
linesPos = linesWritePos;
|
||||
Printer::setMenuMode(MENU_MODE_PRINTING, Printer::isPrinting());
|
||||
}
|
||||
// Only called from bresenham -> inside interrupt handle
|
||||
inline void updateAdvanceSteps(speed_t v, uint8_t max_loops, bool accelerate) {
|
||||
#if USE_ADVANCE
|
||||
if(!Printer::isAdvanceActivated()) return;
|
||||
#if ENABLE_QUADRATIC_ADVANCE
|
||||
long advanceTarget = Printer::advanceExecuted;
|
||||
if(accelerate) {
|
||||
for(uint8_t loop = 0; loop < max_loops; loop++) advanceTarget += advanceRate;
|
||||
if(advanceTarget > advanceFull)
|
||||
advanceTarget = advanceFull;
|
||||
} else {
|
||||
for(uint8_t loop = 0; loop < max_loops; loop++) advanceTarget -= advanceRate;
|
||||
if(advanceTarget < advanceEnd)
|
||||
advanceTarget = advanceEnd;
|
||||
}
|
||||
long h = HAL::mulu16xu16to32(v, advanceL);
|
||||
int tred = ((advanceTarget + h) >> 16);
|
||||
HAL::forbidInterrupts();
|
||||
Printer::extruderStepsNeeded += tred - Printer::advanceStepsSet;
|
||||
if(tred > 0 && Printer::advanceStepsSet <= 0)
|
||||
Printer::extruderStepsNeeded += Extruder::current->advanceBacklash;
|
||||
else if(tred < 0 && Printer::advanceStepsSet >= 0)
|
||||
Printer::extruderStepsNeeded -= Extruder::current->advanceBacklash;
|
||||
Printer::advanceStepsSet = tred;
|
||||
HAL::allowInterrupts();
|
||||
Printer::advanceExecuted = advanceTarget;
|
||||
#else
|
||||
int tred = HAL::mulu6xu16shift16(v, advanceL);
|
||||
HAL::forbidInterrupts();
|
||||
Printer::extruderStepsNeeded += tred - Printer::advanceStepsSet;
|
||||
if(tred > 0 && Printer::advanceStepsSet <= 0)
|
||||
Printer::extruderStepsNeeded += (Extruder::current->advanceBacklash << 1);
|
||||
else if(tred < 0 && Printer::advanceStepsSet >= 0)
|
||||
Printer::extruderStepsNeeded -= (Extruder::current->advanceBacklash << 1);
|
||||
Printer::advanceStepsSet = tred;
|
||||
HAL::allowInterrupts();
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
INLINE bool moveDecelerating() {
|
||||
if(stepsRemaining <= static_cast<int32_t>(decelSteps)) {
|
||||
if (!(flags & FLAG_DECELERATING)) {
|
||||
Printer::timer = 0;
|
||||
flags |= FLAG_DECELERATING;
|
||||
}
|
||||
return true;
|
||||
} else return false;
|
||||
}
|
||||
INLINE bool moveAccelerating() {
|
||||
return Printer::stepNumber <= accelSteps;
|
||||
}
|
||||
INLINE void startXStep() {
|
||||
#if !(GANTRY) || defined(FAST_COREXYZ)
|
||||
Printer::startXStep();
|
||||
#else
|
||||
#if DRIVE_SYSTEM == XY_GANTRY || DRIVE_SYSTEM == XZ_GANTRY
|
||||
if(isXPositiveMove()) {
|
||||
Printer::motorX++;
|
||||
Printer::motorYorZ++;
|
||||
} else {
|
||||
Printer::motorX--;
|
||||
Printer::motorYorZ--;
|
||||
}
|
||||
#endif
|
||||
#if DRIVE_SYSTEM == YX_GANTRY || DRIVE_SYSTEM == ZX_GANTRY
|
||||
if(isXPositiveMove()) {
|
||||
Printer::motorX++;
|
||||
Printer::motorYorZ--;
|
||||
} else {
|
||||
Printer::motorX--;
|
||||
Printer::motorYorZ++;
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
#ifdef DEBUG_STEPCOUNT
|
||||
totalStepsRemaining--;
|
||||
#endif
|
||||
}
|
||||
INLINE void startYStep() {
|
||||
#if !(GANTRY) || DRIVE_SYSTEM == ZX_GANTRY || DRIVE_SYSTEM == XZ_GANTRY || defined(FAST_COREXYZ)
|
||||
Printer::startYStep();
|
||||
#else
|
||||
#if DRIVE_SYSTEM == XY_GANTRY
|
||||
if(isYPositiveMove()) {
|
||||
Printer::motorX++;
|
||||
Printer::motorYorZ--;
|
||||
} else {
|
||||
Printer::motorX--;
|
||||
Printer::motorYorZ++;
|
||||
}
|
||||
#endif
|
||||
#if DRIVE_SYSTEM == YX_GANTRY
|
||||
if(isYPositiveMove()) {
|
||||
Printer::motorX++;
|
||||
Printer::motorYorZ++;
|
||||
} else {
|
||||
Printer::motorX--;
|
||||
Printer::motorYorZ--;
|
||||
}
|
||||
#endif
|
||||
#endif // GANTRY
|
||||
#ifdef DEBUG_STEPCOUNT
|
||||
totalStepsRemaining--;
|
||||
#endif
|
||||
|
||||
}
|
||||
INLINE void startZStep() {
|
||||
#if !(GANTRY) || DRIVE_SYSTEM == YX_GANTRY || DRIVE_SYSTEM == XY_GANTRY || defined(FAST_COREXYZ)
|
||||
Printer::startZStep();
|
||||
#else
|
||||
#if DRIVE_SYSTEM == XZ_GANTRY
|
||||
if(isZPositiveMove()) {
|
||||
Printer::motorX++;
|
||||
Printer::motorYorZ--;
|
||||
} else {
|
||||
Printer::motorX--;
|
||||
Printer::motorYorZ++;
|
||||
}
|
||||
#endif
|
||||
#if DRIVE_SYSTEM == ZX_GANTRY
|
||||
if(isZPositiveMove()) {
|
||||
Printer::motorX++;
|
||||
Printer::motorYorZ++;
|
||||
} else {
|
||||
Printer::motorX--;
|
||||
Printer::motorYorZ--;
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
#ifdef DEBUG_STEPCOUNT
|
||||
totalStepsRemaining--;
|
||||
#endif
|
||||
}
|
||||
void updateStepsParameter();
|
||||
float safeSpeed(fast8_t drivingAxis);
|
||||
void calculateMove(float axis_diff[], uint8_t pathOptimize, fast8_t distanceBase);
|
||||
void logLine();
|
||||
INLINE long getWaitTicks() {
|
||||
return timeInTicks;
|
||||
}
|
||||
INLINE void setWaitTicks(long wait) {
|
||||
timeInTicks = wait;
|
||||
}
|
||||
|
||||
static INLINE bool hasLines() {
|
||||
return linesCount;
|
||||
}
|
||||
static INLINE void setCurrentLine() {
|
||||
cur = &lines[linesPos];
|
||||
#if CPU_ARCH==ARCH_ARM
|
||||
PrintLine::nlFlag = true;
|
||||
#endif
|
||||
}
|
||||
// Only called from within interrupts
|
||||
static INLINE void removeCurrentLineForbidInterrupt() {
|
||||
nextPlannerIndex(linesPos);
|
||||
cur = NULL;
|
||||
#if CPU_ARCH == ARCH_ARM
|
||||
nlFlag = false;
|
||||
#endif
|
||||
HAL::forbidInterrupts();
|
||||
--linesCount;
|
||||
if(!linesCount)
|
||||
Printer::setMenuMode(MENU_MODE_PRINTING, Printer::isPrinting());
|
||||
}
|
||||
static INLINE void pushLine() {
|
||||
nextPlannerIndex(linesWritePos);
|
||||
Printer::setMenuMode(MENU_MODE_PRINTING, true);
|
||||
InterruptProtectedBlock noInts;
|
||||
linesCount++;
|
||||
}
|
||||
static uint8_t getLinesCount() {
|
||||
InterruptProtectedBlock noInts;
|
||||
return linesCount;
|
||||
}
|
||||
static PrintLine *getNextWriteLine() {
|
||||
return &lines[linesWritePos];
|
||||
}
|
||||
static inline void computeMaxJunctionSpeed(PrintLine *previous, PrintLine *current);
|
||||
static int32_t bresenhamStep();
|
||||
static void waitForXFreeLines(uint8_t b = 1, bool allowMoves = false);
|
||||
static inline void forwardPlanner(ufast8_t p);
|
||||
static inline void backwardPlanner(ufast8_t p, ufast8_t last);
|
||||
static void updateTrapezoids();
|
||||
static uint8_t insertWaitMovesIfNeeded(uint8_t pathOptimize, uint8_t waitExtraLines);
|
||||
static void LaserWarmUp(uint32_t wait);
|
||||
#if !NONLINEAR_SYSTEM || defined(DOXYGEN)
|
||||
static void queueCartesianMove(uint8_t check_endstops, uint8_t pathOptimize);
|
||||
#if DISTORTION_CORRECTION || defined(DOXYGEN)
|
||||
static void queueCartesianSegmentTo(uint8_t check_endstops, uint8_t pathOptimize);
|
||||
#endif
|
||||
#endif
|
||||
static void moveRelativeDistanceInSteps(int32_t x, int32_t y, int32_t z, int32_t e, float feedrate, bool waitEnd, bool check_endstop, bool pathOptimize = true);
|
||||
static void moveRelativeDistanceInStepsReal(int32_t x, int32_t y, int32_t z, int32_t e, float feedrate, bool waitEnd, bool pathOptimize = true);
|
||||
#if ARC_SUPPORT || defined(DOXYGEN)
|
||||
static void arc(float *position, float *target, float *offset, float radius, uint8_t isclockwise);
|
||||
#endif
|
||||
static INLINE void previousPlannerIndex(ufast8_t &p) {
|
||||
p = (p ? p - 1 : PRINTLINE_CACHE_SIZE - 1);
|
||||
}
|
||||
static INLINE void nextPlannerIndex(ufast8_t& p) {
|
||||
p = (p >= PRINTLINE_CACHE_SIZE - 1 ? 0 : p + 1);
|
||||
}
|
||||
#if NONLINEAR_SYSTEM || defined(DOXYGEN)
|
||||
static uint8_t queueNonlinearMove(uint8_t check_endstops, uint8_t pathOptimize, uint8_t softEndstop);
|
||||
static inline void queueEMove(int32_t e_diff, uint8_t check_endstops, uint8_t pathOptimize);
|
||||
inline uint16_t calculateNonlinearSubSegments(uint8_t softEndstop);
|
||||
static inline void calculateDirectionAndDelta(int32_t difference[], ufast8_t *dir, int32_t delta[]);
|
||||
static inline uint8_t calculateDistance(float axis_diff[], uint8_t dir, float *distance);
|
||||
#if (SOFTWARE_LEVELING && DRIVE_SYSTEM == DELTA) || defined(DOXYGEN)
|
||||
static void calculatePlane(int32_t factors[], int32_t p1[], int32_t p2[], int32_t p3[]);
|
||||
static float calcZOffset(int32_t factors[], int32_t pointX, int32_t pointY);
|
||||
#endif
|
||||
#endif
|
||||
};
|
||||
|
||||
|
||||
|
||||
#endif // MOTION_H_INCLUDED
|
3244
Repetier-Firmware 1.0.3/Repetier/pins.h
Normal file
3244
Repetier-Firmware 1.0.3/Repetier/pins.h
Normal file
File diff suppressed because it is too large
Load Diff
40
Repetier-Firmware 1.0.3/Repetier/src/SdFat/BlockDriver.h
Normal file
40
Repetier-Firmware 1.0.3/Repetier/src/SdFat/BlockDriver.h
Normal file
@ -0,0 +1,40 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
/**
|
||||
* \file
|
||||
* \brief Define block driver.
|
||||
*/
|
||||
#ifndef BlockDriver_h
|
||||
#define BlockDriver_h
|
||||
#include "FatLib/BaseBlockDriver.h"
|
||||
#include "SdCard/SdSpiCard.h"
|
||||
//-----------------------------------------------------------------------------
|
||||
/** typedef for BlockDriver */
|
||||
#if ENABLE_EXTENDED_TRANSFER_CLASS || ENABLE_SDIO_CLASS
|
||||
typedef BaseBlockDriver BlockDriver;
|
||||
#else // ENABLE_EXTENDED_TRANSFER_CLASS || ENABLE_SDIO_CLASS
|
||||
typedef SdSpiCard BlockDriver;
|
||||
#endif // ENABLE_EXTENDED_TRANSFER_CLASS || ENABLE_SDIO_CLASS
|
||||
#endif // BlockDriver_h
|
249
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/ArduinoFiles.h
Normal file
249
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/ArduinoFiles.h
Normal file
@ -0,0 +1,249 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
/**
|
||||
* \file
|
||||
* \brief PrintFile class
|
||||
*/
|
||||
#ifndef ArduinoFiles_h
|
||||
#define ArduinoFiles_h
|
||||
#include "FatLibConfig.h"
|
||||
#if ENABLE_ARDUINO_FEATURES
|
||||
#include "FatFile.h"
|
||||
#include <limits.h>
|
||||
//------------------------------------------------------------------------------
|
||||
/** Arduino SD.h style flag for open for read. */
|
||||
#define FILE_READ O_READ
|
||||
/** Arduino SD.h style flag for open at EOF for read/write with create. */
|
||||
#define FILE_WRITE (O_RDWR | O_CREAT | O_AT_END)
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class PrintFile
|
||||
* \brief FatFile with Print.
|
||||
*/
|
||||
class PrintFile : public FatFile, public Print {
|
||||
public:
|
||||
PrintFile() {}
|
||||
/** Create a file object and open it in the current working directory.
|
||||
*
|
||||
* \param[in] path A path for a file to be opened.
|
||||
*
|
||||
* \param[in] oflag Values for \a oflag are constructed by a
|
||||
* bitwise-inclusive OR of open flags. see
|
||||
* FatFile::open(FatFile*, const char*, uint8_t).
|
||||
*/
|
||||
PrintFile(const char* path, uint8_t oflag) : FatFile(path, oflag) {}
|
||||
#if DESTRUCTOR_CLOSES_FILE
|
||||
~PrintFile() {}
|
||||
#endif // DESTRUCTOR_CLOSES_FILE
|
||||
using FatFile::clearWriteError;
|
||||
using FatFile::getWriteError;
|
||||
using FatFile::read;
|
||||
using FatFile::write;
|
||||
/** \return number of bytes available from the current position to EOF
|
||||
* or INT_MAX if more than INT_MAX bytes are available.
|
||||
*/
|
||||
int available() {
|
||||
uint32_t n = FatFile::available();
|
||||
return n > INT_MAX ? INT_MAX : n;
|
||||
}
|
||||
/** Ensure that any bytes written to the file are saved to the SD card. */
|
||||
void flush() {
|
||||
FatFile::sync();
|
||||
}
|
||||
/** Return the next available byte without consuming it.
|
||||
*
|
||||
* \return The byte if no error and not at eof else -1;
|
||||
*/
|
||||
int peek() {
|
||||
return FatFile::peek();
|
||||
}
|
||||
/** Read the next byte from a file.
|
||||
*
|
||||
* \return For success return the next byte in the file as an int.
|
||||
* If an error occurs or end of file is reached return -1.
|
||||
*/
|
||||
// int read() {
|
||||
// return FatFile::read();
|
||||
// }
|
||||
/** Write a byte to a file. Required by the Arduino Print class.
|
||||
* \param[in] b the byte to be written.
|
||||
* Use getWriteError to check for errors.
|
||||
* \return 1 for success and 0 for failure.
|
||||
*/
|
||||
size_t write(uint8_t b) {
|
||||
return FatFile::write(b);
|
||||
}
|
||||
/** Write data to an open file. Form required by Print.
|
||||
*
|
||||
* \note Data is moved to the cache but may not be written to the
|
||||
* storage device until sync() is called.
|
||||
*
|
||||
* \param[in] buf Pointer to the location of the data to be written.
|
||||
*
|
||||
* \param[in] size Number of bytes to write.
|
||||
*
|
||||
* \return For success write() returns the number of bytes written, always
|
||||
* \a nbyte. If an error occurs, write() returns -1. Possible errors
|
||||
* include write() is called before a file has been opened, write is called
|
||||
* for a read-only file, device is full, a corrupt file system or an
|
||||
* I/O error.
|
||||
*/
|
||||
size_t write(const uint8_t *buf, size_t size) {
|
||||
return FatFile::write(buf, size);
|
||||
}
|
||||
};
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class File
|
||||
* \brief Arduino SD.h style File API
|
||||
*/
|
||||
class File : public FatFile, public Stream {
|
||||
public:
|
||||
File() {}
|
||||
/** Create a file object and open it in the current working directory.
|
||||
*
|
||||
* \param[in] path A path with a valid 8.3 DOS name for a file to be opened.
|
||||
*
|
||||
* \param[in] oflag Values for \a oflag are constructed by a
|
||||
* bitwise-inclusive OR of open flags. see
|
||||
* FatFile::open(FatFile*, const char*, uint8_t).
|
||||
*/
|
||||
File(const char* path, uint8_t oflag) {
|
||||
open(path, oflag);
|
||||
}
|
||||
using FatFile::clearWriteError;
|
||||
using FatFile::getWriteError;
|
||||
using FatFile::read;
|
||||
using FatFile::write;
|
||||
/** The parenthesis operator.
|
||||
*
|
||||
* \return true if a file is open.
|
||||
*/
|
||||
operator bool() {
|
||||
return isOpen();
|
||||
}
|
||||
/** \return number of bytes available from the current position to EOF
|
||||
* or INT_MAX if more than INT_MAX bytes are available.
|
||||
*/
|
||||
int available() {
|
||||
uint32_t n = FatFile::available();
|
||||
return n > INT_MAX ? INT_MAX : n;
|
||||
}
|
||||
/** Ensure that any bytes written to the file are saved to the SD card. */
|
||||
void flush() {
|
||||
FatFile::sync();
|
||||
}
|
||||
/** This function reports if the current file is a directory or not.
|
||||
* \return true if the file is a directory.
|
||||
*/
|
||||
bool isDirectory() {
|
||||
return isDir();
|
||||
}
|
||||
/** No longer implemented due to Long File Names.
|
||||
*
|
||||
* Use getName(char* name, size_t size).
|
||||
* \return a pointer to replacement suggestion.
|
||||
*/
|
||||
const char* name() const {
|
||||
return "use getName()";
|
||||
}
|
||||
/** Return the next available byte without consuming it.
|
||||
*
|
||||
* \return The byte if no error and not at eof else -1;
|
||||
*/
|
||||
int peek() {
|
||||
return FatFile::peek();
|
||||
}
|
||||
/** \return the current file position. */
|
||||
uint32_t position() {
|
||||
return curPosition();
|
||||
}
|
||||
/** Opens the next file or folder in a directory.
|
||||
*
|
||||
* \param[in] mode open mode flags.
|
||||
* \return a File object.
|
||||
*/
|
||||
File openNextFile(uint8_t mode = O_READ) {
|
||||
File tmpFile;
|
||||
tmpFile.openNext(this, mode);
|
||||
return tmpFile;
|
||||
}
|
||||
/** Read the next byte from a file.
|
||||
*
|
||||
* \return For success return the next byte in the file as an int.
|
||||
* If an error occurs or end of file is reached return -1.
|
||||
*/
|
||||
int read() {
|
||||
return FatFile::read();
|
||||
}
|
||||
/** Rewind a file if it is a directory */
|
||||
void rewindDirectory() {
|
||||
if (isDir()) {
|
||||
rewind();
|
||||
}
|
||||
}
|
||||
/**
|
||||
* Seek to a new position in the file, which must be between
|
||||
* 0 and the size of the file (inclusive).
|
||||
*
|
||||
* \param[in] pos the new file position.
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool seek(uint32_t pos) {
|
||||
return seekSet(pos);
|
||||
}
|
||||
/** \return the file's size. */
|
||||
uint32_t size() {
|
||||
return fileSize();
|
||||
}
|
||||
/** Write a byte to a file. Required by the Arduino Print class.
|
||||
* \param[in] b the byte to be written.
|
||||
* Use getWriteError to check for errors.
|
||||
* \return 1 for success and 0 for failure.
|
||||
*/
|
||||
size_t write(uint8_t b) {
|
||||
return FatFile::write(b);
|
||||
}
|
||||
/** Write data to an open file. Form required by Print.
|
||||
*
|
||||
* \note Data is moved to the cache but may not be written to the
|
||||
* storage device until sync() is called.
|
||||
*
|
||||
* \param[in] buf Pointer to the location of the data to be written.
|
||||
*
|
||||
* \param[in] size Number of bytes to write.
|
||||
*
|
||||
* \return For success write() returns the number of bytes written, always
|
||||
* \a nbyte. If an error occurs, write() returns -1. Possible errors
|
||||
* include write() is called before a file has been opened, write is called
|
||||
* for a read-only file, device is full, a corrupt file system or an
|
||||
* I/O error.
|
||||
*/
|
||||
size_t write(const uint8_t *buf, size_t size) {
|
||||
return FatFile::write(buf, size);
|
||||
}
|
||||
};
|
||||
#endif // ENABLE_ARDUINO_FEATURES
|
||||
#endif // ArduinoFiles_h
|
@ -0,0 +1,153 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef ArduinoStream_h
|
||||
#define ArduinoStream_h
|
||||
/**
|
||||
* \file
|
||||
* \brief ArduinoInStream and ArduinoOutStream classes
|
||||
*/
|
||||
#include "FatLibConfig.h"
|
||||
#if ENABLE_ARDUINO_FEATURES
|
||||
#include "bufstream.h"
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class ArduinoInStream
|
||||
* \brief Input stream for Arduino Stream objects
|
||||
*/
|
||||
class ArduinoInStream : public ibufstream {
|
||||
public:
|
||||
/**
|
||||
* Constructor
|
||||
* \param[in] hws hardware stream
|
||||
* \param[in] buf buffer for input line
|
||||
* \param[in] size size of input buffer
|
||||
*/
|
||||
ArduinoInStream(Stream &hws, char* buf, size_t size) {
|
||||
m_hw = &hws;
|
||||
m_line = buf;
|
||||
m_size = size;
|
||||
}
|
||||
/** read a line. */
|
||||
void readline() {
|
||||
size_t i = 0;
|
||||
uint32_t t;
|
||||
m_line[0] = '\0';
|
||||
while (!m_hw->available()) {
|
||||
yield();
|
||||
}
|
||||
|
||||
while (1) {
|
||||
t = millis();
|
||||
while (!m_hw->available()) {
|
||||
if ((millis() - t) > 10) {
|
||||
goto done;
|
||||
}
|
||||
}
|
||||
if (i >= (m_size - 1)) {
|
||||
setstate(failbit);
|
||||
return;
|
||||
}
|
||||
m_line[i++] = m_hw->read();
|
||||
m_line[i] = '\0';
|
||||
}
|
||||
done:
|
||||
init(m_line);
|
||||
}
|
||||
|
||||
protected:
|
||||
/** Internal - do not use.
|
||||
* \param[in] off
|
||||
* \param[in] way
|
||||
* \return true/false.
|
||||
*/
|
||||
bool seekoff(off_type off, seekdir way) {
|
||||
(void)off;
|
||||
(void)way;
|
||||
return false;
|
||||
}
|
||||
/** Internal - do not use.
|
||||
* \param[in] pos
|
||||
* \return true/false.
|
||||
*/
|
||||
bool seekpos(pos_type pos) {
|
||||
(void)pos;
|
||||
return false;
|
||||
}
|
||||
|
||||
private:
|
||||
char *m_line;
|
||||
size_t m_size;
|
||||
Stream* m_hw;
|
||||
};
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class ArduinoOutStream
|
||||
* \brief Output stream for Arduino Print objects
|
||||
*/
|
||||
class ArduinoOutStream : public ostream {
|
||||
public:
|
||||
/** constructor
|
||||
*
|
||||
* \param[in] pr Print object for this ArduinoOutStream.
|
||||
*/
|
||||
explicit ArduinoOutStream(Print& pr) : m_pr(&pr) {}
|
||||
|
||||
protected:
|
||||
/// @cond SHOW_PROTECTED
|
||||
/**
|
||||
* Internal do not use
|
||||
* \param[in] c
|
||||
*/
|
||||
void putch(char c) {
|
||||
if (c == '\n') {
|
||||
m_pr->write('\r');
|
||||
}
|
||||
m_pr->write(c);
|
||||
}
|
||||
void putstr(const char* str) {
|
||||
m_pr->write(str);
|
||||
}
|
||||
bool seekoff(off_type off, seekdir way) {
|
||||
(void)off;
|
||||
(void)way;
|
||||
return false;
|
||||
}
|
||||
bool seekpos(pos_type pos) {
|
||||
(void)pos;
|
||||
return false;
|
||||
}
|
||||
bool sync() {
|
||||
return true;
|
||||
}
|
||||
pos_type tellpos() {
|
||||
return 0;
|
||||
}
|
||||
/// @endcond
|
||||
private:
|
||||
ArduinoOutStream() {}
|
||||
Print* m_pr;
|
||||
};
|
||||
#endif // ENABLE_ARDUINO_FEATURES
|
||||
#endif // ArduinoStream_h
|
@ -0,0 +1,80 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef BaseBlockDriver_h
|
||||
#define BaseBlockDriver_h
|
||||
#include "FatLibConfig.h"
|
||||
/**
|
||||
* \class BaseBlockDriver
|
||||
* \brief Base block driver.
|
||||
*/
|
||||
class BaseBlockDriver {
|
||||
public:
|
||||
/**
|
||||
* Read a 512 byte block from an SD card.
|
||||
*
|
||||
* \param[in] block Logical block to be read.
|
||||
* \param[out] dst Pointer to the location that will receive the data.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
virtual bool readBlock(uint32_t block, uint8_t* dst) = 0;
|
||||
/** End multi-block transfer and go to idle state.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
virtual bool syncBlocks() = 0;
|
||||
/**
|
||||
* Writes a 512 byte block to an SD card.
|
||||
*
|
||||
* \param[in] block Logical block to be written.
|
||||
* \param[in] src Pointer to the location of the data to be written.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
virtual bool writeBlock(uint32_t block, const uint8_t* src) = 0;
|
||||
#if USE_MULTI_BLOCK_IO
|
||||
/**
|
||||
* Read multiple 512 byte blocks from an SD card.
|
||||
*
|
||||
* \param[in] block Logical block to be read.
|
||||
* \param[in] nb Number of blocks to be read.
|
||||
* \param[out] dst Pointer to the location that will receive the data.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
virtual bool readBlocks(uint32_t block, uint8_t* dst, size_t nb) = 0;
|
||||
/**
|
||||
* Write multiple 512 byte blocks to an SD card.
|
||||
*
|
||||
* \param[in] block Logical block to be written.
|
||||
* \param[in] nb Number of blocks to be written.
|
||||
* \param[in] src Pointer to the location of the data to be written.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
virtual bool writeBlocks(uint32_t block, const uint8_t* src, size_t nb) = 0;
|
||||
#endif // USE_MULTI_BLOCK_IO
|
||||
};
|
||||
#endif // BaseBlockDriver_h
|
@ -0,0 +1,72 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef FatApiConstants_h
|
||||
#define FatApiConstants_h
|
||||
//------------------------------------------------------------------------------
|
||||
// use the gnu style oflag in open()
|
||||
/** open() oflag for reading */
|
||||
const uint8_t O_READ = 0X01;
|
||||
/** open() oflag - same as O_IN */
|
||||
const uint8_t O_RDONLY = O_READ;
|
||||
/** open() oflag for write */
|
||||
const uint8_t O_WRITE = 0X02;
|
||||
/** open() oflag - same as O_WRITE */
|
||||
const uint8_t O_WRONLY = O_WRITE;
|
||||
/** open() oflag for reading and writing */
|
||||
const uint8_t O_RDWR = (O_READ | O_WRITE);
|
||||
/** open() oflag mask for access modes */
|
||||
const uint8_t O_ACCMODE = (O_READ | O_WRITE);
|
||||
/** The file offset shall be set to the end of the file prior to each write. */
|
||||
const uint8_t O_APPEND = 0X04;
|
||||
/** synchronous writes - call sync() after each write */
|
||||
const uint8_t O_SYNC = 0X08;
|
||||
/** truncate the file to zero length */
|
||||
const uint8_t O_TRUNC = 0X10;
|
||||
/** set the initial position at the end of the file */
|
||||
const uint8_t O_AT_END = 0X20;
|
||||
/** create the file if nonexistent */
|
||||
const uint8_t O_CREAT = 0X40;
|
||||
/** If O_CREAT and O_EXCL are set, open() shall fail if the file exists */
|
||||
const uint8_t O_EXCL = 0X80;
|
||||
|
||||
// FatFile class static and const definitions
|
||||
// flags for ls()
|
||||
/** ls() flag for list all files including hidden. */
|
||||
const uint8_t LS_A = 1;
|
||||
/** ls() flag to print modify. date */
|
||||
const uint8_t LS_DATE = 2;
|
||||
/** ls() flag to print file size. */
|
||||
const uint8_t LS_SIZE = 4;
|
||||
/** ls() flag for recursive list of subdirectories */
|
||||
const uint8_t LS_R = 8;
|
||||
|
||||
// flags for timestamp
|
||||
/** set the file's last access date */
|
||||
const uint8_t T_ACCESS = 1;
|
||||
/** set the file's creation date and time */
|
||||
const uint8_t T_CREATE = 2;
|
||||
/** Set the file's write date and time */
|
||||
const uint8_t T_WRITE = 4;
|
||||
#endif // FatApiConstants_h
|
1497
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/FatFile.cpp
Normal file
1497
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/FatFile.cpp
Normal file
File diff suppressed because it is too large
Load Diff
969
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/FatFile.h
Normal file
969
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/FatFile.h
Normal file
@ -0,0 +1,969 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef FatFile_h
|
||||
#define FatFile_h
|
||||
/**
|
||||
* \file
|
||||
* \brief FatFile class
|
||||
*/
|
||||
// #include <ctype.h>
|
||||
#include <string.h>
|
||||
#include <stddef.h>
|
||||
#include <limits.h>
|
||||
#include "FatLibConfig.h"
|
||||
#include "FatApiConstants.h"
|
||||
#include "FatStructs.h"
|
||||
#include "FatVolume.h"
|
||||
class FatFileSystem;
|
||||
//------------------------------------------------------------------------------
|
||||
// Stuff to store strings in AVR flash.
|
||||
#ifdef __AVR__
|
||||
#include <avr/pgmspace.h>
|
||||
#else // __AVR__
|
||||
#ifndef PSTR
|
||||
/** store literal string in flash for ARM */
|
||||
#define PSTR(x) (x)
|
||||
#endif // PSTR
|
||||
#ifndef pgm_read_byte
|
||||
/** read 8-bits from flash for ARM */
|
||||
#define pgm_read_byte(addr) (*(const unsigned char*)(addr))
|
||||
#endif // pgm_read_byte
|
||||
#ifndef pgm_read_word
|
||||
/** read 16-bits from flash for ARM */
|
||||
#define pgm_read_word(addr) (*(const uint16_t*)(addr))
|
||||
#endif // pgm_read_word
|
||||
#ifndef PROGMEM
|
||||
/** store in flash for ARM */
|
||||
#define PROGMEM
|
||||
#endif // PROGMEM
|
||||
#endif // __AVR__
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* \struct FatPos_t
|
||||
* \brief Internal type for file position - do not use in user apps.
|
||||
*/
|
||||
struct FatPos_t {
|
||||
/** stream position */
|
||||
uint32_t position;
|
||||
/** cluster for position */
|
||||
uint32_t cluster;
|
||||
FatPos_t() : position(0), cluster(0) {}
|
||||
};
|
||||
//------------------------------------------------------------------------------
|
||||
/** Expression for path name separator. */
|
||||
#define isDirSeparator(c) ((c) == '/')
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* \struct fname_t
|
||||
* \brief Internal type for Short File Name - do not use in user apps.
|
||||
*/
|
||||
struct fname_t {
|
||||
/** Flags for base and extension character case and LFN. */
|
||||
uint8_t flags;
|
||||
/** length of Long File Name */
|
||||
size_t len;
|
||||
/** Long File Name start. */
|
||||
const char* lfn;
|
||||
/** position for sequence number */
|
||||
uint8_t seqPos;
|
||||
/** Short File Name */
|
||||
uint8_t sfn[11];
|
||||
};
|
||||
/** Derived from a LFN with loss or conversion of characters. */
|
||||
const uint8_t FNAME_FLAG_LOST_CHARS = 0X01;
|
||||
/** Base-name or extension has mixed case. */
|
||||
const uint8_t FNAME_FLAG_MIXED_CASE = 0X02;
|
||||
/** LFN entries are required for file name. */
|
||||
const uint8_t FNAME_FLAG_NEED_LFN =
|
||||
FNAME_FLAG_LOST_CHARS | FNAME_FLAG_MIXED_CASE;
|
||||
/** Filename base-name is all lower case */
|
||||
const uint8_t FNAME_FLAG_LC_BASE = DIR_NT_LC_BASE;
|
||||
/** Filename extension is all lower case. */
|
||||
const uint8_t FNAME_FLAG_LC_EXT = DIR_NT_LC_EXT;
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class FatFile
|
||||
* \brief Basic file class.
|
||||
*/
|
||||
class FatFile {
|
||||
public:
|
||||
/** Create an instance. */
|
||||
FatFile() : m_attr(FILE_ATTR_CLOSED), m_error(0) {}
|
||||
/** Create a file object and open it in the current working directory.
|
||||
*
|
||||
* \param[in] path A path with a valid 8.3 DOS name for a file to be opened.
|
||||
*
|
||||
* \param[in] oflag Values for \a oflag are constructed by a bitwise-inclusive
|
||||
* OR of open flags. see FatFile::open(FatFile*, const char*, uint8_t).
|
||||
*/
|
||||
FatFile(const char* path, uint8_t oflag) {
|
||||
m_attr = FILE_ATTR_CLOSED;
|
||||
m_error = 0;
|
||||
open(path, oflag);
|
||||
}
|
||||
#if DESTRUCTOR_CLOSES_FILE
|
||||
~FatFile() {
|
||||
if (isOpen()) {
|
||||
close();
|
||||
}
|
||||
}
|
||||
#endif // DESTRUCTOR_CLOSES_FILE
|
||||
|
||||
/** \return value of writeError */
|
||||
bool getWriteError() {
|
||||
return m_error & WRITE_ERROR;
|
||||
}
|
||||
/** Set writeError to zero */
|
||||
void clearWriteError() {
|
||||
m_error &= ~WRITE_ERROR;
|
||||
}
|
||||
/** Clear all error bits. */
|
||||
void clearError() {
|
||||
m_error = 0;
|
||||
}
|
||||
/** \return All error bits. */
|
||||
uint8_t getError() {
|
||||
return m_error;
|
||||
}
|
||||
/** get position for streams
|
||||
* \param[out] pos struct to receive position
|
||||
*/
|
||||
void getpos(FatPos_t* pos);
|
||||
/** set position for streams
|
||||
* \param[out] pos struct with value for new position
|
||||
*/
|
||||
void setpos(FatPos_t* pos);
|
||||
/** \return The number of bytes available from the current position
|
||||
* to EOF for normal files. Zero is returned for directory files.
|
||||
*/
|
||||
uint32_t available() {
|
||||
return isFile() ? fileSize() - curPosition() : 0;
|
||||
}
|
||||
/** Close a file and force cached data and directory information
|
||||
* to be written to the storage device.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool close();
|
||||
/** Check for contiguous file and return its raw block range.
|
||||
*
|
||||
* \param[out] bgnBlock the first block address for the file.
|
||||
* \param[out] endBlock the last block address for the file.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock);
|
||||
/** Create and open a new contiguous file of a specified size.
|
||||
*
|
||||
* \param[in] dirFile The directory where the file will be created.
|
||||
* \param[in] path A path with a validfile name.
|
||||
* \param[in] size The desired file size.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false, is returned for failure.
|
||||
*/
|
||||
bool createContiguous(FatFile* dirFile,
|
||||
const char* path, uint32_t size);
|
||||
/** Create and open a new contiguous file of a specified size.
|
||||
*
|
||||
* \param[in] path A path with a validfile name.
|
||||
* \param[in] size The desired file size.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false, is returned for failure.
|
||||
*/
|
||||
bool createContiguous(const char* path, uint32_t size) {
|
||||
return createContiguous(m_cwd, path, size);
|
||||
}
|
||||
/** \return The current cluster number for a file or directory. */
|
||||
uint32_t curCluster() const {
|
||||
return m_curCluster;
|
||||
}
|
||||
/** \return The current position for a file or directory. */
|
||||
uint32_t curPosition() const {
|
||||
return m_curPosition;
|
||||
}
|
||||
/** \return Current working directory */
|
||||
static FatFile* cwd() {
|
||||
return m_cwd;
|
||||
}
|
||||
/** Set the date/time callback function
|
||||
*
|
||||
* \param[in] dateTime The user's call back function. The callback
|
||||
* function is of the form:
|
||||
*
|
||||
* \code
|
||||
* void dateTime(uint16_t* date, uint16_t* time) {
|
||||
* uint16_t year;
|
||||
* uint8_t month, day, hour, minute, second;
|
||||
*
|
||||
* // User gets date and time from GPS or real-time clock here
|
||||
*
|
||||
* // return date using FAT_DATE macro to format fields
|
||||
* *date = FAT_DATE(year, month, day);
|
||||
*
|
||||
* // return time using FAT_TIME macro to format fields
|
||||
* *time = FAT_TIME(hour, minute, second);
|
||||
* }
|
||||
* \endcode
|
||||
*
|
||||
* Sets the function that is called when a file is created or when
|
||||
* a file's directory entry is modified by sync(). All timestamps,
|
||||
* access, creation, and modify, are set when a file is created.
|
||||
* sync() maintains the last access date and last modify date/time.
|
||||
*
|
||||
* See the timestamp() function.
|
||||
*/
|
||||
static void dateTimeCallback(
|
||||
void (*dateTime)(uint16_t* date, uint16_t* time)) {
|
||||
m_dateTime = dateTime;
|
||||
}
|
||||
/** Cancel the date/time callback function. */
|
||||
static void dateTimeCallbackCancel() {
|
||||
m_dateTime = 0;
|
||||
}
|
||||
/** Return a file's directory entry.
|
||||
*
|
||||
* \param[out] dir Location for return of the file's directory entry.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool dirEntry(dir_t* dir);
|
||||
/**
|
||||
* \return The index of this file in it's directory.
|
||||
*/
|
||||
uint16_t dirIndex() {
|
||||
return m_dirIndex;
|
||||
}
|
||||
/** Format the name field of \a dir into the 13 byte array
|
||||
* \a name in standard 8.3 short name format.
|
||||
*
|
||||
* \param[in] dir The directory structure containing the name.
|
||||
* \param[out] name A 13 byte char array for the formatted name.
|
||||
* \return length of the name.
|
||||
*/
|
||||
static uint8_t dirName(const dir_t* dir, char* name);
|
||||
/** \return The number of bytes allocated to a directory or zero
|
||||
* if an error occurs.
|
||||
*/
|
||||
uint32_t dirSize();
|
||||
/** Dump file in Hex
|
||||
* \param[in] pr Print stream for list.
|
||||
* \param[in] pos Start position in file.
|
||||
* \param[in] n number of locations to dump.
|
||||
*/
|
||||
void dmpFile(uint32_t pos, size_t n);
|
||||
/** Test for the existence of a file in a directory
|
||||
*
|
||||
* \param[in] path Path of the file to be tested for.
|
||||
*
|
||||
* The calling instance must be an open directory file.
|
||||
*
|
||||
* dirFile.exists("TOFIND.TXT") searches for "TOFIND.TXT" in the directory
|
||||
* dirFile.
|
||||
*
|
||||
* \return true if the file exists else false.
|
||||
*/
|
||||
bool exists(const char* path) {
|
||||
FatFile file;
|
||||
return file.open(this, path, O_READ);
|
||||
}
|
||||
/**
|
||||
* Get a string from a file.
|
||||
*
|
||||
* fgets() reads bytes from a file into the array pointed to by \a str, until
|
||||
* \a num - 1 bytes are read, or a delimiter is read and transferred to \a str,
|
||||
* or end-of-file is encountered. The string is then terminated
|
||||
* with a null byte.
|
||||
*
|
||||
* fgets() deletes CR, '\\r', from the string. This insures only a '\\n'
|
||||
* terminates the string for Windows text files which use CRLF for newline.
|
||||
*
|
||||
* \param[out] str Pointer to the array where the string is stored.
|
||||
* \param[in] num Maximum number of characters to be read
|
||||
* (including the final null byte). Usually the length
|
||||
* of the array \a str is used.
|
||||
* \param[in] delim Optional set of delimiters. The default is "\n".
|
||||
*
|
||||
* \return For success fgets() returns the length of the string in \a str.
|
||||
* If no data is read, fgets() returns zero for EOF or -1 if an error occurred.
|
||||
*/
|
||||
int16_t fgets(char* str, int16_t num, char* delim = 0);
|
||||
/** \return The total number of bytes in a file. */
|
||||
uint32_t fileSize() const {
|
||||
return m_fileSize;
|
||||
}
|
||||
/** \return The first cluster number for a file or directory. */
|
||||
uint32_t firstCluster() const {
|
||||
return m_firstCluster;
|
||||
}
|
||||
/**
|
||||
* Get a file's name followed by a zero byte.
|
||||
*
|
||||
* \param[out] name An array of characters for the file's name.
|
||||
* \param[in] size The size of the array in bytes. The array
|
||||
* must be at least 13 bytes long. The file's name will be
|
||||
* truncated if the file's name is too long.
|
||||
* \return The value true, is returned for success and
|
||||
* the value false, is returned for failure.
|
||||
*/
|
||||
bool getName(char* name, size_t size);
|
||||
/**
|
||||
* Get a file's Short File Name followed by a zero byte.
|
||||
*
|
||||
* \param[out] name An array of characters for the file's name.
|
||||
* The array must be at least 13 bytes long.
|
||||
* \return The value true, is returned for success and
|
||||
* the value false, is returned for failure.
|
||||
*/
|
||||
bool getSFN(char* name);
|
||||
/** \return True if this is a directory else false. */
|
||||
bool isDir() const {
|
||||
return m_attr & FILE_ATTR_DIR;
|
||||
}
|
||||
/** \return True if this is a normal file else false. */
|
||||
bool isFile() const {
|
||||
return m_attr & FILE_ATTR_FILE;
|
||||
}
|
||||
/** \return True if this is a hidden file else false. */
|
||||
bool isHidden() const {
|
||||
return m_attr & FILE_ATTR_HIDDEN;
|
||||
}
|
||||
/** \return true if this file has a Long File Name. */
|
||||
bool isLFN() const {
|
||||
return m_lfnOrd;
|
||||
}
|
||||
/** \return True if this is an open file/directory else false. */
|
||||
bool isOpen() const {
|
||||
return m_attr;
|
||||
}
|
||||
/** \return True if this is the root directory. */
|
||||
bool isRoot() const {
|
||||
return m_attr & FILE_ATTR_ROOT;
|
||||
}
|
||||
/** \return True if this is the FAT32 root directory. */
|
||||
bool isRoot32() const {
|
||||
return m_attr & FILE_ATTR_ROOT32;
|
||||
}
|
||||
/** \return True if this is the FAT12 of FAT16 root directory. */
|
||||
bool isRootFixed() const {
|
||||
return m_attr & FILE_ATTR_ROOT_FIXED;
|
||||
}
|
||||
/** \return True if file is read-only */
|
||||
bool isReadOnly() const {
|
||||
return m_attr & FILE_ATTR_READ_ONLY;
|
||||
}
|
||||
/** \return True if this is a subdirectory else false. */
|
||||
bool isSubDir() const {
|
||||
return m_attr & FILE_ATTR_SUBDIR;
|
||||
}
|
||||
/** \return True if this is a system file else false. */
|
||||
bool isSystem() const {
|
||||
return m_attr & FILE_ATTR_SYSTEM;
|
||||
}
|
||||
void lsRecursive(uint8_t level, bool isJson);
|
||||
#if JSON_OUTPUT
|
||||
void lsJSON();
|
||||
#endif
|
||||
|
||||
/** Check for a legal 8.3 character.
|
||||
* \param[in] c Character to be checked.
|
||||
* \return true for a legal 8.3 character else false.
|
||||
*/
|
||||
static bool legal83Char(uint8_t c) {
|
||||
if (c == '"' || c == '|') {
|
||||
return false;
|
||||
}
|
||||
// *+,./
|
||||
if (0X2A <= c && c <= 0X2F && c != 0X2D) {
|
||||
return false;
|
||||
}
|
||||
// :;<=>?
|
||||
if (0X3A <= c && c <= 0X3F) {
|
||||
return false;
|
||||
}
|
||||
// [\]
|
||||
if (0X5B <= c && c <= 0X5D) {
|
||||
return false;
|
||||
}
|
||||
return 0X20 < c && c < 0X7F;
|
||||
}
|
||||
/** List directory contents.
|
||||
*
|
||||
* \param[in] pr Print stream for list.
|
||||
*
|
||||
* \param[in] flags The inclusive OR of
|
||||
*
|
||||
* LS_DATE - %Print file modification date
|
||||
*
|
||||
* LS_SIZE - %Print file size.
|
||||
*
|
||||
* LS_R - Recursive list of subdirectories.
|
||||
*
|
||||
* \param[in] indent Amount of space before file name. Used for recursive
|
||||
* list to indicate subdirectory level.
|
||||
*/
|
||||
void ls(uint8_t flags = 0, uint8_t indent = 0);
|
||||
/** Make a new directory.
|
||||
*
|
||||
* \param[in] dir An open FatFile instance for the directory that will
|
||||
* contain the new directory.
|
||||
*
|
||||
* \param[in] path A path with a valid 8.3 DOS name for the new directory.
|
||||
*
|
||||
* \param[in] pFlag Create missing parent directories if true.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool mkdir(FatFile* dir, const char* path, bool pFlag = true);
|
||||
/** Open a file in the volume working directory of a FatFileSystem.
|
||||
*
|
||||
* \param[in] fs File System where the file is located.
|
||||
*
|
||||
* \param[in] path with a valid 8.3 DOS name for a file to be opened.
|
||||
*
|
||||
* \param[in] oflag bitwise-inclusive OR of open mode flags.
|
||||
* See see FatFile::open(FatFile*, const char*, uint8_t).
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool open(FatFileSystem* fs, const char* path, uint8_t oflag);
|
||||
/** Open a file by index.
|
||||
*
|
||||
* \param[in] dirFile An open FatFile instance for the directory.
|
||||
*
|
||||
* \param[in] index The \a index of the directory entry for the file to be
|
||||
* opened. The value for \a index is (directory file position)/32.
|
||||
*
|
||||
* \param[in] oflag bitwise-inclusive OR of open mode flags.
|
||||
* See see FatFile::open(FatFile*, const char*, uint8_t).
|
||||
*
|
||||
* See open() by path for definition of flags.
|
||||
* \return true for success or false for failure.
|
||||
*/
|
||||
bool open(FatFile* dirFile, uint16_t index, uint8_t oflag);
|
||||
/** Open a file or directory by name.
|
||||
*
|
||||
* \param[in] dirFile An open FatFile instance for the directory containing
|
||||
* the file to be opened.
|
||||
*
|
||||
* \param[in] path A path with a valid 8.3 DOS name for a file to be opened.
|
||||
*
|
||||
* \param[in] oflag Values for \a oflag are constructed by a
|
||||
* bitwise-inclusive OR of flags from the following list
|
||||
*
|
||||
* O_READ - Open for reading.
|
||||
*
|
||||
* O_RDONLY - Same as O_READ.
|
||||
*
|
||||
* O_WRITE - Open for writing.
|
||||
*
|
||||
* O_WRONLY - Same as O_WRITE.
|
||||
*
|
||||
* O_RDWR - Open for reading and writing.
|
||||
*
|
||||
* O_APPEND - If set, the file offset shall be set to the end of the
|
||||
* file prior to each write.
|
||||
*
|
||||
* O_AT_END - Set the initial position at the end of the file.
|
||||
*
|
||||
* O_CREAT - If the file exists, this flag has no effect except as noted
|
||||
* under O_EXCL below. Otherwise, the file shall be created
|
||||
*
|
||||
* O_EXCL - If O_CREAT and O_EXCL are set, open() shall fail if the file exists.
|
||||
*
|
||||
* O_SYNC - Call sync() after each write. This flag should not be used with
|
||||
* write(uint8_t) or any functions do character at a time writes since sync()
|
||||
* will be called after each byte.
|
||||
*
|
||||
* O_TRUNC - If the file exists and is a regular file, and the file is
|
||||
* successfully opened and is not read only, its length shall be truncated to 0.
|
||||
*
|
||||
* WARNING: A given file must not be opened by more than one FatFile object
|
||||
* or file corruption may occur.
|
||||
*
|
||||
* \note Directory files must be opened read only. Write and truncation is
|
||||
* not allowed for directory files.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool open(FatFile* dirFile, const char* path, uint8_t oflag);
|
||||
/** Open a file in the current working directory.
|
||||
*
|
||||
* \param[in] path A path with a valid 8.3 DOS name for a file to be opened.
|
||||
*
|
||||
* \param[in] oflag bitwise-inclusive OR of open mode flags.
|
||||
* See see FatFile::open(FatFile*, const char*, uint8_t).
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool open(const char* path, uint8_t oflag = O_READ) {
|
||||
return open(m_cwd, path, oflag);
|
||||
}
|
||||
/** Open the next file or subdirectory in a directory.
|
||||
*
|
||||
* \param[in] dirFile An open FatFile instance for the directory
|
||||
* containing the file to be opened.
|
||||
*
|
||||
* \param[in] oflag bitwise-inclusive OR of open mode flags.
|
||||
* See see FatFile::open(FatFile*, const char*, uint8_t).
|
||||
*
|
||||
* \return true for success or false for failure.
|
||||
*/
|
||||
bool openNext(FatFile* dirFile, uint8_t oflag = O_READ);
|
||||
/** Open a volume's root directory.
|
||||
*
|
||||
* \param[in] vol The FAT volume containing the root directory to be opened.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool openRoot(FatVolume* vol);
|
||||
/** Return the next available byte without consuming it.
|
||||
*
|
||||
* \return The byte if no error and not at eof else -1;
|
||||
*/
|
||||
int peek();
|
||||
/** Print a file's creation date and time
|
||||
*
|
||||
* \param[in] pr Print stream for output.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool printCreateDateTime();
|
||||
/** %Print a directory date field.
|
||||
*
|
||||
* Format is yyyy-mm-dd.
|
||||
*
|
||||
* \param[in] pr Print stream for output.
|
||||
* \param[in] fatDate The date field from a directory entry.
|
||||
*/
|
||||
static void printFatDate(uint16_t fatDate);
|
||||
/** %Print a directory time field.
|
||||
*
|
||||
* Format is hh:mm:ss.
|
||||
*
|
||||
* \param[in] pr Print stream for output.
|
||||
* \param[in] fatTime The time field from a directory entry.
|
||||
*/
|
||||
static void printFatTime(uint16_t fatTime);
|
||||
/** Print a number followed by a field terminator.
|
||||
* \param[in] value The number to be printed.
|
||||
* \param[in] term The field terminator. Use '\\n' for CR LF.
|
||||
* \param[in] prec Number of digits after decimal point.
|
||||
* \return The number of bytes written or -1 if an error occurs.
|
||||
*/
|
||||
int printField(float value, char term, uint8_t prec = 2);
|
||||
/** Print a number followed by a field terminator.
|
||||
* \param[in] value The number to be printed.
|
||||
* \param[in] term The field terminator. Use '\\n' for CR LF.
|
||||
* \return The number of bytes written or -1 if an error occurs.
|
||||
*/
|
||||
int printField(int16_t value, char term);
|
||||
/** Print a number followed by a field terminator.
|
||||
* \param[in] value The number to be printed.
|
||||
* \param[in] term The field terminator. Use '\\n' for CR LF.
|
||||
* \return The number of bytes written or -1 if an error occurs.
|
||||
*/
|
||||
int printField(uint16_t value, char term);
|
||||
/** Print a number followed by a field terminator.
|
||||
* \param[in] value The number to be printed.
|
||||
* \param[in] term The field terminator. Use '\\n' for CR LF.
|
||||
* \return The number of bytes written or -1 if an error occurs.
|
||||
*/
|
||||
int printField(int32_t value, char term);
|
||||
/** Print a number followed by a field terminator.
|
||||
* \param[in] value The number to be printed.
|
||||
* \param[in] term The field terminator. Use '\\n' for CR LF.
|
||||
* \return The number of bytes written or -1 if an error occurs.
|
||||
*/
|
||||
int printField(uint32_t value, char term);
|
||||
/** Print a file's modify date and time
|
||||
*
|
||||
* \param[in] pr Print stream for output.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool printModifyDateTime();
|
||||
/** Print a file's name
|
||||
*
|
||||
* \param[in] pr Print stream for output.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
void printName();
|
||||
/** Print a file's size.
|
||||
*
|
||||
* \param[in] pr Print stream for output.
|
||||
*
|
||||
* \return The number of characters printed is returned
|
||||
* for success and zero is returned for failure.
|
||||
*/
|
||||
void printFileSize();
|
||||
/** Print a file's Short File Name.
|
||||
*
|
||||
* \param[in] pr Print stream for output.
|
||||
*
|
||||
* \return The number of characters printed is returned
|
||||
* for success and zero is returned for failure.
|
||||
*/
|
||||
void printSFN();
|
||||
/** Read the next byte from a file.
|
||||
*
|
||||
* \return For success read returns the next byte in the file as an int.
|
||||
* If an error occurs or end of file is reached -1 is returned.
|
||||
*/
|
||||
int read() {
|
||||
uint8_t b;
|
||||
return read(&b, 1) == 1 ? b : -1;
|
||||
}
|
||||
/** Read data from a file starting at the current position.
|
||||
*
|
||||
* \param[out] buf Pointer to the location that will receive the data.
|
||||
*
|
||||
* \param[in] nbyte Maximum number of bytes to read.
|
||||
*
|
||||
* \return For success read() returns the number of bytes read.
|
||||
* A value less than \a nbyte, including zero, will be returned
|
||||
* if end of file is reached.
|
||||
* If an error occurs, read() returns -1. Possible errors include
|
||||
* read() called before a file has been opened, corrupt file system
|
||||
* or an I/O error occurred.
|
||||
*/
|
||||
int read(void* buf, size_t nbyte);
|
||||
/** Read the next directory entry from a directory file.
|
||||
*
|
||||
* \param[out] dir The dir_t struct that will receive the data.
|
||||
*
|
||||
* \return For success readDir() returns the number of bytes read.
|
||||
* A value of zero will be returned if end of file is reached.
|
||||
* If an error occurs, readDir() returns -1. Possible errors include
|
||||
* readDir() called before a directory has been opened, this is not
|
||||
* a directory file or an I/O error occurred.
|
||||
*/
|
||||
int8_t readDir(dir_t* dir);
|
||||
/** Remove a file.
|
||||
*
|
||||
* The directory entry and all data for the file are deleted.
|
||||
*
|
||||
* \note This function should not be used to delete the 8.3 version of a
|
||||
* file that has a long name. For example if a file has the long name
|
||||
* "New Text Document.txt" you should not delete the 8.3 name "NEWTEX~1.TXT".
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool remove();
|
||||
/** Remove a file.
|
||||
*
|
||||
* The directory entry and all data for the file are deleted.
|
||||
*
|
||||
* \param[in] dirFile The directory that contains the file.
|
||||
* \param[in] path Path for the file to be removed.
|
||||
*
|
||||
* \note This function should not be used to delete the 8.3 version of a
|
||||
* file that has a long name. For example if a file has the long name
|
||||
* "New Text Document.txt" you should not delete the 8.3 name "NEWTEX~1.TXT".
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
static bool remove(FatFile* dirFile, const char* path);
|
||||
/** Set the file's current position to zero. */
|
||||
void rewind() {
|
||||
seekSet(0);
|
||||
}
|
||||
/** Rename a file or subdirectory.
|
||||
*
|
||||
* \param[in] dirFile Directory for the new path.
|
||||
* \param[in] newPath New path name for the file/directory.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool rename(FatFile* dirFile, const char* newPath);
|
||||
/** Remove a directory file.
|
||||
*
|
||||
* The directory file will be removed only if it is empty and is not the
|
||||
* root directory. rmdir() follows DOS and Windows and ignores the
|
||||
* read-only attribute for the directory.
|
||||
*
|
||||
* \note This function should not be used to delete the 8.3 version of a
|
||||
* directory that has a long name. For example if a directory has the
|
||||
* long name "New folder" you should not delete the 8.3 name "NEWFOL~1".
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool rmdir();
|
||||
/** Recursively delete a directory and all contained files.
|
||||
*
|
||||
* This is like the Unix/Linux 'rm -rf *' if called with the root directory
|
||||
* hence the name.
|
||||
*
|
||||
* Warning - This will remove all contents of the directory including
|
||||
* subdirectories. The directory will then be removed if it is not root.
|
||||
* The read-only attribute for files will be ignored.
|
||||
*
|
||||
* \note This function should not be used to delete the 8.3 version of
|
||||
* a directory that has a long name. See remove() and rmdir().
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool rmRfStar();
|
||||
/** Set the files position to current position + \a pos. See seekSet().
|
||||
* \param[in] offset The new position in bytes from the current position.
|
||||
* \return true for success or false for failure.
|
||||
*/
|
||||
bool seekCur(int32_t offset) {
|
||||
return seekSet(m_curPosition + offset);
|
||||
}
|
||||
/** Set the files position to end-of-file + \a offset. See seekSet().
|
||||
* Can't be used for directory files since file size is not defined.
|
||||
* \param[in] offset The new position in bytes from end-of-file.
|
||||
* \return true for success or false for failure.
|
||||
*/
|
||||
bool seekEnd(int32_t offset = 0) {
|
||||
return isFile() ? seekSet(m_fileSize + offset) : false;
|
||||
}
|
||||
/** Sets a file's position.
|
||||
*
|
||||
* \param[in] pos The new position in bytes from the beginning of the file.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool seekSet(uint32_t pos);
|
||||
/** Set the current working directory.
|
||||
*
|
||||
* \param[in] dir New current working directory.
|
||||
*
|
||||
* \return true for success else false.
|
||||
*/
|
||||
static bool setCwd(FatFile* dir) {
|
||||
if (!dir->isDir()) {
|
||||
return false;
|
||||
}
|
||||
m_cwd = dir;
|
||||
return true;
|
||||
}
|
||||
/** \return first block of file or zero for empty file. */
|
||||
uint32_t firstBlock() {
|
||||
if (m_firstCluster) {
|
||||
return m_vol->clusterFirstBlock(m_firstCluster);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
/** The sync() call causes all modified data and directory fields
|
||||
* to be written to the storage device.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool sync();
|
||||
/** Copy a file's timestamps
|
||||
*
|
||||
* \param[in] file File to copy timestamps from.
|
||||
*
|
||||
* \note
|
||||
* Modify and access timestamps may be overwritten if a date time callback
|
||||
* function has been set by dateTimeCallback().
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool timestamp(FatFile* file);
|
||||
/** Set a file's timestamps in its directory entry.
|
||||
*
|
||||
* \param[in] flags Values for \a flags are constructed by a bitwise-inclusive
|
||||
* OR of flags from the following list
|
||||
*
|
||||
* T_ACCESS - Set the file's last access date.
|
||||
*
|
||||
* T_CREATE - Set the file's creation date and time.
|
||||
*
|
||||
* T_WRITE - Set the file's last write/modification date and time.
|
||||
*
|
||||
* \param[in] year Valid range 1980 - 2107 inclusive.
|
||||
*
|
||||
* \param[in] month Valid range 1 - 12 inclusive.
|
||||
*
|
||||
* \param[in] day Valid range 1 - 31 inclusive.
|
||||
*
|
||||
* \param[in] hour Valid range 0 - 23 inclusive.
|
||||
*
|
||||
* \param[in] minute Valid range 0 - 59 inclusive.
|
||||
*
|
||||
* \param[in] second Valid range 0 - 59 inclusive
|
||||
*
|
||||
* \note It is possible to set an invalid date since there is no check for
|
||||
* the number of days in a month.
|
||||
*
|
||||
* \note
|
||||
* Modify and access timestamps may be overwritten if a date time callback
|
||||
* function has been set by dateTimeCallback().
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool timestamp(uint8_t flags, uint16_t year, uint8_t month, uint8_t day,
|
||||
uint8_t hour, uint8_t minute, uint8_t second);
|
||||
/** Type of file. You should use isFile() or isDir() instead of fileType()
|
||||
* if possible.
|
||||
*
|
||||
* \return The file or directory type.
|
||||
*/
|
||||
uint8_t fileAttr() const {
|
||||
return m_attr;
|
||||
}
|
||||
/** Truncate a file to a specified length. The current file position
|
||||
* will be maintained if it is less than or equal to \a length otherwise
|
||||
* it will be set to end of file.
|
||||
*
|
||||
* \param[in] length The desired length for the file.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool truncate(uint32_t length);
|
||||
/** \return FatVolume that contains this file. */
|
||||
FatVolume* volume() const {
|
||||
return m_vol;
|
||||
}
|
||||
/** Write a string to a file. Used by the Arduino Print class.
|
||||
* \param[in] str Pointer to the string.
|
||||
* Use getWriteError to check for errors.
|
||||
* \return count of characters written for success or -1 for failure.
|
||||
*/
|
||||
int write(const char* str) {
|
||||
return write(str, strlen(str));
|
||||
}
|
||||
/** Write a single byte.
|
||||
* \param[in] b The byte to be written.
|
||||
* \return +1 for success or -1 for failure.
|
||||
*/
|
||||
int write(uint8_t b) {
|
||||
return write(&b, 1);
|
||||
}
|
||||
/** Write data to an open file.
|
||||
*
|
||||
* \note Data is moved to the cache but may not be written to the
|
||||
* storage device until sync() is called.
|
||||
*
|
||||
* \param[in] buf Pointer to the location of the data to be written.
|
||||
*
|
||||
* \param[in] nbyte Number of bytes to write.
|
||||
*
|
||||
* \return For success write() returns the number of bytes written, always
|
||||
* \a nbyte. If an error occurs, write() returns -1. Possible errors
|
||||
* include write() is called before a file has been opened, write is called
|
||||
* for a read-only file, device is full, a corrupt file system or an I/O error.
|
||||
*
|
||||
*/
|
||||
int write(const void* buf, size_t nbyte);
|
||||
//------------------------------------------------------------------------------
|
||||
private:
|
||||
/** This file has not been opened. */
|
||||
static const uint8_t FILE_ATTR_CLOSED = 0;
|
||||
/** File is read-only. */
|
||||
static const uint8_t FILE_ATTR_READ_ONLY = DIR_ATT_READ_ONLY;
|
||||
/** File should be hidden in directory listings. */
|
||||
static const uint8_t FILE_ATTR_HIDDEN = DIR_ATT_HIDDEN;
|
||||
/** Entry is for a system file. */
|
||||
static const uint8_t FILE_ATTR_SYSTEM = DIR_ATT_SYSTEM;
|
||||
/** Entry for normal data file */
|
||||
static const uint8_t FILE_ATTR_FILE = 0X08;
|
||||
/** Entry is for a subdirectory */
|
||||
static const uint8_t FILE_ATTR_SUBDIR = DIR_ATT_DIRECTORY;
|
||||
/** A FAT12 or FAT16 root directory */
|
||||
static const uint8_t FILE_ATTR_ROOT_FIXED = 0X20;
|
||||
/** A FAT32 root directory */
|
||||
static const uint8_t FILE_ATTR_ROOT32 = 0X40;
|
||||
/** Entry is for root. */
|
||||
static const uint8_t FILE_ATTR_ROOT = FILE_ATTR_ROOT_FIXED | FILE_ATTR_ROOT32;
|
||||
/** Directory type bits */
|
||||
static const uint8_t FILE_ATTR_DIR = FILE_ATTR_SUBDIR | FILE_ATTR_ROOT;
|
||||
/** Attributes to copy from directory entry */
|
||||
static const uint8_t FILE_ATTR_COPY = DIR_ATT_READ_ONLY | DIR_ATT_HIDDEN |
|
||||
DIR_ATT_SYSTEM | DIR_ATT_DIRECTORY;
|
||||
|
||||
/** experimental don't use */
|
||||
|
||||
bool openParent(FatFile* dir);
|
||||
|
||||
// private functions
|
||||
bool addCluster();
|
||||
bool addDirCluster();
|
||||
dir_t* cacheDirEntry(uint8_t action);
|
||||
static uint8_t lfnChecksum(uint8_t* name);
|
||||
bool lfnUniqueSfn(fname_t* fname);
|
||||
bool openCluster(FatFile* file);
|
||||
static bool parsePathName(const char* str, fname_t* fname, const char** ptr);
|
||||
bool mkdir(FatFile* parent, fname_t* fname);
|
||||
bool open(FatFile* dirFile, fname_t* fname, uint8_t oflag);
|
||||
bool openCachedEntry(FatFile* dirFile, uint16_t cacheIndex, uint8_t oflag,
|
||||
uint8_t lfnOrd);
|
||||
bool readLBN(uint32_t* lbn);
|
||||
dir_t* readDirCache(bool skipReadOk = false);
|
||||
bool setDirSize();
|
||||
|
||||
// bits defined in m_flags
|
||||
// should be 0X0F
|
||||
static const uint8_t F_OFLAG = (O_ACCMODE | O_APPEND | O_SYNC);
|
||||
// sync of directory entry required
|
||||
static const uint8_t F_FILE_DIR_DIRTY = 0X80;
|
||||
|
||||
// global pointer to cwd dir
|
||||
static FatFile* m_cwd;
|
||||
// data time callback function
|
||||
static void (*m_dateTime)(uint16_t* date, uint16_t* time);
|
||||
// private data
|
||||
static const uint8_t WRITE_ERROR = 0X1;
|
||||
static const uint8_t READ_ERROR = 0X2;
|
||||
uint8_t m_attr; // File attributes
|
||||
uint8_t m_error; // Error bits.
|
||||
uint8_t m_flags; // See above for definition of m_flags bits
|
||||
uint8_t m_lfnOrd;
|
||||
uint16_t m_dirIndex; // index of directory entry in dir file
|
||||
FatVolume* m_vol; // volume where file is located
|
||||
uint32_t m_dirCluster;
|
||||
uint32_t m_curCluster; // cluster for current file position
|
||||
uint32_t m_curPosition; // current file position
|
||||
uint32_t m_dirBlock; // block for this files directory entry
|
||||
uint32_t m_fileSize; // file size in bytes
|
||||
uint32_t m_firstCluster; // first cluster of file
|
||||
};
|
||||
#endif // FatFile_h
|
689
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/FatFileLFN.cpp
Normal file
689
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/FatFileLFN.cpp
Normal file
@ -0,0 +1,689 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#include "../../../Repetier.h"
|
||||
#include "FatFile.h"
|
||||
#if SDSUPPORT
|
||||
//------------------------------------------------------------------------------
|
||||
//
|
||||
uint8_t FatFile::lfnChecksum(uint8_t* name) {
|
||||
uint8_t sum = 0;
|
||||
for (uint8_t i = 0; i < 11; i++) {
|
||||
sum = (((sum & 1) << 7) | ((sum & 0xfe) >> 1)) + name[i];
|
||||
}
|
||||
return sum;
|
||||
}
|
||||
#if USE_LONG_FILE_NAMES
|
||||
//------------------------------------------------------------------------------
|
||||
// Saves about 90 bytes of flash on 328 over tolower().
|
||||
inline char lfnToLower(char c) {
|
||||
return 'A' <= c && c <= 'Z' ? c + 'a' - 'A' : c;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// Daniel Bernstein University of Illinois at Chicago.
|
||||
// Original had + instead of ^
|
||||
static uint16_t Bernstein(uint16_t hash, const char *str, size_t len) {
|
||||
for (size_t i = 0; i < len; i++) {
|
||||
// hash = hash * 33 ^ str[i];
|
||||
hash = ((hash << 5) + hash) ^ str[i];
|
||||
}
|
||||
return hash;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Fetch a 16-bit long file name character.
|
||||
*
|
||||
* \param[in] ldir Pointer to long file name directory entry.
|
||||
* \param[in] i Index of character.
|
||||
* \return The 16-bit character.
|
||||
*/
|
||||
static uint16_t lfnGetChar(ldir_t *ldir, uint8_t i) {
|
||||
if (i < LDIR_NAME1_DIM) {
|
||||
return ldir->name1[i];
|
||||
} else if (i < (LDIR_NAME1_DIM + LDIR_NAME2_DIM)) {
|
||||
return ldir->name2[i - LDIR_NAME1_DIM];
|
||||
} else if (i < (LDIR_NAME1_DIM + LDIR_NAME2_DIM + LDIR_NAME2_DIM)) {
|
||||
return ldir->name3[i - LDIR_NAME1_DIM - LDIR_NAME2_DIM];
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
static bool lfnGetName(ldir_t *ldir, char* name, size_t n) {
|
||||
uint8_t i;
|
||||
size_t k = 13*((ldir->ord & 0X1F) - 1);
|
||||
for (i = 0; i < 13; i++) {
|
||||
uint16_t c = lfnGetChar(ldir, i);
|
||||
if (c == 0 || k >= n) {
|
||||
break;
|
||||
}
|
||||
name[k++] = c >= 0X7F ? '?' : c;
|
||||
}
|
||||
// Terminate with zero byte if name fits.
|
||||
if (k < n && (ldir->ord & LDIR_ORD_LAST_LONG_ENTRY)) {
|
||||
name[k] = 0;
|
||||
}
|
||||
// Truncate if name is too long.
|
||||
name[n - 1] = 0;
|
||||
return true;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
inline bool lfnLegalChar(char c) {
|
||||
if (c == '/' || c == '\\' || c == '"' || c == '*' ||
|
||||
c == ':' || c == '<' || c == '>' || c == '?' || c == '|') {
|
||||
return false;
|
||||
}
|
||||
return 0X1F < c && c < 0X7F;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Store a 16-bit long file name character.
|
||||
*
|
||||
* \param[in] ldir Pointer to long file name directory entry.
|
||||
* \param[in] i Index of character.
|
||||
* \param[in] c The 16-bit character.
|
||||
*/
|
||||
static void lfnPutChar(ldir_t *ldir, uint8_t i, uint16_t c) {
|
||||
if (i < LDIR_NAME1_DIM) {
|
||||
ldir->name1[i] = c;
|
||||
} else if (i < (LDIR_NAME1_DIM + LDIR_NAME2_DIM)) {
|
||||
ldir->name2[i - LDIR_NAME1_DIM] = c;
|
||||
} else if (i < (LDIR_NAME1_DIM + LDIR_NAME2_DIM + LDIR_NAME2_DIM)) {
|
||||
ldir->name3[i - LDIR_NAME1_DIM - LDIR_NAME2_DIM] = c;
|
||||
}
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
static void lfnPutName(ldir_t *ldir, const char* name, size_t n) {
|
||||
size_t k = 13*((ldir->ord & 0X1F) - 1);
|
||||
for (uint8_t i = 0; i < 13; i++, k++) {
|
||||
uint16_t c = k < n ? name[k] : k == n ? 0 : 0XFFFF;
|
||||
lfnPutChar(ldir, i, c);
|
||||
}
|
||||
}
|
||||
//==============================================================================
|
||||
bool FatFile::getName(char* name, size_t size) {
|
||||
FatFile dirFile;
|
||||
ldir_t* ldir;
|
||||
if (!isOpen() || size < 13) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
if (!isLFN() || m_lfnOrd > MAX_VFAT_ENTRIES) {
|
||||
return getSFN(name);
|
||||
}
|
||||
if (!dirFile.openCluster(this)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
for (uint8_t ord = 1; ord <= m_lfnOrd; ord++) {
|
||||
if (!dirFile.seekSet(32UL*(m_dirIndex - ord))) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
ldir = reinterpret_cast<ldir_t*>(dirFile.readDirCache());
|
||||
if (!ldir) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
if (ldir->attr != DIR_ATT_LONG_NAME) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
if (ord != (ldir->ord & 0X1F)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
if (!lfnGetName(ldir, name, size)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
if (ldir->ord & LDIR_ORD_LAST_LONG_ENTRY) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
// Fall into fail.
|
||||
DBG_FAIL_MACRO;
|
||||
|
||||
fail:
|
||||
name[0] = 0;
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool FatFile::openCluster(FatFile* file) {
|
||||
if (file->m_dirCluster == 0) {
|
||||
return openRoot(file->m_vol);
|
||||
}
|
||||
memset(this, 0, sizeof(FatFile));
|
||||
m_attr = FILE_ATTR_SUBDIR;
|
||||
m_flags = O_READ;
|
||||
m_vol = file->m_vol;
|
||||
m_firstCluster = file->m_dirCluster;
|
||||
return true;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool FatFile::parsePathName(const char* path,
|
||||
fname_t* fname, const char** ptr) {
|
||||
char c;
|
||||
bool is83;
|
||||
uint8_t bit = DIR_NT_LC_BASE;
|
||||
uint8_t lc = 0;
|
||||
uint8_t uc = 0;
|
||||
uint8_t i = 0;
|
||||
uint8_t in = 7;
|
||||
int end;
|
||||
int len = 0;
|
||||
int si;
|
||||
int dot;
|
||||
|
||||
// Skip leading spaces.
|
||||
while (*path == ' ') {
|
||||
path++;
|
||||
}
|
||||
fname->lfn = path;
|
||||
|
||||
for (len = 0; ; len++) {
|
||||
c = path[len];
|
||||
if (c == 0 || isDirSeparator(c)) {
|
||||
break;
|
||||
}
|
||||
if (!lfnLegalChar(c)) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
// Advance to next path component.
|
||||
for (end = len; path[end] == ' ' || isDirSeparator(path[end]); end++) {}
|
||||
*ptr = &path[end];
|
||||
|
||||
// Back over spaces and dots.
|
||||
while (len) {
|
||||
c = path[len - 1];
|
||||
if (c != '.' && c != ' ') {
|
||||
break;
|
||||
}
|
||||
len--;
|
||||
}
|
||||
// Max length of LFN is 255.
|
||||
if (len > 255) {
|
||||
return false;
|
||||
}
|
||||
fname->len = len;
|
||||
// Blank file short name.
|
||||
for (uint8_t k = 0; k < 11; k++) {
|
||||
fname->sfn[k] = ' ';
|
||||
}
|
||||
// skip leading spaces and dots.
|
||||
for (si = 0; path[si] == '.' || path[si] == ' '; si++) {}
|
||||
// Not 8.3 if leading dot or space.
|
||||
is83 = !si;
|
||||
|
||||
// find last dot.
|
||||
for (dot = len - 1; dot >= 0 && path[dot] != '.'; dot--) {}
|
||||
for (; si < len; si++) {
|
||||
c = path[si];
|
||||
if (c == ' ' || (c == '.' && dot != si)) {
|
||||
is83 = false;
|
||||
continue;
|
||||
}
|
||||
if (!legal83Char(c) && si != dot) {
|
||||
is83 = false;
|
||||
c = '_';
|
||||
}
|
||||
if (si == dot || i > in) {
|
||||
if (in == 10) {
|
||||
// Done - extension longer than three characters.
|
||||
is83 = false;
|
||||
break;
|
||||
}
|
||||
if (si != dot) {
|
||||
is83 = false;
|
||||
}
|
||||
// Break if no dot and base-name is longer than eight characters.
|
||||
if (si > dot) {
|
||||
break;
|
||||
}
|
||||
si = dot;
|
||||
in = 10; // Max index for full 8.3 name.
|
||||
i = 8; // Place for extension.
|
||||
bit = DIR_NT_LC_EXT; // bit for extension.
|
||||
} else {
|
||||
if ('a' <= c && c <= 'z') {
|
||||
c += 'A' - 'a';
|
||||
lc |= bit;
|
||||
} else if ('A' <= c && c <= 'Z') {
|
||||
uc |= bit;
|
||||
}
|
||||
fname->sfn[i++] = c;
|
||||
if (i < 7) {
|
||||
fname->seqPos = i;
|
||||
}
|
||||
}
|
||||
}
|
||||
if (fname->sfn[0] == ' ') {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (is83) {
|
||||
fname->flags = lc & uc ? FNAME_FLAG_MIXED_CASE : lc;
|
||||
} else {
|
||||
fname->flags = FNAME_FLAG_LOST_CHARS;
|
||||
fname->sfn[fname->seqPos] = '~';
|
||||
fname->sfn[fname->seqPos + 1] = '1';
|
||||
}
|
||||
return true;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool FatFile::open(FatFile* dirFile, fname_t* fname, uint8_t oflag) {
|
||||
bool fnameFound = false;
|
||||
uint8_t lfnOrd = 0;
|
||||
uint8_t freeNeed;
|
||||
uint8_t freeFound = 0;
|
||||
uint8_t ord = 0;
|
||||
uint8_t chksum = 0;
|
||||
uint16_t freeIndex = 0;
|
||||
uint16_t curIndex;
|
||||
dir_t* dir;
|
||||
ldir_t* ldir;
|
||||
size_t len = fname->len;
|
||||
|
||||
if (!dirFile->isDir() || isOpen()) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
// Number of directory entries needed.
|
||||
freeNeed = fname->flags & FNAME_FLAG_NEED_LFN ? 1 + (len + 12)/13 : 1;
|
||||
|
||||
dirFile->rewind();
|
||||
while (1) {
|
||||
curIndex = dirFile->m_curPosition/32;
|
||||
dir = dirFile->readDirCache(true);
|
||||
if (!dir) {
|
||||
if (dirFile->getError()) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
// At EOF
|
||||
goto create;
|
||||
}
|
||||
if (dir->name[0] == DIR_NAME_DELETED || dir->name[0] == DIR_NAME_FREE) {
|
||||
if (freeFound == 0) {
|
||||
freeIndex = curIndex;
|
||||
}
|
||||
if (freeFound < freeNeed) {
|
||||
freeFound++;
|
||||
}
|
||||
if (dir->name[0] == DIR_NAME_FREE) {
|
||||
goto create;
|
||||
}
|
||||
} else {
|
||||
if (freeFound < freeNeed) {
|
||||
freeFound = 0;
|
||||
}
|
||||
}
|
||||
// skip empty slot or '.' or '..'
|
||||
if (dir->name[0] == DIR_NAME_DELETED || dir->name[0] == '.') {
|
||||
lfnOrd = 0;
|
||||
} else if (DIR_IS_LONG_NAME(dir)) {
|
||||
ldir_t *ldir = reinterpret_cast<ldir_t*>(dir);
|
||||
if (!lfnOrd) {
|
||||
if ((ldir->ord & LDIR_ORD_LAST_LONG_ENTRY) == 0) {
|
||||
continue;
|
||||
}
|
||||
lfnOrd = ord = ldir->ord & 0X1F;
|
||||
chksum = ldir->chksum;
|
||||
} else if (ldir->ord != --ord || chksum != ldir->chksum) {
|
||||
lfnOrd = 0;
|
||||
continue;
|
||||
}
|
||||
size_t k = 13*(ord - 1);
|
||||
if (k >= len) {
|
||||
// Not found.
|
||||
lfnOrd = 0;
|
||||
continue;
|
||||
}
|
||||
for (uint8_t i = 0; i < 13; i++) {
|
||||
uint16_t u = lfnGetChar(ldir, i);
|
||||
if (k == len) {
|
||||
if (u != 0) {
|
||||
// Not found.
|
||||
lfnOrd = 0;
|
||||
}
|
||||
break;
|
||||
}
|
||||
if (u > 255 || lfnToLower(u) != lfnToLower(fname->lfn[k++])) {
|
||||
// Not found.
|
||||
lfnOrd = 0;
|
||||
break;
|
||||
}
|
||||
}
|
||||
} else if (DIR_IS_FILE_OR_SUBDIR(dir)) {
|
||||
if (lfnOrd) {
|
||||
if (1 == ord && lfnChecksum(dir->name) == chksum) {
|
||||
goto found;
|
||||
}
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
if (!memcmp(dir->name, fname->sfn, sizeof(fname->sfn))) {
|
||||
if (!(fname->flags & FNAME_FLAG_LOST_CHARS)) {
|
||||
goto found;
|
||||
}
|
||||
fnameFound = true;
|
||||
}
|
||||
} else {
|
||||
lfnOrd = 0;
|
||||
}
|
||||
}
|
||||
|
||||
found:
|
||||
// Don't open if create only.
|
||||
if (oflag & O_EXCL) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
goto open;
|
||||
|
||||
create:
|
||||
// don't create unless O_CREAT and O_WRITE
|
||||
if (!(oflag & O_CREAT) || !(oflag & O_WRITE)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
// If at EOF start in next cluster.
|
||||
if (freeFound == 0) {
|
||||
freeIndex = curIndex;
|
||||
}
|
||||
|
||||
while (freeFound < freeNeed) {
|
||||
dir = dirFile->readDirCache();
|
||||
if (!dir) {
|
||||
if (dirFile->getError()) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
// EOF if no error.
|
||||
break;
|
||||
}
|
||||
freeFound++;
|
||||
}
|
||||
while (freeFound < freeNeed) {
|
||||
// Will fail if FAT16 root.
|
||||
if (!dirFile->addDirCluster()) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
// Done if more than one block per cluster. Max freeNeed is 21.
|
||||
if (dirFile->m_vol->blocksPerCluster() > 1) {
|
||||
break;
|
||||
}
|
||||
freeFound += 16;
|
||||
}
|
||||
if (fnameFound) {
|
||||
if (!dirFile->lfnUniqueSfn(fname)) {
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
if (!dirFile->seekSet(32UL*freeIndex)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
lfnOrd = freeNeed - 1;
|
||||
for (uint8_t ord = lfnOrd ; ord ; ord--) {
|
||||
ldir = reinterpret_cast<ldir_t*>(dirFile->readDirCache());
|
||||
if (!ldir) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
dirFile->m_vol->cacheDirty();
|
||||
ldir->ord = ord == lfnOrd ? LDIR_ORD_LAST_LONG_ENTRY | ord : ord;
|
||||
ldir->attr = DIR_ATT_LONG_NAME;
|
||||
ldir->type = 0;
|
||||
ldir->chksum = lfnChecksum(fname->sfn);
|
||||
ldir->mustBeZero = 0;
|
||||
lfnPutName(ldir, fname->lfn, len);
|
||||
}
|
||||
curIndex = dirFile->m_curPosition/32;
|
||||
dir = dirFile->readDirCache();
|
||||
if (!dir) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
// initialize as empty file
|
||||
memset(dir, 0, sizeof(dir_t));
|
||||
memcpy(dir->name, fname->sfn, 11);
|
||||
|
||||
// Set base-name and extension lower case bits.
|
||||
dir->reservedNT = (DIR_NT_LC_BASE | DIR_NT_LC_EXT) & fname->flags;
|
||||
|
||||
// set timestamps
|
||||
if (m_dateTime) {
|
||||
// call user date/time function
|
||||
m_dateTime(&dir->creationDate, &dir->creationTime);
|
||||
} else {
|
||||
// use default date/time
|
||||
dir->creationDate = FAT_DEFAULT_DATE;
|
||||
dir->creationTime = FAT_DEFAULT_TIME;
|
||||
}
|
||||
dir->lastAccessDate = dir->creationDate;
|
||||
dir->lastWriteDate = dir->creationDate;
|
||||
dir->lastWriteTime = dir->creationTime;
|
||||
|
||||
// Force write of entry to device.
|
||||
dirFile->m_vol->cacheDirty();
|
||||
|
||||
open:
|
||||
// open entry in cache.
|
||||
if (!openCachedEntry(dirFile, curIndex, oflag, lfnOrd)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void FatFile::printName() {
|
||||
FatFile dirFile;
|
||||
uint16_t u;
|
||||
size_t n = 0;
|
||||
ldir_t* ldir;
|
||||
|
||||
if (!isLFN()) {
|
||||
printSFN();
|
||||
return;
|
||||
}
|
||||
if (!dirFile.openCluster(this)) {
|
||||
DBG_FAIL_MACRO;
|
||||
return;
|
||||
}
|
||||
for (uint8_t ord = 1; ord <= m_lfnOrd; ord++) {
|
||||
if (!dirFile.seekSet(32UL*(m_dirIndex - ord))) {
|
||||
DBG_FAIL_MACRO;
|
||||
return;
|
||||
}
|
||||
ldir = reinterpret_cast<ldir_t*>(dirFile.readDirCache());
|
||||
if (!ldir) {
|
||||
DBG_FAIL_MACRO;
|
||||
return;
|
||||
}
|
||||
if (ldir->attr != DIR_ATT_LONG_NAME ||
|
||||
ord != (ldir->ord & 0X1F)) {
|
||||
DBG_FAIL_MACRO;
|
||||
return;
|
||||
}
|
||||
for (uint8_t i = 0; i < 13; i++) {
|
||||
u = lfnGetChar(ldir, i);
|
||||
if (u == 0) {
|
||||
// End of name.
|
||||
break;
|
||||
}
|
||||
if (u > 0X7E) {
|
||||
u = '?';
|
||||
}
|
||||
Com::print(static_cast<char>(u));
|
||||
n++;
|
||||
}
|
||||
if (ldir->ord & LDIR_ORD_LAST_LONG_ENTRY) {
|
||||
return;
|
||||
}
|
||||
}
|
||||
// Fall into fail;
|
||||
DBG_FAIL_MACRO;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool FatFile::remove() {
|
||||
bool last;
|
||||
uint8_t chksum;
|
||||
uint8_t ord;
|
||||
FatFile dirFile;
|
||||
dir_t* dir;
|
||||
ldir_t* ldir;
|
||||
|
||||
// Cant' remove not open for write.
|
||||
if (!isFile() || !(m_flags & O_WRITE)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
// Free any clusters.
|
||||
if (m_firstCluster && !m_vol->freeChain(m_firstCluster)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
// Cache directory entry.
|
||||
dir = cacheDirEntry(FatCache::CACHE_FOR_WRITE);
|
||||
if (!dir) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
chksum = lfnChecksum(dir->name);
|
||||
|
||||
// Mark entry deleted.
|
||||
dir->name[0] = DIR_NAME_DELETED;
|
||||
|
||||
// Set this file closed.
|
||||
m_attr = FILE_ATTR_CLOSED;
|
||||
|
||||
// Write entry to device.
|
||||
if (!m_vol->cacheSync()) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
if (!isLFN()) {
|
||||
// Done, no LFN entries.
|
||||
return true;
|
||||
}
|
||||
if (!dirFile.openCluster(this)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
for (ord = 1; ord <= m_lfnOrd; ord++) {
|
||||
if (!dirFile.seekSet(32UL*(m_dirIndex - ord))) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
ldir = reinterpret_cast<ldir_t*>(dirFile.readDirCache());
|
||||
if (!ldir) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
if (ldir->attr != DIR_ATT_LONG_NAME ||
|
||||
ord != (ldir->ord & 0X1F) ||
|
||||
chksum != ldir->chksum) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
last = ldir->ord & LDIR_ORD_LAST_LONG_ENTRY;
|
||||
ldir->ord = DIR_NAME_DELETED;
|
||||
m_vol->cacheDirty();
|
||||
if (last) {
|
||||
if (!m_vol->cacheSync()) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
}
|
||||
// Fall into fail.
|
||||
DBG_FAIL_MACRO;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool FatFile::lfnUniqueSfn(fname_t* fname) {
|
||||
const uint8_t FIRST_HASH_SEQ = 2; // min value is 2
|
||||
uint8_t pos = fname->seqPos;;
|
||||
dir_t *dir;
|
||||
uint16_t hex;
|
||||
|
||||
DBG_HALT_IF(!(fname->flags & FNAME_FLAG_LOST_CHARS));
|
||||
DBG_HALT_IF(fname->sfn[pos] != '~' && fname->sfn[pos + 1] != '1');
|
||||
|
||||
for (uint8_t seq = 2; seq < 100; seq++) {
|
||||
if (seq < FIRST_HASH_SEQ) {
|
||||
fname->sfn[pos + 1] = '0' + seq;
|
||||
} else {
|
||||
DBG_PRINT_IF(seq > FIRST_HASH_SEQ);
|
||||
hex = Bernstein(seq + fname->len, fname->lfn, fname->len);
|
||||
if (pos > 3) {
|
||||
// Make space in name for ~HHHH.
|
||||
pos = 3;
|
||||
}
|
||||
for (uint8_t i = pos + 4 ; i > pos; i--) {
|
||||
uint8_t h = hex & 0XF;
|
||||
fname->sfn[i] = h < 10 ? h + '0' : h + 'A' - 10;
|
||||
hex >>= 4;
|
||||
}
|
||||
}
|
||||
fname->sfn[pos] = '~';
|
||||
rewind();
|
||||
while (1) {
|
||||
dir = readDirCache(true);
|
||||
if (!dir) {
|
||||
if (!getError()) {
|
||||
// At EOF and name not found if no error.
|
||||
goto done;
|
||||
}
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
if (dir->name[0] == DIR_NAME_FREE) {
|
||||
goto done;
|
||||
}
|
||||
if (DIR_IS_FILE_OR_SUBDIR(dir) && !memcmp(fname->sfn, dir->name, 11)) {
|
||||
// Name found - try another.
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
// fall inti fail - too many tries.
|
||||
DBG_FAIL_MACRO;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
|
||||
done:
|
||||
return true;
|
||||
}
|
||||
#endif // #if USE_LONG_FILE_NAMES
|
||||
#endif
|
@ -0,0 +1,373 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#include "../../../Repetier.h"
|
||||
#include <math.h>
|
||||
#include "FatFile.h"
|
||||
#include "FmtNumber.h"
|
||||
#if SDSUPPORT
|
||||
//------------------------------------------------------------------------------
|
||||
// print uint8_t with width 2
|
||||
static void print2u(uint8_t v) {
|
||||
char c0 = '?';
|
||||
char c1 = '?';
|
||||
if (v < 100) {
|
||||
c1 = v/10;
|
||||
c0 = v - 10*c1 + '0';
|
||||
c1 += '0';
|
||||
}
|
||||
Com::print(c1);
|
||||
Com::print(c0);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
static void printU32(uint32_t v) {
|
||||
char buf[11];
|
||||
char* ptr = buf + sizeof(buf);
|
||||
*--ptr = 0;
|
||||
Com::print(fmtDec(v, ptr));
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
static void printHex(uint8_t w, uint16_t h) {
|
||||
char buf[5];
|
||||
char* ptr = buf + sizeof(buf);
|
||||
*--ptr = 0;
|
||||
for (uint8_t i = 0; i < w; i++) {
|
||||
char c = h & 0XF;
|
||||
*--ptr = c < 10 ? c + '0' : c + 'A' - 10;
|
||||
h >>= 4;
|
||||
}
|
||||
Com::print(ptr);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void FatFile::dmpFile(uint32_t pos, size_t n) {
|
||||
char text[17];
|
||||
text[16] = 0;
|
||||
if (n >= 0XFFF0) {
|
||||
n = 0XFFF0;
|
||||
}
|
||||
if (!seekSet(pos)) {
|
||||
return;
|
||||
}
|
||||
for (size_t i = 0; i <= n; i++) {
|
||||
if ((i & 15) == 0) {
|
||||
if (i) {
|
||||
Com::print(' ');
|
||||
Com::print(text);
|
||||
if (i == n) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
Com::println();
|
||||
if (i >= n) {
|
||||
break;
|
||||
}
|
||||
printHex(4, i);
|
||||
Com::print(' ');
|
||||
}
|
||||
int16_t h = read();
|
||||
if (h < 0) {
|
||||
break;
|
||||
}
|
||||
Com::print(' ');
|
||||
printHex(2, h);
|
||||
text[i&15] = ' ' <= h && h < 0X7F ? h : '.';
|
||||
}
|
||||
Com::println();
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
|
||||
/*
|
||||
void FatFile::ls(uint8_t flags, uint8_t indent) {
|
||||
FatFile file;
|
||||
rewind();
|
||||
while (file.openNext(this, O_READ)) {
|
||||
// indent for dir level
|
||||
if (!file.isHidden() || (flags & LS_A)) {
|
||||
for (uint8_t i = 0; i < indent; i++) {
|
||||
Com::print(' ');
|
||||
}
|
||||
if (flags & LS_DATE) {
|
||||
file.printModifyDateTime();
|
||||
Com::print(' ');
|
||||
}
|
||||
if (flags & LS_SIZE) {
|
||||
file.printFileSize();
|
||||
Com::print(' ');
|
||||
}
|
||||
file.printName();
|
||||
if (file.isDir()) {
|
||||
Com::print('/');
|
||||
}
|
||||
Com::println();
|
||||
if ((flags & LS_R) && file.isDir()) {
|
||||
file.ls(flags, indent + 2);
|
||||
}
|
||||
}
|
||||
file.close();
|
||||
}
|
||||
}
|
||||
*/
|
||||
extern int8_t RFstricmp(const char* s1, const char* s2);
|
||||
extern int8_t RFstrnicmp(const char* s1, const char* s2, size_t n);
|
||||
|
||||
void FatFile::lsRecursive(uint8_t level, bool isJson)
|
||||
{
|
||||
FatFile file;
|
||||
#if JSON_OUTPUT
|
||||
bool firstFile = true;
|
||||
#endif
|
||||
rewind();
|
||||
|
||||
while (file.openNext(this, O_READ)) {
|
||||
file.getName(tempLongFilename, LONG_FILENAME_LENGTH);
|
||||
HAL::pingWatchdog();
|
||||
if(file.isHidden()) {
|
||||
file.close();
|
||||
continue;
|
||||
}
|
||||
// if (! (file.isFile() || file.isDir())) continue;
|
||||
if (strcmp(tempLongFilename, "..") == 0) {
|
||||
file.close();
|
||||
continue;
|
||||
}
|
||||
if (tempLongFilename[0] == '.') {
|
||||
file.close();
|
||||
continue; // MAC CRAP
|
||||
}
|
||||
if (file.isDir()) {
|
||||
if (level >= SD_MAX_FOLDER_DEPTH) {
|
||||
file.close();
|
||||
continue; // can't go deeper
|
||||
}
|
||||
if (level && !isJson) {
|
||||
Com::print(fullName);
|
||||
Com::printF(Com::tSlash);
|
||||
}
|
||||
#if JSON_OUTPUT
|
||||
if (isJson) {
|
||||
if (!firstFile) Com::print(',');
|
||||
Com::print('"');Com::print('*');
|
||||
SDCard::printEscapeChars(tempLongFilename);
|
||||
Com::print('"');
|
||||
firstFile = false;
|
||||
} else {
|
||||
Com::print(tempLongFilename);
|
||||
Com::printFLN(Com::tSlash); // End with / to mark it as directory entry, so we can see empty directories.
|
||||
}
|
||||
#else
|
||||
Com::print(tempLongFilename);
|
||||
Com::printFLN(Com::tSlash); // End with / to mark it as directory entry, so we can see empty directories.
|
||||
#endif
|
||||
char *tmp;
|
||||
// Add directory name
|
||||
if(level) strcat(fullName, "/");
|
||||
strcat(fullName, tempLongFilename);
|
||||
if(!isJson) {
|
||||
file.lsRecursive(level + 1, false);
|
||||
}
|
||||
// remove added directory name
|
||||
if ((tmp = strrchr(fullName, '/')) != NULL)
|
||||
*tmp = 0;
|
||||
else
|
||||
*fullName = 0;
|
||||
} else { // is filename
|
||||
if(level && !isJson) {
|
||||
Com::print(fullName);
|
||||
Com::printF(Com::tSlash);
|
||||
}
|
||||
#if JSON_OUTPUT
|
||||
if (isJson) {
|
||||
if (!firstFile) Com::printF(Com::tComma);
|
||||
Com::print('"');
|
||||
SDCard::printEscapeChars(tempLongFilename);
|
||||
Com::print('"');
|
||||
firstFile = false;
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
Com::print(tempLongFilename);
|
||||
#if SD_EXTENDED_DIR
|
||||
Com::printF(Com::tSpace, (long) file.fileSize());
|
||||
#endif
|
||||
Com::println();
|
||||
}
|
||||
}
|
||||
file.close();
|
||||
}
|
||||
}
|
||||
|
||||
//------------------------------------------------------------------------------
|
||||
/** List directory contents.
|
||||
*
|
||||
* \param[in] pr Print stream for list.
|
||||
*
|
||||
* \param[in] flags The inclusive OR of
|
||||
*
|
||||
* LS_DATE - %Print file modification date
|
||||
*
|
||||
* LS_SIZE - %Print file size.
|
||||
*
|
||||
* LS_R - Recursive list of subdirectories.
|
||||
*
|
||||
* \param[in] indent Amount of space before file name. Used for recursive
|
||||
* list to indicate subdirectory level.
|
||||
*/
|
||||
void FatFile::ls(uint8_t flags, uint8_t indent) {
|
||||
*fullName = 0;
|
||||
lsRecursive(0, false);
|
||||
}
|
||||
|
||||
#if JSON_OUTPUT
|
||||
void FatFile::lsJSON() {
|
||||
*fullName = 0;
|
||||
lsRecursive(0, true);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
//------------------------------------------------------------------------------
|
||||
bool FatFile::printCreateDateTime() {
|
||||
dir_t dir;
|
||||
if (!dirEntry(&dir)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
printFatDate(dir.creationDate);
|
||||
Com::print(' ');
|
||||
printFatTime(dir.creationTime);
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void FatFile::printFatDate(uint16_t fatDate) {
|
||||
printU32(FAT_YEAR(fatDate));
|
||||
Com::print('-');
|
||||
print2u(FAT_MONTH(fatDate));
|
||||
Com::print('-');
|
||||
print2u(FAT_DAY(fatDate));
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void FatFile::printFatTime(uint16_t fatTime) {
|
||||
print2u(FAT_HOUR(fatTime));
|
||||
Com::print(':');
|
||||
print2u(FAT_MINUTE(fatTime));
|
||||
Com::print(':');
|
||||
print2u(FAT_SECOND(fatTime));
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Template for FatFile::printField() */
|
||||
template <typename Type>
|
||||
static int printFieldT(FatFile* file, char sign, Type value, char term) {
|
||||
char buf[3*sizeof(Type) + 3];
|
||||
char* str = &buf[sizeof(buf)];
|
||||
|
||||
if (term) {
|
||||
*--str = term;
|
||||
if (term == '\n') {
|
||||
*--str = '\r';
|
||||
}
|
||||
}
|
||||
#ifdef OLD_FMT
|
||||
do {
|
||||
Type m = value;
|
||||
value /= 10;
|
||||
*--str = '0' + m - 10*value;
|
||||
} while (value);
|
||||
#else // OLD_FMT
|
||||
str = fmtDec(value, str);
|
||||
#endif // OLD_FMT
|
||||
if (sign) {
|
||||
*--str = sign;
|
||||
}
|
||||
return file->write(str, &buf[sizeof(buf)] - str);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
|
||||
int FatFile::printField(float value, char term, uint8_t prec) {
|
||||
char buf[24];
|
||||
char* str = &buf[sizeof(buf)];
|
||||
if (term) {
|
||||
*--str = term;
|
||||
if (term == '\n') {
|
||||
*--str = '\r';
|
||||
}
|
||||
}
|
||||
str = fmtFloat(value, str, prec);
|
||||
return write(str, buf + sizeof(buf) - str);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int FatFile::printField(uint16_t value, char term) {
|
||||
return printFieldT(this, 0, value, term);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int FatFile::printField(int16_t value, char term) {
|
||||
char sign = 0;
|
||||
if (value < 0) {
|
||||
sign = '-';
|
||||
value = -value;
|
||||
}
|
||||
return printFieldT(this, sign, (uint16_t)value, term);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int FatFile::printField(uint32_t value, char term) {
|
||||
return printFieldT(this, 0, value, term);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int FatFile::printField(int32_t value, char term) {
|
||||
char sign = 0;
|
||||
if (value < 0) {
|
||||
sign = '-';
|
||||
value = -value;
|
||||
}
|
||||
return printFieldT(this, sign, (uint32_t)value, term);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool FatFile::printModifyDateTime() {
|
||||
dir_t dir;
|
||||
if (!dirEntry(&dir)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
printFatDate(dir.lastWriteDate);
|
||||
Com::print(' ');
|
||||
printFatTime(dir.lastWriteTime);
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void FatFile::printFileSize() {
|
||||
char buf[11];
|
||||
char *ptr = buf + sizeof(buf);
|
||||
*--ptr = 0;
|
||||
ptr = fmtDec(fileSize(), ptr);
|
||||
while (ptr > buf) {
|
||||
*--ptr = ' ';
|
||||
}
|
||||
Com::print(buf);
|
||||
}
|
||||
#endif
|
279
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/FatFileSFN.cpp
Normal file
279
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/FatFileSFN.cpp
Normal file
@ -0,0 +1,279 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#include "../../../Repetier.h"
|
||||
#include "FatFile.h"
|
||||
#include "FatFileSystem.h"
|
||||
#if SDSUPPORT
|
||||
//------------------------------------------------------------------------------
|
||||
bool FatFile::getSFN(char* name) {
|
||||
dir_t* dir;
|
||||
if (!isOpen()) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
if (isRoot()) {
|
||||
name[0] = '/';
|
||||
name[1] = '\0';
|
||||
return true;
|
||||
}
|
||||
// cache entry
|
||||
dir = cacheDirEntry(FatCache::CACHE_FOR_READ);
|
||||
if (!dir) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
// format name
|
||||
dirName(dir, name);
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void FatFile::printSFN() {
|
||||
char name[13];
|
||||
if (!getSFN(name)) {
|
||||
DBG_FAIL_MACRO;
|
||||
return;
|
||||
}
|
||||
Com::print(name);
|
||||
|
||||
}
|
||||
#if !USE_LONG_FILE_NAMES
|
||||
//------------------------------------------------------------------------------
|
||||
bool FatFile::getName(char* name, size_t size) {
|
||||
return size < 13 ? 0 : getSFN(name);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// format directory name field from a 8.3 name string
|
||||
bool FatFile::parsePathName(const char* path, fname_t* fname,
|
||||
const char** ptr) {
|
||||
uint8_t uc = 0;
|
||||
uint8_t lc = 0;
|
||||
uint8_t bit = FNAME_FLAG_LC_BASE;
|
||||
// blank fill name and extension
|
||||
for (uint8_t i = 0; i < 11; i++) {
|
||||
fname->sfn[i] = ' ';
|
||||
}
|
||||
|
||||
for (uint8_t i = 0, n = 7;; path++) {
|
||||
uint8_t c = *path;
|
||||
if (c == 0 || isDirSeparator(c)) {
|
||||
// Done.
|
||||
break;
|
||||
}
|
||||
if (c == '.' && n == 7) {
|
||||
n = 10; // max index for full 8.3 name
|
||||
i = 8; // place for extension
|
||||
|
||||
// bit for extension.
|
||||
bit = FNAME_FLAG_LC_EXT;
|
||||
} else {
|
||||
if (!legal83Char(c) || i > n) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
if ('a' <= c && c <= 'z') {
|
||||
c += 'A' - 'a';
|
||||
lc |= bit;
|
||||
} else if ('A' <= c && c <= 'Z') {
|
||||
uc |= bit;
|
||||
}
|
||||
fname->sfn[i++] = c;
|
||||
}
|
||||
}
|
||||
// must have a file name, extension is optional
|
||||
if (fname->sfn[0] == ' ') {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
// Set base-name and extension bits.
|
||||
fname->flags = lc & uc ? 0 : lc;
|
||||
while (isDirSeparator(*path)) {
|
||||
path++;
|
||||
}
|
||||
*ptr = path;
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// open with filename in fname
|
||||
#define SFN_OPEN_USES_CHKSUM 0
|
||||
bool FatFile::open(FatFile* dirFile, fname_t* fname, uint8_t oflag) {
|
||||
bool emptyFound = false;
|
||||
#if SFN_OPEN_USES_CHKSUM
|
||||
uint8_t chksum;
|
||||
#endif
|
||||
uint8_t lfnOrd = 0;
|
||||
uint16_t emptyIndex;
|
||||
uint16_t index = 0;
|
||||
dir_t* dir;
|
||||
ldir_t* ldir;
|
||||
|
||||
dirFile->rewind();
|
||||
while (1) {
|
||||
if (!emptyFound) {
|
||||
emptyIndex = index;
|
||||
}
|
||||
dir = dirFile->readDirCache(true);
|
||||
if (!dir) {
|
||||
if (dirFile->getError()) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
// At EOF if no error.
|
||||
break;
|
||||
}
|
||||
if (dir->name[0] == DIR_NAME_FREE) {
|
||||
emptyFound = true;
|
||||
break;
|
||||
}
|
||||
if (dir->name[0] == DIR_NAME_DELETED) {
|
||||
lfnOrd = 0;
|
||||
emptyFound = true;
|
||||
} else if (DIR_IS_FILE_OR_SUBDIR(dir)) {
|
||||
if (!memcmp(fname->sfn, dir->name, 11)) {
|
||||
// don't open existing file if O_EXCL
|
||||
if (oflag & O_EXCL) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
#if SFN_OPEN_USES_CHKSUM
|
||||
if (lfnOrd && chksum != lfnChecksum(dir->name)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
#endif // SFN_OPEN_USES_CHKSUM
|
||||
if (!openCachedEntry(dirFile, index, oflag, lfnOrd)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
return true;
|
||||
} else {
|
||||
lfnOrd = 0;
|
||||
}
|
||||
} else if (DIR_IS_LONG_NAME(dir)) {
|
||||
ldir = reinterpret_cast<ldir_t*>(dir);
|
||||
if (ldir->ord & LDIR_ORD_LAST_LONG_ENTRY) {
|
||||
lfnOrd = ldir->ord & 0X1F;
|
||||
#if SFN_OPEN_USES_CHKSUM
|
||||
chksum = ldir->chksum;
|
||||
#endif // SFN_OPEN_USES_CHKSUM
|
||||
}
|
||||
} else {
|
||||
lfnOrd = 0;
|
||||
}
|
||||
index++;
|
||||
}
|
||||
// don't create unless O_CREAT and O_WRITE
|
||||
if (!(oflag & O_CREAT) || !(oflag & O_WRITE)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
if (emptyFound) {
|
||||
index = emptyIndex;
|
||||
} else {
|
||||
if (!dirFile->addDirCluster()) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
if (!dirFile->seekSet(32UL*index)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
dir = dirFile->readDirCache();
|
||||
if (!dir) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
// initialize as empty file
|
||||
memset(dir, 0, sizeof(dir_t));
|
||||
memcpy(dir->name, fname->sfn, 11);
|
||||
|
||||
// Set base-name and extension lower case bits.
|
||||
dir->reservedNT = (DIR_NT_LC_BASE | DIR_NT_LC_EXT) & fname->flags;
|
||||
|
||||
// set timestamps
|
||||
if (m_dateTime) {
|
||||
// call user date/time function
|
||||
m_dateTime(&dir->creationDate, &dir->creationTime);
|
||||
} else {
|
||||
// use default date/time
|
||||
dir->creationDate = FAT_DEFAULT_DATE;
|
||||
dir->creationTime = FAT_DEFAULT_TIME;
|
||||
}
|
||||
dir->lastAccessDate = dir->creationDate;
|
||||
dir->lastWriteDate = dir->creationDate;
|
||||
dir->lastWriteTime = dir->creationTime;
|
||||
|
||||
// Force write of entry to device.
|
||||
dirFile->m_vol->cacheDirty();
|
||||
|
||||
// open entry in cache.
|
||||
return openCachedEntry(dirFile, index, oflag, 0);
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void FatFile::printName() {
|
||||
printSFN();
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool FatFile::remove() {
|
||||
dir_t* dir;
|
||||
// Can't remove if LFN or not open for write.
|
||||
if (!isFile() || isLFN() || !(m_flags & O_WRITE)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
// Free any clusters.
|
||||
if (m_firstCluster && !m_vol->freeChain(m_firstCluster)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
// Cache directory entry.
|
||||
dir = cacheDirEntry(FatCache::CACHE_FOR_WRITE);
|
||||
if (!dir) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
// Mark entry deleted.
|
||||
dir->name[0] = DIR_NAME_DELETED;
|
||||
|
||||
// Set this file closed.
|
||||
m_attr = FILE_ATTR_CLOSED;
|
||||
|
||||
// Write entry to device.
|
||||
return m_vol->cacheSync();
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
#endif // !USE_LONG_FILE_NAMES
|
||||
#endif
|
@ -0,0 +1,623 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef FatFileSystem_h
|
||||
#define FatFileSystem_h
|
||||
#include "FatVolume.h"
|
||||
#include "FatFile.h"
|
||||
#include "ArduinoFiles.h"
|
||||
/**
|
||||
* \file
|
||||
* \brief FatFileSystem class
|
||||
*/
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* \class FatFileSystem
|
||||
* \brief Integration class for the FatLib library.
|
||||
*/
|
||||
class FatFileSystem : public FatVolume {
|
||||
public:
|
||||
/**
|
||||
* Initialize an FatFileSystem object.
|
||||
* \param[in] blockDev Device block driver.
|
||||
* \param[in] part partition to initialize.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool begin(BlockDriver* blockDev, uint8_t part = 0) {
|
||||
m_blockDev = blockDev;
|
||||
vwd()->close();
|
||||
return (part ? init(part) : init(1) || init(0))
|
||||
&& vwd()->openRoot(this) && FatFile::setCwd(vwd());
|
||||
}
|
||||
#if ENABLE_ARDUINO_FEATURES
|
||||
/** open a file
|
||||
*
|
||||
* \param[in] path location of file to be opened.
|
||||
* \param[in] mode open mode flags.
|
||||
* \return a File object.
|
||||
*/
|
||||
File open(const char* path, uint8_t mode = FILE_READ) {
|
||||
File tmpFile;
|
||||
tmpFile.open(vwd(), path, mode);
|
||||
return tmpFile;
|
||||
}
|
||||
/** open a file
|
||||
*
|
||||
* \param[in] path location of file to be opened.
|
||||
* \param[in] mode open mode flags.
|
||||
* \return a File object.
|
||||
*/
|
||||
File open(const String& path, uint8_t mode = FILE_READ) {
|
||||
return open(path.c_str(), mode);
|
||||
}
|
||||
#endif // ENABLE_ARDUINO_FEATURES
|
||||
/** Change a volume's working directory to root
|
||||
*
|
||||
* Changes the volume's working directory to the SD's root directory.
|
||||
* Optionally set the current working directory to the volume's
|
||||
* working directory.
|
||||
*
|
||||
* \param[in] set_cwd Set the current working directory to this volume's
|
||||
* working directory if true.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool chdir(bool set_cwd = false) {
|
||||
vwd()->close();
|
||||
return vwd()->openRoot(this) && (set_cwd ? FatFile::setCwd(vwd()) : true);
|
||||
}
|
||||
/** Change a volume's working directory
|
||||
*
|
||||
* Changes the volume working directory to the \a path subdirectory.
|
||||
* Optionally set the current working directory to the volume's
|
||||
* working directory.
|
||||
*
|
||||
* Example: If the volume's working directory is "/DIR", chdir("SUB")
|
||||
* will change the volume's working directory from "/DIR" to "/DIR/SUB".
|
||||
*
|
||||
* If path is "/", the volume's working directory will be changed to the
|
||||
* root directory
|
||||
*
|
||||
* \param[in] path The name of the subdirectory.
|
||||
*
|
||||
* \param[in] set_cwd Set the current working directory to this volume's
|
||||
* working directory if true.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
//----------------------------------------------------------------------------
|
||||
bool chdir(const char* path, bool set_cwd = false) {
|
||||
FatFile dir;
|
||||
if (path[0] == '/' && path[1] == '\0') {
|
||||
return chdir(set_cwd);
|
||||
}
|
||||
if (!dir.open(vwd(), path, O_READ)) {
|
||||
goto fail;
|
||||
}
|
||||
if (!dir.isDir()) {
|
||||
goto fail;
|
||||
}
|
||||
m_vwd = dir;
|
||||
if (set_cwd) {
|
||||
FatFile::setCwd(vwd());
|
||||
}
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Set the current working directory to a volume's working directory.
|
||||
*
|
||||
* This is useful with multiple SD cards.
|
||||
*
|
||||
* The current working directory is changed to this
|
||||
* volume's working directory.
|
||||
*
|
||||
* This is like the Windows/DOS \<drive letter>: command.
|
||||
*/
|
||||
void chvol() {
|
||||
FatFile::setCwd(vwd());
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/**
|
||||
* Test for the existence of a file.
|
||||
*
|
||||
* \param[in] path Path of the file to be tested for.
|
||||
*
|
||||
* \return true if the file exists else false.
|
||||
*/
|
||||
bool exists(const char* path) {
|
||||
return vwd()->exists(path);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** List the directory contents of the volume working directory.
|
||||
*
|
||||
* \param[in] pr Print stream for list.
|
||||
*
|
||||
* \param[in] flags The inclusive OR of
|
||||
*
|
||||
* LS_DATE - %Print file modification date
|
||||
*
|
||||
* LS_SIZE - %Print file size.
|
||||
*
|
||||
* LS_R - Recursive list of subdirectories.
|
||||
*/
|
||||
void ls(uint8_t flags = 0) {
|
||||
vwd()->ls(flags);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** List the directory contents of a directory.
|
||||
*
|
||||
* \param[in] pr Print stream for list.
|
||||
*
|
||||
* \param[in] path directory to list.
|
||||
*
|
||||
* \param[in] flags The inclusive OR of
|
||||
*
|
||||
* LS_DATE - %Print file modification date
|
||||
*
|
||||
* LS_SIZE - %Print file size.
|
||||
*
|
||||
* LS_R - Recursive list of subdirectories.
|
||||
*/
|
||||
void ls(const char* path, uint8_t flags) {
|
||||
FatFile dir;
|
||||
dir.open(vwd(), path, O_READ);
|
||||
dir.ls(flags);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Make a subdirectory in the volume working directory.
|
||||
*
|
||||
* \param[in] path A path with a valid 8.3 DOS name for the subdirectory.
|
||||
*
|
||||
* \param[in] pFlag Create missing parent directories if true.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool mkdir(const char* path, bool pFlag = true) {
|
||||
FatFile sub;
|
||||
return sub.mkdir(vwd(), path, pFlag);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Remove a file from the volume working directory.
|
||||
*
|
||||
* \param[in] path A path with a valid 8.3 DOS name for the file.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool remove(const char* path) {
|
||||
return FatFile::remove(vwd(), path);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Rename a file or subdirectory.
|
||||
*
|
||||
* \param[in] oldPath Path name to the file or subdirectory to be renamed.
|
||||
*
|
||||
* \param[in] newPath New path name of the file or subdirectory.
|
||||
*
|
||||
* The \a newPath object must not exist before the rename call.
|
||||
*
|
||||
* The file to be renamed must not be open. The directory entry may be
|
||||
* moved and file system corruption could occur if the file is accessed by
|
||||
* a file object that was opened before the rename() call.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool rename(const char* oldPath, const char* newPath) {
|
||||
FatFile file;
|
||||
if (!file.open(vwd(), oldPath, O_READ)) {
|
||||
return false;
|
||||
}
|
||||
return file.rename(vwd(), newPath);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Remove a subdirectory from the volume's working directory.
|
||||
*
|
||||
* \param[in] path A path with a valid 8.3 DOS name for the subdirectory.
|
||||
*
|
||||
* The subdirectory file will be removed only if it is empty.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool rmdir(const char* path) {
|
||||
FatFile sub;
|
||||
if (!sub.open(vwd(), path, O_READ)) {
|
||||
return false;
|
||||
}
|
||||
return sub.rmdir();
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Truncate a file to a specified length. The current file position
|
||||
* will be maintained if it is less than or equal to \a length otherwise
|
||||
* it will be set to end of file.
|
||||
*
|
||||
* \param[in] path A path with a valid 8.3 DOS name for the file.
|
||||
* \param[in] length The desired length for the file.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool truncate(const char* path, uint32_t length) {
|
||||
FatFile file;
|
||||
if (!file.open(vwd(), path, O_WRITE)) {
|
||||
return false;
|
||||
}
|
||||
return file.truncate(length);
|
||||
}
|
||||
/** \return a pointer to the FatVolume object. */
|
||||
FatVolume* vol() {
|
||||
return this;
|
||||
}
|
||||
/** \return a pointer to the volume working directory. */
|
||||
FatFile* vwd() {
|
||||
return &m_vwd;
|
||||
}
|
||||
/** Wipe all data from the volume. You must reinitialize the volume before
|
||||
* accessing it again.
|
||||
* \param[in] pr print stream for status dots.
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool wipe() {
|
||||
vwd()->close();
|
||||
return FatVolume::wipe();
|
||||
}
|
||||
|
||||
private:
|
||||
FatFile m_vwd;
|
||||
};
|
||||
#endif // FatFileSystem_h
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef FatFileSystem_h
|
||||
#define FatFileSystem_h
|
||||
#include "FatVolume.h"
|
||||
#include "FatFile.h"
|
||||
#include "ArduinoStream.h"
|
||||
#include "ArduinoFiles.h"
|
||||
/**
|
||||
* \file
|
||||
* \brief FatFileSystem class
|
||||
*/
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* \class FatFileSystem
|
||||
* \brief Integration class for the FatLib library.
|
||||
*/
|
||||
class FatFileSystem : public FatVolume {
|
||||
public:
|
||||
/**
|
||||
* Initialize an FatFileSystem object.
|
||||
* \param[in] blockDev Device block driver.
|
||||
* \param[in] part partition to initialize.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool begin(BlockDriver* blockDev, uint8_t part = 0) {
|
||||
m_blockDev = blockDev;
|
||||
vwd()->close();
|
||||
return (part ? init(part) : init(1) || init(0))
|
||||
&& vwd()->openRoot(this) && FatFile::setCwd(vwd());
|
||||
}
|
||||
#if ENABLE_ARDUINO_FEATURES
|
||||
/** List the directory contents of the volume working directory to Serial.
|
||||
*
|
||||
* \param[in] flags The inclusive OR of
|
||||
*
|
||||
* LS_DATE - %Print file modification date
|
||||
*
|
||||
* LS_SIZE - %Print file size.
|
||||
*
|
||||
* LS_R - Recursive list of subdirectories.
|
||||
*/
|
||||
void ls(uint8_t flags = 0) {
|
||||
ls(&Serial, flags);
|
||||
}
|
||||
/** List the directory contents of a directory to Serial.
|
||||
*
|
||||
* \param[in] path directory to list.
|
||||
*
|
||||
* \param[in] flags The inclusive OR of
|
||||
*
|
||||
* LS_DATE - %Print file modification date
|
||||
*
|
||||
* LS_SIZE - %Print file size.
|
||||
*
|
||||
* LS_R - Recursive list of subdirectories.
|
||||
*/
|
||||
void ls(const char* path, uint8_t flags = 0) {
|
||||
ls(&Serial, path, flags);
|
||||
}
|
||||
/** open a file
|
||||
*
|
||||
* \param[in] path location of file to be opened.
|
||||
* \param[in] mode open mode flags.
|
||||
* \return a File object.
|
||||
*/
|
||||
File open(const char* path, uint8_t mode = FILE_READ) {
|
||||
File tmpFile;
|
||||
tmpFile.open(vwd(), path, mode);
|
||||
return tmpFile;
|
||||
}
|
||||
/** open a file
|
||||
*
|
||||
* \param[in] path location of file to be opened.
|
||||
* \param[in] mode open mode flags.
|
||||
* \return a File object.
|
||||
*/
|
||||
File open(const String& path, uint8_t mode = FILE_READ) {
|
||||
return open(path.c_str(), mode);
|
||||
}
|
||||
#endif // ENABLE_ARDUINO_FEATURES
|
||||
/** Change a volume's working directory to root
|
||||
*
|
||||
* Changes the volume's working directory to the SD's root directory.
|
||||
* Optionally set the current working directory to the volume's
|
||||
* working directory.
|
||||
*
|
||||
* \param[in] set_cwd Set the current working directory to this volume's
|
||||
* working directory if true.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool chdir(bool set_cwd = false) {
|
||||
vwd()->close();
|
||||
return vwd()->openRoot(this) && (set_cwd ? FatFile::setCwd(vwd()) : true);
|
||||
}
|
||||
/** Change a volume's working directory
|
||||
*
|
||||
* Changes the volume working directory to the \a path subdirectory.
|
||||
* Optionally set the current working directory to the volume's
|
||||
* working directory.
|
||||
*
|
||||
* Example: If the volume's working directory is "/DIR", chdir("SUB")
|
||||
* will change the volume's working directory from "/DIR" to "/DIR/SUB".
|
||||
*
|
||||
* If path is "/", the volume's working directory will be changed to the
|
||||
* root directory
|
||||
*
|
||||
* \param[in] path The name of the subdirectory.
|
||||
*
|
||||
* \param[in] set_cwd Set the current working directory to this volume's
|
||||
* working directory if true.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
//----------------------------------------------------------------------------
|
||||
bool chdir(const char* path, bool set_cwd = false) {
|
||||
FatFile dir;
|
||||
if (path[0] == '/' && path[1] == '\0') {
|
||||
return chdir(set_cwd);
|
||||
}
|
||||
if (!dir.open(vwd(), path, O_READ)) {
|
||||
goto fail;
|
||||
}
|
||||
if (!dir.isDir()) {
|
||||
goto fail;
|
||||
}
|
||||
m_vwd = dir;
|
||||
if (set_cwd) {
|
||||
FatFile::setCwd(vwd());
|
||||
}
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Set the current working directory to a volume's working directory.
|
||||
*
|
||||
* This is useful with multiple SD cards.
|
||||
*
|
||||
* The current working directory is changed to this
|
||||
* volume's working directory.
|
||||
*
|
||||
* This is like the Windows/DOS \<drive letter>: command.
|
||||
*/
|
||||
void chvol() {
|
||||
FatFile::setCwd(vwd());
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/**
|
||||
* Test for the existence of a file.
|
||||
*
|
||||
* \param[in] path Path of the file to be tested for.
|
||||
*
|
||||
* \return true if the file exists else false.
|
||||
*/
|
||||
bool exists(const char* path) {
|
||||
return vwd()->exists(path);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** List the directory contents of the volume working directory.
|
||||
*
|
||||
* \param[in] pr Print stream for list.
|
||||
*
|
||||
* \param[in] flags The inclusive OR of
|
||||
*
|
||||
* LS_DATE - %Print file modification date
|
||||
*
|
||||
* LS_SIZE - %Print file size.
|
||||
*
|
||||
* LS_R - Recursive list of subdirectories.
|
||||
*/
|
||||
void ls(uint8_t flags = 0) {
|
||||
vwd()->ls(flags);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** List the directory contents of a directory.
|
||||
*
|
||||
* \param[in] pr Print stream for list.
|
||||
*
|
||||
* \param[in] path directory to list.
|
||||
*
|
||||
* \param[in] flags The inclusive OR of
|
||||
*
|
||||
* LS_DATE - %Print file modification date
|
||||
*
|
||||
* LS_SIZE - %Print file size.
|
||||
*
|
||||
* LS_R - Recursive list of subdirectories.
|
||||
*/
|
||||
void ls(const char* path, uint8_t flags) {
|
||||
FatFile dir;
|
||||
dir.open(vwd(), path, O_READ);
|
||||
dir.ls(pr, flags);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Make a subdirectory in the volume working directory.
|
||||
*
|
||||
* \param[in] path A path with a valid 8.3 DOS name for the subdirectory.
|
||||
*
|
||||
* \param[in] pFlag Create missing parent directories if true.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool mkdir(const char* path, bool pFlag = true) {
|
||||
FatFile sub;
|
||||
return sub.mkdir(vwd(), path, pFlag);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Remove a file from the volume working directory.
|
||||
*
|
||||
* \param[in] path A path with a valid 8.3 DOS name for the file.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool remove(const char* path) {
|
||||
return FatFile::remove(vwd(), path);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Rename a file or subdirectory.
|
||||
*
|
||||
* \param[in] oldPath Path name to the file or subdirectory to be renamed.
|
||||
*
|
||||
* \param[in] newPath New path name of the file or subdirectory.
|
||||
*
|
||||
* The \a newPath object must not exist before the rename call.
|
||||
*
|
||||
* The file to be renamed must not be open. The directory entry may be
|
||||
* moved and file system corruption could occur if the file is accessed by
|
||||
* a file object that was opened before the rename() call.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool rename(const char* oldPath, const char* newPath) {
|
||||
FatFile file;
|
||||
if (!file.open(vwd(), oldPath, O_READ)) {
|
||||
return false;
|
||||
}
|
||||
return file.rename(vwd(), newPath);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Remove a subdirectory from the volume's working directory.
|
||||
*
|
||||
* \param[in] path A path with a valid 8.3 DOS name for the subdirectory.
|
||||
*
|
||||
* The subdirectory file will be removed only if it is empty.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool rmdir(const char* path) {
|
||||
FatFile sub;
|
||||
if (!sub.open(vwd(), path, O_READ)) {
|
||||
return false;
|
||||
}
|
||||
return sub.rmdir();
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Truncate a file to a specified length. The current file position
|
||||
* will be maintained if it is less than or equal to \a length otherwise
|
||||
* it will be set to end of file.
|
||||
*
|
||||
* \param[in] path A path with a valid 8.3 DOS name for the file.
|
||||
* \param[in] length The desired length for the file.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool truncate(const char* path, uint32_t length) {
|
||||
FatFile file;
|
||||
if (!file.open(vwd(), path, O_WRITE)) {
|
||||
return false;
|
||||
}
|
||||
return file.truncate(length);
|
||||
}
|
||||
/** \return a pointer to the FatVolume object. */
|
||||
FatVolume* vol() {
|
||||
return this;
|
||||
}
|
||||
/** \return a pointer to the volume working directory. */
|
||||
FatFile* vwd() {
|
||||
return &m_vwd;
|
||||
}
|
||||
/** Wipe all data from the volume. You must reinitialize the volume before
|
||||
* accessing it again.
|
||||
* \param[in] pr print stream for status dots.
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool wipe() {
|
||||
vwd()->close();
|
||||
return FatVolume::wipe();
|
||||
}
|
||||
|
||||
private:
|
||||
FatFile m_vwd;
|
||||
};
|
||||
#endif // FatFileSystem_h
|
36
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/FatLib.h
Normal file
36
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/FatLib.h
Normal file
@ -0,0 +1,36 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef FatLib_h
|
||||
#define FatLib_h
|
||||
#include "ArduinoFiles.h"
|
||||
#include "FatFileSystem.h"
|
||||
#include "FatLibConfig.h"
|
||||
#include "FatVolume.h"
|
||||
#include "FatFile.h"
|
||||
#include "StdioStream.h"
|
||||
//------------------------------------------------------------------------------
|
||||
/** FatFileSystem version YYYYMMDD */
|
||||
#define FAT_LIB_VERSION 20150131
|
||||
#endif // FatLib_h
|
146
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/FatLibConfig.h
Normal file
146
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/FatLibConfig.h
Normal file
@ -0,0 +1,146 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
/**
|
||||
* \file
|
||||
* \brief configuration definitions
|
||||
*/
|
||||
#ifndef FatLibConfig_h
|
||||
#define FatLibConfig_h
|
||||
#include <stdint.h>
|
||||
// Allow this file to override defaults.
|
||||
#include "../SdFatConfig.h"
|
||||
|
||||
#ifdef __AVR__
|
||||
#include <avr/io.h>
|
||||
#endif // __AVR__
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Set USE_LONG_FILE_NAMES nonzero to use long file names (LFN).
|
||||
* Long File Name are limited to a maximum length of 255 characters.
|
||||
*
|
||||
* This implementation allows 7-bit characters in the range
|
||||
* 0X20 to 0X7E. The following characters are not allowed:
|
||||
*
|
||||
* < (less than)
|
||||
* > (greater than)
|
||||
* : (colon)
|
||||
* " (double quote)
|
||||
* / (forward slash)
|
||||
* \ (backslash)
|
||||
* | (vertical bar or pipe)
|
||||
* ? (question mark)
|
||||
* * (asterisk)
|
||||
*
|
||||
*/
|
||||
#ifndef USE_LONG_FILE_NAMES
|
||||
#define USE_LONG_FILE_NAMES 1
|
||||
#endif // USE_LONG_FILE_NAMES
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Set USE_SEPARATE_FAT_CACHE non-zero to use a second 512 byte cache
|
||||
* for FAT table entries. Improves performance for large writes that
|
||||
* are not a multiple of 512 bytes.
|
||||
*/
|
||||
#ifndef USE_SEPARATE_FAT_CACHE
|
||||
#ifdef __arm__
|
||||
#define USE_SEPARATE_FAT_CACHE 1
|
||||
#else // __arm__
|
||||
#define USE_SEPARATE_FAT_CACHE 0
|
||||
#endif // __arm__
|
||||
#endif // USE_SEPARATE_FAT_CACHE
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Set USE_MULTI_BLOCK_IO non-zero to use multi-block SD read/write.
|
||||
*
|
||||
* Don't use mult-block read/write on small AVR boards.
|
||||
*/
|
||||
#ifndef USE_MULTI_BLOCK_IO
|
||||
#if defined(RAMEND) && RAMEND < 3000
|
||||
#define USE_MULTI_BLOCK_IO 0
|
||||
#else // RAMEND
|
||||
#define USE_MULTI_BLOCK_IO 1
|
||||
#endif // RAMEND
|
||||
#endif // USE_MULTI_BLOCK_IO
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Set MAINTAIN_FREE_CLUSTER_COUNT nonzero to keep the count of free clusters
|
||||
* updated. This will increase the speed of the freeClusterCount() call
|
||||
* after the first call. Extra flash will be required.
|
||||
*/
|
||||
#ifndef MAINTAIN_FREE_CLUSTER_COUNT
|
||||
#define MAINTAIN_FREE_CLUSTER_COUNT 0
|
||||
#endif // MAINTAIN_FREE_CLUSTER_COUNT
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Set DESTRUCTOR_CLOSES_FILE non-zero to close a file in its destructor.
|
||||
*
|
||||
* Causes use of lots of heap in ARM.
|
||||
*/
|
||||
#ifndef DESTRUCTOR_CLOSES_FILE
|
||||
#define DESTRUCTOR_CLOSES_FILE 0
|
||||
#endif // DESTRUCTOR_CLOSES_FILE
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Call flush for endl if ENDL_CALLS_FLUSH is non-zero
|
||||
*
|
||||
* The standard for iostreams is to call flush. This is very costly for
|
||||
* SdFat. Each call to flush causes 2048 bytes of I/O to the SD.
|
||||
*
|
||||
* SdFat has a single 512 byte buffer for I/O so it must write the current
|
||||
* data block to the SD, read the directory block from the SD, update the
|
||||
* directory entry, write the directory block to the SD and read the data
|
||||
* block back into the buffer.
|
||||
*
|
||||
* The SD flash memory controller is not designed for this many rewrites
|
||||
* so performance may be reduced by more than a factor of 100.
|
||||
*
|
||||
* If ENDL_CALLS_FLUSH is zero, you must call flush and/or close to force
|
||||
* all data to be written to the SD.
|
||||
*/
|
||||
#ifndef ENDL_CALLS_FLUSH
|
||||
#define ENDL_CALLS_FLUSH 0
|
||||
#endif // ENDL_CALLS_FLUSH
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Allow FAT12 volumes if FAT12_SUPPORT is non-zero.
|
||||
* FAT12 has not been well tested.
|
||||
*/
|
||||
#ifndef FAT12_SUPPORT
|
||||
#define FAT12_SUPPORT 0
|
||||
#endif // FAT12_SUPPORT
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Enable Extra features for Arduino.
|
||||
*/
|
||||
// #define ENABLE_ARDUINO_FEATURES 0 ////////////////////////FIX THIS /////////////////
|
||||
#ifndef ENABLE_ARDUINO_FEATURES
|
||||
#include <Arduino.h>
|
||||
#if defined(ARDUINO) || defined(PLATFORM_ID) || defined(DOXYGEN)
|
||||
#define ENABLE_ARDUINO_FEATURES 1
|
||||
#else // #if defined(ARDUINO) || defined(DOXYGEN)
|
||||
#define ENABLE_ARDUINO_FEATURES 0
|
||||
#endif // defined(ARDUINO) || defined(DOXYGEN)
|
||||
#endif // ENABLE_ARDUINO_FEATURES
|
||||
#endif // FatLibConfig_h
|
882
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/FatStructs.h
Normal file
882
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/FatStructs.h
Normal file
@ -0,0 +1,882 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef FatStructs_h
|
||||
#define FatStructs_h
|
||||
/**
|
||||
* \file
|
||||
* \brief FAT file structures
|
||||
*/
|
||||
/*
|
||||
* mostly from Microsoft document fatgen103.doc
|
||||
* http://www.microsoft.com/whdc/system/platform/firmware/fatgen.mspx
|
||||
*/
|
||||
//------------------------------------------------------------------------------
|
||||
/** Value for byte 510 of boot block or MBR */
|
||||
const uint8_t BOOTSIG0 = 0X55;
|
||||
/** Value for byte 511 of boot block or MBR */
|
||||
const uint8_t BOOTSIG1 = 0XAA;
|
||||
/** Value for bootSignature field int FAT/FAT32 boot sector */
|
||||
const uint8_t EXTENDED_BOOT_SIG = 0X29;
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* \struct partitionTable
|
||||
* \brief MBR partition table entry
|
||||
*
|
||||
* A partition table entry for a MBR formatted storage device.
|
||||
* The MBR partition table has four entries.
|
||||
*/
|
||||
struct partitionTable {
|
||||
/**
|
||||
* Boot Indicator . Indicates whether the volume is the active
|
||||
* partition. Legal values include: 0X00. Do not use for booting.
|
||||
* 0X80 Active partition.
|
||||
*/
|
||||
uint8_t boot;
|
||||
/**
|
||||
* Head part of Cylinder-head-sector address of the first block in
|
||||
* the partition. Legal values are 0-255. Only used in old PC BIOS.
|
||||
*/
|
||||
uint8_t beginHead;
|
||||
/**
|
||||
* Sector part of Cylinder-head-sector address of the first block in
|
||||
* the partition. Legal values are 1-63. Only used in old PC BIOS.
|
||||
*/
|
||||
unsigned beginSector : 6;
|
||||
/** High bits cylinder for first block in partition. */
|
||||
unsigned beginCylinderHigh : 2;
|
||||
/**
|
||||
* Combine beginCylinderLow with beginCylinderHigh. Legal values
|
||||
* are 0-1023. Only used in old PC BIOS.
|
||||
*/
|
||||
uint8_t beginCylinderLow;
|
||||
/**
|
||||
* Partition type. See defines that begin with PART_TYPE_ for
|
||||
* some Microsoft partition types.
|
||||
*/
|
||||
uint8_t type;
|
||||
/**
|
||||
* head part of cylinder-head-sector address of the last sector in the
|
||||
* partition. Legal values are 0-255. Only used in old PC BIOS.
|
||||
*/
|
||||
uint8_t endHead;
|
||||
/**
|
||||
* Sector part of cylinder-head-sector address of the last sector in
|
||||
* the partition. Legal values are 1-63. Only used in old PC BIOS.
|
||||
*/
|
||||
unsigned endSector : 6;
|
||||
/** High bits of end cylinder */
|
||||
unsigned endCylinderHigh : 2;
|
||||
/**
|
||||
* Combine endCylinderLow with endCylinderHigh. Legal values
|
||||
* are 0-1023. Only used in old PC BIOS.
|
||||
*/
|
||||
uint8_t endCylinderLow;
|
||||
/** Logical block address of the first block in the partition. */
|
||||
uint32_t firstSector;
|
||||
/** Length of the partition, in blocks. */
|
||||
uint32_t totalSectors;
|
||||
} __attribute__((packed));
|
||||
/** Type name for partitionTable */
|
||||
typedef struct partitionTable part_t;
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* \struct masterBootRecord
|
||||
*
|
||||
* \brief Master Boot Record
|
||||
*
|
||||
* The first block of a storage device that is formatted with a MBR.
|
||||
*/
|
||||
struct masterBootRecord {
|
||||
/** Code Area for master boot program. */
|
||||
uint8_t codeArea[440];
|
||||
/** Optional Windows NT disk signature. May contain boot code. */
|
||||
uint32_t diskSignature;
|
||||
/** Usually zero but may be more boot code. */
|
||||
uint16_t usuallyZero;
|
||||
/** Partition tables. */
|
||||
part_t part[4];
|
||||
/** First MBR signature byte. Must be 0X55 */
|
||||
uint8_t mbrSig0;
|
||||
/** Second MBR signature byte. Must be 0XAA */
|
||||
uint8_t mbrSig1;
|
||||
} __attribute__((packed));
|
||||
/** Type name for masterBootRecord */
|
||||
typedef struct masterBootRecord mbr_t;
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* \struct biosParmBlock
|
||||
*
|
||||
* \brief BIOS parameter block
|
||||
*
|
||||
* The BIOS parameter block describes the physical layout of a FAT volume.
|
||||
*/
|
||||
struct biosParmBlock {
|
||||
/**
|
||||
* Count of bytes per sector. This value may take on only the
|
||||
* following values: 512, 1024, 2048 or 4096
|
||||
*/
|
||||
uint16_t bytesPerSector;
|
||||
/**
|
||||
* Number of sectors per allocation unit. This value must be a
|
||||
* power of 2 that is greater than 0. The legal values are
|
||||
* 1, 2, 4, 8, 16, 32, 64, and 128.
|
||||
*/
|
||||
uint8_t sectorsPerCluster;
|
||||
/**
|
||||
* Number of sectors before the first FAT.
|
||||
* This value must not be zero.
|
||||
*/
|
||||
uint16_t reservedSectorCount;
|
||||
/** The count of FAT data structures on the volume. This field should
|
||||
* always contain the value 2 for any FAT volume of any type.
|
||||
*/
|
||||
uint8_t fatCount;
|
||||
/**
|
||||
* For FAT12 and FAT16 volumes, this field contains the count of
|
||||
* 32-byte directory entries in the root directory. For FAT32 volumes,
|
||||
* this field must be set to 0. For FAT12 and FAT16 volumes, this
|
||||
* value should always specify a count that when multiplied by 32
|
||||
* results in a multiple of bytesPerSector. FAT16 volumes should
|
||||
* use the value 512.
|
||||
*/
|
||||
uint16_t rootDirEntryCount;
|
||||
/**
|
||||
* This field is the old 16-bit total count of sectors on the volume.
|
||||
* This count includes the count of all sectors in all four regions
|
||||
* of the volume. This field can be 0; if it is 0, then totalSectors32
|
||||
* must be nonzero. For FAT32 volumes, this field must be 0. For
|
||||
* FAT12 and FAT16 volumes, this field contains the sector count, and
|
||||
* totalSectors32 is 0 if the total sector count fits
|
||||
* (is less than 0x10000).
|
||||
*/
|
||||
uint16_t totalSectors16;
|
||||
/**
|
||||
* This dates back to the old MS-DOS 1.x media determination and is
|
||||
* no longer usually used for anything. 0xF8 is the standard value
|
||||
* for fixed (nonremovable) media. For removable media, 0xF0 is
|
||||
* frequently used. Legal values are 0xF0 or 0xF8-0xFF.
|
||||
*/
|
||||
uint8_t mediaType;
|
||||
/**
|
||||
* Count of sectors occupied by one FAT on FAT12/FAT16 volumes.
|
||||
* On FAT32 volumes this field must be 0, and sectorsPerFat32
|
||||
* contains the FAT size count.
|
||||
*/
|
||||
uint16_t sectorsPerFat16;
|
||||
/** Sectors per track for interrupt 0x13. Not used otherwise. */
|
||||
uint16_t sectorsPerTrtack;
|
||||
/** Number of heads for interrupt 0x13. Not used otherwise. */
|
||||
uint16_t headCount;
|
||||
/**
|
||||
* Count of hidden sectors preceding the partition that contains this
|
||||
* FAT volume. This field is generally only relevant for media
|
||||
* visible on interrupt 0x13.
|
||||
*/
|
||||
uint32_t hidddenSectors;
|
||||
/**
|
||||
* This field is the new 32-bit total count of sectors on the volume.
|
||||
* This count includes the count of all sectors in all four regions
|
||||
* of the volume. This field can be 0; if it is 0, then
|
||||
* totalSectors16 must be nonzero.
|
||||
*/
|
||||
uint32_t totalSectors32;
|
||||
/**
|
||||
* Count of sectors occupied by one FAT on FAT32 volumes.
|
||||
*/
|
||||
uint32_t sectorsPerFat32;
|
||||
/**
|
||||
* This field is only defined for FAT32 media and does not exist on
|
||||
* FAT12 and FAT16 media.
|
||||
* Bits 0-3 -- Zero-based number of active FAT.
|
||||
* Only valid if mirroring is disabled.
|
||||
* Bits 4-6 -- Reserved.
|
||||
* Bit 7 -- 0 means the FAT is mirrored at runtime into all FATs.
|
||||
* -- 1 means only one FAT is active; it is the one referenced in bits 0-3.
|
||||
* Bits 8-15 -- Reserved.
|
||||
*/
|
||||
uint16_t fat32Flags;
|
||||
/**
|
||||
* FAT32 version. High byte is major revision number.
|
||||
* Low byte is minor revision number. Only 0.0 define.
|
||||
*/
|
||||
uint16_t fat32Version;
|
||||
/**
|
||||
* Cluster number of the first cluster of the root directory for FAT32.
|
||||
* This usually 2 but not required to be 2.
|
||||
*/
|
||||
uint32_t fat32RootCluster;
|
||||
/**
|
||||
* Sector number of FSINFO structure in the reserved area of the
|
||||
* FAT32 volume. Usually 1.
|
||||
*/
|
||||
uint16_t fat32FSInfo;
|
||||
/**
|
||||
* If nonzero, indicates the sector number in the reserved area
|
||||
* of the volume of a copy of the boot record. Usually 6.
|
||||
* No value other than 6 is recommended.
|
||||
*/
|
||||
uint16_t fat32BackBootBlock;
|
||||
/**
|
||||
* Reserved for future expansion. Code that formats FAT32 volumes
|
||||
* should always set all of the bytes of this field to 0.
|
||||
*/
|
||||
uint8_t fat32Reserved[12];
|
||||
} __attribute__((packed));
|
||||
/** Type name for biosParmBlock */
|
||||
typedef struct biosParmBlock bpb_t;
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* \struct fat_boot
|
||||
*
|
||||
* \brief Boot sector for a FAT12/FAT16 volume.
|
||||
*
|
||||
*/
|
||||
struct fat_boot {
|
||||
/**
|
||||
* The first three bytes of the boot sector must be valid,
|
||||
* executable x 86-based CPU instructions. This includes a
|
||||
* jump instruction that skips the next non-executable bytes.
|
||||
*/
|
||||
uint8_t jump[3];
|
||||
/**
|
||||
* This is typically a string of characters that identifies
|
||||
* the operating system that formatted the volume.
|
||||
*/
|
||||
char oemId[8];
|
||||
/**
|
||||
* The size of a hardware sector. Valid decimal values for this
|
||||
* field are 512, 1024, 2048, and 4096. For most disks used in
|
||||
* the United States, the value of this field is 512.
|
||||
*/
|
||||
uint16_t bytesPerSector;
|
||||
/**
|
||||
* Number of sectors per allocation unit. This value must be a
|
||||
* power of 2 that is greater than 0. The legal values are
|
||||
* 1, 2, 4, 8, 16, 32, 64, and 128. 128 should be avoided.
|
||||
*/
|
||||
uint8_t sectorsPerCluster;
|
||||
/**
|
||||
* The number of sectors preceding the start of the first FAT,
|
||||
* including the boot sector. The value of this field is always 1.
|
||||
*/
|
||||
uint16_t reservedSectorCount;
|
||||
/**
|
||||
* The number of copies of the FAT on the volume.
|
||||
* The value of this field is always 2.
|
||||
*/
|
||||
uint8_t fatCount;
|
||||
/**
|
||||
* For FAT12 and FAT16 volumes, this field contains the count of
|
||||
* 32-byte directory entries in the root directory. For FAT32 volumes,
|
||||
* this field must be set to 0. For FAT12 and FAT16 volumes, this
|
||||
* value should always specify a count that when multiplied by 32
|
||||
* results in a multiple of bytesPerSector. FAT16 volumes should
|
||||
* use the value 512.
|
||||
*/
|
||||
uint16_t rootDirEntryCount;
|
||||
/**
|
||||
* This field is the old 16-bit total count of sectors on the volume.
|
||||
* This count includes the count of all sectors in all four regions
|
||||
* of the volume. This field can be 0; if it is 0, then totalSectors32
|
||||
* must be non-zero. For FAT32 volumes, this field must be 0. For
|
||||
* FAT12 and FAT16 volumes, this field contains the sector count, and
|
||||
* totalSectors32 is 0 if the total sector count fits
|
||||
* (is less than 0x10000).
|
||||
*/
|
||||
uint16_t totalSectors16;
|
||||
/**
|
||||
* This dates back to the old MS-DOS 1.x media determination and is
|
||||
* no longer usually used for anything. 0xF8 is the standard value
|
||||
* for fixed (non-removable) media. For removable media, 0xF0 is
|
||||
* frequently used. Legal values are 0xF0 or 0xF8-0xFF.
|
||||
*/
|
||||
uint8_t mediaType;
|
||||
/**
|
||||
* Count of sectors occupied by one FAT on FAT12/FAT16 volumes.
|
||||
* On FAT32 volumes this field must be 0, and sectorsPerFat32
|
||||
* contains the FAT size count.
|
||||
*/
|
||||
uint16_t sectorsPerFat16;
|
||||
/** Sectors per track for interrupt 0x13. Not used otherwise. */
|
||||
uint16_t sectorsPerTrack;
|
||||
/** Number of heads for interrupt 0x13. Not used otherwise. */
|
||||
uint16_t headCount;
|
||||
/**
|
||||
* Count of hidden sectors preceding the partition that contains this
|
||||
* FAT volume. This field is generally only relevant for media
|
||||
* visible on interrupt 0x13.
|
||||
*/
|
||||
uint32_t hidddenSectors;
|
||||
/**
|
||||
* This field is the new 32-bit total count of sectors on the volume.
|
||||
* This count includes the count of all sectors in all four regions
|
||||
* of the volume. This field can be 0; if it is 0, then
|
||||
* totalSectors16 must be non-zero.
|
||||
*/
|
||||
uint32_t totalSectors32;
|
||||
/**
|
||||
* Related to the BIOS physical drive number. Floppy drives are
|
||||
* identified as 0x00 and physical hard disks are identified as
|
||||
* 0x80, regardless of the number of physical disk drives.
|
||||
* Typically, this value is set prior to issuing an INT 13h BIOS
|
||||
* call to specify the device to access. The value is only
|
||||
* relevant if the device is a boot device.
|
||||
*/
|
||||
uint8_t driveNumber;
|
||||
/** used by Windows NT - should be zero for FAT */
|
||||
uint8_t reserved1;
|
||||
/** 0X29 if next three fields are valid */
|
||||
uint8_t bootSignature;
|
||||
/**
|
||||
* A random serial number created when formatting a disk,
|
||||
* which helps to distinguish between disks.
|
||||
* Usually generated by combining date and time.
|
||||
*/
|
||||
uint32_t volumeSerialNumber;
|
||||
/**
|
||||
* A field once used to store the volume label. The volume label
|
||||
* is now stored as a special file in the root directory.
|
||||
*/
|
||||
char volumeLabel[11];
|
||||
/**
|
||||
* A field with a value of either FAT, FAT12 or FAT16,
|
||||
* depending on the disk format.
|
||||
*/
|
||||
char fileSystemType[8];
|
||||
/** X86 boot code */
|
||||
uint8_t bootCode[448];
|
||||
/** must be 0X55 */
|
||||
uint8_t bootSectorSig0;
|
||||
/** must be 0XAA */
|
||||
uint8_t bootSectorSig1;
|
||||
} __attribute__((packed));
|
||||
/** Type name for FAT Boot Sector */
|
||||
typedef struct fat_boot fat_boot_t;
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* \struct fat32_boot
|
||||
*
|
||||
* \brief Boot sector for a FAT32 volume.
|
||||
*
|
||||
*/
|
||||
struct fat32_boot {
|
||||
/**
|
||||
* The first three bytes of the boot sector must be valid,
|
||||
* executable x 86-based CPU instructions. This includes a
|
||||
* jump instruction that skips the next non-executable bytes.
|
||||
*/
|
||||
uint8_t jump[3];
|
||||
/**
|
||||
* This is typically a string of characters that identifies
|
||||
* the operating system that formatted the volume.
|
||||
*/
|
||||
char oemId[8];
|
||||
/**
|
||||
* The size of a hardware sector. Valid decimal values for this
|
||||
* field are 512, 1024, 2048, and 4096. For most disks used in
|
||||
* the United States, the value of this field is 512.
|
||||
*/
|
||||
uint16_t bytesPerSector;
|
||||
/**
|
||||
* Number of sectors per allocation unit. This value must be a
|
||||
* power of 2 that is greater than 0. The legal values are
|
||||
* 1, 2, 4, 8, 16, 32, 64, and 128. 128 should be avoided.
|
||||
*/
|
||||
uint8_t sectorsPerCluster;
|
||||
/**
|
||||
* The number of sectors preceding the start of the first FAT,
|
||||
* including the boot sector. Must not be zero
|
||||
*/
|
||||
uint16_t reservedSectorCount;
|
||||
/**
|
||||
* The number of copies of the FAT on the volume.
|
||||
* The value of this field is always 2.
|
||||
*/
|
||||
uint8_t fatCount;
|
||||
/**
|
||||
* FAT12/FAT16 only. For FAT32 volumes, this field must be set to 0.
|
||||
*/
|
||||
uint16_t rootDirEntryCount;
|
||||
/**
|
||||
* For FAT32 volumes, this field must be 0.
|
||||
*/
|
||||
uint16_t totalSectors16;
|
||||
/**
|
||||
* This dates back to the old MS-DOS 1.x media determination and is
|
||||
* no longer usually used for anything. 0xF8 is the standard value
|
||||
* for fixed (non-removable) media. For removable media, 0xF0 is
|
||||
* frequently used. Legal values are 0xF0 or 0xF8-0xFF.
|
||||
*/
|
||||
uint8_t mediaType;
|
||||
/**
|
||||
* On FAT32 volumes this field must be 0, and sectorsPerFat32
|
||||
* contains the FAT size count.
|
||||
*/
|
||||
uint16_t sectorsPerFat16;
|
||||
/** Sectors per track for interrupt 0x13. Not used otherwise. */
|
||||
uint16_t sectorsPerTrack;
|
||||
/** Number of heads for interrupt 0x13. Not used otherwise. */
|
||||
uint16_t headCount;
|
||||
/**
|
||||
* Count of hidden sectors preceding the partition that contains this
|
||||
* FAT volume. This field is generally only relevant for media
|
||||
* visible on interrupt 0x13.
|
||||
*/
|
||||
uint32_t hidddenSectors;
|
||||
/**
|
||||
* Contains the total number of sectors in the FAT32 volume.
|
||||
*/
|
||||
uint32_t totalSectors32;
|
||||
/**
|
||||
* Count of sectors occupied by one FAT on FAT32 volumes.
|
||||
*/
|
||||
uint32_t sectorsPerFat32;
|
||||
/**
|
||||
* This field is only defined for FAT32 media and does not exist on
|
||||
* FAT12 and FAT16 media.
|
||||
* Bits 0-3 -- Zero-based number of active FAT.
|
||||
* Only valid if mirroring is disabled.
|
||||
* Bits 4-6 -- Reserved.
|
||||
* Bit 7 -- 0 means the FAT is mirrored at runtime into all FATs.
|
||||
* -- 1 means only one FAT is active; it is the one referenced
|
||||
* in bits 0-3.
|
||||
* Bits 8-15 -- Reserved.
|
||||
*/
|
||||
uint16_t fat32Flags;
|
||||
/**
|
||||
* FAT32 version. High byte is major revision number.
|
||||
* Low byte is minor revision number. Only 0.0 define.
|
||||
*/
|
||||
uint16_t fat32Version;
|
||||
/**
|
||||
* Cluster number of the first cluster of the root directory for FAT32.
|
||||
* This usually 2 but not required to be 2.
|
||||
*/
|
||||
uint32_t fat32RootCluster;
|
||||
/**
|
||||
* Sector number of FSINFO structure in the reserved area of the
|
||||
* FAT32 volume. Usually 1.
|
||||
*/
|
||||
uint16_t fat32FSInfo;
|
||||
/**
|
||||
* If non-zero, indicates the sector number in the reserved area
|
||||
* of the volume of a copy of the boot record. Usually 6.
|
||||
* No value other than 6 is recommended.
|
||||
*/
|
||||
uint16_t fat32BackBootBlock;
|
||||
/**
|
||||
* Reserved for future expansion. Code that formats FAT32 volumes
|
||||
* should always set all of the bytes of this field to 0.
|
||||
*/
|
||||
uint8_t fat32Reserved[12];
|
||||
/**
|
||||
* Related to the BIOS physical drive number. Floppy drives are
|
||||
* identified as 0x00 and physical hard disks are identified as
|
||||
* 0x80, regardless of the number of physical disk drives.
|
||||
* Typically, this value is set prior to issuing an INT 13h BIOS
|
||||
* call to specify the device to access. The value is only
|
||||
* relevant if the device is a boot device.
|
||||
*/
|
||||
uint8_t driveNumber;
|
||||
/** used by Windows NT - should be zero for FAT */
|
||||
uint8_t reserved1;
|
||||
/** 0X29 if next three fields are valid */
|
||||
uint8_t bootSignature;
|
||||
/**
|
||||
* A random serial number created when formatting a disk,
|
||||
* which helps to distinguish between disks.
|
||||
* Usually generated by combining date and time.
|
||||
*/
|
||||
uint32_t volumeSerialNumber;
|
||||
/**
|
||||
* A field once used to store the volume label. The volume label
|
||||
* is now stored as a special file in the root directory.
|
||||
*/
|
||||
char volumeLabel[11];
|
||||
/**
|
||||
* A text field with a value of FAT32.
|
||||
*/
|
||||
char fileSystemType[8];
|
||||
/** X86 boot code */
|
||||
uint8_t bootCode[420];
|
||||
/** must be 0X55 */
|
||||
uint8_t bootSectorSig0;
|
||||
/** must be 0XAA */
|
||||
uint8_t bootSectorSig1;
|
||||
} __attribute__((packed));
|
||||
/** Type name for FAT32 Boot Sector */
|
||||
typedef struct fat32_boot fat32_boot_t;
|
||||
//------------------------------------------------------------------------------
|
||||
/** Lead signature for a FSINFO sector */
|
||||
const uint32_t FSINFO_LEAD_SIG = 0x41615252;
|
||||
/** Struct signature for a FSINFO sector */
|
||||
const uint32_t FSINFO_STRUCT_SIG = 0x61417272;
|
||||
/**
|
||||
* \struct fat32_fsinfo
|
||||
*
|
||||
* \brief FSINFO sector for a FAT32 volume.
|
||||
*
|
||||
*/
|
||||
struct fat32_fsinfo {
|
||||
/** must be 0X52, 0X52, 0X61, 0X41 */
|
||||
uint32_t leadSignature;
|
||||
/** must be zero */
|
||||
uint8_t reserved1[480];
|
||||
/** must be 0X72, 0X72, 0X41, 0X61 */
|
||||
uint32_t structSignature;
|
||||
/**
|
||||
* Contains the last known free cluster count on the volume.
|
||||
* If the value is 0xFFFFFFFF, then the free count is unknown
|
||||
* and must be computed. Any other value can be used, but is
|
||||
* not necessarily correct. It should be range checked at least
|
||||
* to make sure it is <= volume cluster count.
|
||||
*/
|
||||
uint32_t freeCount;
|
||||
/**
|
||||
* This is a hint for the FAT driver. It indicates the cluster
|
||||
* number at which the driver should start looking for free clusters.
|
||||
* If the value is 0xFFFFFFFF, then there is no hint and the driver
|
||||
* should start looking at cluster 2.
|
||||
*/
|
||||
uint32_t nextFree;
|
||||
/** must be zero */
|
||||
uint8_t reserved2[12];
|
||||
/** must be 0X00, 0X00, 0X55, 0XAA */
|
||||
uint8_t tailSignature[4];
|
||||
} __attribute__((packed));
|
||||
/** Type name for FAT32 FSINFO Sector */
|
||||
typedef struct fat32_fsinfo fat32_fsinfo_t;
|
||||
//------------------------------------------------------------------------------
|
||||
// End Of Chain values for FAT entries
|
||||
/** FAT12 end of chain value used by Microsoft. */
|
||||
const uint16_t FAT12EOC = 0XFFF;
|
||||
/** Minimum value for FAT12 EOC. Use to test for EOC. */
|
||||
const uint16_t FAT12EOC_MIN = 0XFF8;
|
||||
/** FAT16 end of chain value used by Microsoft. */
|
||||
const uint16_t FAT16EOC = 0XFFFF;
|
||||
/** Minimum value for FAT16 EOC. Use to test for EOC. */
|
||||
const uint16_t FAT16EOC_MIN = 0XFFF8;
|
||||
/** FAT32 end of chain value used by Microsoft. */
|
||||
const uint32_t FAT32EOC = 0X0FFFFFFF;
|
||||
/** Minimum value for FAT32 EOC. Use to test for EOC. */
|
||||
const uint32_t FAT32EOC_MIN = 0X0FFFFFF8;
|
||||
/** Mask a for FAT32 entry. Entries are 28 bits. */
|
||||
const uint32_t FAT32MASK = 0X0FFFFFFF;
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* \struct directoryEntry
|
||||
* \brief FAT short directory entry
|
||||
*
|
||||
* Short means short 8.3 name, not the entry size.
|
||||
*
|
||||
* Date Format. A FAT directory entry date stamp is a 16-bit field that is
|
||||
* basically a date relative to the MS-DOS epoch of 01/01/1980. Here is the
|
||||
* format (bit 0 is the LSB of the 16-bit word, bit 15 is the MSB of the
|
||||
* 16-bit word):
|
||||
*
|
||||
* Bits 9-15: Count of years from 1980, valid value range 0-127
|
||||
* inclusive (1980-2107).
|
||||
*
|
||||
* Bits 5-8: Month of year, 1 = January, valid value range 1-12 inclusive.
|
||||
*
|
||||
* Bits 0-4: Day of month, valid value range 1-31 inclusive.
|
||||
*
|
||||
* Time Format. A FAT directory entry time stamp is a 16-bit field that has
|
||||
* a granularity of 2 seconds. Here is the format (bit 0 is the LSB of the
|
||||
* 16-bit word, bit 15 is the MSB of the 16-bit word).
|
||||
*
|
||||
* Bits 11-15: Hours, valid value range 0-23 inclusive.
|
||||
*
|
||||
* Bits 5-10: Minutes, valid value range 0-59 inclusive.
|
||||
*
|
||||
* Bits 0-4: 2-second count, valid value range 0-29 inclusive (0 - 58 seconds).
|
||||
*
|
||||
* The valid time range is from Midnight 00:00:00 to 23:59:58.
|
||||
*/
|
||||
struct directoryEntry {
|
||||
/** Short 8.3 name.
|
||||
*
|
||||
* The first eight bytes contain the file name with blank fill.
|
||||
* The last three bytes contain the file extension with blank fill.
|
||||
*/
|
||||
uint8_t name[11];
|
||||
/** Entry attributes.
|
||||
*
|
||||
* The upper two bits of the attribute byte are reserved and should
|
||||
* always be set to 0 when a file is created and never modified or
|
||||
* looked at after that. See defines that begin with DIR_ATT_.
|
||||
*/
|
||||
uint8_t attributes;
|
||||
/**
|
||||
* Reserved for use by Windows NT. Set value to 0 when a file is
|
||||
* created and never modify or look at it after that.
|
||||
*/
|
||||
uint8_t reservedNT;
|
||||
/**
|
||||
* The granularity of the seconds part of creationTime is 2 seconds
|
||||
* so this field is a count of tenths of a second and its valid
|
||||
* value range is 0-199 inclusive. (WHG note - seems to be hundredths)
|
||||
*/
|
||||
uint8_t creationTimeTenths;
|
||||
/** Time file was created. */
|
||||
uint16_t creationTime;
|
||||
/** Date file was created. */
|
||||
uint16_t creationDate;
|
||||
/**
|
||||
* Last access date. Note that there is no last access time, only
|
||||
* a date. This is the date of last read or write. In the case of
|
||||
* a write, this should be set to the same date as lastWriteDate.
|
||||
*/
|
||||
uint16_t lastAccessDate;
|
||||
/**
|
||||
* High word of this entry's first cluster number (always 0 for a
|
||||
* FAT12 or FAT16 volume).
|
||||
*/
|
||||
uint16_t firstClusterHigh;
|
||||
/** Time of last write. File creation is considered a write. */
|
||||
uint16_t lastWriteTime;
|
||||
/** Date of last write. File creation is considered a write. */
|
||||
uint16_t lastWriteDate;
|
||||
/** Low word of this entry's first cluster number. */
|
||||
uint16_t firstClusterLow;
|
||||
/** 32-bit unsigned holding this file's size in bytes. */
|
||||
uint32_t fileSize;
|
||||
} __attribute__((packed));
|
||||
/** Type name for directoryEntry */
|
||||
typedef struct directoryEntry dir_t;
|
||||
//------------------------------------------------------------------------------
|
||||
// Definitions for directory entries
|
||||
//
|
||||
/** escape for name[0] = 0XE5 */
|
||||
const uint8_t DIR_NAME_0XE5 = 0X05;
|
||||
/** name[0] value for entry that is free after being "deleted" */
|
||||
const uint8_t DIR_NAME_DELETED = 0XE5;
|
||||
/** name[0] value for entry that is free and no allocated entries follow */
|
||||
const uint8_t DIR_NAME_FREE = 0X00;
|
||||
/** file is read-only */
|
||||
const uint8_t DIR_ATT_READ_ONLY = 0X01;
|
||||
/** File should e hidden in directory listings */
|
||||
const uint8_t DIR_ATT_HIDDEN = 0X02;
|
||||
/** Entry is for a system file */
|
||||
const uint8_t DIR_ATT_SYSTEM = 0X04;
|
||||
/** Directory entry contains the volume label */
|
||||
const uint8_t DIR_ATT_VOLUME_ID = 0X08;
|
||||
/** Entry is for a directory */
|
||||
const uint8_t DIR_ATT_DIRECTORY = 0X10;
|
||||
/** Old DOS archive bit for backup support */
|
||||
const uint8_t DIR_ATT_ARCHIVE = 0X20;
|
||||
/** Test value for long name entry. Test is
|
||||
(d->attributes & DIR_ATT_LONG_NAME_MASK) == DIR_ATT_LONG_NAME. */
|
||||
const uint8_t DIR_ATT_LONG_NAME = 0X0F;
|
||||
/** Test mask for long name entry */
|
||||
const uint8_t DIR_ATT_LONG_NAME_MASK = 0X3F;
|
||||
/** defined attribute bits */
|
||||
const uint8_t DIR_ATT_DEFINED_BITS = 0X3F;
|
||||
|
||||
/** Mask for file/subdirectory tests */
|
||||
const uint8_t DIR_ATT_FILE_TYPE_MASK = (DIR_ATT_VOLUME_ID | DIR_ATT_DIRECTORY);
|
||||
|
||||
/** Filename base-name is all lower case */
|
||||
const uint8_t DIR_NT_LC_BASE = 0X08;
|
||||
/** Filename extension is all lower case.*/
|
||||
const uint8_t DIR_NT_LC_EXT = 0X10;
|
||||
|
||||
|
||||
/** Directory entry is for a file
|
||||
* \param[in] dir Pointer to a directory entry.
|
||||
*
|
||||
* \return true if the entry is for a normal file else false.
|
||||
*/
|
||||
static inline uint8_t DIR_IS_FILE(const dir_t* dir) {
|
||||
return (dir->attributes & DIR_ATT_FILE_TYPE_MASK) == 0;
|
||||
}
|
||||
/** Directory entry is for a file or subdirectory
|
||||
* \param[in] dir Pointer to a directory entry.
|
||||
*
|
||||
* \return true if the entry is for a normal file or subdirectory else false.
|
||||
*/
|
||||
static inline uint8_t DIR_IS_FILE_OR_SUBDIR(const dir_t* dir) {
|
||||
return (dir->attributes & DIR_ATT_VOLUME_ID) == 0;
|
||||
}
|
||||
/** Directory entry is part of a long name
|
||||
* \param[in] dir Pointer to a directory entry.
|
||||
*
|
||||
* \return true if the entry is for part of a long name else false.
|
||||
*/
|
||||
static inline uint8_t DIR_IS_LONG_NAME(const dir_t* dir) {
|
||||
return dir->attributes == DIR_ATT_LONG_NAME;
|
||||
}
|
||||
/** Directory entry is hidden
|
||||
* \param[in] dir Pointer to a directory entry.
|
||||
*
|
||||
* \return true if the entry is hidden else false.
|
||||
*/
|
||||
static inline uint8_t DIR_IS_HIDDEN(const dir_t* dir) {
|
||||
return dir->attributes & DIR_ATT_HIDDEN;
|
||||
}
|
||||
/** Directory entry is for a subdirectory
|
||||
* \param[in] dir Pointer to a directory entry.
|
||||
*
|
||||
* \return true if the entry is for a subdirectory else false.
|
||||
*/
|
||||
static inline uint8_t DIR_IS_SUBDIR(const dir_t* dir) {
|
||||
return (dir->attributes & DIR_ATT_FILE_TYPE_MASK) == DIR_ATT_DIRECTORY;
|
||||
}
|
||||
/** Directory entry is system type
|
||||
* \param[in] dir Pointer to a directory entry.
|
||||
*
|
||||
* \return true if the entry is system else false.
|
||||
*/
|
||||
static inline uint8_t DIR_IS_SYSTEM(const dir_t* dir) {
|
||||
return dir->attributes & DIR_ATT_SYSTEM;
|
||||
}
|
||||
/** date field for FAT directory entry
|
||||
* \param[in] year [1980,2107]
|
||||
* \param[in] month [1,12]
|
||||
* \param[in] day [1,31]
|
||||
*
|
||||
* \return Packed date for dir_t entry.
|
||||
*/
|
||||
static inline uint16_t FAT_DATE(uint16_t year, uint8_t month, uint8_t day) {
|
||||
return (year - 1980) << 9 | month << 5 | day;
|
||||
}
|
||||
/** year part of FAT directory date field
|
||||
* \param[in] fatDate Date in packed dir format.
|
||||
*
|
||||
* \return Extracted year [1980,2107]
|
||||
*/
|
||||
static inline uint16_t FAT_YEAR(uint16_t fatDate) {
|
||||
return 1980 + (fatDate >> 9);
|
||||
}
|
||||
/** month part of FAT directory date field
|
||||
* \param[in] fatDate Date in packed dir format.
|
||||
*
|
||||
* \return Extracted month [1,12]
|
||||
*/
|
||||
static inline uint8_t FAT_MONTH(uint16_t fatDate) {
|
||||
return (fatDate >> 5) & 0XF;
|
||||
}
|
||||
/** day part of FAT directory date field
|
||||
* \param[in] fatDate Date in packed dir format.
|
||||
*
|
||||
* \return Extracted day [1,31]
|
||||
*/
|
||||
static inline uint8_t FAT_DAY(uint16_t fatDate) {
|
||||
return fatDate & 0X1F;
|
||||
}
|
||||
/** time field for FAT directory entry
|
||||
* \param[in] hour [0,23]
|
||||
* \param[in] minute [0,59]
|
||||
* \param[in] second [0,59]
|
||||
*
|
||||
* \return Packed time for dir_t entry.
|
||||
*/
|
||||
static inline uint16_t FAT_TIME(uint8_t hour, uint8_t minute, uint8_t second) {
|
||||
return hour << 11 | minute << 5 | second >> 1;
|
||||
}
|
||||
/** hour part of FAT directory time field
|
||||
* \param[in] fatTime Time in packed dir format.
|
||||
*
|
||||
* \return Extracted hour [0,23]
|
||||
*/
|
||||
static inline uint8_t FAT_HOUR(uint16_t fatTime) {
|
||||
return fatTime >> 11;
|
||||
}
|
||||
/** minute part of FAT directory time field
|
||||
* \param[in] fatTime Time in packed dir format.
|
||||
*
|
||||
* \return Extracted minute [0,59]
|
||||
*/
|
||||
static inline uint8_t FAT_MINUTE(uint16_t fatTime) {
|
||||
return (fatTime >> 5) & 0X3F;
|
||||
}
|
||||
/** second part of FAT directory time field
|
||||
* Note second/2 is stored in packed time.
|
||||
*
|
||||
* \param[in] fatTime Time in packed dir format.
|
||||
*
|
||||
* \return Extracted second [0,58]
|
||||
*/
|
||||
static inline uint8_t FAT_SECOND(uint16_t fatTime) {
|
||||
return 2*(fatTime & 0X1F);
|
||||
}
|
||||
/** Default date for file timestamps is 1 Jan 2000 */
|
||||
const uint16_t FAT_DEFAULT_DATE = ((2000 - 1980) << 9) | (1 << 5) | 1;
|
||||
/** Default time for file timestamp is 1 am */
|
||||
const uint16_t FAT_DEFAULT_TIME = (1 << 11);
|
||||
//------------------------------------------------------------------------------
|
||||
/** Dimension of first name field in long directory entry */
|
||||
const uint8_t LDIR_NAME1_DIM = 5;
|
||||
/** Dimension of first name field in long directory entry */
|
||||
const uint8_t LDIR_NAME2_DIM = 6;
|
||||
/** Dimension of first name field in long directory entry */
|
||||
const uint8_t LDIR_NAME3_DIM = 2;
|
||||
/**
|
||||
* \struct longDirectoryEntry
|
||||
* \brief FAT long directory entry
|
||||
*/
|
||||
struct longDirectoryEntry {
|
||||
/**
|
||||
* The order of this entry in the sequence of long dir entries
|
||||
* associated with the short dir entry at the end of the long dir set.
|
||||
*
|
||||
* If masked with 0X40 (LAST_LONG_ENTRY), this indicates the
|
||||
* entry is the last long dir entry in a set of long dir entries.
|
||||
* All valid sets of long dir entries must begin with an entry having
|
||||
* this mask.
|
||||
*/
|
||||
uint8_t ord;
|
||||
/** Characters 1-5 of the long-name sub-component in this entry. */
|
||||
uint16_t name1[LDIR_NAME1_DIM];
|
||||
/** Attributes - must be ATTR_LONG_NAME */
|
||||
uint8_t attr;
|
||||
/**
|
||||
* If zero, indicates a directory entry that is a sub-component of a
|
||||
* long name. NOTE: Other values reserved for future extensions.
|
||||
*
|
||||
* Non-zero implies other directory entry types.
|
||||
*/
|
||||
uint8_t type;
|
||||
/**
|
||||
* Checksum of name in the short dir entry at the end of the
|
||||
* long dir set.
|
||||
*/
|
||||
uint8_t chksum;
|
||||
/** Characters 6-11 of the long-name sub-component in this entry. */
|
||||
uint16_t name2[LDIR_NAME2_DIM];
|
||||
/** Must be ZERO. This is an artifact of the FAT "first cluster" */
|
||||
uint16_t mustBeZero;
|
||||
/** Characters 12 and 13 of the long-name sub-component in this entry. */
|
||||
uint16_t name3[LDIR_NAME3_DIM];
|
||||
} __attribute__((packed));
|
||||
/** Type name for longDirectoryEntry */
|
||||
typedef struct longDirectoryEntry ldir_t;
|
||||
/**
|
||||
* Ord mast that indicates the entry is the last long dir entry in a
|
||||
* set of long dir entries. All valid sets of long dir entries must
|
||||
* begin with an entry having this mask.
|
||||
*/
|
||||
const uint8_t LDIR_ORD_LAST_LONG_ENTRY = 0X40;
|
||||
#endif // FatStructs_h
|
606
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/FatVolume.cpp
Normal file
606
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/FatVolume.cpp
Normal file
@ -0,0 +1,606 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
|
||||
#include "../../../Repetier.h"
|
||||
#include <string.h>
|
||||
#include "FatVolume.h"
|
||||
//------------------------------------------------------------------------------
|
||||
cache_t* FatCache::read(uint32_t lbn, uint8_t option) {
|
||||
if (m_lbn != lbn) {
|
||||
if (!sync()) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
if (!(option & CACHE_OPTION_NO_READ)) {
|
||||
if (!m_vol->readBlock(lbn, m_block.data)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
m_status = 0;
|
||||
m_lbn = lbn;
|
||||
}
|
||||
m_status |= option & CACHE_STATUS_MASK;
|
||||
return &m_block;
|
||||
|
||||
fail:
|
||||
|
||||
return 0;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool FatCache::sync() {
|
||||
if (m_status & CACHE_STATUS_DIRTY) {
|
||||
if (!m_vol->writeBlock(m_lbn, m_block.data)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
// mirror second FAT
|
||||
if (m_status & CACHE_STATUS_MIRROR_FAT) {
|
||||
uint32_t lbn = m_lbn + m_vol->blocksPerFat();
|
||||
if (!m_vol->writeBlock(lbn, m_block.data)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
m_status &= ~CACHE_STATUS_DIRTY;
|
||||
}
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool FatVolume::allocateCluster(uint32_t current, uint32_t* next) {
|
||||
uint32_t find = current ? current : m_allocSearchStart;
|
||||
uint32_t start = find;
|
||||
while (1) {
|
||||
find++;
|
||||
// If at end of FAT go to beginning of FAT.
|
||||
if (find > m_lastCluster) {
|
||||
find = 2;
|
||||
}
|
||||
uint32_t f;
|
||||
int8_t fg = fatGet(find, &f);
|
||||
if (fg < 0) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
if (fg && f == 0) {
|
||||
break;
|
||||
}
|
||||
if (find == start) {
|
||||
// Can't find space checked all clusters.
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
// mark end of chain
|
||||
if (!fatPutEOC(find)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
if (current) {
|
||||
// link clusters
|
||||
if (!fatPut(current, find)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
} else {
|
||||
// Remember place for search start.
|
||||
m_allocSearchStart = find;
|
||||
}
|
||||
updateFreeClusterCount(-1);
|
||||
*next = find;
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// find a contiguous group of clusters
|
||||
bool FatVolume::allocContiguous(uint32_t count, uint32_t* firstCluster) {
|
||||
// flag to save place to start next search
|
||||
bool setStart = true;
|
||||
// start of group
|
||||
uint32_t bgnCluster;
|
||||
// end of group
|
||||
uint32_t endCluster;
|
||||
// Start at cluster after last allocated cluster.
|
||||
uint32_t startCluster = m_allocSearchStart;
|
||||
endCluster = bgnCluster = startCluster + 1;
|
||||
|
||||
// search the FAT for free clusters
|
||||
while (1) {
|
||||
// If past end - start from beginning of FAT.
|
||||
if (endCluster > m_lastCluster) {
|
||||
bgnCluster = endCluster = 2;
|
||||
}
|
||||
uint32_t f;
|
||||
int8_t fg = fatGet(endCluster, &f);
|
||||
if (fg < 0) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
if (f || fg == 0) {
|
||||
// cluster in use try next cluster as bgnCluster
|
||||
bgnCluster = endCluster + 1;
|
||||
|
||||
// don't update search start if unallocated clusters before endCluster.
|
||||
if (bgnCluster != endCluster) {
|
||||
setStart = false;
|
||||
}
|
||||
} else if ((endCluster - bgnCluster + 1) == count) {
|
||||
// done - found space
|
||||
break;
|
||||
}
|
||||
// Can't find space if all clusters checked.
|
||||
if (startCluster == endCluster) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
endCluster++;
|
||||
}
|
||||
// remember possible next free cluster
|
||||
if (setStart) {
|
||||
m_allocSearchStart = endCluster + 1;
|
||||
}
|
||||
|
||||
// mark end of chain
|
||||
if (!fatPutEOC(endCluster)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
// link clusters
|
||||
while (endCluster > bgnCluster) {
|
||||
if (!fatPut(endCluster - 1, endCluster)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
endCluster--;
|
||||
}
|
||||
// Maintain count of free clusters.
|
||||
updateFreeClusterCount(-count);
|
||||
|
||||
// return first cluster number to caller
|
||||
*firstCluster = bgnCluster;
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
uint32_t FatVolume::clusterFirstBlock(uint32_t cluster) const {
|
||||
return m_dataStartBlock + ((cluster - 2) << m_clusterSizeShift);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// Fetch a FAT entry - return -1 error, 0 EOC, else 1.
|
||||
int8_t FatVolume::fatGet(uint32_t cluster, uint32_t* value) {
|
||||
uint32_t lba;
|
||||
uint32_t next;
|
||||
cache_t* pc;
|
||||
|
||||
// error if reserved cluster of beyond FAT
|
||||
if (cluster < 2 || cluster > m_lastCluster) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
|
||||
if (fatType() == 32) {
|
||||
lba = m_fatStartBlock + (cluster >> 7);
|
||||
pc = cacheFetchFat(lba, FatCache::CACHE_FOR_READ);
|
||||
if (!pc) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
next = pc->fat32[cluster & 0X7F] & FAT32MASK;
|
||||
goto done;
|
||||
}
|
||||
if (fatType() == 16) {
|
||||
lba = m_fatStartBlock + ((cluster >> 8) & 0XFF);
|
||||
pc = cacheFetchFat(lba, FatCache::CACHE_FOR_READ);
|
||||
if (!pc) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
next = pc->fat16[cluster & 0XFF];
|
||||
goto done;
|
||||
}
|
||||
if (FAT12_SUPPORT && fatType() == 12) {
|
||||
uint16_t index = cluster;
|
||||
index += index >> 1;
|
||||
lba = m_fatStartBlock + (index >> 9);
|
||||
pc = cacheFetchFat(lba, FatCache::CACHE_FOR_READ);
|
||||
if (!pc) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
index &= 0X1FF;
|
||||
uint16_t tmp = pc->data[index];
|
||||
index++;
|
||||
if (index == 512) {
|
||||
pc = cacheFetchFat(lba + 1, FatCache::CACHE_FOR_READ);
|
||||
if (!pc) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
index = 0;
|
||||
}
|
||||
tmp |= pc->data[index] << 8;
|
||||
next = cluster & 1 ? tmp >> 4 : tmp & 0XFFF;
|
||||
goto done;
|
||||
} else {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
done:
|
||||
if (isEOC(next)) {
|
||||
return 0;
|
||||
}
|
||||
*value = next;
|
||||
return 1;
|
||||
|
||||
fail:
|
||||
return -1;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// Store a FAT entry
|
||||
bool FatVolume::fatPut(uint32_t cluster, uint32_t value) {
|
||||
uint32_t lba;
|
||||
cache_t* pc;
|
||||
|
||||
// error if reserved cluster of beyond FAT
|
||||
if (cluster < 2 || cluster > m_lastCluster) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
|
||||
if (fatType() == 32) {
|
||||
lba = m_fatStartBlock + (cluster >> 7);
|
||||
pc = cacheFetchFat(lba, FatCache::CACHE_FOR_WRITE);
|
||||
if (!pc) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
pc->fat32[cluster & 0X7F] = value;
|
||||
return true;
|
||||
}
|
||||
|
||||
if (fatType() == 16) {
|
||||
lba = m_fatStartBlock + ((cluster >> 8) & 0XFF);
|
||||
pc = cacheFetchFat(lba, FatCache::CACHE_FOR_WRITE);
|
||||
if (!pc) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
pc->fat16[cluster & 0XFF] = value;
|
||||
return true;
|
||||
}
|
||||
|
||||
if (FAT12_SUPPORT && fatType() == 12) {
|
||||
uint16_t index = cluster;
|
||||
index += index >> 1;
|
||||
lba = m_fatStartBlock + (index >> 9);
|
||||
pc = cacheFetchFat(lba, FatCache::CACHE_FOR_WRITE);
|
||||
if (!pc) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
index &= 0X1FF;
|
||||
uint8_t tmp = value;
|
||||
if (cluster & 1) {
|
||||
tmp = (pc->data[index] & 0XF) | tmp << 4;
|
||||
}
|
||||
pc->data[index] = tmp;
|
||||
|
||||
index++;
|
||||
if (index == 512) {
|
||||
lba++;
|
||||
index = 0;
|
||||
pc = cacheFetchFat(lba, FatCache::CACHE_FOR_WRITE);
|
||||
if (!pc) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
tmp = value >> 4;
|
||||
if (!(cluster & 1)) {
|
||||
tmp = ((pc->data[index] & 0XF0)) | tmp >> 4;
|
||||
}
|
||||
pc->data[index] = tmp;
|
||||
return true;
|
||||
} else {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// free a cluster chain
|
||||
bool FatVolume::freeChain(uint32_t cluster) {
|
||||
uint32_t next;
|
||||
int8_t fg;
|
||||
do {
|
||||
fg = fatGet(cluster, &next);
|
||||
if (fg < 0) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
// free cluster
|
||||
if (!fatPut(cluster, 0)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
// Add one to count of free clusters.
|
||||
updateFreeClusterCount(1);
|
||||
|
||||
if (cluster < m_allocSearchStart) {
|
||||
m_allocSearchStart = cluster;
|
||||
}
|
||||
cluster = next;
|
||||
} while (fg);
|
||||
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int32_t FatVolume::freeClusterCount() {
|
||||
#if MAINTAIN_FREE_CLUSTER_COUNT
|
||||
if (m_freeClusterCount >= 0) {
|
||||
return m_freeClusterCount;
|
||||
}
|
||||
#endif // MAINTAIN_FREE_CLUSTER_COUNT
|
||||
uint32_t free = 0;
|
||||
uint32_t lba;
|
||||
uint32_t todo = m_lastCluster + 1;
|
||||
uint16_t n;
|
||||
|
||||
if (FAT12_SUPPORT && fatType() == 12) {
|
||||
for (unsigned i = 2; i < todo; i++) {
|
||||
uint32_t c;
|
||||
int8_t fg = fatGet(i, &c);
|
||||
if (fg < 0) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
if (fg && c == 0) {
|
||||
free++;
|
||||
}
|
||||
}
|
||||
} else if (fatType() == 16 || fatType() == 32) {
|
||||
lba = m_fatStartBlock;
|
||||
while (todo) {
|
||||
cache_t* pc = cacheFetchFat(lba++, FatCache::CACHE_FOR_READ);
|
||||
if (!pc) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
n = fatType() == 16 ? 256 : 128;
|
||||
if (todo < n) {
|
||||
n = todo;
|
||||
}
|
||||
if (fatType() == 16) {
|
||||
for (uint16_t i = 0; i < n; i++) {
|
||||
if (pc->fat16[i] == 0) {
|
||||
free++;
|
||||
}
|
||||
}
|
||||
} else {
|
||||
for (uint16_t i = 0; i < n; i++) {
|
||||
if (pc->fat32[i] == 0) {
|
||||
free++;
|
||||
}
|
||||
}
|
||||
}
|
||||
todo -= n;
|
||||
}
|
||||
} else {
|
||||
// invalid FAT type
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
setFreeClusterCount(free);
|
||||
return free;
|
||||
|
||||
fail:
|
||||
return -1;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool FatVolume::init(uint8_t part) {
|
||||
uint32_t clusterCount;
|
||||
uint32_t totalBlocks;
|
||||
uint32_t volumeStartBlock = 0;
|
||||
fat32_boot_t* fbs;
|
||||
cache_t* pc;
|
||||
uint8_t tmp;
|
||||
m_fatType = 0;
|
||||
m_allocSearchStart = 1;
|
||||
m_cache.init(this);
|
||||
#if USE_SEPARATE_FAT_CACHE
|
||||
m_fatCache.init(this);
|
||||
#endif // USE_SEPARATE_FAT_CACHE
|
||||
// if part == 0 assume super floppy with FAT boot sector in block zero
|
||||
// if part > 0 assume mbr volume with partition table
|
||||
if (part) {
|
||||
if (part > 4) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
pc = cacheFetchData(0, FatCache::CACHE_FOR_READ);
|
||||
if (!pc) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
part_t* p = &pc->mbr.part[part - 1];
|
||||
if ((p->boot & 0X7F) != 0 || p->firstSector == 0) {
|
||||
// not a valid partition
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
volumeStartBlock = p->firstSector;
|
||||
}
|
||||
pc = cacheFetchData(volumeStartBlock, FatCache::CACHE_FOR_READ);
|
||||
if (!pc) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
fbs = &(pc->fbs32);
|
||||
if (fbs->bytesPerSector != 512 ||
|
||||
fbs->fatCount != 2 ||
|
||||
fbs->reservedSectorCount == 0) {
|
||||
// not valid FAT volume
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
m_blocksPerCluster = fbs->sectorsPerCluster;
|
||||
m_clusterBlockMask = m_blocksPerCluster - 1;
|
||||
// determine shift that is same as multiply by m_blocksPerCluster
|
||||
m_clusterSizeShift = 0;
|
||||
for (tmp = 1; m_blocksPerCluster != tmp; tmp <<= 1, m_clusterSizeShift++) {
|
||||
if (tmp == 0) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
m_blocksPerFat = fbs->sectorsPerFat16 ?
|
||||
fbs->sectorsPerFat16 : fbs->sectorsPerFat32;
|
||||
|
||||
m_fatStartBlock = volumeStartBlock + fbs->reservedSectorCount;
|
||||
|
||||
// count for FAT16 zero for FAT32
|
||||
m_rootDirEntryCount = fbs->rootDirEntryCount;
|
||||
|
||||
// directory start for FAT16 dataStart for FAT32
|
||||
m_rootDirStart = m_fatStartBlock + 2 * m_blocksPerFat;
|
||||
// data start for FAT16 and FAT32
|
||||
m_dataStartBlock = m_rootDirStart + ((32 * fbs->rootDirEntryCount + 511)/512);
|
||||
|
||||
// total blocks for FAT16 or FAT32
|
||||
totalBlocks = fbs->totalSectors16 ?
|
||||
fbs->totalSectors16 : fbs->totalSectors32;
|
||||
// total data blocks
|
||||
clusterCount = totalBlocks - (m_dataStartBlock - volumeStartBlock);
|
||||
|
||||
// divide by cluster size to get cluster count
|
||||
clusterCount >>= m_clusterSizeShift;
|
||||
m_lastCluster = clusterCount + 1;
|
||||
|
||||
// Indicate unknown number of free clusters.
|
||||
setFreeClusterCount(-1);
|
||||
// FAT type is determined by cluster count
|
||||
if (clusterCount < 4085) {
|
||||
m_fatType = 12;
|
||||
if (!FAT12_SUPPORT) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
} else if (clusterCount < 65525) {
|
||||
m_fatType = 16;
|
||||
} else {
|
||||
m_rootDirStart = fbs->fat32RootCluster;
|
||||
m_fatType = 32;
|
||||
}
|
||||
return true;
|
||||
|
||||
fail:
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool FatVolume::wipe() {
|
||||
cache_t* cache;
|
||||
uint16_t count;
|
||||
uint32_t lbn;
|
||||
if (!fatType()) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
cache = cacheClear();
|
||||
if (!cache) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
memset(cache->data, 0, 512);
|
||||
// Zero root.
|
||||
if (fatType() == 32) {
|
||||
lbn = clusterFirstBlock(m_rootDirStart);
|
||||
count = m_blocksPerCluster;
|
||||
} else {
|
||||
lbn = m_rootDirStart;
|
||||
count = m_rootDirEntryCount/16;
|
||||
}
|
||||
for (uint32_t n = 0; n < count; n++) {
|
||||
if (!writeBlock(lbn + n, cache->data)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
// Clear FATs.
|
||||
count = 2*m_blocksPerFat;
|
||||
lbn = m_fatStartBlock;
|
||||
for (uint32_t nb = 0; nb < count; nb++) {
|
||||
if ((nb & 0XFF) == 0) {
|
||||
Com::print('.');
|
||||
}
|
||||
if (!writeBlock(lbn + nb, cache->data)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
// Reserve first two clusters.
|
||||
if (fatType() == 32) {
|
||||
cache->fat32[0] = 0x0FFFFFF8;
|
||||
cache->fat32[1] = 0x0FFFFFFF;
|
||||
} else if (fatType() == 16) {
|
||||
cache->fat16[0] = 0XFFF8;
|
||||
cache->fat16[1] = 0XFFFF;
|
||||
} else if (FAT12_SUPPORT && fatType() == 12) {
|
||||
cache->fat32[0] = 0XFFFFF8;
|
||||
} else {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
if (!writeBlock(m_fatStartBlock, cache->data) ||
|
||||
!writeBlock(m_fatStartBlock + m_blocksPerFat, cache->data)) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
if (fatType() == 32) {
|
||||
// Reserve root cluster.
|
||||
if (!fatPutEOC(m_rootDirStart) || !cacheSync()) {
|
||||
DBG_FAIL_MACRO;
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
Com::println();
|
||||
m_fatType = 0;
|
||||
return true;
|
||||
|
||||
fail:
|
||||
m_fatType = 0;
|
||||
return false;
|
||||
}
|
375
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/FatVolume.h
Normal file
375
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/FatVolume.h
Normal file
@ -0,0 +1,375 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef FatVolume_h
|
||||
#define FatVolume_h
|
||||
/**
|
||||
* \file
|
||||
* \brief FatVolume class
|
||||
*/
|
||||
#include <stddef.h>
|
||||
#include "FatLibConfig.h"
|
||||
#include "FatStructs.h"
|
||||
#include "../BlockDriver.h"
|
||||
//------------------------------------------------------------------------------
|
||||
#ifndef DOXYGEN_SHOULD_SKIP_THIS
|
||||
/** Macro for debug. */
|
||||
#define DEBUG_MODE 0
|
||||
#if DEBUG_MODE
|
||||
#define DBG_FAIL_MACRO Serial.print(F(__FILE__)); Serial.println(__LINE__);
|
||||
#define DBG_PRINT_IF(b) if (b) {Serial.println(F(#b)); DBG_FAIL_MACRO;}
|
||||
#define DBG_HALT_IF(b) if (b) {Serial.println(F(#b));\
|
||||
DBG_FAIL_MACRO; while (1);}
|
||||
#else // DEBUG_MODE
|
||||
#define DBG_FAIL_MACRO
|
||||
#define DBG_PRINT_IF(b)
|
||||
#define DBG_HALT_IF(b)
|
||||
#endif // DEBUG_MODE
|
||||
#endif // DOXYGEN_SHOULD_SKIP_THIS
|
||||
//------------------------------------------------------------------------------
|
||||
#if ENABLE_ARDUINO_FEATURES
|
||||
/** Use Print for Arduino */
|
||||
// typedef Print print_t;
|
||||
#else // ENABLE_ARDUINO_FEATURES
|
||||
/**
|
||||
* \class CharWriter
|
||||
* \brief Character output - often serial port.
|
||||
*/
|
||||
/*class CharWriter {
|
||||
public:
|
||||
virtual size_t write(char c) = 0;
|
||||
virtual size_t write(const char* s) = 0;
|
||||
};
|
||||
typedef CharWriter print_t;*/
|
||||
#endif // ENABLE_ARDUINO_FEATURES
|
||||
//------------------------------------------------------------------------------
|
||||
// Forward declaration of FatVolume.
|
||||
class FatVolume;
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* \brief Cache for an raw data block.
|
||||
*/
|
||||
union cache_t {
|
||||
/** Used to access cached file data blocks. */
|
||||
uint8_t data[512];
|
||||
/** Used to access cached FAT16 entries. */
|
||||
uint16_t fat16[256];
|
||||
/** Used to access cached FAT32 entries. */
|
||||
uint32_t fat32[128];
|
||||
/** Used to access cached directory entries. */
|
||||
dir_t dir[16];
|
||||
/** Used to access a cached Master Boot Record. */
|
||||
mbr_t mbr;
|
||||
/** Used to access to a cached FAT boot sector. */
|
||||
fat_boot_t fbs;
|
||||
/** Used to access to a cached FAT32 boot sector. */
|
||||
fat32_boot_t fbs32;
|
||||
/** Used to access to a cached FAT32 FSINFO sector. */
|
||||
fat32_fsinfo_t fsinfo;
|
||||
};
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class FatCache
|
||||
* \brief Block cache.
|
||||
*/
|
||||
class FatCache {
|
||||
public:
|
||||
/** Cached block is dirty */
|
||||
static const uint8_t CACHE_STATUS_DIRTY = 1;
|
||||
/** Cashed block is FAT entry and must be mirrored in second FAT. */
|
||||
static const uint8_t CACHE_STATUS_MIRROR_FAT = 2;
|
||||
/** Cache block status bits */
|
||||
static const uint8_t CACHE_STATUS_MASK
|
||||
= CACHE_STATUS_DIRTY | CACHE_STATUS_MIRROR_FAT;
|
||||
/** Sync existing block but do not read new block. */
|
||||
static const uint8_t CACHE_OPTION_NO_READ = 4;
|
||||
/** Cache block for read. */
|
||||
static const uint8_t CACHE_FOR_READ = 0;
|
||||
/** Cache block for write. */
|
||||
static const uint8_t CACHE_FOR_WRITE = CACHE_STATUS_DIRTY;
|
||||
/** Reserve cache block for write - do not read from block device. */
|
||||
static const uint8_t CACHE_RESERVE_FOR_WRITE
|
||||
= CACHE_STATUS_DIRTY | CACHE_OPTION_NO_READ;
|
||||
/** \return Cache block address. */
|
||||
cache_t* block() {
|
||||
return &m_block;
|
||||
}
|
||||
/** Set current block dirty. */
|
||||
void dirty() {
|
||||
m_status |= CACHE_STATUS_DIRTY;
|
||||
}
|
||||
/** Initialize the cache.
|
||||
* \param[in] vol FatVolume that owns this FatCache.
|
||||
*/
|
||||
void init(FatVolume *vol) {
|
||||
m_vol = vol;
|
||||
invalidate();
|
||||
}
|
||||
/** Invalidate current cache block. */
|
||||
void invalidate() {
|
||||
m_status = 0;
|
||||
m_lbn = 0XFFFFFFFF;
|
||||
}
|
||||
/** \return dirty status */
|
||||
bool isDirty() {
|
||||
return m_status & CACHE_STATUS_DIRTY;
|
||||
}
|
||||
/** \return Logical block number for cached block. */
|
||||
uint32_t lbn() {
|
||||
return m_lbn;
|
||||
}
|
||||
/** Read a block into the cache.
|
||||
* \param[in] lbn Block to read.
|
||||
* \param[in] option mode for cached block.
|
||||
* \return Address of cached block. */
|
||||
cache_t* read(uint32_t lbn, uint8_t option);
|
||||
/** Write current block if dirty.
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool sync();
|
||||
|
||||
private:
|
||||
uint8_t m_status;
|
||||
FatVolume* m_vol;
|
||||
uint32_t m_lbn;
|
||||
cache_t m_block;
|
||||
};
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class FatVolume
|
||||
* \brief Access FAT16 and FAT32 volumes on raw file devices.
|
||||
*/
|
||||
class FatVolume {
|
||||
public:
|
||||
/** Create an instance of FatVolume
|
||||
*/
|
||||
FatVolume() : m_fatType(0) {}
|
||||
|
||||
/** \return The volume's cluster size in blocks. */
|
||||
uint8_t blocksPerCluster() const {
|
||||
return m_blocksPerCluster;
|
||||
}
|
||||
/** \return The number of blocks in one FAT. */
|
||||
uint32_t blocksPerFat() const {
|
||||
return m_blocksPerFat;
|
||||
}
|
||||
/** Clear the cache and returns a pointer to the cache. Not for normal apps.
|
||||
* \return A pointer to the cache buffer or zero if an error occurs.
|
||||
*/
|
||||
cache_t* cacheClear() {
|
||||
if (!cacheSync()) {
|
||||
return 0;
|
||||
}
|
||||
m_cache.invalidate();
|
||||
return m_cache.block();
|
||||
}
|
||||
/** \return The total number of clusters in the volume. */
|
||||
uint32_t clusterCount() const {
|
||||
return m_lastCluster - 1;
|
||||
}
|
||||
/** \return The shift count required to multiply by blocksPerCluster. */
|
||||
uint8_t clusterSizeShift() const {
|
||||
return m_clusterSizeShift;
|
||||
}
|
||||
/** \return The logical block number for the start of file data. */
|
||||
uint32_t dataStartBlock() const {
|
||||
return m_dataStartBlock;
|
||||
}
|
||||
/** \return The number of File Allocation Tables. */
|
||||
uint8_t fatCount() {
|
||||
return 2;
|
||||
}
|
||||
/** \return The logical block number for the start of the first FAT. */
|
||||
uint32_t fatStartBlock() const {
|
||||
return m_fatStartBlock;
|
||||
}
|
||||
/** \return The FAT type of the volume. Values are 12, 16 or 32. */
|
||||
uint8_t fatType() const {
|
||||
return m_fatType;
|
||||
}
|
||||
/** Volume free space in clusters.
|
||||
*
|
||||
* \return Count of free clusters for success or -1 if an error occurs.
|
||||
*/
|
||||
int32_t freeClusterCount();
|
||||
/** Initialize a FAT volume. Try partition one first then try super
|
||||
* floppy format.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool init() {
|
||||
return init(1) || init(0);
|
||||
}
|
||||
/** Initialize a FAT volume.
|
||||
|
||||
* \param[in] part The partition to be used. Legal values for \a part are
|
||||
* 1-4 to use the corresponding partition on a device formatted with
|
||||
* a MBR, Master Boot Record, or zero if the device is formatted as
|
||||
* a super floppy with the FAT boot sector in block zero.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool init(uint8_t part);
|
||||
/** \return The number of entries in the root directory for FAT16 volumes. */
|
||||
uint16_t rootDirEntryCount() const {
|
||||
return m_rootDirEntryCount;
|
||||
}
|
||||
/** \return The logical block number for the start of the root directory
|
||||
on FAT16 volumes or the first cluster number on FAT32 volumes. */
|
||||
uint32_t rootDirStart() const {
|
||||
return m_rootDirStart;
|
||||
}
|
||||
/** \return The number of blocks in the volume */
|
||||
uint32_t volumeBlockCount() const {
|
||||
return blocksPerCluster()*clusterCount();
|
||||
}
|
||||
/** Wipe all data from the volume.
|
||||
* \param[in] pr print stream for status dots.
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool wipe();
|
||||
/** Debug access to FAT table
|
||||
*
|
||||
* \param[in] n cluster number.
|
||||
* \param[out] v value of entry
|
||||
* \return true for success or false for failure
|
||||
*/
|
||||
int8_t dbgFat(uint32_t n, uint32_t* v) {
|
||||
return fatGet(n, v);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
private:
|
||||
// Allow FatFile and FatCache access to FatVolume private functions.
|
||||
friend class FatCache;
|
||||
friend class FatFile;
|
||||
friend class FatFileSystem;
|
||||
//------------------------------------------------------------------------------
|
||||
BlockDriver* m_blockDev; // block device
|
||||
uint8_t m_blocksPerCluster; // Cluster size in blocks.
|
||||
uint8_t m_clusterBlockMask; // Mask to extract block of cluster.
|
||||
uint8_t m_clusterSizeShift; // Cluster count to block count shift.
|
||||
uint8_t m_fatType; // Volume type (12, 16, OR 32).
|
||||
uint16_t m_rootDirEntryCount; // Number of entries in FAT16 root dir.
|
||||
uint32_t m_allocSearchStart; // Start cluster for alloc search.
|
||||
uint32_t m_blocksPerFat; // FAT size in blocks
|
||||
uint32_t m_dataStartBlock; // First data block number.
|
||||
uint32_t m_fatStartBlock; // Start block for first FAT.
|
||||
uint32_t m_lastCluster; // Last cluster number in FAT.
|
||||
uint32_t m_rootDirStart; // Start block for FAT16, cluster for FAT32.
|
||||
//------------------------------------------------------------------------------
|
||||
// block I/O functions.
|
||||
bool readBlock(uint32_t block, uint8_t* dst) {
|
||||
return m_blockDev->readBlock(block, dst);
|
||||
}
|
||||
bool syncBlocks() {
|
||||
return m_blockDev->syncBlocks();
|
||||
}
|
||||
bool writeBlock(uint32_t block, const uint8_t* src) {
|
||||
return m_blockDev->writeBlock(block, src);
|
||||
}
|
||||
#if USE_MULTI_BLOCK_IO
|
||||
bool readBlocks(uint32_t block, uint8_t* dst, size_t nb) {
|
||||
return m_blockDev->readBlocks(block, dst, nb);
|
||||
}
|
||||
bool writeBlocks(uint32_t block, const uint8_t* src, size_t nb) {
|
||||
return m_blockDev->writeBlocks(block, src, nb);
|
||||
}
|
||||
#endif // USE_MULTI_BLOCK_IO
|
||||
#if MAINTAIN_FREE_CLUSTER_COUNT
|
||||
int32_t m_freeClusterCount; // Count of free clusters in volume.
|
||||
void setFreeClusterCount(int32_t value) {
|
||||
m_freeClusterCount = value;
|
||||
}
|
||||
void updateFreeClusterCount(int32_t change) {
|
||||
if (m_freeClusterCount >= 0) {
|
||||
m_freeClusterCount += change;
|
||||
}
|
||||
}
|
||||
#else // MAINTAIN_FREE_CLUSTER_COUNT
|
||||
void setFreeClusterCount(int32_t value) {
|
||||
(void)value;
|
||||
}
|
||||
void updateFreeClusterCount(int32_t change) {
|
||||
(void)change;
|
||||
}
|
||||
#endif // MAINTAIN_FREE_CLUSTER_COUNT
|
||||
|
||||
// block caches
|
||||
FatCache m_cache;
|
||||
#if USE_SEPARATE_FAT_CACHE
|
||||
FatCache m_fatCache;
|
||||
cache_t* cacheFetchFat(uint32_t blockNumber, uint8_t options) {
|
||||
return m_fatCache.read(blockNumber,
|
||||
options | FatCache::CACHE_STATUS_MIRROR_FAT);
|
||||
}
|
||||
bool cacheSync() {
|
||||
return m_cache.sync() && m_fatCache.sync() && syncBlocks();
|
||||
}
|
||||
#else //
|
||||
cache_t* cacheFetchFat(uint32_t blockNumber, uint8_t options) {
|
||||
return cacheFetchData(blockNumber,
|
||||
options | FatCache::CACHE_STATUS_MIRROR_FAT);
|
||||
}
|
||||
bool cacheSync() {
|
||||
return m_cache.sync() && syncBlocks();
|
||||
}
|
||||
#endif // USE_SEPARATE_FAT_CACHE
|
||||
cache_t* cacheFetchData(uint32_t blockNumber, uint8_t options) {
|
||||
return m_cache.read(blockNumber, options);
|
||||
}
|
||||
void cacheInvalidate() {
|
||||
m_cache.invalidate();
|
||||
}
|
||||
bool cacheSyncData() {
|
||||
return m_cache.sync();
|
||||
}
|
||||
cache_t *cacheAddress() {
|
||||
return m_cache.block();
|
||||
}
|
||||
uint32_t cacheBlockNumber() {
|
||||
return m_cache.lbn();
|
||||
}
|
||||
void cacheDirty() {
|
||||
m_cache.dirty();
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool allocateCluster(uint32_t current, uint32_t* next);
|
||||
bool allocContiguous(uint32_t count, uint32_t* firstCluster);
|
||||
uint8_t blockOfCluster(uint32_t position) const {
|
||||
return (position >> 9) & m_clusterBlockMask;
|
||||
}
|
||||
uint32_t clusterFirstBlock(uint32_t cluster) const;
|
||||
int8_t fatGet(uint32_t cluster, uint32_t* value);
|
||||
bool fatPut(uint32_t cluster, uint32_t value);
|
||||
bool fatPutEOC(uint32_t cluster) {
|
||||
return fatPut(cluster, 0x0FFFFFFF);
|
||||
}
|
||||
bool freeChain(uint32_t cluster);
|
||||
bool isEOC(uint32_t cluster) const {
|
||||
return cluster > m_lastCluster;
|
||||
}
|
||||
};
|
||||
#endif // FatVolume
|
460
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/FmtNumber.cpp
Normal file
460
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/FmtNumber.cpp
Normal file
@ -0,0 +1,460 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#include "FmtNumber.h"
|
||||
// Use Stimmer div/mod 10 on avr
|
||||
#ifdef __AVR__
|
||||
#include <avr/pgmspace.h>
|
||||
#define USE_STIMMER
|
||||
#endif // __AVR__
|
||||
//------------------------------------------------------------------------------
|
||||
// Stimmer div/mod 10 for AVR
|
||||
// this code fragment works out i/10 and i%10 by calculating
|
||||
// i*(51/256)*(256/255)/2 == i*51/510 == i/10
|
||||
// by "j.k" I mean 32.8 fixed point, j is integer part, k is fractional part
|
||||
// j.k = ((j+1.0)*51.0)/256.0
|
||||
// (we add 1 because we will be using the floor of the result later)
|
||||
// divmod10_asm16 and divmod10_asm32 are public domain code by Stimmer.
|
||||
// http://forum.arduino.cc/index.php?topic=167414.msg1293679#msg1293679
|
||||
#define divmod10_asm16(in32, mod8, tmp8) \
|
||||
asm volatile( \
|
||||
" ldi %2,51 \n\t" \
|
||||
" mul %A0,%2 \n\t" \
|
||||
" clr %A0 \n\t" \
|
||||
" add r0,%2 \n\t" \
|
||||
" adc %A0,r1 \n\t" \
|
||||
" mov %1,r0 \n\t" \
|
||||
" mul %B0,%2 \n\t" \
|
||||
" clr %B0 \n\t" \
|
||||
" add %A0,r0 \n\t" \
|
||||
" adc %B0,r1 \n\t" \
|
||||
" clr r1 \n\t" \
|
||||
" add %1,%A0 \n\t" \
|
||||
" adc %A0,%B0 \n\t" \
|
||||
" adc %B0,r1 \n\t" \
|
||||
" add %1,%B0 \n\t" \
|
||||
" adc %A0,r1 \n\t" \
|
||||
" adc %B0,r1 \n\t" \
|
||||
" lsr %B0 \n\t" \
|
||||
" ror %A0 \n\t" \
|
||||
" ror %1 \n\t" \
|
||||
" ldi %2,10 \n\t" \
|
||||
" mul %1,%2 \n\t" \
|
||||
" mov %1,r1 \n\t" \
|
||||
" clr r1 \n\t" \
|
||||
:"+r"(in32), "=d"(mod8), "=d"(tmp8) : : "r0")
|
||||
|
||||
#define divmod10_asm32(in32, mod8, tmp8) \
|
||||
asm volatile( \
|
||||
" ldi %2,51 \n\t" \
|
||||
" mul %A0,%2 \n\t" \
|
||||
" clr %A0 \n\t" \
|
||||
" add r0,%2 \n\t" \
|
||||
" adc %A0,r1 \n\t" \
|
||||
" mov %1,r0 \n\t" \
|
||||
" mul %B0,%2 \n\t" \
|
||||
" clr %B0 \n\t" \
|
||||
" add %A0,r0 \n\t" \
|
||||
" adc %B0,r1 \n\t" \
|
||||
" mul %C0,%2 \n\t" \
|
||||
" clr %C0 \n\t" \
|
||||
" add %B0,r0 \n\t" \
|
||||
" adc %C0,r1 \n\t" \
|
||||
" mul %D0,%2 \n\t" \
|
||||
" clr %D0 \n\t" \
|
||||
" add %C0,r0 \n\t" \
|
||||
" adc %D0,r1 \n\t" \
|
||||
" clr r1 \n\t" \
|
||||
" add %1,%A0 \n\t" \
|
||||
" adc %A0,%B0 \n\t" \
|
||||
" adc %B0,%C0 \n\t" \
|
||||
" adc %C0,%D0 \n\t" \
|
||||
" adc %D0,r1 \n\t" \
|
||||
" add %1,%B0 \n\t" \
|
||||
" adc %A0,%C0 \n\t" \
|
||||
" adc %B0,%D0 \n\t" \
|
||||
" adc %C0,r1 \n\t" \
|
||||
" adc %D0,r1 \n\t" \
|
||||
" add %1,%D0 \n\t" \
|
||||
" adc %A0,r1 \n\t" \
|
||||
" adc %B0,r1 \n\t" \
|
||||
" adc %C0,r1 \n\t" \
|
||||
" adc %D0,r1 \n\t" \
|
||||
" lsr %D0 \n\t" \
|
||||
" ror %C0 \n\t" \
|
||||
" ror %B0 \n\t" \
|
||||
" ror %A0 \n\t" \
|
||||
" ror %1 \n\t" \
|
||||
" ldi %2,10 \n\t" \
|
||||
" mul %1,%2 \n\t" \
|
||||
" mov %1,r1 \n\t" \
|
||||
" clr r1 \n\t" \
|
||||
:"+r"(in32), "=d"(mod8), "=d"(tmp8) : : "r0")
|
||||
//------------------------------------------------------------------------------
|
||||
/*
|
||||
// C++ code is based on this version of divmod10 by robtillaart.
|
||||
// http://forum.arduino.cc/index.php?topic=167414.msg1246851#msg1246851
|
||||
// from robtillaart post:
|
||||
// The code is based upon the divu10() code from the book Hackers Delight1.
|
||||
// My insight was that the error formula in divu10() was in fact modulo 10
|
||||
// but not always. Sometimes it was 10 more.
|
||||
void divmod10(uint32_t in, uint32_t &div, uint32_t &mod)
|
||||
{
|
||||
// q = in * 0.8;
|
||||
uint32_t q = (in >> 1) + (in >> 2);
|
||||
q = q + (q >> 4);
|
||||
q = q + (q >> 8);
|
||||
q = q + (q >> 16); // not needed for 16 bit version
|
||||
|
||||
// q = q / 8; ==> q = in *0.1;
|
||||
q = q >> 3;
|
||||
|
||||
// determine error
|
||||
uint32_t r = in - ((q << 3) + (q << 1)); // r = in - q*10;
|
||||
div = q + (r > 9);
|
||||
if (r > 9) mod = r - 10;
|
||||
else mod = r;
|
||||
}
|
||||
// Hackers delight function is here:
|
||||
// http://www.hackersdelight.org/hdcodetxt/divuc.c.txt
|
||||
// Code below uses 8/10 = 0.1100 1100 1100 1100 1100 1100 1100 1100.
|
||||
// 15 ops including the multiply, or 17 elementary ops.
|
||||
unsigned divu10(unsigned n) {
|
||||
unsigned q, r;
|
||||
|
||||
q = (n >> 1) + (n >> 2);
|
||||
q = q + (q >> 4);
|
||||
q = q + (q >> 8);
|
||||
q = q + (q >> 16);
|
||||
q = q >> 3;
|
||||
r = n - q*10;
|
||||
return q + ((r + 6) >> 4);
|
||||
// return q + (r > 9);
|
||||
}
|
||||
*/
|
||||
//------------------------------------------------------------------------------
|
||||
#ifndef DOXYGEN_SHOULD_SKIP_THIS
|
||||
#ifdef __AVR__
|
||||
static const float m[] PROGMEM = {1e-1, 1e-2, 1e-4, 1e-8, 1e-16, 1e-32};
|
||||
static const float p[] PROGMEM = {1e+1, 1e+2, 1e+4, 1e+8, 1e+16, 1e+32};
|
||||
#else // __AVR__
|
||||
static const float m[] = {1e-1, 1e-2, 1e-4, 1e-8, 1e-16, 1e-32};
|
||||
static const float p[] = {1e+1, 1e+2, 1e+4, 1e+8, 1e+16, 1e+32};
|
||||
#endif // __AVR__
|
||||
#endif // DOXYGEN_SHOULD_SKIP_THIS
|
||||
// scale float v by power of ten. return v*10^n
|
||||
float scale10(float v, int8_t n) {
|
||||
const float *s;
|
||||
if (n < 0) {
|
||||
n = -n;
|
||||
s = m;
|
||||
} else {
|
||||
s = p;
|
||||
}
|
||||
n &= 63;
|
||||
for (uint8_t i = 0; n; n >>= 1, i++) {
|
||||
#ifdef __AVR__
|
||||
if (n & 1) {
|
||||
v *= pgm_read_float(&s[i]);
|
||||
}
|
||||
#else // __AVR__
|
||||
if (n & 1) {
|
||||
v *= s[i];
|
||||
}
|
||||
#endif // __AVR__
|
||||
}
|
||||
return v;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// Format 16-bit unsigned
|
||||
char* fmtDec(uint16_t n, char* p) {
|
||||
while (n > 9) {
|
||||
#ifdef USE_STIMMER
|
||||
uint8_t tmp8, r;
|
||||
divmod10_asm16(n, r, tmp8);
|
||||
#else // USE_STIMMER
|
||||
uint16_t t = n;
|
||||
n = (n >> 1) + (n >> 2);
|
||||
n = n + (n >> 4);
|
||||
n = n + (n >> 8);
|
||||
// n = n + (n >> 16); // no code for 16-bit n
|
||||
n = n >> 3;
|
||||
uint8_t r = t - (((n << 2) + n) << 1);
|
||||
if (r > 9) {
|
||||
n++;
|
||||
r -= 10;
|
||||
}
|
||||
#endif // USE_STIMMER
|
||||
*--p = r + '0';
|
||||
}
|
||||
*--p = n + '0';
|
||||
return p;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// format 32-bit unsigned
|
||||
char* fmtDec(uint32_t n, char* p) {
|
||||
while (n >> 16) {
|
||||
#ifdef USE_STIMMER
|
||||
uint8_t tmp8, r;
|
||||
divmod10_asm32(n, r, tmp8);
|
||||
#else // USE_STIMMER
|
||||
uint32_t t = n;
|
||||
n = (n >> 1) + (n >> 2);
|
||||
n = n + (n >> 4);
|
||||
n = n + (n >> 8);
|
||||
n = n + (n >> 16);
|
||||
n = n >> 3;
|
||||
uint8_t r = t - (((n << 2) + n) << 1);
|
||||
if (r > 9) {
|
||||
n++;
|
||||
r -= 10;
|
||||
}
|
||||
#endif // USE_STIMMER
|
||||
*--p = r + '0';
|
||||
}
|
||||
return fmtDec((uint16_t)n, p);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
char* fmtFloat(float value, char* p, uint8_t prec) {
|
||||
char sign = value < 0 ? '-' : 0;
|
||||
if (sign) {
|
||||
value = -value;
|
||||
}
|
||||
|
||||
if (isnan(value)) {
|
||||
*--p = 'n';
|
||||
*--p = 'a';
|
||||
*--p = 'n';
|
||||
return p;
|
||||
}
|
||||
if (isinf(value)) {
|
||||
*--p = 'f';
|
||||
*--p = 'n';
|
||||
*--p = 'i';
|
||||
return p;
|
||||
}
|
||||
if (value > 4294967040.0) {
|
||||
*--p = 'f';
|
||||
*--p = 'v';
|
||||
*--p = 'o';
|
||||
return p;
|
||||
}
|
||||
if (prec > 9) {
|
||||
prec = 9;
|
||||
}
|
||||
value += scale10(0.5, -prec);
|
||||
|
||||
uint32_t whole = value;
|
||||
if (prec) {
|
||||
char* tmp = p - prec;
|
||||
uint32_t fraction = scale10(value - whole, prec);
|
||||
p = fmtDec(fraction, p);
|
||||
while (p > tmp) {
|
||||
*--p = '0';
|
||||
}
|
||||
*--p = '.';
|
||||
}
|
||||
p = fmtDec(whole, p);
|
||||
if (sign) {
|
||||
*--p = sign;
|
||||
}
|
||||
return p;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Print a number followed by a field terminator.
|
||||
* \param[in] value The number to be printed.
|
||||
* \param[in] ptr Pointer to last char in buffer.
|
||||
* \param[in] prec Number of digits after decimal point.
|
||||
* \param[in] expChar Use exp format if non zero.
|
||||
* \return Pointer to first character of result.
|
||||
*/
|
||||
char* fmtFloat(float value, char* ptr, uint8_t prec, char expChar) {
|
||||
bool neg = value < 0;
|
||||
if (neg) {
|
||||
value = -value;
|
||||
}
|
||||
|
||||
// check for nan inf ovf
|
||||
if (isnan(value)) {
|
||||
*--ptr = 'n';
|
||||
*--ptr = 'a';
|
||||
*--ptr = 'n';
|
||||
return ptr;
|
||||
}
|
||||
if (isinf(value)) {
|
||||
*--ptr = 'f';
|
||||
*--ptr = 'n';
|
||||
*--ptr = 'i';
|
||||
return ptr;
|
||||
}
|
||||
if (!expChar && value > 4294967040.0) {
|
||||
*--ptr = 'f';
|
||||
*--ptr = 'v';
|
||||
*--ptr = 'o';
|
||||
return ptr;
|
||||
}
|
||||
if (prec > 9) {
|
||||
prec = 9;
|
||||
}
|
||||
float round = scale10(0.5, -prec);
|
||||
if (expChar) {
|
||||
int8_t exp = 0;
|
||||
bool expNeg = false;
|
||||
if (value) {
|
||||
while (value > 10.0) {
|
||||
value *= 0.1;
|
||||
exp++;
|
||||
}
|
||||
while (value < 1.0) {
|
||||
value *= 10.0;
|
||||
exp--;
|
||||
}
|
||||
value += round;
|
||||
if (value > 10.0) {
|
||||
value *= 0.1;
|
||||
exp++;
|
||||
}
|
||||
expNeg = exp < 0;
|
||||
if (expNeg) {
|
||||
exp = -exp;
|
||||
}
|
||||
}
|
||||
ptr = fmtDec((uint16_t)exp, ptr);
|
||||
if (exp < 10) {
|
||||
*--ptr = '0';
|
||||
}
|
||||
*--ptr = expNeg ? '-' : '+';
|
||||
*--ptr = expChar;
|
||||
} else {
|
||||
// round value
|
||||
value += round;
|
||||
}
|
||||
uint32_t whole = value;
|
||||
if (prec) {
|
||||
char* tmp = ptr - prec;
|
||||
uint32_t fraction = scale10(value - whole, prec);
|
||||
ptr = fmtDec(fraction, ptr);
|
||||
while (ptr > tmp) {
|
||||
*--ptr = '0';
|
||||
}
|
||||
*--ptr = '.';
|
||||
}
|
||||
ptr = fmtDec(whole, ptr);
|
||||
if (neg) {
|
||||
*--ptr = '-';
|
||||
}
|
||||
return ptr;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
char* fmtHex(uint32_t n, char* p) {
|
||||
do {
|
||||
uint8_t h = n & 0XF;
|
||||
*--p = h + (h < 10 ? '0' : 'A' - 10);
|
||||
n >>= 4;
|
||||
} while (n);
|
||||
return p;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
float scanFloat(const char* str, char** ptr) {
|
||||
int16_t const EXP_LIMIT = 100;
|
||||
bool digit = false;
|
||||
bool dot = false;
|
||||
uint32_t fract = 0;
|
||||
int fracExp = 0;
|
||||
uint8_t nd = 0;
|
||||
bool neg;
|
||||
int c;
|
||||
float v;
|
||||
const char* successPtr = str;
|
||||
|
||||
if (ptr) {
|
||||
*ptr = const_cast<char*>(str);
|
||||
}
|
||||
|
||||
while (isSpace((c = *str++))) {}
|
||||
neg = c == '-';
|
||||
if (c == '-' || c == '+') {
|
||||
c = *str++;
|
||||
}
|
||||
// Skip leading zeros
|
||||
while (c == '0') {
|
||||
c = *str++;
|
||||
digit = true;
|
||||
}
|
||||
for (;;) {
|
||||
if (isDigit(c)) {
|
||||
digit = true;
|
||||
if (nd < 9) {
|
||||
fract = 10*fract + c - '0';
|
||||
nd++;
|
||||
if (dot) {
|
||||
fracExp--;
|
||||
}
|
||||
} else {
|
||||
if (!dot) {
|
||||
fracExp++;
|
||||
}
|
||||
}
|
||||
} else if (c == '.') {
|
||||
if (dot) {
|
||||
goto fail;
|
||||
}
|
||||
dot = true;
|
||||
} else {
|
||||
if (!digit) {
|
||||
goto fail;
|
||||
}
|
||||
break;
|
||||
}
|
||||
successPtr = str;
|
||||
c = *str++;
|
||||
}
|
||||
if (c == 'e' || c == 'E') {
|
||||
int exp = 0;
|
||||
c = *str++;
|
||||
bool expNeg = c == '-';
|
||||
if (c == '-' || c == '+') {
|
||||
c = *str++;
|
||||
}
|
||||
while (isDigit(c)) {
|
||||
if (exp > EXP_LIMIT) {
|
||||
goto fail;
|
||||
}
|
||||
exp = 10*exp + c - '0';
|
||||
successPtr = str;
|
||||
c = *str++;
|
||||
}
|
||||
fracExp += expNeg ? -exp : exp;
|
||||
}
|
||||
if (ptr) {
|
||||
*ptr = const_cast<char*>(successPtr);
|
||||
}
|
||||
v = scale10(static_cast<float>(fract), fracExp);
|
||||
return neg ? -v : v;
|
||||
|
||||
fail:
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -0,0 +1,43 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef FmtNumber_h
|
||||
#define FmtNumber_h
|
||||
// #include <ctype.h>
|
||||
inline bool isDigit(char c) {
|
||||
return '0' <= c && c <= '9';
|
||||
}
|
||||
inline bool isSpace(char c) {
|
||||
return c == ' ' || (0X9 <= c && c <= 0XD);
|
||||
}
|
||||
#include <math.h>
|
||||
#include <stdint.h>
|
||||
char* fmtDec(uint16_t n, char* p);
|
||||
char* fmtDec(uint32_t n, char* p);
|
||||
char* fmtFloat(float value, char* p, uint8_t prec);
|
||||
char* fmtFloat(float value, char* ptr, uint8_t prec, char expChar);
|
||||
char* fmtHex(uint32_t n, char* p);
|
||||
float scale10(float v, int8_t n);
|
||||
float scanFloat(const char* str, char** ptr);
|
||||
#endif // FmtNumber_h
|
@ -0,0 +1,525 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#include "../../../Repetier.h"
|
||||
#include "StdioStream.h"
|
||||
#include "FmtNumber.h"
|
||||
//------------------------------------------------------------------------------
|
||||
int StdioStream::fclose() {
|
||||
int rtn = 0;
|
||||
if (!m_flags) {
|
||||
return EOF;
|
||||
}
|
||||
if (m_flags & F_SWR) {
|
||||
if (!flushBuf()) {
|
||||
rtn = EOF;
|
||||
}
|
||||
}
|
||||
if (!FatFile::close()) {
|
||||
rtn = EOF;
|
||||
}
|
||||
m_r = 0;
|
||||
m_w = 0;
|
||||
m_flags = 0;
|
||||
return rtn;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int StdioStream::fflush() {
|
||||
if ((m_flags & (F_SWR | F_SRW)) && !(m_flags & F_SRD)) {
|
||||
if (flushBuf() && FatFile::sync()) {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
return EOF;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
char* StdioStream::fgets(char* str, size_t num, size_t* len) {
|
||||
char* s = str;
|
||||
size_t n;
|
||||
if (num-- == 0) {
|
||||
return 0;
|
||||
}
|
||||
while (num) {
|
||||
if ((n = m_r) == 0) {
|
||||
if (!fillBuf()) {
|
||||
if (s == str) {
|
||||
return 0;
|
||||
}
|
||||
break;
|
||||
}
|
||||
n = m_r;
|
||||
}
|
||||
if (n > num) {
|
||||
n = num;
|
||||
}
|
||||
uint8_t* end = reinterpret_cast<uint8_t*>(memchr(m_p, '\n', n));
|
||||
if (end != 0) {
|
||||
n = ++end - m_p;
|
||||
memcpy(s, m_p, n);
|
||||
m_r -= n;
|
||||
m_p = end;
|
||||
s += n;
|
||||
break;
|
||||
}
|
||||
memcpy(s, m_p, n);
|
||||
m_r -= n;
|
||||
m_p += n;
|
||||
s += n;
|
||||
num -= n;
|
||||
}
|
||||
*s = 0;
|
||||
if (len) {
|
||||
*len = s - str;
|
||||
}
|
||||
return str;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool StdioStream::fopen(const char* path, const char* mode) {
|
||||
uint8_t oflag;
|
||||
switch (*mode++) {
|
||||
case 'a':
|
||||
m_flags = F_SWR;
|
||||
oflag = O_WRITE | O_CREAT | O_APPEND | O_AT_END;
|
||||
break;
|
||||
|
||||
case 'r':
|
||||
m_flags = F_SRD;
|
||||
oflag = O_READ;
|
||||
break;
|
||||
|
||||
case 'w':
|
||||
m_flags = F_SWR;
|
||||
oflag = O_WRITE | O_CREAT | O_TRUNC;
|
||||
break;
|
||||
|
||||
default:
|
||||
goto fail;
|
||||
}
|
||||
while (*mode) {
|
||||
switch (*mode++) {
|
||||
case '+':
|
||||
m_flags |= F_SRW;
|
||||
oflag |= O_RDWR;
|
||||
break;
|
||||
|
||||
case 'b':
|
||||
break;
|
||||
|
||||
case 'x':
|
||||
oflag |= O_EXCL;
|
||||
break;
|
||||
|
||||
default:
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
if ((oflag & O_EXCL) && !(oflag & O_WRITE)) {
|
||||
goto fail;
|
||||
}
|
||||
if (!FatFile::open(path, oflag)) {
|
||||
goto fail;
|
||||
}
|
||||
m_r = 0;
|
||||
m_w = 0;
|
||||
m_p = m_buf;
|
||||
return true;
|
||||
|
||||
fail:
|
||||
m_flags = 0;
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int StdioStream::fputs(const char* str) {
|
||||
size_t len = strlen(str);
|
||||
return fwrite(str, 1, len) == len ? len : EOF;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
size_t StdioStream::fread(void* ptr, size_t size, size_t count) {
|
||||
uint8_t* dst = reinterpret_cast<uint8_t*>(ptr);
|
||||
size_t total = size * count;
|
||||
if (total == 0) {
|
||||
return 0;
|
||||
}
|
||||
size_t need = total;
|
||||
while (need > m_r) {
|
||||
memcpy(dst, m_p, m_r);
|
||||
dst += m_r;
|
||||
m_p += m_r;
|
||||
need -= m_r;
|
||||
if (!fillBuf()) {
|
||||
return (total - need) / size;
|
||||
}
|
||||
}
|
||||
memcpy(dst, m_p, need);
|
||||
m_r -= need;
|
||||
m_p += need;
|
||||
return count;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int StdioStream::fseek(int32_t offset, int origin) {
|
||||
int32_t pos;
|
||||
if (m_flags & F_SWR) {
|
||||
if (!flushBuf()) {
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
switch (origin) {
|
||||
case SEEK_CUR:
|
||||
pos = ftell();
|
||||
if (pos < 0) {
|
||||
goto fail;
|
||||
}
|
||||
pos += offset;
|
||||
if (!FatFile::seekCur(pos)) {
|
||||
goto fail;
|
||||
}
|
||||
break;
|
||||
|
||||
case SEEK_SET:
|
||||
if (!FatFile::seekSet(offset)) {
|
||||
goto fail;
|
||||
}
|
||||
break;
|
||||
|
||||
case SEEK_END:
|
||||
if (!FatFile::seekEnd(offset)) {
|
||||
goto fail;
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
goto fail;
|
||||
}
|
||||
m_r = 0;
|
||||
m_p = m_buf;
|
||||
return 0;
|
||||
|
||||
fail:
|
||||
return EOF;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int32_t StdioStream::ftell() {
|
||||
uint32_t pos = FatFile::curPosition();
|
||||
if (m_flags & F_SRD) {
|
||||
if (m_r > pos) {
|
||||
return -1L;
|
||||
}
|
||||
pos -= m_r;
|
||||
} else if (m_flags & F_SWR) {
|
||||
pos += m_p - m_buf;
|
||||
}
|
||||
return pos;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
size_t StdioStream::fwrite(const void* ptr, size_t size, size_t count) {
|
||||
return write(ptr, count * size) < 0 ? EOF : count;
|
||||
#if 0 ////////////////////////////////////////////////////////////////////////////////////
|
||||
const uint8_t* src = static_cast<const uint8_t*>(ptr);
|
||||
size_t total = count*size;
|
||||
if (total == 0) {
|
||||
return 0;
|
||||
}
|
||||
size_t todo = total;
|
||||
|
||||
while (todo > m_w) {
|
||||
memcpy(m_p, src, m_w);
|
||||
m_p += m_w;
|
||||
src += m_w;
|
||||
todo -= m_w;
|
||||
if (!flushBuf()) {
|
||||
return (total - todo)/size;
|
||||
}
|
||||
}
|
||||
memcpy(m_p, src, todo);
|
||||
m_p += todo;
|
||||
m_w -= todo;
|
||||
return count;
|
||||
#endif //////////////////////////////////////////////////////////////////////////////////
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int StdioStream::write(const void* buf, size_t count) {
|
||||
const uint8_t* src = static_cast<const uint8_t*>(buf);
|
||||
size_t todo = count;
|
||||
|
||||
while (todo > m_w) {
|
||||
memcpy(m_p, src, m_w);
|
||||
m_p += m_w;
|
||||
src += m_w;
|
||||
todo -= m_w;
|
||||
if (!flushBuf()) {
|
||||
return EOF;
|
||||
}
|
||||
}
|
||||
memcpy(m_p, src, todo);
|
||||
m_p += todo;
|
||||
m_w -= todo;
|
||||
return count;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
#if (defined(ARDUINO) && ENABLE_ARDUINO_FEATURES) || defined(DOXYGEN)
|
||||
size_t StdioStream::print(const __FlashStringHelper* str) {
|
||||
const char* p = (const char*)str;
|
||||
uint8_t c;
|
||||
while ((c = pgm_read_byte(p))) {
|
||||
if (putc(c) < 0) {
|
||||
return 0;
|
||||
}
|
||||
p++;
|
||||
}
|
||||
return p - (const char*)str;
|
||||
}
|
||||
#endif // (defined(ARDUINO) && ENABLE_ARDUINO_FEATURES) || defined(DOXYGEN)
|
||||
//------------------------------------------------------------------------------
|
||||
int StdioStream::printDec(float value, uint8_t prec) {
|
||||
char buf[24];
|
||||
char* ptr = fmtFloat(value, buf + sizeof(buf), prec);
|
||||
return write(ptr, buf + sizeof(buf) - ptr);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int StdioStream::printDec(signed char n) {
|
||||
if (n < 0) {
|
||||
if (fputc('-') < 0) {
|
||||
return -1;
|
||||
}
|
||||
n = -n;
|
||||
}
|
||||
return printDec((unsigned char)n);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int StdioStream::printDec(int16_t n) {
|
||||
int s;
|
||||
uint8_t rtn = 0;
|
||||
if (n < 0) {
|
||||
if (fputc('-') < 0) {
|
||||
return -1;
|
||||
}
|
||||
n = -n;
|
||||
rtn++;
|
||||
}
|
||||
if ((s = printDec((uint16_t)n)) < 0) {
|
||||
return s;
|
||||
}
|
||||
return rtn;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int StdioStream::printDec(uint16_t n) {
|
||||
#define NEW_WAY
|
||||
#ifdef NEW_WAY
|
||||
char buf[5];
|
||||
char* ptr = fmtDec(n, buf + sizeof(buf));
|
||||
uint8_t len = buf + sizeof(buf) - ptr;
|
||||
return write(ptr, len);
|
||||
#else
|
||||
uint8_t len;
|
||||
if (n < 100) {
|
||||
len = n < 10 ? 1 : 2;
|
||||
} else {
|
||||
len = n < 1000 ? 3 : n < 10000 ? 4 : 5;
|
||||
}
|
||||
char* str = fmtSpace(len);
|
||||
if (!str) {
|
||||
return -1;
|
||||
}
|
||||
fmtDec(n, str);
|
||||
return len;
|
||||
#endif
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int StdioStream::printDec(int32_t n) {
|
||||
uint8_t s = 0;
|
||||
if (n < 0) {
|
||||
if (fputc('-') < 0) {
|
||||
return -1;
|
||||
}
|
||||
n = -n;
|
||||
s = 1;
|
||||
}
|
||||
int rtn = printDec((uint32_t)n);
|
||||
return rtn > 0 ? rtn + s : -1;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int StdioStream::printDec(uint32_t n) {
|
||||
#ifdef NEW_WAY
|
||||
char buf[10];
|
||||
char* ptr = fmtDec(n, buf + sizeof(buf));
|
||||
uint8_t len = buf + sizeof(buf) - ptr;
|
||||
return write(ptr, len);
|
||||
#else
|
||||
uint8_t len;
|
||||
if (n < 0X10000) {
|
||||
return printDec((uint16_t)n);
|
||||
}
|
||||
if (n < 10000000) {
|
||||
len = n < 100000 ? 5 : n < 1000000 ? 6 : 7;
|
||||
} else {
|
||||
len = n < 100000000 ? 8 : n < 1000000000 ? 9 : 10;
|
||||
}
|
||||
|
||||
char* str = fmtSpace(len);
|
||||
if (!str) {
|
||||
return -1;
|
||||
}
|
||||
fmtDec(n, str);
|
||||
return len;
|
||||
#endif
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int StdioStream::printHex(uint32_t n) {
|
||||
#ifdef NEW_WAY
|
||||
char buf[8];
|
||||
char* ptr = fmtHex(n, buf + sizeof(buf));
|
||||
uint8_t len = buf + sizeof(buf) - ptr;
|
||||
return write(ptr, len);
|
||||
#else
|
||||
size_t len;
|
||||
if (n < 0X10000) {
|
||||
len = n < 0X10 ? 1 : n < 0X100 ? 2 : n < 0X1000 ? 3 : 4;
|
||||
} else {
|
||||
len = n < 0X100000 ? 5 : n < 0X1000000 ? 6 : n < 0X10000000 ? 7 : 8;
|
||||
}
|
||||
char* str = fmtSpace(len);
|
||||
if (!str) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
do {
|
||||
uint8_t h = n & 0XF;
|
||||
*str-- = h + (h < 10 ? '0' : 'A' - 10);
|
||||
n >>= 4;
|
||||
} while (n);
|
||||
return len;
|
||||
#endif
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool StdioStream::rewind() {
|
||||
if (m_flags & F_SWR) {
|
||||
if (!flushBuf()) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
FatFile::seekSet(0);
|
||||
m_r = 0;
|
||||
return true;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int StdioStream::ungetc(int c) {
|
||||
// error if EOF.
|
||||
if (c == EOF) {
|
||||
return EOF;
|
||||
}
|
||||
// error if not reading.
|
||||
if ((m_flags & F_SRD) == 0) {
|
||||
return EOF;
|
||||
}
|
||||
// error if no space.
|
||||
if (m_p == m_buf) {
|
||||
return EOF;
|
||||
}
|
||||
m_r++;
|
||||
m_flags &= ~F_EOF;
|
||||
return *--m_p = (uint8_t)c;
|
||||
}
|
||||
//==============================================================================
|
||||
// private
|
||||
//------------------------------------------------------------------------------
|
||||
int StdioStream::fillGet() {
|
||||
if (!fillBuf()) {
|
||||
return EOF;
|
||||
}
|
||||
m_r--;
|
||||
return *m_p++;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// private
|
||||
bool StdioStream::fillBuf() {
|
||||
if (!(m_flags & F_SRD)) { // check for F_ERR and F_EOF ??/////////////////
|
||||
if (!(m_flags & F_SRW)) {
|
||||
m_flags |= F_ERR;
|
||||
return false;
|
||||
}
|
||||
if (m_flags & F_SWR) {
|
||||
if (!flushBuf()) {
|
||||
return false;
|
||||
}
|
||||
m_flags &= ~F_SWR;
|
||||
m_flags |= F_SRD;
|
||||
m_w = 0;
|
||||
}
|
||||
}
|
||||
m_p = m_buf + UNGETC_BUF_SIZE;
|
||||
int nr = FatFile::read(m_p, sizeof(m_buf) - UNGETC_BUF_SIZE);
|
||||
if (nr <= 0) {
|
||||
m_flags |= nr < 0 ? F_ERR : F_EOF;
|
||||
m_r = 0;
|
||||
return false;
|
||||
}
|
||||
m_r = nr;
|
||||
return true;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// private
|
||||
bool StdioStream::flushBuf() {
|
||||
if (!(m_flags & F_SWR)) { // check for F_ERR ??////////////////////////
|
||||
if (!(m_flags & F_SRW)) {
|
||||
m_flags |= F_ERR;
|
||||
return false;
|
||||
}
|
||||
m_flags &= ~F_SRD;
|
||||
m_flags |= F_SWR;
|
||||
m_r = 0;
|
||||
m_w = sizeof(m_buf);
|
||||
m_p = m_buf;
|
||||
return true;
|
||||
}
|
||||
uint8_t n = m_p - m_buf;
|
||||
m_p = m_buf;
|
||||
m_w = sizeof(m_buf);
|
||||
if (FatFile::write(m_buf, n) == n) {
|
||||
return true;
|
||||
}
|
||||
m_flags |= F_ERR;
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int StdioStream::flushPut(uint8_t c) {
|
||||
if (!flushBuf()) {
|
||||
return EOF;
|
||||
}
|
||||
m_w--;
|
||||
return *m_p++ = c;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
char* StdioStream::fmtSpace(uint8_t len) {
|
||||
if (m_w < len) {
|
||||
if (!flushBuf() || m_w < len) {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
if (len > m_w) {
|
||||
return 0;
|
||||
}
|
||||
m_p += len;
|
||||
m_w -= len;
|
||||
return reinterpret_cast<char*>(m_p);
|
||||
}
|
667
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/StdioStream.h
Normal file
667
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/StdioStream.h
Normal file
@ -0,0 +1,667 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef StdioStream_h
|
||||
#define StdioStream_h
|
||||
/**
|
||||
* \file
|
||||
* \brief StdioStream class
|
||||
*/
|
||||
#include <limits.h>
|
||||
#include "FatFile.h"
|
||||
//------------------------------------------------------------------------------
|
||||
/** Total size of stream buffer. The entire buffer is used for output.
|
||||
* During input UNGETC_BUF_SIZE of this space is reserved for ungetc.
|
||||
*/
|
||||
const uint8_t STREAM_BUF_SIZE = 64;
|
||||
/** Amount of buffer allocated for ungetc during input. */
|
||||
const uint8_t UNGETC_BUF_SIZE = 2;
|
||||
//------------------------------------------------------------------------------
|
||||
// Get rid of any macros defined in <stdio.h>.
|
||||
#include <stdio.h>
|
||||
#undef clearerr
|
||||
#undef fclose
|
||||
#undef feof
|
||||
#undef ferror
|
||||
#undef fflush
|
||||
#undef fgetc
|
||||
#undef fgetpos
|
||||
#undef fgets
|
||||
#undef fopen
|
||||
#undef fprintf
|
||||
#undef fputc
|
||||
#undef fputs
|
||||
#undef fread
|
||||
#undef freopen
|
||||
#undef fscanf
|
||||
#undef fseek
|
||||
#undef fsetpos
|
||||
#undef ftell
|
||||
#undef fwrite
|
||||
#undef getc
|
||||
#undef getchar
|
||||
#undef gets
|
||||
#undef perror
|
||||
//#undef printf // NOLINT
|
||||
#undef putc
|
||||
#undef putchar
|
||||
#undef puts
|
||||
#undef remove
|
||||
#undef rename
|
||||
#undef rewind
|
||||
#undef scanf
|
||||
#undef setbuf
|
||||
#undef setvbuf
|
||||
//#undef sprintf // NOLINT
|
||||
#undef sscanf
|
||||
#undef tmpfile
|
||||
#undef tmpnam
|
||||
#undef ungetc
|
||||
#undef vfprintf
|
||||
#undef vprintf
|
||||
#undef vsprintf
|
||||
|
||||
// make sure needed macros are defined
|
||||
#ifndef EOF
|
||||
/** End-of-file return value. */
|
||||
#define EOF (-1)
|
||||
#endif // EOF
|
||||
#ifndef NULL
|
||||
/** Null pointer */
|
||||
#define NULL 0
|
||||
#endif // NULL
|
||||
#ifndef SEEK_CUR
|
||||
/** Seek relative to current position. */
|
||||
#define SEEK_CUR 1
|
||||
#endif // SEEK_CUR
|
||||
#ifndef SEEK_END
|
||||
/** Seek relative to end-of-file. */
|
||||
#define SEEK_END 2
|
||||
#endif // SEEK_END
|
||||
#ifndef SEEK_SET
|
||||
/** Seek relative to start-of-file. */
|
||||
#define SEEK_SET 0
|
||||
#endif // SEEK_SET
|
||||
//------------------------------------------------------------------------------
|
||||
/** \class StdioStream
|
||||
* \brief StdioStream implements a minimal stdio stream.
|
||||
*
|
||||
* StdioStream does not support subdirectories or long file names.
|
||||
*/
|
||||
class StdioStream : private FatFile {
|
||||
public:
|
||||
/** Constructor
|
||||
*
|
||||
*/
|
||||
StdioStream() {
|
||||
m_w = m_r = 0;
|
||||
m_p = m_buf;
|
||||
m_flags = 0;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Clear the stream's end-of-file and error indicators. */
|
||||
void clearerr() {
|
||||
m_flags &= ~(F_ERR | F_EOF);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Close a stream.
|
||||
*
|
||||
* A successful call to the fclose function causes the stream to be
|
||||
* flushed and the associated file to be closed. Any unwritten buffered
|
||||
* data is written to the file; any unread buffered data is discarded.
|
||||
* Whether or not the call succeeds, the stream is disassociated from
|
||||
* the file.
|
||||
*
|
||||
* \return zero if the stream was successfully closed, or EOF if any any
|
||||
* errors are detected.
|
||||
*/
|
||||
int fclose();
|
||||
//----------------------------------------------------------------------------
|
||||
/** Test the stream's end-of-file indicator.
|
||||
* \return non-zero if and only if the end-of-file indicator is set.
|
||||
*/
|
||||
int feof() {
|
||||
return (m_flags & F_EOF) != 0;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Test the stream's error indicator.
|
||||
* \return return non-zero if and only if the error indicator is set.
|
||||
*/
|
||||
int ferror() {
|
||||
return (m_flags & F_ERR) != 0;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Flush the stream.
|
||||
*
|
||||
* If stream is an output stream or an update stream in which the most
|
||||
* recent operation was not input, any unwritten data is written to the
|
||||
* file; otherwise the call is an error since any buffered input data
|
||||
* would be lost.
|
||||
*
|
||||
* \return sets the error indicator for the stream and returns EOF if an
|
||||
* error occurs, otherwise it returns zero.
|
||||
*/
|
||||
int fflush();
|
||||
//----------------------------------------------------------------------------
|
||||
/** Get a byte from the stream.
|
||||
*
|
||||
* \return If the end-of-file indicator for the stream is set, or if the
|
||||
* stream is at end-of-file, the end-of-file indicator for the stream is
|
||||
* set and the fgetc function returns EOF. Otherwise, the fgetc function
|
||||
* returns the next character from the input stream.
|
||||
*/
|
||||
int fgetc() {
|
||||
return m_r-- == 0 ? fillGet() : *m_p++;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Get a string from a stream.
|
||||
*
|
||||
* The fgets function reads at most one less than the number of
|
||||
* characters specified by num from the stream into the array pointed
|
||||
* to by str. No additional characters are read after a new-line
|
||||
* character (which is retained) or after end-of-file. A null character
|
||||
* is written immediately after the last character read into the array.
|
||||
*
|
||||
* \param[out] str Pointer to an array of where the string is copied.
|
||||
*
|
||||
* \param[in] num Maximum number of characters including the null
|
||||
* character.
|
||||
*
|
||||
* \param[out] len If len is not null and fgets is successful, the
|
||||
* length of the string is returned.
|
||||
*
|
||||
* \return str if successful. If end-of-file is encountered and no
|
||||
* characters have been read into the array, the contents of the array
|
||||
* remain unchanged and a null pointer is returned. If a read error
|
||||
* occurs during the operation, the array contents are indeterminate
|
||||
* and a null pointer is returned.
|
||||
*/
|
||||
char* fgets(char* str, size_t num, size_t* len = 0);
|
||||
//----------------------------------------------------------------------------
|
||||
/** Open a stream.
|
||||
*
|
||||
* Open a file and associates the stream with it.
|
||||
*
|
||||
* \param[in] path file to be opened.
|
||||
*
|
||||
* \param[in] mode a string that indicates the open mode.
|
||||
*
|
||||
* <table>
|
||||
* <tr>
|
||||
* <td>"r" or "rb"</td>
|
||||
* <td>Open a file for reading. The file must exist.</td>
|
||||
* </tr>
|
||||
* <tr>
|
||||
* <td>"w" or "wb"</td>
|
||||
* <td>Truncate an existing to zero length or create an empty file
|
||||
* for writing.</td>
|
||||
* </tr>
|
||||
* <tr>
|
||||
* <td>"wx" or "wbx"</td>
|
||||
* <td>Create a file for writing. Fails if the file already exists.</td>
|
||||
* </tr>
|
||||
* <tr>
|
||||
* <td>"a" or "ab"</td>
|
||||
* <td>Append; open or create file for writing at end-of-file.</td>
|
||||
* </tr>
|
||||
* <tr>
|
||||
* <td>"r+" or "rb+" or "r+b"</td>
|
||||
* <td>Open a file for update (reading and writing).</td>
|
||||
* </tr>
|
||||
* <tr>
|
||||
* <td>"w+" or "w+b" or "wb+"</td>
|
||||
* <td>Truncate an existing to zero length or create a file for update.</td>
|
||||
* </tr>
|
||||
* <tr>
|
||||
* <td>"w+x" or "w+bx" or "wb+x"</td>
|
||||
* <td>Create a file for update. Fails if the file already exists.</td>
|
||||
* </tr>
|
||||
* <tr>
|
||||
* <td>"a+" or "a+b" or "ab+"</td>
|
||||
* <td>Append; open or create a file for update, writing at end-of-file.</td>
|
||||
* </tr>
|
||||
* </table>
|
||||
* The character 'b' shall have no effect, but is allowed for ISO C
|
||||
* standard conformance.
|
||||
*
|
||||
* Opening a file with append mode causes all subsequent writes to the
|
||||
* file to be forced to the then current end-of-file, regardless of
|
||||
* intervening calls to the fseek function.
|
||||
*
|
||||
* When a file is opened with update mode, both input and output may be
|
||||
* performed on the associated stream. However, output shall not be
|
||||
* directly followed by input without an intervening call to the fflush
|
||||
* function or to a file positioning function (fseek, or rewind), and
|
||||
* input shall not be directly followed by output without an intervening
|
||||
* call to a file positioning function, unless the input operation
|
||||
* encounters end-of-file.
|
||||
*
|
||||
* \return true for success or false for failure.
|
||||
*/
|
||||
bool fopen(const char* path, const char * mode);
|
||||
//----------------------------------------------------------------------------
|
||||
/** Write a byte to a stream.
|
||||
*
|
||||
* \param[in] c the byte to be written (converted to an unsigned char).
|
||||
*
|
||||
* \return Upon successful completion, fputc() returns the value it
|
||||
* has written. Otherwise, it returns EOF and sets the error indicator for
|
||||
* the stream.
|
||||
*/
|
||||
int fputc(int c) {
|
||||
return m_w-- == 0 ? flushPut(c) : *m_p++ = c;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Write a string to a stream.
|
||||
*
|
||||
* \param[in] str a pointer to the string to be written.
|
||||
*
|
||||
* \return for success, fputs() returns a non-negative
|
||||
* number. Otherwise, it returns EOF and sets the error indicator for
|
||||
* the stream.
|
||||
*/
|
||||
int fputs(const char* str);
|
||||
//----------------------------------------------------------------------------
|
||||
/** Binary input.
|
||||
*
|
||||
* Reads an array of up to count elements, each one with a size of size
|
||||
* bytes.
|
||||
* \param[out] ptr pointer to area of at least (size*count) bytes where
|
||||
* the data will be stored.
|
||||
*
|
||||
* \param[in] size the size, in bytes, of each element to be read.
|
||||
*
|
||||
* \param[in] count the number of elements to be read.
|
||||
*
|
||||
* \return number of elements successfully read, which may be less than
|
||||
* count if a read error or end-of-file is encountered. If size or count
|
||||
* is zero, fread returns zero and the contents of the array and the
|
||||
* state of the stream remain unchanged.
|
||||
*/
|
||||
size_t fread(void* ptr, size_t size, size_t count);
|
||||
//----------------------------------------------------------------------------
|
||||
/** Set the file position for the stream.
|
||||
*
|
||||
* \param[in] offset number of offset from the origin.
|
||||
*
|
||||
* \param[in] origin position used as reference for the offset. It is
|
||||
* specified by one of the following constants.
|
||||
*
|
||||
* SEEK_SET - Beginning of file.
|
||||
*
|
||||
* SEEK_CUR - Current position of the file pointer.
|
||||
*
|
||||
* SEEK_END - End of file.
|
||||
*
|
||||
* \return zero for success. Otherwise, it returns non-zero and sets the
|
||||
* error indicator for the stream.
|
||||
*/
|
||||
int fseek(int32_t offset, int origin);
|
||||
//----------------------------------------------------------------------------
|
||||
/** Get the current position in a stream.
|
||||
*
|
||||
* \return If successful, ftell return the current value of the position
|
||||
* indicator. On failure, ftell returns −1L.
|
||||
*/
|
||||
int32_t ftell();
|
||||
//----------------------------------------------------------------------------
|
||||
/** Binary output.
|
||||
*
|
||||
* Writes an array of up to count elements, each one with a size of size
|
||||
* bytes.
|
||||
* \param[in] ptr pointer to (size*count) bytes of data to be written.
|
||||
*
|
||||
* \param[in] size the size, in bytes, of each element to be written.
|
||||
*
|
||||
* \param[in] count the number of elements to be written.
|
||||
*
|
||||
* \return number of elements successfully written. if this number is
|
||||
* less than count, an error has occurred. If size or count is zero,
|
||||
* fwrite returns zero.
|
||||
*/
|
||||
size_t fwrite(const void * ptr, size_t size, size_t count);
|
||||
//----------------------------------------------------------------------------
|
||||
/** Get a byte from the stream.
|
||||
*
|
||||
* getc and fgetc are equivalent but getc is in-line so it is faster but
|
||||
* require more flash memory.
|
||||
*
|
||||
* \return If the end-of-file indicator for the stream is set, or if the
|
||||
* stream is at end-of-file, the end-of-file indicator for the stream is
|
||||
* set and the fgetc function returns EOF. Otherwise, the fgetc function
|
||||
* returns the next character from the input stream.
|
||||
*/
|
||||
inline __attribute__((always_inline))
|
||||
int getc() {
|
||||
return m_r-- == 0 ? fillGet() : *m_p++;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Write a byte to a stream.
|
||||
*
|
||||
* putc and fputc are equivalent but putc is in-line so it is faster but
|
||||
* require more flash memory.
|
||||
*
|
||||
* \param[in] c the byte to be written (converted to an unsigned char).
|
||||
*
|
||||
* \return Upon successful completion, fputc() returns the value it
|
||||
* has written. Otherwise, it returns EOF and sets the error indicator for
|
||||
* the stream.
|
||||
*/
|
||||
inline __attribute__((always_inline))
|
||||
int putc(int c) {
|
||||
return m_w-- == 0 ? flushPut(c) : *m_p++ = c;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Write a CR/LF.
|
||||
*
|
||||
* \return two, the number of bytes written, for success or -1 for failure.
|
||||
*/
|
||||
inline __attribute__((always_inline))
|
||||
int putCRLF() {
|
||||
if (m_w < 2) {
|
||||
if (!flushBuf()) {
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
*m_p++ = '\r';
|
||||
*m_p++ = '\n';
|
||||
m_w -= 2;
|
||||
return 2;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Write a character.
|
||||
* \param[in] c the character to write.
|
||||
* \return the number of bytes written.
|
||||
*/
|
||||
size_t print(char c) {
|
||||
return putc(c) < 0 ? 0 : 1;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Write a string.
|
||||
*
|
||||
* \param[in] str the string to be written.
|
||||
*
|
||||
* \return the number of bytes written.
|
||||
*/
|
||||
size_t print(const char* str) {
|
||||
int n = fputs(str);
|
||||
return n < 0 ? 0 : n;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
#if (defined(ARDUINO) && ENABLE_ARDUINO_FEATURES) || defined(DOXYGEN)
|
||||
/** Print a string stored in flash memory.
|
||||
*
|
||||
* \param[in] str the string to print.
|
||||
*
|
||||
* \return the number of bytes written.
|
||||
*/
|
||||
size_t print(const __FlashStringHelper *str);
|
||||
#endif // (defined(ARDUINO) && ENABLE_ARDUINO_FEATURES) || defined(DOXYGEN)
|
||||
//----------------------------------------------------------------------------
|
||||
/** Print a floating point number.
|
||||
*
|
||||
* \param[in] prec Number of digits after decimal point.
|
||||
*
|
||||
* \param[in] val the number to be printed.
|
||||
*
|
||||
* \return the number of bytes written.
|
||||
*/
|
||||
size_t print(double val, uint8_t prec = 2) {
|
||||
return print(static_cast<float>(val), prec);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Print a floating point number.
|
||||
*
|
||||
* \param[in] prec Number of digits after decimal point.
|
||||
*
|
||||
* \param[in] val the number to be printed.
|
||||
*
|
||||
* \return the number of bytes written.
|
||||
*/
|
||||
size_t print(float val, uint8_t prec = 2) {
|
||||
int n = printDec(val, prec);
|
||||
return n > 0 ? n : 0;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Print a number.
|
||||
*
|
||||
* \param[in] val the number to be printed.
|
||||
*
|
||||
* \return the number of bytes written.
|
||||
*/
|
||||
template <typename T>
|
||||
size_t print(T val) {
|
||||
int n = printDec(val);
|
||||
return n > 0 ? n : 0;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Write a CR/LF.
|
||||
*
|
||||
* \return two, the number of bytes written, for success or zero for failure.
|
||||
*/
|
||||
size_t println() {
|
||||
return putCRLF() > 0 ? 2 : 0;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Print a floating point number followed by CR/LF.
|
||||
*
|
||||
* \param[in] val the number to be printed.
|
||||
*
|
||||
* \param[in] prec Number of digits after decimal point.
|
||||
*
|
||||
* \return the number of bytes written.
|
||||
*/
|
||||
size_t println(double val, uint8_t prec = 2) {
|
||||
return println(static_cast<float>(val), prec);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Print a floating point number followed by CR/LF.
|
||||
*
|
||||
* \param[in] val the number to be printed.
|
||||
*
|
||||
* \param[in] prec Number of digits after decimal point.
|
||||
*
|
||||
* \return the number of bytes written.
|
||||
*/
|
||||
size_t println(float val, uint8_t prec = 2) {
|
||||
int n = printDec(val, prec);
|
||||
return n > 0 && putCRLF() > 0 ? n + 2 : 0;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Print an item followed by CR/LF
|
||||
*
|
||||
* \param[in] val the item to be printed.
|
||||
*
|
||||
* \return the number of bytes written.
|
||||
*/
|
||||
template <typename T>
|
||||
size_t println(T val) {
|
||||
int n = print(val);
|
||||
return putCRLF() > 0 ? n + 2 : 0;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Print a char as a number.
|
||||
* \param[in] n number to be printed.
|
||||
* \return The number of bytes written or -1 if an error occurs.
|
||||
*/
|
||||
int printDec(char n) {
|
||||
if (CHAR_MIN == 0) {
|
||||
return printDec((unsigned char)n);
|
||||
} else {
|
||||
return printDec((signed char)n);
|
||||
}
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** print a signed 8-bit integer
|
||||
* \param[in] n number to be printed.
|
||||
* \return The number of bytes written or -1 if an error occurs.
|
||||
*/
|
||||
int printDec(signed char n);
|
||||
//----------------------------------------------------------------------------
|
||||
/** Print an unsigned 8-bit number.
|
||||
* \param[in] n number to be print.
|
||||
* \return The number of bytes written or -1 if an error occurs.
|
||||
*/
|
||||
int printDec(unsigned char n) {
|
||||
return printDec((uint16_t)n);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Print a int16_t
|
||||
* \param[in] n number to be printed.
|
||||
* \return The number of bytes written or -1 if an error occurs.
|
||||
*/
|
||||
int printDec(int16_t n);
|
||||
//----------------------------------------------------------------------------
|
||||
/** print a uint16_t.
|
||||
* \param[in] n number to be printed.
|
||||
* \return The number of bytes written or -1 if an error occurs.
|
||||
*/
|
||||
int printDec(uint16_t n);
|
||||
//----------------------------------------------------------------------------
|
||||
/** Print a signed 32-bit integer.
|
||||
* \param[in] n number to be printed.
|
||||
* \return The number of bytes written or -1 if an error occurs.
|
||||
*/
|
||||
int printDec(int32_t n);
|
||||
//----------------------------------------------------------------------------
|
||||
/** Write an unsigned 32-bit number.
|
||||
* \param[in] n number to be printed.
|
||||
* \return The number of bytes written or -1 if an error occurs.
|
||||
*/
|
||||
int printDec(uint32_t n);
|
||||
//----------------------------------------------------------------------------
|
||||
/** Print a double.
|
||||
* \param[in] value The number to be printed.
|
||||
* \param[in] prec Number of digits after decimal point.
|
||||
* \return The number of bytes written or -1 if an error occurs.
|
||||
*/
|
||||
int printDec(double value, uint8_t prec) {
|
||||
return printDec(static_cast<float>(value), prec);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Print a float.
|
||||
* \param[in] value The number to be printed.
|
||||
* \param[in] prec Number of digits after decimal point.
|
||||
* \return The number of bytes written or -1 if an error occurs.
|
||||
*/
|
||||
int printDec(float value, uint8_t prec);
|
||||
//----------------------------------------------------------------------------
|
||||
/** Print a number followed by a field terminator.
|
||||
* \param[in] value The number to be printed.
|
||||
* \param[in] term The field terminator.
|
||||
* \param[in] prec Number of digits after decimal point.
|
||||
* \return The number of bytes written or -1 if an error occurs.
|
||||
*/
|
||||
int printField(double value, char term, uint8_t prec = 2) {
|
||||
return printField(static_cast<float>(value), term, prec) > 0;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Print a number followed by a field terminator.
|
||||
* \param[in] value The number to be printed.
|
||||
* \param[in] term The field terminator.
|
||||
* \param[in] prec Number of digits after decimal point.
|
||||
* \return The number of bytes written or -1 if an error occurs.
|
||||
*/
|
||||
int printField(float value, char term, uint8_t prec = 2) {
|
||||
int rtn = printDec(value, prec);
|
||||
return rtn < 0 || putc(term) < 0 ? -1 : rtn + 1;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Print a number followed by a field terminator.
|
||||
* \param[in] value The number to be printed.
|
||||
* \param[in] term The field terminator.
|
||||
* \return The number of bytes written or -1 if an error occurs.
|
||||
*/
|
||||
template <typename T>
|
||||
int printField(T value, char term) {
|
||||
int rtn = printDec(value);
|
||||
return rtn < 0 || putc(term) < 0 ? -1 : rtn + 1;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Print HEX
|
||||
* \param[in] n number to be printed as HEX.
|
||||
*
|
||||
* \return The number of bytes written or -1 if an error occurs.
|
||||
*/
|
||||
int printHex(uint32_t n);
|
||||
//----------------------------------------------------------------------------
|
||||
/** Print HEX with CRLF
|
||||
* \param[in] n number to be printed as HEX.
|
||||
*
|
||||
* \return The number of bytes written or -1 if an error occurs.
|
||||
*/
|
||||
int printHexln(uint32_t n) {
|
||||
int rtn = printHex(n);
|
||||
return rtn < 0 || putCRLF() != 2 ? -1 : rtn + 2;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Set position of a stream to the beginning.
|
||||
*
|
||||
* The rewind function sets the file position to the beginning of the
|
||||
* file. It is equivalent to fseek(0L, SEEK_SET) except that the error
|
||||
* indicator for the stream is also cleared.
|
||||
*
|
||||
* \return true for success or false for failure.
|
||||
*/
|
||||
bool rewind();
|
||||
//----------------------------------------------------------------------------
|
||||
/** Push a byte back into an input stream.
|
||||
*
|
||||
* \param[in] c the byte (converted to an unsigned char) to be pushed back.
|
||||
*
|
||||
* One character of push-back is guaranteed. If the ungetc function is
|
||||
* called too many times without an intervening read or file positioning
|
||||
* operation on that stream, the operation may fail.
|
||||
*
|
||||
* A successful intervening call to a file positioning function (fseek,
|
||||
* fsetpos, or rewind) discards any pushed-back characters for the stream.
|
||||
*
|
||||
* \return Upon successful completion, ungetc() returns the byte pushed
|
||||
* back after conversion. Otherwise it returns EOF.
|
||||
*/
|
||||
int ungetc(int c);
|
||||
//============================================================================
|
||||
private:
|
||||
bool fillBuf();
|
||||
int fillGet();
|
||||
bool flushBuf();
|
||||
int flushPut(uint8_t c);
|
||||
char* fmtSpace(uint8_t len);
|
||||
int write(const void* buf, size_t count);
|
||||
//----------------------------------------------------------------------------
|
||||
// F_SRD and F_WR are never simultaneously asserted
|
||||
static const uint8_t F_SRD = 0x01; // OK to read
|
||||
static const uint8_t F_SWR = 0x02; // OK to write
|
||||
static const uint8_t F_SRW = 0x04; // open for reading & writing
|
||||
static const uint8_t F_EOF = 0x10; // found EOF
|
||||
static const uint8_t F_ERR = 0x20; // found error
|
||||
//----------------------------------------------------------------------------
|
||||
uint8_t m_flags;
|
||||
uint8_t* m_p;
|
||||
uint8_t m_r;
|
||||
uint8_t m_w;
|
||||
uint8_t m_buf[STREAM_BUF_SIZE];
|
||||
};
|
||||
//------------------------------------------------------------------------------
|
||||
#endif // StdioStream_h
|
172
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/bufstream.h
Normal file
172
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/bufstream.h
Normal file
@ -0,0 +1,172 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef bufstream_h
|
||||
#define bufstream_h
|
||||
/**
|
||||
* \file
|
||||
* \brief \ref ibufstream and \ref obufstream classes
|
||||
*/
|
||||
#include <string.h>
|
||||
#include "iostream.h"
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class ibufstream
|
||||
* \brief parse a char string
|
||||
*/
|
||||
class ibufstream : public istream {
|
||||
public:
|
||||
/** Constructor */
|
||||
ibufstream() : m_buf(0), m_len(0) {}
|
||||
/** Constructor
|
||||
* \param[in] str pointer to string to be parsed
|
||||
* Warning: The string will not be copied so must stay in scope.
|
||||
*/
|
||||
explicit ibufstream(const char* str) {
|
||||
init(str);
|
||||
}
|
||||
/** Initialize an ibufstream
|
||||
* \param[in] str pointer to string to be parsed
|
||||
* Warning: The string will not be copied so must stay in scope.
|
||||
*/
|
||||
void init(const char* str) {
|
||||
m_buf = str;
|
||||
m_len = strlen(m_buf);
|
||||
m_pos = 0;
|
||||
clear();
|
||||
}
|
||||
|
||||
protected:
|
||||
/// @cond SHOW_PROTECTED
|
||||
int16_t getch() {
|
||||
if (m_pos < m_len) {
|
||||
return m_buf[m_pos++];
|
||||
}
|
||||
setstate(eofbit);
|
||||
return -1;
|
||||
}
|
||||
void getpos(FatPos_t *pos) {
|
||||
pos->position = m_pos;
|
||||
}
|
||||
bool seekoff(off_type off, seekdir way) {
|
||||
(void)off;
|
||||
(void)way;
|
||||
return false;
|
||||
}
|
||||
bool seekpos(pos_type pos) {
|
||||
if (pos < m_len) {
|
||||
m_pos = pos;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
void setpos(FatPos_t *pos) {
|
||||
m_pos = pos->position;
|
||||
}
|
||||
pos_type tellpos() {
|
||||
return m_pos;
|
||||
}
|
||||
/// @endcond
|
||||
private:
|
||||
const char* m_buf;
|
||||
size_t m_len;
|
||||
size_t m_pos;
|
||||
};
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class obufstream
|
||||
* \brief format a char string
|
||||
*/
|
||||
class obufstream : public ostream {
|
||||
public:
|
||||
/** constructor */
|
||||
obufstream() : m_in(0) {}
|
||||
/** Constructor
|
||||
* \param[in] buf buffer for formatted string
|
||||
* \param[in] size buffer size
|
||||
*/
|
||||
obufstream(char *buf, size_t size) {
|
||||
init(buf, size);
|
||||
}
|
||||
/** Initialize an obufstream
|
||||
* \param[in] buf buffer for formatted string
|
||||
* \param[in] size buffer size
|
||||
*/
|
||||
void init(char *buf, size_t size) {
|
||||
m_buf = buf;
|
||||
buf[0] = '\0';
|
||||
m_size = size;
|
||||
m_in = 0;
|
||||
}
|
||||
/** \return a pointer to the buffer */
|
||||
char* buf() {
|
||||
return m_buf;
|
||||
}
|
||||
/** \return the length of the formatted string */
|
||||
size_t length() {
|
||||
return m_in;
|
||||
}
|
||||
|
||||
protected:
|
||||
/// @cond SHOW_PROTECTED
|
||||
void putch(char c) {
|
||||
if (m_in >= (m_size - 1)) {
|
||||
setstate(badbit);
|
||||
return;
|
||||
}
|
||||
m_buf[m_in++] = c;
|
||||
m_buf[m_in] = '\0';
|
||||
}
|
||||
void putstr(const char *str) {
|
||||
while (*str) {
|
||||
putch(*str++);
|
||||
}
|
||||
}
|
||||
bool seekoff(off_type off, seekdir way) {
|
||||
(void)off;
|
||||
(void)way;
|
||||
return false;
|
||||
}
|
||||
bool seekpos(pos_type pos) {
|
||||
if (pos > m_in) {
|
||||
return false;
|
||||
}
|
||||
m_in = pos;
|
||||
m_buf[m_in] = '\0';
|
||||
return true;
|
||||
}
|
||||
bool sync() {
|
||||
return true;
|
||||
}
|
||||
|
||||
pos_type tellpos() {
|
||||
return m_in;
|
||||
}
|
||||
/// @endcond
|
||||
private:
|
||||
char *m_buf;
|
||||
size_t m_size;
|
||||
size_t m_in;
|
||||
};
|
||||
#endif // bufstream_h
|
173
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/fstream.cpp
Normal file
173
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/fstream.cpp
Normal file
@ -0,0 +1,173 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#include "../../../Repetier.h"
|
||||
#include "fstream.h"
|
||||
//==============================================================================
|
||||
/// @cond SHOW_PROTECTED
|
||||
int16_t FatStreamBase::getch() {
|
||||
uint8_t c;
|
||||
int8_t s = read(&c, 1);
|
||||
if (s != 1) {
|
||||
if (s < 0) {
|
||||
setstate(badbit);
|
||||
} else {
|
||||
setstate(eofbit);
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
if (c != '\r' || (getmode() & ios::binary)) {
|
||||
return c;
|
||||
}
|
||||
s = read(&c, 1);
|
||||
if (s == 1 && c == '\n') {
|
||||
return c;
|
||||
}
|
||||
if (s == 1) {
|
||||
seekCur(-1);
|
||||
}
|
||||
return '\r';
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void FatStreamBase::open(const char* path, ios::openmode mode) {
|
||||
uint8_t flags;
|
||||
switch (mode & (app | in | out | trunc)) {
|
||||
case app | in:
|
||||
case app | in | out:
|
||||
flags = O_RDWR | O_APPEND | O_CREAT;
|
||||
break;
|
||||
|
||||
case app:
|
||||
case app | out:
|
||||
flags = O_WRITE | O_APPEND | O_CREAT;
|
||||
break;
|
||||
|
||||
case in:
|
||||
flags = O_READ;
|
||||
break;
|
||||
|
||||
case in | out:
|
||||
flags = O_RDWR;
|
||||
break;
|
||||
|
||||
case in | out | trunc:
|
||||
flags = O_RDWR | O_TRUNC | O_CREAT;
|
||||
break;
|
||||
|
||||
case out:
|
||||
case out | trunc:
|
||||
flags = O_WRITE | O_TRUNC | O_CREAT;
|
||||
break;
|
||||
|
||||
default:
|
||||
goto fail;
|
||||
}
|
||||
if (mode & ios::ate) {
|
||||
flags |= O_AT_END;
|
||||
}
|
||||
if (!FatFile::open(path, flags)) {
|
||||
goto fail;
|
||||
}
|
||||
setmode(mode);
|
||||
clear();
|
||||
return;
|
||||
|
||||
fail:
|
||||
FatFile::close();
|
||||
setstate(failbit);
|
||||
return;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void FatStreamBase::putch(char c) {
|
||||
if (c == '\n' && !(getmode() & ios::binary)) {
|
||||
write('\r');
|
||||
}
|
||||
write(c);
|
||||
if (getWriteError()) {
|
||||
setstate(badbit);
|
||||
}
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void FatStreamBase::putstr(const char* str) {
|
||||
size_t n = 0;
|
||||
while (1) {
|
||||
char c = str[n];
|
||||
if (c == '\0' || (c == '\n' && !(getmode() & ios::binary))) {
|
||||
if (n > 0) {
|
||||
write(str, n);
|
||||
}
|
||||
if (c == '\0') {
|
||||
break;
|
||||
}
|
||||
write('\r');
|
||||
str += n;
|
||||
n = 0;
|
||||
}
|
||||
n++;
|
||||
}
|
||||
if (getWriteError()) {
|
||||
setstate(badbit);
|
||||
}
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Internal do not use
|
||||
* \param[in] off
|
||||
* \param[in] way
|
||||
*/
|
||||
bool FatStreamBase::seekoff(off_type off, seekdir way) {
|
||||
pos_type pos;
|
||||
switch (way) {
|
||||
case beg:
|
||||
pos = off;
|
||||
break;
|
||||
|
||||
case cur:
|
||||
pos = curPosition() + off;
|
||||
break;
|
||||
|
||||
case end:
|
||||
pos = fileSize() + off;
|
||||
break;
|
||||
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
return seekpos(pos);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Internal do not use
|
||||
* \param[in] pos
|
||||
*/
|
||||
bool FatStreamBase::seekpos(pos_type pos) {
|
||||
return seekSet(pos);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int FatStreamBase::write(const void* buf, size_t n) {
|
||||
return FatFile::write(buf, n);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void FatStreamBase::write(char c) {
|
||||
write(&c, 1);
|
||||
}
|
||||
/// @endcond
|
320
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/fstream.h
Normal file
320
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/fstream.h
Normal file
@ -0,0 +1,320 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef fstream_h
|
||||
#define fstream_h
|
||||
/**
|
||||
* \file
|
||||
* \brief \ref fstream, \ref ifstream, and \ref ofstream classes
|
||||
*/
|
||||
#include "FatFile.h"
|
||||
#include "iostream.h"
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class FatStreamBase
|
||||
* \brief Base class for C++ style streams
|
||||
*/
|
||||
class FatStreamBase : protected FatFile, virtual public ios {
|
||||
protected:
|
||||
/// @cond SHOW_PROTECTED
|
||||
int16_t getch();
|
||||
void putch(char c);
|
||||
void putstr(const char *str);
|
||||
void open(const char* path, ios::openmode mode);
|
||||
/** Internal do not use
|
||||
* \return mode
|
||||
*/
|
||||
ios::openmode getmode() {
|
||||
return m_mode;
|
||||
}
|
||||
/** Internal do not use
|
||||
* \param[in] mode
|
||||
*/
|
||||
void setmode(ios::openmode mode) {
|
||||
m_mode = mode;
|
||||
}
|
||||
bool seekoff(off_type off, seekdir way);
|
||||
bool seekpos(pos_type pos);
|
||||
int write(const void* buf, size_t n);
|
||||
void write(char c);
|
||||
/// @endcond
|
||||
private:
|
||||
ios::openmode m_mode;
|
||||
};
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class fstream
|
||||
* \brief file input/output stream.
|
||||
*/
|
||||
class fstream : public iostream, FatStreamBase {
|
||||
public:
|
||||
using iostream::peek;
|
||||
fstream() {}
|
||||
/** Constructor with open
|
||||
*
|
||||
* \param[in] path path to open
|
||||
* \param[in] mode open mode
|
||||
*/
|
||||
explicit fstream(const char* path, openmode mode = in | out) {
|
||||
open(path, mode);
|
||||
}
|
||||
#if DESTRUCTOR_CLOSES_FILE
|
||||
~fstream() {}
|
||||
#endif // DESTRUCTOR_CLOSES_FILE
|
||||
/** Clear state and writeError
|
||||
* \param[in] state new state for stream
|
||||
*/
|
||||
void clear(iostate state = goodbit) {
|
||||
ios::clear(state);
|
||||
FatFile::clearWriteError();
|
||||
}
|
||||
/** Close a file and force cached data and directory information
|
||||
* to be written to the storage device.
|
||||
*/
|
||||
void close() {
|
||||
FatFile::close();
|
||||
}
|
||||
/** Open a fstream
|
||||
* \param[in] path file to open
|
||||
* \param[in] mode open mode
|
||||
*
|
||||
* Valid open modes are (at end, ios::ate, and/or ios::binary may be added):
|
||||
*
|
||||
* ios::in - Open file for reading.
|
||||
*
|
||||
* ios::out or ios::out | ios::trunc - Truncate to 0 length, if existent,
|
||||
* or create a file for writing only.
|
||||
*
|
||||
* ios::app or ios::out | ios::app - Append; open or create file for
|
||||
* writing at end-of-file.
|
||||
*
|
||||
* ios::in | ios::out - Open file for update (reading and writing).
|
||||
*
|
||||
* ios::in | ios::out | ios::trunc - Truncate to zero length, if existent,
|
||||
* or create file for update.
|
||||
*
|
||||
* ios::in | ios::app or ios::in | ios::out | ios::app - Append; open or
|
||||
* create text file for update, writing at end of file.
|
||||
*/
|
||||
void open(const char* path, openmode mode = in | out) {
|
||||
FatStreamBase::open(path, mode);
|
||||
}
|
||||
/** \return True if stream is open else false. */
|
||||
bool is_open() {
|
||||
return FatFile::isOpen();
|
||||
}
|
||||
|
||||
protected:
|
||||
/// @cond SHOW_PROTECTED
|
||||
/** Internal - do not use
|
||||
* \return
|
||||
*/
|
||||
int16_t getch() {
|
||||
return FatStreamBase::getch();
|
||||
}
|
||||
/** Internal - do not use
|
||||
* \param[out] pos
|
||||
*/
|
||||
void getpos(FatPos_t* pos) {
|
||||
FatFile::getpos(pos);
|
||||
}
|
||||
/** Internal - do not use
|
||||
* \param[in] c
|
||||
*/
|
||||
void putch(char c) {
|
||||
FatStreamBase::putch(c);
|
||||
}
|
||||
/** Internal - do not use
|
||||
* \param[in] str
|
||||
*/
|
||||
void putstr(const char *str) {
|
||||
FatStreamBase::putstr(str);
|
||||
}
|
||||
/** Internal - do not use
|
||||
* \param[in] pos
|
||||
*/
|
||||
bool seekoff(off_type off, seekdir way) {
|
||||
return FatStreamBase::seekoff(off, way);
|
||||
}
|
||||
bool seekpos(pos_type pos) {
|
||||
return FatStreamBase::seekpos(pos);
|
||||
}
|
||||
void setpos(FatPos_t* pos) {
|
||||
FatFile::setpos(pos);
|
||||
}
|
||||
bool sync() {
|
||||
return FatStreamBase::sync();
|
||||
}
|
||||
pos_type tellpos() {
|
||||
return FatStreamBase::curPosition();
|
||||
}
|
||||
/// @endcond
|
||||
};
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class ifstream
|
||||
* \brief file input stream.
|
||||
*/
|
||||
class ifstream : public istream, FatStreamBase {
|
||||
public:
|
||||
using istream::peek;
|
||||
ifstream() {}
|
||||
/** Constructor with open
|
||||
* \param[in] path file to open
|
||||
* \param[in] mode open mode
|
||||
*/
|
||||
explicit ifstream(const char* path, openmode mode = in) {
|
||||
open(path, mode);
|
||||
}
|
||||
#if DESTRUCTOR_CLOSES_FILE
|
||||
~ifstream() {}
|
||||
#endif // DESTRUCTOR_CLOSES_FILE
|
||||
/** Close a file and force cached data and directory information
|
||||
* to be written to the storage device.
|
||||
*/
|
||||
void close() {
|
||||
FatFile::close();
|
||||
}
|
||||
/** \return True if stream is open else false. */
|
||||
bool is_open() {
|
||||
return FatFile::isOpen();
|
||||
}
|
||||
/** Open an ifstream
|
||||
* \param[in] path file to open
|
||||
* \param[in] mode open mode
|
||||
*
|
||||
* \a mode See fstream::open() for valid modes.
|
||||
*/
|
||||
void open(const char* path, openmode mode = in) {
|
||||
FatStreamBase::open(path, mode | in);
|
||||
}
|
||||
|
||||
protected:
|
||||
/// @cond SHOW_PROTECTED
|
||||
/** Internal - do not use
|
||||
* \return
|
||||
*/
|
||||
int16_t getch() {
|
||||
return FatStreamBase::getch();
|
||||
}
|
||||
/** Internal - do not use
|
||||
* \param[out] pos
|
||||
*/
|
||||
void getpos(FatPos_t* pos) {
|
||||
FatFile::getpos(pos);
|
||||
}
|
||||
/** Internal - do not use
|
||||
* \param[in] pos
|
||||
*/
|
||||
bool seekoff(off_type off, seekdir way) {
|
||||
return FatStreamBase::seekoff(off, way);
|
||||
}
|
||||
bool seekpos(pos_type pos) {
|
||||
return FatStreamBase::seekpos(pos);
|
||||
}
|
||||
void setpos(FatPos_t* pos) {
|
||||
FatFile::setpos(pos);
|
||||
}
|
||||
pos_type tellpos() {
|
||||
return FatStreamBase::curPosition();
|
||||
}
|
||||
/// @endcond
|
||||
};
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class ofstream
|
||||
* \brief file output stream.
|
||||
*/
|
||||
class ofstream : public ostream, FatStreamBase {
|
||||
public:
|
||||
ofstream() {}
|
||||
/** Constructor with open
|
||||
* \param[in] path file to open
|
||||
* \param[in] mode open mode
|
||||
*/
|
||||
explicit ofstream(const char* path, ios::openmode mode = out) {
|
||||
open(path, mode);
|
||||
}
|
||||
#if DESTRUCTOR_CLOSES_FILE
|
||||
~ofstream() {}
|
||||
#endif // DESTRUCTOR_CLOSES_FILE
|
||||
/** Clear state and writeError
|
||||
* \param[in] state new state for stream
|
||||
*/
|
||||
void clear(iostate state = goodbit) {
|
||||
ios::clear(state);
|
||||
FatFile::clearWriteError();
|
||||
}
|
||||
/** Close a file and force cached data and directory information
|
||||
* to be written to the storage device.
|
||||
*/
|
||||
void close() {
|
||||
FatFile::close();
|
||||
}
|
||||
/** Open an ofstream
|
||||
* \param[in] path file to open
|
||||
* \param[in] mode open mode
|
||||
*
|
||||
* \a mode See fstream::open() for valid modes.
|
||||
*/
|
||||
void open(const char* path, openmode mode = out) {
|
||||
FatStreamBase::open(path, mode | out);
|
||||
}
|
||||
/** \return True if stream is open else false. */
|
||||
bool is_open() {
|
||||
return FatFile::isOpen();
|
||||
}
|
||||
|
||||
protected:
|
||||
/// @cond SHOW_PROTECTED
|
||||
/**
|
||||
* Internal do not use
|
||||
* \param[in] c
|
||||
*/
|
||||
void putch(char c) {
|
||||
FatStreamBase::putch(c);
|
||||
}
|
||||
void putstr(const char* str) {
|
||||
FatStreamBase::putstr(str);
|
||||
}
|
||||
bool seekoff(off_type off, seekdir way) {
|
||||
return FatStreamBase::seekoff(off, way);
|
||||
}
|
||||
bool seekpos(pos_type pos) {
|
||||
return FatStreamBase::seekpos(pos);
|
||||
}
|
||||
/**
|
||||
* Internal do not use
|
||||
* \param[in] b
|
||||
*/
|
||||
bool sync() {
|
||||
return FatStreamBase::sync();
|
||||
}
|
||||
pos_type tellpos() {
|
||||
return FatStreamBase::curPosition();
|
||||
}
|
||||
/// @endcond
|
||||
};
|
||||
//------------------------------------------------------------------------------
|
||||
#endif // fstream_h
|
423
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/ios.h
Normal file
423
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/ios.h
Normal file
@ -0,0 +1,423 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef ios_h
|
||||
#define ios_h
|
||||
#include "FatFile.h"
|
||||
/**
|
||||
* \file
|
||||
* \brief \ref ios_base and \ref ios classes
|
||||
*/
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class ios_base
|
||||
* \brief Base class for all streams
|
||||
*/
|
||||
class ios_base {
|
||||
public:
|
||||
/** typedef for iostate bitmask */
|
||||
typedef unsigned char iostate;
|
||||
// State flags.
|
||||
/** iostate for no flags */
|
||||
static const iostate goodbit = 0x00;
|
||||
/** iostate bad bit for a nonrecoverable error. */
|
||||
static const iostate badbit = 0X01;
|
||||
/** iostate bit for end of file reached */
|
||||
static const iostate eofbit = 0x02;
|
||||
/** iostate fail bit for nonfatal error */
|
||||
static const iostate failbit = 0X04;
|
||||
/**
|
||||
* unsigned size that can represent maximum file size.
|
||||
* (violates spec - should be signed)
|
||||
*/
|
||||
typedef uint32_t streamsize;
|
||||
/** type for absolute seek position */
|
||||
typedef uint32_t pos_type;
|
||||
/** type for relative seek offset */
|
||||
typedef int32_t off_type;
|
||||
|
||||
/** enumerated type for the direction of relative seeks */
|
||||
enum seekdir {
|
||||
/** seek relative to the beginning of the stream */
|
||||
beg,
|
||||
/** seek relative to the current stream position */
|
||||
cur,
|
||||
/** seek relative to the end of the stream */
|
||||
end
|
||||
};
|
||||
/** type for format flags */
|
||||
typedef unsigned int fmtflags;
|
||||
/** left adjust fields */
|
||||
static const fmtflags left = 0x0001;
|
||||
/** right adjust fields */
|
||||
static const fmtflags right = 0x0002;
|
||||
/** fill between sign/base prefix and number */
|
||||
static const fmtflags internal = 0x0004;
|
||||
/** base 10 flag*/
|
||||
static const fmtflags dec = 0x0008;
|
||||
/** base 16 flag */
|
||||
static const fmtflags hex = 0x0010;
|
||||
/** base 8 flag */
|
||||
static const fmtflags oct = 0x0020;
|
||||
// static const fmtflags fixed = 0x0040;
|
||||
// static const fmtflags scientific = 0x0080;
|
||||
/** use strings true/false for bool */
|
||||
static const fmtflags boolalpha = 0x0100;
|
||||
/** use prefix 0X for hex and 0 for oct */
|
||||
static const fmtflags showbase = 0x0200;
|
||||
/** always show '.' for floating numbers */
|
||||
static const fmtflags showpoint = 0x0400;
|
||||
/** show + sign for nonnegative numbers */
|
||||
static const fmtflags showpos = 0x0800;
|
||||
/** skip initial white space */
|
||||
static const fmtflags skipws = 0x1000;
|
||||
// static const fmtflags unitbuf = 0x2000;
|
||||
/** use uppercase letters in number representations */
|
||||
static const fmtflags uppercase = 0x4000;
|
||||
/** mask for adjustfield */
|
||||
static const fmtflags adjustfield = left | right | internal;
|
||||
/** mask for basefield */
|
||||
static const fmtflags basefield = dec | hex | oct;
|
||||
// static const fmtflags floatfield = scientific | fixed;
|
||||
//----------------------------------------------------------------------------
|
||||
/** typedef for iostream open mode */
|
||||
typedef uint8_t openmode;
|
||||
|
||||
// Openmode flags.
|
||||
/** seek to end before each write */
|
||||
static const openmode app = 0X4;
|
||||
/** open and seek to end immediately after opening */
|
||||
static const openmode ate = 0X8;
|
||||
/** perform input and output in binary mode (as opposed to text mode) */
|
||||
static const openmode binary = 0X10;
|
||||
/** open for input */
|
||||
static const openmode in = 0X20;
|
||||
/** open for output */
|
||||
static const openmode out = 0X40;
|
||||
/** truncate an existing stream when opening */
|
||||
static const openmode trunc = 0X80;
|
||||
//----------------------------------------------------------------------------
|
||||
ios_base() : m_fill(' '), m_fmtflags(dec | right | skipws)
|
||||
, m_precision(2), m_width(0) {}
|
||||
/** \return fill character */
|
||||
char fill() {
|
||||
return m_fill;
|
||||
}
|
||||
/** Set fill character
|
||||
* \param[in] c new fill character
|
||||
* \return old fill character
|
||||
*/
|
||||
char fill(char c) {
|
||||
char r = m_fill;
|
||||
m_fill = c;
|
||||
return r;
|
||||
}
|
||||
/** \return format flags */
|
||||
fmtflags flags() const {
|
||||
return m_fmtflags;
|
||||
}
|
||||
/** set format flags
|
||||
* \param[in] fl new flag
|
||||
* \return old flags
|
||||
*/
|
||||
fmtflags flags(fmtflags fl) {
|
||||
fmtflags tmp = m_fmtflags;
|
||||
m_fmtflags = fl;
|
||||
return tmp;
|
||||
}
|
||||
/** \return precision */
|
||||
int precision() const {
|
||||
return m_precision;
|
||||
}
|
||||
/** set precision
|
||||
* \param[in] n new precision
|
||||
* \return old precision
|
||||
*/
|
||||
int precision(unsigned int n) {
|
||||
int r = m_precision;
|
||||
m_precision = n;
|
||||
return r;
|
||||
}
|
||||
/** set format flags
|
||||
* \param[in] fl new flags to be or'ed in
|
||||
* \return old flags
|
||||
*/
|
||||
fmtflags setf(fmtflags fl) {
|
||||
fmtflags r = m_fmtflags;
|
||||
m_fmtflags |= fl;
|
||||
return r;
|
||||
}
|
||||
/** modify format flags
|
||||
* \param[in] mask flags to be removed
|
||||
* \param[in] fl flags to be set after mask bits have been cleared
|
||||
* \return old flags
|
||||
*/
|
||||
fmtflags setf(fmtflags fl, fmtflags mask) {
|
||||
fmtflags r = m_fmtflags;
|
||||
m_fmtflags &= ~mask;
|
||||
m_fmtflags |= fl;
|
||||
return r;
|
||||
}
|
||||
/** clear format flags
|
||||
* \param[in] fl flags to be cleared
|
||||
* \return old flags
|
||||
*/
|
||||
void unsetf(fmtflags fl) {
|
||||
m_fmtflags &= ~fl;
|
||||
}
|
||||
/** \return width */
|
||||
unsigned width() {
|
||||
return m_width;
|
||||
}
|
||||
/** set width
|
||||
* \param[in] n new width
|
||||
* \return old width
|
||||
*/
|
||||
unsigned width(unsigned n) {
|
||||
unsigned r = m_width;
|
||||
m_width = n;
|
||||
return r;
|
||||
}
|
||||
|
||||
protected:
|
||||
/** \return current number base */
|
||||
uint8_t flagsToBase() {
|
||||
uint8_t f = flags() & basefield;
|
||||
return f == oct ? 8 : f != hex ? 10 : 16;
|
||||
}
|
||||
|
||||
private:
|
||||
char m_fill;
|
||||
fmtflags m_fmtflags;
|
||||
unsigned char m_precision;
|
||||
unsigned int m_width;
|
||||
};
|
||||
//------------------------------------------------------------------------------
|
||||
/** function for boolalpha manipulator
|
||||
* \param[in] str The stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline ios_base& boolalpha(ios_base& str) {
|
||||
str.setf(ios_base::boolalpha);
|
||||
return str;
|
||||
}
|
||||
/** function for dec manipulator
|
||||
* \param[in] str The stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline ios_base& dec(ios_base& str) {
|
||||
str.setf(ios_base::dec, ios_base::basefield);
|
||||
return str;
|
||||
}
|
||||
/** function for hex manipulator
|
||||
* \param[in] str The stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline ios_base& hex(ios_base& str) {
|
||||
str.setf(ios_base::hex, ios_base::basefield);
|
||||
return str;
|
||||
}
|
||||
/** function for internal manipulator
|
||||
* \param[in] str The stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline ios_base& internal(ios_base& str) {
|
||||
str.setf(ios_base::internal, ios_base::adjustfield);
|
||||
return str;
|
||||
}
|
||||
/** function for left manipulator
|
||||
* \param[in] str The stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline ios_base& left(ios_base& str) {
|
||||
str.setf(ios_base::left, ios_base::adjustfield);
|
||||
return str;
|
||||
}
|
||||
/** function for noboolalpha manipulator
|
||||
* \param[in] str The stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline ios_base& noboolalpha(ios_base& str) {
|
||||
str.unsetf(ios_base::boolalpha);
|
||||
return str;
|
||||
}
|
||||
/** function for noshowbase manipulator
|
||||
* \param[in] str The stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline ios_base& noshowbase(ios_base& str) {
|
||||
str.unsetf(ios_base::showbase);
|
||||
return str;
|
||||
}
|
||||
/** function for noshowpoint manipulator
|
||||
* \param[in] str The stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline ios_base& noshowpoint(ios_base& str) {
|
||||
str.unsetf(ios_base::showpoint);
|
||||
return str;
|
||||
}
|
||||
/** function for noshowpos manipulator
|
||||
* \param[in] str The stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline ios_base& noshowpos(ios_base& str) {
|
||||
str.unsetf(ios_base::showpos);
|
||||
return str;
|
||||
}
|
||||
/** function for noskipws manipulator
|
||||
* \param[in] str The stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline ios_base& noskipws(ios_base& str) {
|
||||
str.unsetf(ios_base::skipws);
|
||||
return str;
|
||||
}
|
||||
/** function for nouppercase manipulator
|
||||
* \param[in] str The stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline ios_base& nouppercase(ios_base& str) {
|
||||
str.unsetf(ios_base::uppercase);
|
||||
return str;
|
||||
}
|
||||
/** function for oct manipulator
|
||||
* \param[in] str The stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline ios_base& oct(ios_base& str) {
|
||||
str.setf(ios_base::oct, ios_base::basefield);
|
||||
return str;
|
||||
}
|
||||
/** function for right manipulator
|
||||
* \param[in] str The stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline ios_base& right(ios_base& str) {
|
||||
str.setf(ios_base::right, ios_base::adjustfield);
|
||||
return str;
|
||||
}
|
||||
/** function for showbase manipulator
|
||||
* \param[in] str The stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline ios_base& showbase(ios_base& str) {
|
||||
str.setf(ios_base::showbase);
|
||||
return str;
|
||||
}
|
||||
/** function for showpos manipulator
|
||||
* \param[in] str The stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline ios_base& showpos(ios_base& str) {
|
||||
str.setf(ios_base::showpos);
|
||||
return str;
|
||||
}
|
||||
/** function for showpoint manipulator
|
||||
* \param[in] str The stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline ios_base& showpoint(ios_base& str) {
|
||||
str.setf(ios_base::showpoint);
|
||||
return str;
|
||||
}
|
||||
/** function for skipws manipulator
|
||||
* \param[in] str The stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline ios_base& skipws(ios_base& str) {
|
||||
str.setf(ios_base::skipws);
|
||||
return str;
|
||||
}
|
||||
/** function for uppercase manipulator
|
||||
* \param[in] str The stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline ios_base& uppercase(ios_base& str) {
|
||||
str.setf(ios_base::uppercase);
|
||||
return str;
|
||||
}
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class ios
|
||||
* \brief Error and state information for all streams
|
||||
*/
|
||||
class ios : public ios_base {
|
||||
public:
|
||||
/** Create ios with no error flags set */
|
||||
ios() : m_iostate(0) {}
|
||||
|
||||
/** \return null pointer if fail() is true. */
|
||||
operator const void*() const {
|
||||
return !fail() ? reinterpret_cast<const void*>(this) : 0;
|
||||
}
|
||||
/** \return true if fail() else false. */
|
||||
bool operator!() const {
|
||||
return fail();
|
||||
}
|
||||
/** \return The iostate flags for this file. */
|
||||
iostate rdstate() const {
|
||||
return m_iostate;
|
||||
}
|
||||
/** \return True if no iostate flags are set else false. */
|
||||
bool good() const {
|
||||
return m_iostate == goodbit;
|
||||
}
|
||||
/** \return true if end of file has been reached else false.
|
||||
*
|
||||
* Warning: An empty file returns false before the first read.
|
||||
*
|
||||
* Moral: eof() is only useful in combination with fail(), to find out
|
||||
* whether EOF was the cause for failure
|
||||
*/
|
||||
bool eof() const {
|
||||
return m_iostate & eofbit;
|
||||
}
|
||||
/** \return true if any iostate bit other than eof are set else false. */
|
||||
bool fail() const {
|
||||
return m_iostate & (failbit | badbit);
|
||||
}
|
||||
/** \return true if bad bit is set else false. */
|
||||
bool bad() const {
|
||||
return m_iostate & badbit;
|
||||
}
|
||||
/** Clear iostate bits.
|
||||
*
|
||||
* \param[in] state The flags you want to set after clearing all flags.
|
||||
**/
|
||||
void clear(iostate state = goodbit) {
|
||||
m_iostate = state;
|
||||
}
|
||||
/** Set iostate bits.
|
||||
*
|
||||
* \param[in] state Bitts to set.
|
||||
**/
|
||||
void setstate(iostate state) {
|
||||
m_iostate |= state;
|
||||
}
|
||||
|
||||
private:
|
||||
iostate m_iostate;
|
||||
};
|
||||
#endif // ios_h
|
158
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/iostream.h
Normal file
158
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/iostream.h
Normal file
@ -0,0 +1,158 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef iostream_h
|
||||
#define iostream_h
|
||||
/**
|
||||
* \file
|
||||
* \brief \ref iostream class
|
||||
*/
|
||||
#include "istream.h"
|
||||
#include "ostream.h"
|
||||
/** Skip white space
|
||||
* \param[in] is the Stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline istream& ws(istream& is) {
|
||||
is.skipWhite();
|
||||
return is;
|
||||
}
|
||||
/** insert endline
|
||||
* \param[in] os The Stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline ostream& endl(ostream& os) {
|
||||
os.put('\n');
|
||||
#if ENDL_CALLS_FLUSH
|
||||
os.flush();
|
||||
#endif // ENDL_CALLS_FLUSH
|
||||
return os;
|
||||
}
|
||||
/** flush manipulator
|
||||
* \param[in] os The stream
|
||||
* \return The stream
|
||||
*/
|
||||
inline ostream& flush(ostream& os) {
|
||||
os.flush();
|
||||
return os;
|
||||
}
|
||||
/**
|
||||
* \struct setfill
|
||||
* \brief type for setfill manipulator
|
||||
*/
|
||||
struct setfill {
|
||||
/** fill character */
|
||||
char c;
|
||||
/** constructor
|
||||
*
|
||||
* \param[in] arg new fill character
|
||||
*/
|
||||
explicit setfill(char arg) : c(arg) {}
|
||||
};
|
||||
/** setfill manipulator
|
||||
* \param[in] os the stream
|
||||
* \param[in] arg set setfill object
|
||||
* \return the stream
|
||||
*/
|
||||
inline ostream &operator<< (ostream &os, const setfill &arg) {
|
||||
os.fill(arg.c);
|
||||
return os;
|
||||
}
|
||||
/** setfill manipulator
|
||||
* \param[in] obj the stream
|
||||
* \param[in] arg set setfill object
|
||||
* \return the stream
|
||||
*/
|
||||
inline istream &operator>>(istream &obj, const setfill &arg) {
|
||||
obj.fill(arg.c);
|
||||
return obj;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** \struct setprecision
|
||||
* \brief type for setprecision manipulator
|
||||
*/
|
||||
struct setprecision {
|
||||
/** precision */
|
||||
unsigned int p;
|
||||
/** constructor
|
||||
* \param[in] arg new precision
|
||||
*/
|
||||
explicit setprecision(unsigned int arg) : p(arg) {}
|
||||
};
|
||||
/** setprecision manipulator
|
||||
* \param[in] os the stream
|
||||
* \param[in] arg set setprecision object
|
||||
* \return the stream
|
||||
*/
|
||||
inline ostream &operator<< (ostream &os, const setprecision &arg) {
|
||||
os.precision(arg.p);
|
||||
return os;
|
||||
}
|
||||
/** setprecision manipulator
|
||||
* \param[in] is the stream
|
||||
* \param[in] arg set setprecision object
|
||||
* \return the stream
|
||||
*/
|
||||
inline istream &operator>>(istream &is, const setprecision &arg) {
|
||||
is.precision(arg.p);
|
||||
return is;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** \struct setw
|
||||
* \brief type for setw manipulator
|
||||
*/
|
||||
struct setw {
|
||||
/** width */
|
||||
unsigned w;
|
||||
/** constructor
|
||||
* \param[in] arg new width
|
||||
*/
|
||||
explicit setw(unsigned arg) : w(arg) {}
|
||||
};
|
||||
/** setw manipulator
|
||||
* \param[in] os the stream
|
||||
* \param[in] arg set setw object
|
||||
* \return the stream
|
||||
*/
|
||||
inline ostream &operator<< (ostream &os, const setw &arg) {
|
||||
os.width(arg.w);
|
||||
return os;
|
||||
}
|
||||
/** setw manipulator
|
||||
* \param[in] is the stream
|
||||
* \param[in] arg set setw object
|
||||
* \return the stream
|
||||
*/
|
||||
inline istream &operator>>(istream &is, const setw &arg) {
|
||||
is.width(arg.w);
|
||||
return is;
|
||||
}
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class iostream
|
||||
* \brief Input/Output stream
|
||||
*/
|
||||
class iostream : public istream, public ostream {
|
||||
};
|
||||
#endif // iostream_h
|
397
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/istream.cpp
Normal file
397
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/istream.cpp
Normal file
@ -0,0 +1,397 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
// #include <ctype.h>
|
||||
#include "../../../Repetier.h"
|
||||
#include <float.h>
|
||||
#include <ctype.h>
|
||||
#include "istream.h"
|
||||
//------------------------------------------------------------------------------
|
||||
int istream::get() {
|
||||
int c;
|
||||
m_gcount = 0;
|
||||
c = getch();
|
||||
if (c < 0) {
|
||||
setstate(failbit);
|
||||
} else {
|
||||
m_gcount = 1;
|
||||
}
|
||||
return c;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
istream& istream::get(char& c) {
|
||||
int tmp = get();
|
||||
if (tmp >= 0) {
|
||||
c = tmp;
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
istream& istream::get(char* str, streamsize n, char delim) {
|
||||
int c;
|
||||
FatPos_t pos;
|
||||
m_gcount = 0;
|
||||
while ((m_gcount + 1) < n) {
|
||||
c = getch(&pos);
|
||||
if (c < 0) {
|
||||
break;
|
||||
}
|
||||
if (c == delim) {
|
||||
setpos(&pos);
|
||||
break;
|
||||
}
|
||||
str[m_gcount++] = c;
|
||||
}
|
||||
if (n > 0) {
|
||||
str[m_gcount] = '\0';
|
||||
}
|
||||
if (m_gcount == 0) {
|
||||
setstate(failbit);
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void istream::getBool(bool* b) {
|
||||
if ((flags() & boolalpha) == 0) {
|
||||
getNumber(b);
|
||||
return;
|
||||
}
|
||||
#ifdef __AVR__
|
||||
PGM_P truePtr = PSTR("true");
|
||||
PGM_P falsePtr = PSTR("false");
|
||||
#else // __AVR__
|
||||
const char* truePtr = "true";
|
||||
const char* falsePtr = "false";
|
||||
#endif // __AVR
|
||||
const uint8_t true_len = 4;
|
||||
const uint8_t false_len = 5;
|
||||
bool trueOk = true;
|
||||
bool falseOk = true;
|
||||
uint8_t i = 0;
|
||||
int c = readSkip();
|
||||
while (1) {
|
||||
#ifdef __AVR__
|
||||
falseOk = falseOk && c == pgm_read_byte(falsePtr + i);
|
||||
trueOk = trueOk && c == pgm_read_byte(truePtr + i);
|
||||
#else // __AVR__
|
||||
falseOk = falseOk && c == falsePtr[i];
|
||||
trueOk = trueOk && c == truePtr[i];
|
||||
#endif // __AVR__
|
||||
if (trueOk == false && falseOk == false) {
|
||||
break;
|
||||
}
|
||||
i++;
|
||||
if (trueOk && i == true_len) {
|
||||
*b = true;
|
||||
return;
|
||||
}
|
||||
if (falseOk && i == false_len) {
|
||||
*b = false;
|
||||
return;
|
||||
}
|
||||
c = getch();
|
||||
}
|
||||
setstate(failbit);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void istream::getChar(char* ch) {
|
||||
int16_t c = readSkip();
|
||||
if (c < 0) {
|
||||
setstate(failbit);
|
||||
} else {
|
||||
*ch = c;
|
||||
}
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
//
|
||||
// http://www.exploringbinary.com/category/numbers-in-computers/
|
||||
//
|
||||
int16_t const EXP_LIMIT = 100;
|
||||
static const uint32_t uint32_max = (uint32_t)-1;
|
||||
bool istream::getDouble(double* value) {
|
||||
bool got_digit = false;
|
||||
bool got_dot = false;
|
||||
bool neg;
|
||||
int16_t c;
|
||||
bool expNeg = false;
|
||||
int16_t exp = 0;
|
||||
int16_t fracExp = 0;
|
||||
uint32_t frac = 0;
|
||||
FatPos_t endPos;
|
||||
double pow10;
|
||||
double v;
|
||||
|
||||
getpos(&endPos);
|
||||
c = readSkip();
|
||||
neg = c == '-';
|
||||
if (c == '-' || c == '+') {
|
||||
c = getch();
|
||||
}
|
||||
while (1) {
|
||||
if (isdigit(c)) {
|
||||
got_digit = true;
|
||||
if (frac < uint32_max / 10) {
|
||||
frac = frac * 10 + (c - '0');
|
||||
if (got_dot) {
|
||||
fracExp--;
|
||||
}
|
||||
} else {
|
||||
if (!got_dot) {
|
||||
fracExp++;
|
||||
}
|
||||
}
|
||||
} else if (!got_dot && c == '.') {
|
||||
got_dot = true;
|
||||
} else {
|
||||
break;
|
||||
}
|
||||
if (fracExp < -EXP_LIMIT || fracExp > EXP_LIMIT) {
|
||||
goto fail;
|
||||
}
|
||||
c = getch(&endPos);
|
||||
}
|
||||
if (!got_digit) {
|
||||
goto fail;
|
||||
}
|
||||
if (c == 'e' || c == 'E') {
|
||||
c = getch();
|
||||
expNeg = c == '-';
|
||||
if (c == '-' || c == '+') {
|
||||
c = getch();
|
||||
}
|
||||
while (isdigit(c)) {
|
||||
if (exp > EXP_LIMIT) {
|
||||
goto fail;
|
||||
}
|
||||
exp = exp * 10 + (c - '0');
|
||||
c = getch(&endPos);
|
||||
}
|
||||
}
|
||||
v = static_cast<double>(frac);
|
||||
exp = expNeg ? fracExp - exp : fracExp + exp;
|
||||
expNeg = exp < 0;
|
||||
if (expNeg) {
|
||||
exp = -exp;
|
||||
}
|
||||
pow10 = 10.0;
|
||||
while (exp) {
|
||||
if (exp & 1) {
|
||||
if (expNeg) {
|
||||
// check for underflow
|
||||
if (v < FLT_MIN * pow10 && frac != 0) {
|
||||
goto fail;
|
||||
}
|
||||
v /= pow10;
|
||||
} else {
|
||||
// check for overflow
|
||||
if (v > FLT_MAX / pow10) {
|
||||
goto fail;
|
||||
}
|
||||
v *= pow10;
|
||||
}
|
||||
}
|
||||
pow10 *= pow10;
|
||||
exp >>= 1;
|
||||
}
|
||||
setpos(&endPos);
|
||||
*value = neg ? -v : v;
|
||||
return true;
|
||||
|
||||
fail:
|
||||
// error restore position to last good place
|
||||
setpos(&endPos);
|
||||
setstate(failbit);
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
|
||||
istream& istream::getline(char* str, streamsize n, char delim) {
|
||||
FatPos_t pos;
|
||||
int c;
|
||||
m_gcount = 0;
|
||||
if (n > 0) {
|
||||
str[0] = '\0';
|
||||
}
|
||||
while (1) {
|
||||
c = getch(&pos);
|
||||
if (c < 0) {
|
||||
break;
|
||||
}
|
||||
if (c == delim) {
|
||||
m_gcount++;
|
||||
break;
|
||||
}
|
||||
if ((m_gcount + 1) >= n) {
|
||||
setpos(&pos);
|
||||
setstate(failbit);
|
||||
break;
|
||||
}
|
||||
str[m_gcount++] = c;
|
||||
str[m_gcount] = '\0';
|
||||
}
|
||||
if (m_gcount == 0) {
|
||||
setstate(failbit);
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool istream::getNumber(uint32_t posMax, uint32_t negMax, uint32_t* num) {
|
||||
int16_t c;
|
||||
int8_t any = 0;
|
||||
int8_t have_zero = 0;
|
||||
uint8_t neg;
|
||||
uint32_t val = 0;
|
||||
uint32_t cutoff;
|
||||
uint8_t cutlim;
|
||||
FatPos_t endPos;
|
||||
uint8_t f = flags() & basefield;
|
||||
uint8_t base = f == oct ? 8 : f != hex ? 10 : 16;
|
||||
getpos(&endPos);
|
||||
c = readSkip();
|
||||
|
||||
neg = c == '-' ? 1 : 0;
|
||||
if (c == '-' || c == '+') {
|
||||
c = getch();
|
||||
}
|
||||
|
||||
if (base == 16 && c == '0') { // TESTSUITE
|
||||
c = getch(&endPos);
|
||||
if (c == 'X' || c == 'x') {
|
||||
c = getch();
|
||||
// remember zero in case no hex digits follow x/X
|
||||
have_zero = 1;
|
||||
} else {
|
||||
any = 1;
|
||||
}
|
||||
}
|
||||
// set values for overflow test
|
||||
cutoff = neg ? negMax : posMax;
|
||||
cutlim = cutoff % base;
|
||||
cutoff /= base;
|
||||
|
||||
while (1) {
|
||||
if (isdigit(c)) {
|
||||
c -= '0';
|
||||
} else if (isalpha(c)) {
|
||||
c -= isupper(c) ? 'A' - 10 : 'a' - 10;
|
||||
} else {
|
||||
break;
|
||||
}
|
||||
if (c >= base) {
|
||||
break;
|
||||
}
|
||||
if (val > cutoff || (val == cutoff && c > cutlim)) {
|
||||
// indicate overflow error
|
||||
any = -1;
|
||||
break;
|
||||
}
|
||||
val = val * base + c;
|
||||
c = getch(&endPos);
|
||||
any = 1;
|
||||
}
|
||||
setpos(&endPos);
|
||||
if (any > 0 || (have_zero && any >= 0)) {
|
||||
*num = neg ? -val : val;
|
||||
return true;
|
||||
}
|
||||
setstate(failbit);
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void istream::getStr(char* str) {
|
||||
FatPos_t pos;
|
||||
uint16_t i = 0;
|
||||
uint16_t m = width() ? width() - 1 : 0XFFFE;
|
||||
if (m != 0) {
|
||||
getpos(&pos);
|
||||
int c = readSkip();
|
||||
|
||||
while (i < m) {
|
||||
if (c < 0) {
|
||||
break;
|
||||
}
|
||||
if (isspace(c)) {
|
||||
setpos(&pos);
|
||||
break;
|
||||
}
|
||||
str[i++] = c;
|
||||
c = getch(&pos);
|
||||
}
|
||||
}
|
||||
str[i] = '\0';
|
||||
if (i == 0) {
|
||||
setstate(failbit);
|
||||
}
|
||||
width(0);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
istream& istream::ignore(streamsize n, int delim) {
|
||||
int c;
|
||||
m_gcount = 0;
|
||||
while (m_gcount < n) {
|
||||
c = getch();
|
||||
if (c < 0) {
|
||||
break;
|
||||
}
|
||||
m_gcount++;
|
||||
if (c == delim) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int istream::peek() {
|
||||
int16_t c;
|
||||
FatPos_t pos;
|
||||
m_gcount = 0;
|
||||
getpos(&pos);
|
||||
c = getch();
|
||||
if (c < 0) {
|
||||
if (!bad()) {
|
||||
setstate(eofbit);
|
||||
}
|
||||
} else {
|
||||
setpos(&pos);
|
||||
}
|
||||
return c;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int16_t istream::readSkip() {
|
||||
int16_t c;
|
||||
do {
|
||||
c = getch();
|
||||
} while (isspace(c) && (flags() & skipws));
|
||||
return c;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** used to implement ws() */
|
||||
void istream::skipWhite() {
|
||||
int c;
|
||||
FatPos_t pos;
|
||||
do {
|
||||
c = getch(&pos);
|
||||
} while (isspace(c));
|
||||
setpos(&pos);
|
||||
}
|
384
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/istream.h
Normal file
384
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/istream.h
Normal file
@ -0,0 +1,384 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef istream_h
|
||||
#define istream_h
|
||||
/**
|
||||
* \file
|
||||
* \brief \ref istream class
|
||||
*/
|
||||
#include "ios.h"
|
||||
|
||||
/**
|
||||
* \class istream
|
||||
* \brief Input Stream
|
||||
*/
|
||||
class istream : public virtual ios {
|
||||
public:
|
||||
istream() {}
|
||||
/** call manipulator
|
||||
* \param[in] pf function to call
|
||||
* \return the stream
|
||||
*/
|
||||
istream& operator>>(istream& (*pf)(istream& str)) {
|
||||
return pf(*this);
|
||||
}
|
||||
/** call manipulator
|
||||
* \param[in] pf function to call
|
||||
* \return the stream
|
||||
*/
|
||||
istream& operator>>(ios_base& (*pf)(ios_base& str)) {
|
||||
pf(*this);
|
||||
return *this;
|
||||
}
|
||||
/** call manipulator
|
||||
* \param[in] pf function to call
|
||||
* \return the stream
|
||||
*/
|
||||
istream& operator>>(ios& (*pf)(ios& str)) {
|
||||
pf(*this);
|
||||
return *this;
|
||||
}
|
||||
/**
|
||||
* Extract a character string
|
||||
* \param[out] str location to store the string.
|
||||
* \return Is always *this. Failure is indicated by the state of *this.
|
||||
*/
|
||||
istream& operator>>(char *str) {
|
||||
getStr(str);
|
||||
return *this;
|
||||
}
|
||||
/**
|
||||
* Extract a character
|
||||
* \param[out] ch location to store the character.
|
||||
* \return Is always *this. Failure is indicated by the state of *this.
|
||||
*/
|
||||
istream& operator>>(char& ch) {
|
||||
getChar(&ch);
|
||||
return *this;
|
||||
}
|
||||
/**
|
||||
* Extract a character string
|
||||
* \param[out] str location to store the string.
|
||||
* \return Is always *this. Failure is indicated by the state of *this.
|
||||
*/
|
||||
istream& operator>>(signed char *str) {
|
||||
getStr(reinterpret_cast<char*>(str));
|
||||
return *this;
|
||||
}
|
||||
/**
|
||||
* Extract a character
|
||||
* \param[out] ch location to store the character.
|
||||
* \return Is always *this. Failure is indicated by the state of *this.
|
||||
*/
|
||||
istream& operator>>(signed char& ch) {
|
||||
getChar(reinterpret_cast<char*>(&ch));
|
||||
return *this;
|
||||
}
|
||||
/**
|
||||
* Extract a character string
|
||||
* \param[out] str location to store the string.
|
||||
* \return Is always *this. Failure is indicated by the state of *this.
|
||||
*/
|
||||
istream& operator>>(unsigned char *str) {
|
||||
getStr(reinterpret_cast<char*>(str));
|
||||
return *this;
|
||||
}
|
||||
/**
|
||||
* Extract a character
|
||||
* \param[out] ch location to store the character.
|
||||
* \return Is always *this. Failure is indicated by the state of *this.
|
||||
*/
|
||||
istream& operator>>(unsigned char& ch) {
|
||||
getChar(reinterpret_cast<char*>(&ch));
|
||||
return *this;
|
||||
}
|
||||
/**
|
||||
* Extract a value of type bool.
|
||||
* \param[out] arg location to store the value.
|
||||
* \return Is always *this. Failure is indicated by the state of *this.
|
||||
*/
|
||||
istream& operator>>(bool& arg) {
|
||||
getBool(&arg);
|
||||
return *this;
|
||||
}
|
||||
/**
|
||||
* Extract a value of type short.
|
||||
* \param[out] arg location to store the value.
|
||||
* \return Is always *this. Failure is indicated by the state of *this.
|
||||
*/
|
||||
istream &operator>>(short& arg) { // NOLINT
|
||||
getNumber(&arg);
|
||||
return *this;
|
||||
}
|
||||
/**
|
||||
* Extract a value of type unsigned short.
|
||||
* \param[out] arg location to store the value.
|
||||
* \return Is always *this. Failure is indicated by the state of *this.
|
||||
*/
|
||||
istream &operator>>(unsigned short& arg) { // NOLINT
|
||||
getNumber(&arg);
|
||||
return *this;
|
||||
}
|
||||
/**
|
||||
* Extract a value of type int.
|
||||
* \param[out] arg location to store the value.
|
||||
* \return Is always *this. Failure is indicated by the state of *this.
|
||||
*/
|
||||
istream &operator>>(int& arg) {
|
||||
getNumber(&arg);
|
||||
return *this;
|
||||
}
|
||||
/**
|
||||
* Extract a value of type unsigned int.
|
||||
* \param[out] arg location to store the value.
|
||||
* \return Is always *this. Failure is indicated by the state of *this.
|
||||
*/
|
||||
istream &operator>>(unsigned int& arg) {
|
||||
getNumber(&arg);
|
||||
return *this;
|
||||
}
|
||||
/**
|
||||
* Extract a value of type long.
|
||||
* \param[out] arg location to store the value.
|
||||
* \return Is always *this. Failure is indicated by the state of *this.
|
||||
*/
|
||||
istream &operator>>(long& arg) { // NOLINT
|
||||
getNumber(&arg);
|
||||
return *this;
|
||||
}
|
||||
/**
|
||||
* Extract a value of type unsigned long.
|
||||
* \param[out] arg location to store the value.
|
||||
* \return Is always *this. Failure is indicated by the state of *this.
|
||||
*/
|
||||
istream &operator>>(unsigned long& arg) { // NOLINT
|
||||
getNumber(&arg);
|
||||
return *this;
|
||||
}
|
||||
/**
|
||||
* Extract a value of type double.
|
||||
* \param[out] arg location to store the value.
|
||||
* \return Is always *this. Failure is indicated by the state of *this.
|
||||
*/
|
||||
istream &operator>> (double& arg) {
|
||||
getDouble(&arg);
|
||||
return *this;
|
||||
}
|
||||
/**
|
||||
* Extract a value of type float.
|
||||
* \param[out] arg location to store the value.
|
||||
* \return Is always *this. Failure is indicated by the state of *this.
|
||||
*/
|
||||
istream &operator>> (float& arg) {
|
||||
double v;
|
||||
getDouble(&v);
|
||||
arg = v;
|
||||
return *this;
|
||||
}
|
||||
/**
|
||||
* Extract a value of type void*.
|
||||
* \param[out] arg location to store the value.
|
||||
* \return Is always *this. Failure is indicated by the state of *this.
|
||||
*/
|
||||
istream& operator>> (void*& arg) {
|
||||
uint32_t val;
|
||||
getNumber(&val);
|
||||
arg = reinterpret_cast<void*>(val);
|
||||
return *this;
|
||||
}
|
||||
/**
|
||||
* \return The number of characters extracted by the last unformatted
|
||||
* input function.
|
||||
*/
|
||||
streamsize gcount() const {
|
||||
return m_gcount;
|
||||
}
|
||||
/**
|
||||
* Extract a character if one is available.
|
||||
*
|
||||
* \return The character or -1 if a failure occurs. A failure is indicated
|
||||
* by the stream state.
|
||||
*/
|
||||
int get();
|
||||
/**
|
||||
* Extract a character if one is available.
|
||||
*
|
||||
* \param[out] ch location to receive the extracted character.
|
||||
*
|
||||
* \return always returns *this. A failure is indicated by the stream state.
|
||||
*/
|
||||
istream& get(char& ch);
|
||||
/**
|
||||
* Extract characters.
|
||||
*
|
||||
* \param[out] str Location to receive extracted characters.
|
||||
* \param[in] n Size of str.
|
||||
* \param[in] delim Delimiter
|
||||
*
|
||||
* Characters are extracted until extraction fails, n is less than 1,
|
||||
* n-1 characters are extracted, or the next character equals
|
||||
* \a delim (delim is not extracted). If no characters are extracted
|
||||
* failbit is set. If end-of-file occurs the eofbit is set.
|
||||
*
|
||||
* \return always returns *this. A failure is indicated by the stream state.
|
||||
*/
|
||||
istream& get(char *str, streamsize n, char delim = '\n');
|
||||
/**
|
||||
* Extract characters
|
||||
*
|
||||
* \param[out] str Location to receive extracted characters.
|
||||
* \param[in] n Size of str.
|
||||
* \param[in] delim Delimiter
|
||||
*
|
||||
* Characters are extracted until extraction fails,
|
||||
* the next character equals \a delim (delim is extracted), or n-1
|
||||
* characters are extracted.
|
||||
*
|
||||
* The failbit is set if no characters are extracted or n-1 characters
|
||||
* are extracted. If end-of-file occurs the eofbit is set.
|
||||
*
|
||||
* \return always returns *this. A failure is indicated by the stream state.
|
||||
*/
|
||||
istream& getline(char *str, streamsize n, char delim = '\n');
|
||||
/**
|
||||
* Extract characters and discard them.
|
||||
*
|
||||
* \param[in] n maximum number of characters to ignore.
|
||||
* \param[in] delim Delimiter.
|
||||
*
|
||||
* Characters are extracted until extraction fails, \a n characters
|
||||
* are extracted, or the next input character equals \a delim
|
||||
* (the delimiter is extracted). If end-of-file occurs the eofbit is set.
|
||||
*
|
||||
* Failures are indicated by the state of the stream.
|
||||
*
|
||||
* \return *this
|
||||
*
|
||||
*/
|
||||
istream& ignore(streamsize n = 1, int delim = -1);
|
||||
/**
|
||||
* Return the next available character without consuming it.
|
||||
*
|
||||
* \return The character if the stream state is good else -1;
|
||||
*
|
||||
*/
|
||||
int peek();
|
||||
// istream& read(char *str, streamsize count);
|
||||
// streamsize readsome(char *str, streamsize count);
|
||||
/**
|
||||
* \return the stream position
|
||||
*/
|
||||
pos_type tellg() {
|
||||
return tellpos();
|
||||
}
|
||||
/**
|
||||
* Set the stream position
|
||||
* \param[in] pos The absolute position in which to move the read pointer.
|
||||
* \return Is always *this. Failure is indicated by the state of *this.
|
||||
*/
|
||||
istream& seekg(pos_type pos) {
|
||||
if (!seekpos(pos)) {
|
||||
setstate(failbit);
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
/**
|
||||
* Set the stream position.
|
||||
*
|
||||
* \param[in] off An offset to move the read pointer relative to way.
|
||||
* \a off is a signed 32-bit int so the offset is limited to +- 2GB.
|
||||
* \param[in] way One of ios::beg, ios::cur, or ios::end.
|
||||
* \return Is always *this. Failure is indicated by the state of *this.
|
||||
*/
|
||||
istream& seekg(off_type off, seekdir way) {
|
||||
if (!seekoff(off, way)) {
|
||||
setstate(failbit);
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
void skipWhite();
|
||||
|
||||
protected:
|
||||
/// @cond SHOW_PROTECTED
|
||||
/**
|
||||
* Internal - do not use
|
||||
* \return
|
||||
*/
|
||||
virtual int16_t getch() = 0;
|
||||
/**
|
||||
* Internal - do not use
|
||||
* \param[out] pos
|
||||
* \return
|
||||
*/
|
||||
int16_t getch(FatPos_t* pos) {
|
||||
getpos(pos);
|
||||
return getch();
|
||||
}
|
||||
/**
|
||||
* Internal - do not use
|
||||
* \param[out] pos
|
||||
*/
|
||||
virtual void getpos(FatPos_t* pos) = 0;
|
||||
/**
|
||||
* Internal - do not use
|
||||
* \param[in] pos
|
||||
*/
|
||||
virtual bool seekoff(off_type off, seekdir way) = 0;
|
||||
virtual bool seekpos(pos_type pos) = 0;
|
||||
virtual void setpos(FatPos_t* pos) = 0;
|
||||
virtual pos_type tellpos() = 0;
|
||||
|
||||
/// @endcond
|
||||
private:
|
||||
void getBool(bool *b);
|
||||
void getChar(char* ch);
|
||||
bool getDouble(double* value);
|
||||
template <typename T> void getNumber(T* value);
|
||||
bool getNumber(uint32_t posMax, uint32_t negMax, uint32_t* num);
|
||||
void getStr(char *str);
|
||||
int16_t readSkip();
|
||||
|
||||
size_t m_gcount;
|
||||
};
|
||||
//------------------------------------------------------------------------------
|
||||
template <typename T>
|
||||
void istream::getNumber(T* value) {
|
||||
uint32_t tmp;
|
||||
if ((T)-1 < 0) {
|
||||
// number is signed, max positive value
|
||||
uint32_t const m = ((uint32_t)-1) >> (33 - sizeof(T) * 8);
|
||||
// max absolute value of negative number is m + 1.
|
||||
if (getNumber(m, m + 1, &tmp)) {
|
||||
*value = (T)tmp;
|
||||
}
|
||||
} else {
|
||||
// max unsigned value for T
|
||||
uint32_t const m = (T)-1;
|
||||
if (getNumber(m, m, &tmp)) {
|
||||
*value = (T)tmp;
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif // istream_h
|
198
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/ostream.cpp
Normal file
198
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/ostream.cpp
Normal file
@ -0,0 +1,198 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#include "../../../Repetier.h"
|
||||
#include <string.h>
|
||||
#include "ostream.h"
|
||||
#ifndef PSTR
|
||||
#define PSTR(x) x
|
||||
#endif
|
||||
//------------------------------------------------------------------------------
|
||||
void ostream::do_fill(unsigned len) {
|
||||
for (; len < width(); len++) {
|
||||
putch(fill());
|
||||
}
|
||||
width(0);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void ostream::fill_not_left(unsigned len) {
|
||||
if ((flags() & adjustfield) != left) {
|
||||
do_fill(len);
|
||||
}
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
char* ostream::fmtNum(uint32_t n, char* ptr, uint8_t base) {
|
||||
char a = flags() & uppercase ? 'A' - 10 : 'a' - 10;
|
||||
do {
|
||||
uint32_t m = n;
|
||||
n /= base;
|
||||
char c = m - base * n;
|
||||
*--ptr = c < 10 ? c + '0' : c + a;
|
||||
} while (n);
|
||||
return ptr;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void ostream::putBool(bool b) {
|
||||
if (flags() & boolalpha) {
|
||||
if (b) {
|
||||
putPgm(PSTR("true"));
|
||||
} else {
|
||||
putPgm(PSTR("false"));
|
||||
}
|
||||
} else {
|
||||
putChar(b ? '1' : '0');
|
||||
}
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void ostream::putChar(char c) {
|
||||
fill_not_left(1);
|
||||
putch(c);
|
||||
do_fill(1);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void ostream::putDouble(double n) {
|
||||
uint8_t nd = precision();
|
||||
double round = 0.5;
|
||||
char sign;
|
||||
char buf[13]; // room for sign, 10 digits, '.', and zero byte
|
||||
char* end = buf + sizeof(buf) - 1;
|
||||
char* str = end;
|
||||
// terminate string
|
||||
*end = '\0';
|
||||
|
||||
// get sign and make nonnegative
|
||||
if (n < 0.0) {
|
||||
sign = '-';
|
||||
n = -n;
|
||||
} else {
|
||||
sign = flags() & showpos ? '+' : '\0';
|
||||
}
|
||||
// check for larger than uint32_t
|
||||
if (n > 4.0E9) {
|
||||
putPgm(PSTR("BIG FLT"));
|
||||
return;
|
||||
}
|
||||
// round up and separate int and fraction parts
|
||||
for (uint8_t i = 0; i < nd; ++i) {
|
||||
round *= 0.1;
|
||||
}
|
||||
n += round;
|
||||
uint32_t intPart = n;
|
||||
double fractionPart = n - intPart;
|
||||
|
||||
// format intPart and decimal point
|
||||
if (nd || (flags() & showpoint)) {
|
||||
*--str = '.';
|
||||
}
|
||||
str = fmtNum(intPart, str, 10);
|
||||
|
||||
// calculate length for fill
|
||||
uint8_t len = sign ? 1 : 0;
|
||||
len += nd + end - str;
|
||||
|
||||
// extract adjust field
|
||||
fmtflags adj = flags() & adjustfield;
|
||||
if (adj == internal) {
|
||||
if (sign) {
|
||||
putch(sign);
|
||||
}
|
||||
do_fill(len);
|
||||
} else {
|
||||
// do fill for internal or right
|
||||
fill_not_left(len);
|
||||
if (sign) {
|
||||
*--str = sign;
|
||||
}
|
||||
}
|
||||
putstr(str);
|
||||
// output fraction
|
||||
while (nd-- > 0) {
|
||||
fractionPart *= 10.0;
|
||||
int digit = static_cast<int>(fractionPart);
|
||||
putch(digit + '0');
|
||||
fractionPart -= digit;
|
||||
}
|
||||
// do fill if not done above
|
||||
do_fill(len);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void ostream::putNum(int32_t n) {
|
||||
bool neg = n < 0 && flagsToBase() == 10;
|
||||
if (neg) {
|
||||
n = -n;
|
||||
}
|
||||
putNum(n, neg);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void ostream::putNum(uint32_t n, bool neg) {
|
||||
char buf[13];
|
||||
char* end = buf + sizeof(buf) - 1;
|
||||
char* num;
|
||||
char* str;
|
||||
uint8_t base = flagsToBase();
|
||||
*end = '\0';
|
||||
str = num = fmtNum(n, end, base);
|
||||
if (base == 10) {
|
||||
if (neg) {
|
||||
*--str = '-';
|
||||
} else if (flags() & showpos) {
|
||||
*--str = '+';
|
||||
}
|
||||
} else if (flags() & showbase) {
|
||||
if (flags() & hex) {
|
||||
*--str = flags() & uppercase ? 'X' : 'x';
|
||||
}
|
||||
*--str = '0';
|
||||
}
|
||||
uint8_t len = end - str;
|
||||
fmtflags adj = flags() & adjustfield;
|
||||
if (adj == internal) {
|
||||
while (str < num) {
|
||||
putch(*str++);
|
||||
}
|
||||
}
|
||||
if (adj != left) {
|
||||
do_fill(len);
|
||||
}
|
||||
putstr(str);
|
||||
do_fill(len);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void ostream::putPgm(const char* str) {
|
||||
int n;
|
||||
for (n = 0; pgm_read_byte(&str[n]); n++) {
|
||||
}
|
||||
fill_not_left(n);
|
||||
for (uint8_t c; (c = pgm_read_byte(str)); str++) {
|
||||
putch(c);
|
||||
}
|
||||
do_fill(n);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void ostream::putStr(const char* str) {
|
||||
unsigned n = strlen(str);
|
||||
fill_not_left(n);
|
||||
putstr(str);
|
||||
do_fill(n);
|
||||
}
|
276
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/ostream.h
Normal file
276
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FatLib/ostream.h
Normal file
@ -0,0 +1,276 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef ostream_h
|
||||
#define ostream_h
|
||||
/**
|
||||
* \file
|
||||
* \brief \ref ostream class
|
||||
*/
|
||||
#include "ios.h"
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class ostream
|
||||
* \brief Output Stream
|
||||
*/
|
||||
class ostream : public virtual ios {
|
||||
public:
|
||||
ostream() {}
|
||||
|
||||
/** call manipulator
|
||||
* \param[in] pf function to call
|
||||
* \return the stream
|
||||
*/
|
||||
ostream& operator<< (ostream& (*pf)(ostream& str)) {
|
||||
return pf(*this);
|
||||
}
|
||||
/** call manipulator
|
||||
* \param[in] pf function to call
|
||||
* \return the stream
|
||||
*/
|
||||
ostream& operator<< (ios_base& (*pf)(ios_base& str)) {
|
||||
pf(*this);
|
||||
return *this;
|
||||
}
|
||||
/** Output bool
|
||||
* \param[in] arg value to output
|
||||
* \return the stream
|
||||
*/
|
||||
ostream &operator<< (bool arg) {
|
||||
putBool(arg);
|
||||
return *this;
|
||||
}
|
||||
/** Output string
|
||||
* \param[in] arg string to output
|
||||
* \return the stream
|
||||
*/
|
||||
ostream &operator<< (const char *arg) {
|
||||
putStr(arg);
|
||||
return *this;
|
||||
}
|
||||
/** Output string
|
||||
* \param[in] arg string to output
|
||||
* \return the stream
|
||||
*/
|
||||
ostream &operator<< (const signed char *arg) {
|
||||
putStr((const char*)arg);
|
||||
return *this;
|
||||
}
|
||||
/** Output string
|
||||
* \param[in] arg string to output
|
||||
* \return the stream
|
||||
*/
|
||||
ostream &operator<< (const unsigned char *arg) {
|
||||
putStr((const char*)arg);
|
||||
return *this;
|
||||
}
|
||||
/** Output character
|
||||
* \param[in] arg character to output
|
||||
* \return the stream
|
||||
*/
|
||||
ostream &operator<< (char arg) {
|
||||
putChar(arg);
|
||||
return *this;
|
||||
}
|
||||
/** Output character
|
||||
* \param[in] arg character to output
|
||||
* \return the stream
|
||||
*/
|
||||
ostream &operator<< (signed char arg) {
|
||||
putChar(static_cast<char>(arg));
|
||||
return *this;
|
||||
}
|
||||
/** Output character
|
||||
* \param[in] arg character to output
|
||||
* \return the stream
|
||||
*/
|
||||
ostream &operator<< (unsigned char arg) {
|
||||
putChar(static_cast<char>(arg));
|
||||
return *this;
|
||||
}
|
||||
/** Output double
|
||||
* \param[in] arg value to output
|
||||
* \return the stream
|
||||
*/
|
||||
ostream &operator<< (double arg) {
|
||||
putDouble(arg);
|
||||
return *this;
|
||||
}
|
||||
/** Output float
|
||||
* \param[in] arg value to output
|
||||
* \return the stream
|
||||
*/
|
||||
ostream &operator<< (float arg) {
|
||||
putDouble(arg);
|
||||
return *this;
|
||||
}
|
||||
/** Output signed short
|
||||
* \param[in] arg value to output
|
||||
* \return the stream
|
||||
*/
|
||||
ostream &operator<< (short arg) { // NOLINT
|
||||
putNum((int32_t)arg);
|
||||
return *this;
|
||||
}
|
||||
/** Output unsigned short
|
||||
* \param[in] arg value to output
|
||||
* \return the stream
|
||||
*/
|
||||
ostream &operator<< (unsigned short arg) { // NOLINT
|
||||
putNum((uint32_t)arg);
|
||||
return *this;
|
||||
}
|
||||
/** Output signed int
|
||||
* \param[in] arg value to output
|
||||
* \return the stream
|
||||
*/
|
||||
ostream &operator<< (int arg) {
|
||||
putNum((int32_t)arg);
|
||||
return *this;
|
||||
}
|
||||
/** Output unsigned int
|
||||
* \param[in] arg value to output
|
||||
* \return the stream
|
||||
*/
|
||||
ostream &operator<< (unsigned int arg) {
|
||||
putNum((uint32_t)arg);
|
||||
return *this;
|
||||
}
|
||||
/** Output signed long
|
||||
* \param[in] arg value to output
|
||||
* \return the stream
|
||||
*/
|
||||
ostream &operator<< (long arg) { // NOLINT
|
||||
putNum((int32_t)arg);
|
||||
return *this;
|
||||
}
|
||||
/** Output unsigned long
|
||||
* \param[in] arg value to output
|
||||
* \return the stream
|
||||
*/
|
||||
ostream &operator<< (unsigned long arg) { // NOLINT
|
||||
putNum((uint32_t)arg);
|
||||
return *this;
|
||||
}
|
||||
/** Output pointer
|
||||
* \param[in] arg value to output
|
||||
* \return the stream
|
||||
*/
|
||||
ostream& operator<< (const void* arg) {
|
||||
putNum(reinterpret_cast<uint32_t>(arg));
|
||||
return *this;
|
||||
}
|
||||
#if (defined(ARDUINO) && ENABLE_ARDUINO_FEATURES) || defined(DOXYGEN)
|
||||
/** Output a string from flash using the Arduino F() macro.
|
||||
* \param[in] arg pointing to flash string
|
||||
* \return the stream
|
||||
*/
|
||||
ostream &operator<< (const __FlashStringHelper *arg) {
|
||||
putPgm(reinterpret_cast<const char*>(arg));
|
||||
return *this;
|
||||
}
|
||||
#endif // (defined(ARDUINO) && ENABLE_ARDUINO_FEATURES) || defined(DOXYGEN)
|
||||
/**
|
||||
* Puts a character in a stream.
|
||||
*
|
||||
* The unformatted output function inserts the element \a ch.
|
||||
* It returns *this.
|
||||
*
|
||||
* \param[in] ch The character
|
||||
* \return A reference to the ostream object.
|
||||
*/
|
||||
ostream& put(char ch) {
|
||||
putch(ch);
|
||||
return *this;
|
||||
}
|
||||
// ostream& write(char *str, streamsize count);
|
||||
/**
|
||||
* Flushes the buffer associated with this stream. The flush function
|
||||
* calls the sync function of the associated file.
|
||||
* \return A reference to the ostream object.
|
||||
*/
|
||||
ostream& flush() {
|
||||
if (!sync()) {
|
||||
setstate(badbit);
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
/**
|
||||
* \return the stream position
|
||||
*/
|
||||
pos_type tellp() {
|
||||
return tellpos();
|
||||
}
|
||||
/**
|
||||
* Set the stream position
|
||||
* \param[in] pos The absolute position in which to move the write pointer.
|
||||
* \return Is always *this. Failure is indicated by the state of *this.
|
||||
*/
|
||||
ostream& seekp(pos_type pos) {
|
||||
if (!seekpos(pos)) {
|
||||
setstate(failbit);
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
/**
|
||||
* Set the stream position.
|
||||
*
|
||||
* \param[in] off An offset to move the write pointer relative to way.
|
||||
* \a off is a signed 32-bit int so the offset is limited to +- 2GB.
|
||||
* \param[in] way One of ios::beg, ios::cur, or ios::end.
|
||||
* \return Is always *this. Failure is indicated by the state of *this.
|
||||
*/
|
||||
ostream& seekp(off_type off, seekdir way) {
|
||||
if (!seekoff(off, way)) {
|
||||
setstate(failbit);
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
|
||||
protected:
|
||||
/// @cond SHOW_PROTECTED
|
||||
/** Put character with binary/text conversion
|
||||
* \param[in] ch character to write
|
||||
*/
|
||||
virtual void putch(char ch) = 0;
|
||||
virtual void putstr(const char *str) = 0;
|
||||
virtual bool seekoff(off_type pos, seekdir way) = 0;
|
||||
virtual bool seekpos(pos_type pos) = 0;
|
||||
virtual bool sync() = 0;
|
||||
|
||||
virtual pos_type tellpos() = 0;
|
||||
/// @endcond
|
||||
private:
|
||||
void do_fill(unsigned len);
|
||||
void fill_not_left(unsigned len);
|
||||
char* fmtNum(uint32_t n, char *ptr, uint8_t base);
|
||||
void putBool(bool b);
|
||||
void putChar(char c);
|
||||
void putDouble(double n);
|
||||
void putNum(uint32_t n, bool neg = false);
|
||||
void putNum(int32_t n);
|
||||
void putPgm(const char* str);
|
||||
void putStr(const char* str);
|
||||
};
|
||||
#endif // ostream_h
|
61
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FreeStack.h
Normal file
61
Repetier-Firmware 1.0.3/Repetier/src/SdFat/FreeStack.h
Normal file
@ -0,0 +1,61 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef FreeStack_h
|
||||
#define FreeStack_h
|
||||
/**
|
||||
* \file
|
||||
* \brief FreeStack() function.
|
||||
*/
|
||||
#if defined(__AVR__) || defined(DOXYGEN)
|
||||
/** boundary between stack and heap. */
|
||||
extern char *__brkval;
|
||||
/** End of bss section.*/
|
||||
extern char __bss_end;
|
||||
/** Amount of free stack space.
|
||||
* \return The number of free bytes.
|
||||
*/
|
||||
static int FreeStack() {
|
||||
char* sp = reinterpret_cast<char*>(SP);
|
||||
return __brkval ? sp - __brkval : sp - &__bss_end;
|
||||
// char top;
|
||||
// return __brkval ? &top - __brkval : &top - &__bss_end;
|
||||
}
|
||||
#elif defined(PLATFORM_ID) // Particle board
|
||||
static int FreeStack() {
|
||||
return System.freeMemory();
|
||||
}
|
||||
#elif defined(__arm__)
|
||||
extern "C" char* sbrk(int incr);
|
||||
static int FreeStack() {
|
||||
char top = 't';
|
||||
return &top - reinterpret_cast<char*>(sbrk(0));
|
||||
}
|
||||
#else
|
||||
#warning FreeStack is not defined for this system.
|
||||
static int FreeStack() {
|
||||
return 0;
|
||||
}
|
||||
#endif
|
||||
#endif // FreeStack_h
|
21
Repetier-Firmware 1.0.3/Repetier/src/SdFat/LICENSE.md
Normal file
21
Repetier-Firmware 1.0.3/Repetier/src/SdFat/LICENSE.md
Normal file
@ -0,0 +1,21 @@
|
||||
MIT License
|
||||
|
||||
Copyright (c) 2011..2017 Bill Greiman
|
||||
|
||||
Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
of this software and associated documentation files (the "Software"), to deal
|
||||
in the Software without restriction, including without limitation the rights
|
||||
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
copies of the Software, and to permit persons to whom the Software is
|
||||
furnished to do so, subject to the following conditions:
|
||||
|
||||
The above copyright notice and this permission notice shall be included in all
|
||||
copies or substantial portions of the Software.
|
||||
|
||||
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||
SOFTWARE.
|
74
Repetier-Firmware 1.0.3/Repetier/src/SdFat/MinimumSerial.cpp
Normal file
74
Repetier-Firmware 1.0.3/Repetier/src/SdFat/MinimumSerial.cpp
Normal file
@ -0,0 +1,74 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#include "../../Repetier.h"
|
||||
#include "SysCall.h"
|
||||
#if defined(UDR0) || defined(DOXYGEN)
|
||||
#include "MinimumSerial.h"
|
||||
const uint16_t MIN_2X_BAUD = F_CPU / (4 * (2 * 0XFFF + 1)) + 1;
|
||||
//------------------------------------------------------------------------------
|
||||
int MinimumSerial::available() {
|
||||
return UCSR0A & (1 << RXC0) ? 1 : 0;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void MinimumSerial::begin(uint32_t baud) {
|
||||
uint16_t baud_setting;
|
||||
// don't worry, the compiler will squeeze out F_CPU != 16000000UL
|
||||
if ((F_CPU != 16000000UL || baud != 57600) && baud > MIN_2X_BAUD) {
|
||||
// Double the USART Transmission Speed
|
||||
UCSR0A = 1 << U2X0;
|
||||
baud_setting = (F_CPU / 4 / baud - 1) / 2;
|
||||
} else {
|
||||
// hardcoded exception for compatibility with the bootloader shipped
|
||||
// with the Duemilanove and previous boards and the firmware on the 8U2
|
||||
// on the Uno and Mega 2560.
|
||||
UCSR0A = 0;
|
||||
baud_setting = (F_CPU / 8 / baud - 1) / 2;
|
||||
}
|
||||
// assign the baud_setting
|
||||
UBRR0H = baud_setting >> 8;
|
||||
UBRR0L = baud_setting;
|
||||
// enable transmit and receive
|
||||
UCSR0B |= (1 << TXEN0) | (1 << RXEN0);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void MinimumSerial::flush() {
|
||||
while (((1 << UDRIE0) & UCSR0B) || !(UCSR0A & (1 << UDRE0))) {
|
||||
}
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
int MinimumSerial::read() {
|
||||
if (UCSR0A & (1 << RXC0)) {
|
||||
return UDR0;
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
size_t MinimumSerial::write(uint8_t b) {
|
||||
while (((1 << UDRIE0) & UCSR0B) || !(UCSR0A & (1 << UDRE0))) {
|
||||
}
|
||||
UDR0 = b;
|
||||
return 1;
|
||||
}
|
||||
#endif // defined(UDR0) || defined(DOXYGEN)
|
67
Repetier-Firmware 1.0.3/Repetier/src/SdFat/MinimumSerial.h
Normal file
67
Repetier-Firmware 1.0.3/Repetier/src/SdFat/MinimumSerial.h
Normal file
@ -0,0 +1,67 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
/**
|
||||
* \file
|
||||
* \brief Minimal AVR Serial driver.
|
||||
*/
|
||||
#ifndef MinimumSerial_h
|
||||
#define MinimumSerial_h
|
||||
#include "SysCall.h"
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class MinimumSerial
|
||||
* \brief mini serial class for the %SdFat library.
|
||||
*/
|
||||
class MinimumSerial : public Print {
|
||||
public:
|
||||
/** \return true for hardware serial */
|
||||
operator bool() { return true; }
|
||||
/**
|
||||
* \return one if data is available.
|
||||
*/
|
||||
int available();
|
||||
/**
|
||||
* Set baud rate for serial port zero and enable in non interrupt mode.
|
||||
* Do not call this function if you use another serial library.
|
||||
* \param[in] baud rate
|
||||
*/
|
||||
void begin(uint32_t baud);
|
||||
/** Wait for write done. */
|
||||
void flush();
|
||||
/**
|
||||
* Unbuffered read
|
||||
* \return -1 if no character is available or an available character.
|
||||
*/
|
||||
int read();
|
||||
/**
|
||||
* Unbuffered write
|
||||
*
|
||||
* \param[in] b byte to write.
|
||||
* \return 1
|
||||
*/
|
||||
size_t write(uint8_t b);
|
||||
using Print::write;
|
||||
};
|
||||
#endif // MinimumSerial_h
|
58
Repetier-Firmware 1.0.3/Repetier/src/SdFat/README.md
Normal file
58
Repetier-Firmware 1.0.3/Repetier/src/SdFat/README.md
Normal file
@ -0,0 +1,58 @@
|
||||
The Arduino SdFat library provides read/write access to FAT16/FAT32
|
||||
file systems on SD/SDHC flash cards.
|
||||
|
||||
SdFat requires Arduino 1.6x or greater.
|
||||
|
||||
Key changes:
|
||||
|
||||
The SPI divisor has been replaced by SPISettings in the begin() call.
|
||||
|
||||
```
|
||||
bool begin(uint8_t csPin = SS, SPISettings spiSettings = SPI_FULL_SPEED);
|
||||
```
|
||||
|
||||
Several macros have been defined for backward compatibility.
|
||||
|
||||
```
|
||||
#define SD_SCK_MHZ(maxMhz) SPISettings(1000000UL*maxMhz, MSBFIRST, SPI_MODE0)
|
||||
// SPI divisor constants
|
||||
/** Set SCK to max possible rate. */
|
||||
#define SPI_FULL_SPEED SD_SCK_MHZ(50)
|
||||
/** Set SCK rate to F_CPU/3 for Due */
|
||||
#define SPI_DIV3_SPEED SD_SCK_HZ(F_CPU/3)
|
||||
/** Set SCK rate to F_CPU/4. */
|
||||
#define SPI_HALF_SPEED SD_SCK_HZ(F_CPU/4)
|
||||
// ...
|
||||
```
|
||||
|
||||
There are two new classes, SdFatEX and SdFatSoftSpiEX.
|
||||
|
||||
Teensy 3.5/3.6 SDIO support has been added. Try the TeensySdioDemo example.
|
||||
Many other example will work with Teensy SDIO if you use the SdFatSdio classes
|
||||
and call begin with no parameters.
|
||||
|
||||
```
|
||||
SdFatSdio sd;
|
||||
|
||||
....
|
||||
|
||||
if (!sd.begin()) {
|
||||
// Handle failure.
|
||||
}
|
||||
|
||||
```
|
||||
Please read changes.txt and the html documentation in the extras folder for more information.
|
||||
|
||||
Please report problems as issues.
|
||||
|
||||
A number of configuration options can be set by editing SdFatConfig.h
|
||||
define macros. See the html documentation for details
|
||||
|
||||
Please read the html documentation for this library. Start with
|
||||
html/index.html and read the Main Page. Next go to the Classes tab and
|
||||
read the documentation for the classes SdFat, SdFatEX, SdBaseFile,
|
||||
SdFile, File, StdioStream, ifstream, ofstream, and others.
|
||||
|
||||
Please continue by reading the html documentation.
|
||||
|
||||
Updated 26 Apr 2017
|
480
Repetier-Firmware 1.0.3/Repetier/src/SdFat/SdCard/SdInfo.h
Normal file
480
Repetier-Firmware 1.0.3/Repetier/src/SdFat/SdCard/SdInfo.h
Normal file
@ -0,0 +1,480 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef SdInfo_h
|
||||
#define SdInfo_h
|
||||
#include <stdint.h>
|
||||
// Based on the document:
|
||||
//
|
||||
// SD Specifications
|
||||
// Part 1
|
||||
// Physical Layer
|
||||
// Simplified Specification
|
||||
// Version 5.00
|
||||
// Aug 10, 2016
|
||||
//
|
||||
// https://www.sdcard.org/downloads/pls/
|
||||
//------------------------------------------------------------------------------
|
||||
// SD card errors
|
||||
// See the SD Specification for command info.
|
||||
typedef enum {
|
||||
SD_CARD_ERROR_NONE = 0,
|
||||
|
||||
// Basic commands and switch command.
|
||||
SD_CARD_ERROR_CMD0 = 0X20,
|
||||
SD_CARD_ERROR_CMD2,
|
||||
SD_CARD_ERROR_CMD3,
|
||||
SD_CARD_ERROR_CMD6,
|
||||
SD_CARD_ERROR_CMD7,
|
||||
SD_CARD_ERROR_CMD8,
|
||||
SD_CARD_ERROR_CMD9,
|
||||
SD_CARD_ERROR_CMD10,
|
||||
SD_CARD_ERROR_CMD12,
|
||||
SD_CARD_ERROR_CMD13,
|
||||
|
||||
// Read, write, erase, and extension commands.
|
||||
SD_CARD_ERROR_CMD17 = 0X30,
|
||||
SD_CARD_ERROR_CMD18,
|
||||
SD_CARD_ERROR_CMD24,
|
||||
SD_CARD_ERROR_CMD25,
|
||||
SD_CARD_ERROR_CMD32,
|
||||
SD_CARD_ERROR_CMD33,
|
||||
SD_CARD_ERROR_CMD38,
|
||||
SD_CARD_ERROR_CMD58,
|
||||
SD_CARD_ERROR_CMD59,
|
||||
|
||||
// Application specific commands.
|
||||
SD_CARD_ERROR_ACMD6 = 0X40,
|
||||
SD_CARD_ERROR_ACMD13,
|
||||
SD_CARD_ERROR_ACMD23,
|
||||
SD_CARD_ERROR_ACMD41,
|
||||
|
||||
// Read/write errors
|
||||
SD_CARD_ERROR_READ = 0X50,
|
||||
SD_CARD_ERROR_READ_CRC,
|
||||
SD_CARD_ERROR_READ_FIFO,
|
||||
SD_CARD_ERROR_READ_REG,
|
||||
SD_CARD_ERROR_READ_START,
|
||||
SD_CARD_ERROR_READ_TIMEOUT,
|
||||
SD_CARD_ERROR_STOP_TRAN,
|
||||
SD_CARD_ERROR_WRITE,
|
||||
SD_CARD_ERROR_WRITE_FIFO,
|
||||
SD_CARD_ERROR_WRITE_START,
|
||||
SD_CARD_ERROR_WRITE_TIMEOUT,
|
||||
|
||||
// Misc errors.
|
||||
SD_CARD_ERROR_DMA = 0X60,
|
||||
SD_CARD_ERROR_ERASE,
|
||||
SD_CARD_ERROR_ERASE_SINGLE_BLOCK,
|
||||
SD_CARD_ERROR_ERASE_TIMEOUT,
|
||||
SD_CARD_ERROR_INIT_NOT_CALLED,
|
||||
SD_CARD_ERROR_FUNCTION_NOT_SUPPORTED
|
||||
} sd_error_code_t;
|
||||
//------------------------------------------------------------------------------
|
||||
// card types
|
||||
/** Standard capacity V1 SD card */
|
||||
const uint8_t SD_CARD_TYPE_SD1 = 1;
|
||||
/** Standard capacity V2 SD card */
|
||||
const uint8_t SD_CARD_TYPE_SD2 = 2;
|
||||
/** High Capacity SD card */
|
||||
const uint8_t SD_CARD_TYPE_SDHC = 3;
|
||||
//------------------------------------------------------------------------------
|
||||
#define SD_SCK_HZ(maxSpeed) SPISettings(maxSpeed, MSBFIRST, SPI_MODE0)
|
||||
#define SD_SCK_MHZ(maxMhz) SPISettings(1000000UL*maxMhz, MSBFIRST, SPI_MODE0)
|
||||
// SPI divisor constants
|
||||
/** Set SCK to max rate of F_CPU/2. */
|
||||
#define SPI_FULL_SPEED SD_SCK_MHZ(50)
|
||||
/** Set SCK rate to F_CPU/3 for Due */
|
||||
#define SPI_DIV3_SPEED SD_SCK_HZ(F_CPU/3)
|
||||
/** Set SCK rate to F_CPU/4. */
|
||||
#define SPI_HALF_SPEED SD_SCK_HZ(F_CPU/4)
|
||||
/** Set SCK rate to F_CPU/6 for Due */
|
||||
#define SPI_DIV6_SPEED SD_SCK_HZ(F_CPU/6)
|
||||
/** Set SCK rate to F_CPU/8. */
|
||||
#define SPI_QUARTER_SPEED SD_SCK_HZ(F_CPU/8)
|
||||
/** Set SCK rate to F_CPU/16. */
|
||||
#define SPI_EIGHTH_SPEED SD_SCK_HZ(F_CPU/16)
|
||||
/** Set SCK rate to F_CPU/32. */
|
||||
#define SPI_SIXTEENTH_SPEED SD_SCK_HZ(F_CPU/32)
|
||||
//------------------------------------------------------------------------------
|
||||
// SD operation timeouts
|
||||
/** init timeout ms */
|
||||
const uint16_t SD_INIT_TIMEOUT = 2000;
|
||||
/** erase timeout ms */
|
||||
const uint16_t SD_ERASE_TIMEOUT = 10000;
|
||||
/** read timeout ms */
|
||||
const uint16_t SD_READ_TIMEOUT = 300;
|
||||
/** write time out ms */
|
||||
const uint16_t SD_WRITE_TIMEOUT = 600;
|
||||
//------------------------------------------------------------------------------
|
||||
// SD card commands
|
||||
/** GO_IDLE_STATE - init card in spi mode if CS low */
|
||||
const uint8_t CMD0 = 0X00;
|
||||
/** ALL_SEND_CID - Asks any card to send the CID. */
|
||||
const uint8_t CMD2 = 0X02;
|
||||
/** SEND_RELATIVE_ADDR - Ask the card to publish a new RCA. */
|
||||
const uint8_t CMD3 = 0X03;
|
||||
/** SWITCH_FUNC - Switch Function Command */
|
||||
const uint8_t CMD6 = 0X06;
|
||||
/** SELECT/DESELECT_CARD - toggles between the stand-by and transfer states. */
|
||||
const uint8_t CMD7 = 0X07;
|
||||
/** SEND_IF_COND - verify SD Memory Card interface operating condition.*/
|
||||
const uint8_t CMD8 = 0X08;
|
||||
/** SEND_CSD - read the Card Specific Data (CSD register) */
|
||||
const uint8_t CMD9 = 0X09;
|
||||
/** SEND_CID - read the card identification information (CID register) */
|
||||
const uint8_t CMD10 = 0X0A;
|
||||
/** STOP_TRANSMISSION - end multiple block read sequence */
|
||||
const uint8_t CMD12 = 0X0C;
|
||||
/** SEND_STATUS - read the card status register */
|
||||
const uint8_t CMD13 = 0X0D;
|
||||
/** READ_SINGLE_BLOCK - read a single data block from the card */
|
||||
const uint8_t CMD17 = 0X11;
|
||||
/** READ_MULTIPLE_BLOCK - read a multiple data blocks from the card */
|
||||
const uint8_t CMD18 = 0X12;
|
||||
/** WRITE_BLOCK - write a single data block to the card */
|
||||
const uint8_t CMD24 = 0X18;
|
||||
/** WRITE_MULTIPLE_BLOCK - write blocks of data until a STOP_TRANSMISSION */
|
||||
const uint8_t CMD25 = 0X19;
|
||||
/** ERASE_WR_BLK_START - sets the address of the first block to be erased */
|
||||
const uint8_t CMD32 = 0X20;
|
||||
/** ERASE_WR_BLK_END - sets the address of the last block of the continuous
|
||||
range to be erased*/
|
||||
const uint8_t CMD33 = 0X21;
|
||||
/** ERASE - erase all previously selected blocks */
|
||||
const uint8_t CMD38 = 0X26;
|
||||
/** APP_CMD - escape for application specific command */
|
||||
const uint8_t CMD55 = 0X37;
|
||||
/** READ_OCR - read the OCR register of a card */
|
||||
const uint8_t CMD58 = 0X3A;
|
||||
/** CRC_ON_OFF - enable or disable CRC checking */
|
||||
const uint8_t CMD59 = 0X3B;
|
||||
/** SET_BUS_WIDTH - Defines the data bus width for data transfer. */
|
||||
const uint8_t ACMD6 = 0X06;
|
||||
/** SD_STATUS - Send the SD Status. */
|
||||
const uint8_t ACMD13 = 0X0D;
|
||||
/** SET_WR_BLK_ERASE_COUNT - Set the number of write blocks to be
|
||||
pre-erased before writing */
|
||||
const uint8_t ACMD23 = 0X17;
|
||||
/** SD_SEND_OP_COMD - Sends host capacity support information and
|
||||
activates the card's initialization process */
|
||||
const uint8_t ACMD41 = 0X29;
|
||||
//==============================================================================
|
||||
// CARD_STATUS
|
||||
/** The command's argument was out of the allowed range for this card. */
|
||||
const uint32_t CARD_STATUS_OUT_OF_RANGE = 1UL << 31;
|
||||
/** A misaligned address which did not match the block length. */
|
||||
const uint32_t CARD_STATUS_ADDRESS_ERROR = 1UL << 30;
|
||||
/** The transferred block length is not allowed for this card. */
|
||||
const uint32_t CARD_STATUS_BLOCK_LEN_ERROR = 1UL << 29;
|
||||
/** An error in the sequence of erase commands occurred. */
|
||||
const uint32_t CARD_STATUS_ERASE_SEQ_ERROR = 1UL <<28;
|
||||
/** An invalid selection of write-blocks for erase occurred. */
|
||||
const uint32_t CARD_STATUS_ERASE_PARAM = 1UL << 27;
|
||||
/** Set when the host attempts to write to a protected block. */
|
||||
const uint32_t CARD_STATUS_WP_VIOLATION = 1UL << 26;
|
||||
/** When set, signals that the card is locked by the host. */
|
||||
const uint32_t CARD_STATUS_CARD_IS_LOCKED = 1UL << 25;
|
||||
/** Set when a sequence or password error has been detected. */
|
||||
const uint32_t CARD_STATUS_LOCK_UNLOCK_FAILED = 1UL << 24;
|
||||
/** The CRC check of the previous command failed. */
|
||||
const uint32_t CARD_STATUS_COM_CRC_ERROR = 1UL << 23;
|
||||
/** Command not legal for the card state. */
|
||||
const uint32_t CARD_STATUS_ILLEGAL_COMMAND = 1UL << 22;
|
||||
/** Card internal ECC was applied but failed to correct the data. */
|
||||
const uint32_t CARD_STATUS_CARD_ECC_FAILED = 1UL << 21;
|
||||
/** Internal card controller error */
|
||||
const uint32_t CARD_STATUS_CC_ERROR = 1UL << 20;
|
||||
/** A general or an unknown error occurred during the operation. */
|
||||
const uint32_t CARD_STATUS_ERROR = 1UL << 19;
|
||||
// bits 19, 18, and 17 reserved.
|
||||
/** Permanent WP set or attempt to change read only values of CSD. */
|
||||
const uint32_t CARD_STATUS_CSD_OVERWRITE = 1UL <<16;
|
||||
/** partial address space was erased due to write protect. */
|
||||
const uint32_t CARD_STATUS_WP_ERASE_SKIP = 1UL << 15;
|
||||
/** The command has been executed without using the internal ECC. */
|
||||
const uint32_t CARD_STATUS_CARD_ECC_DISABLED = 1UL << 14;
|
||||
/** out of erase sequence command was received. */
|
||||
const uint32_t CARD_STATUS_ERASE_RESET = 1UL << 13;
|
||||
/** The state of the card when receiving the command.
|
||||
* 0 = idle
|
||||
* 1 = ready
|
||||
* 2 = ident
|
||||
* 3 = stby
|
||||
* 4 = tran
|
||||
* 5 = data
|
||||
* 6 = rcv
|
||||
* 7 = prg
|
||||
* 8 = dis
|
||||
* 9-14 = reserved
|
||||
* 15 = reserved for I/O mode
|
||||
*/
|
||||
const uint32_t CARD_STATUS_CURRENT_STATE = 0XF << 9;
|
||||
/** Shift for current state. */
|
||||
const uint32_t CARD_STATUS_CURRENT_STATE_SHIFT = 9;
|
||||
/** Corresponds to buffer empty signaling on the bus. */
|
||||
const uint32_t CARD_STATUS_READY_FOR_DATA = 1UL << 8;
|
||||
// bit 7 reserved.
|
||||
/** Extension Functions may set this bit to get host to deal with events. */
|
||||
const uint32_t CARD_STATUS_FX_EVENT = 1UL << 6;
|
||||
/** The card will expect ACMD, or the command has been interpreted as ACMD */
|
||||
const uint32_t CARD_STATUS_APP_CMD = 1UL << 5;
|
||||
// bit 4 reserved.
|
||||
/** Error in the sequence of the authentication process. */
|
||||
const uint32_t CARD_STATUS_AKE_SEQ_ERROR = 1UL << 3;
|
||||
// bits 2,1, and 0 reserved for manufacturer test mode.
|
||||
//==============================================================================
|
||||
/** status for card in the ready state */
|
||||
const uint8_t R1_READY_STATE = 0X00;
|
||||
/** status for card in the idle state */
|
||||
const uint8_t R1_IDLE_STATE = 0X01;
|
||||
/** status bit for illegal command */
|
||||
const uint8_t R1_ILLEGAL_COMMAND = 0X04;
|
||||
/** start data token for read or write single block*/
|
||||
const uint8_t DATA_START_BLOCK = 0XFE;
|
||||
/** stop token for write multiple blocks*/
|
||||
const uint8_t STOP_TRAN_TOKEN = 0XFD;
|
||||
/** start data token for write multiple blocks*/
|
||||
const uint8_t WRITE_MULTIPLE_TOKEN = 0XFC;
|
||||
/** mask for data response tokens after a write block operation */
|
||||
const uint8_t DATA_RES_MASK = 0X1F;
|
||||
/** write data accepted token */
|
||||
const uint8_t DATA_RES_ACCEPTED = 0X05;
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class CID
|
||||
* \brief Card IDentification (CID) register.
|
||||
*/
|
||||
typedef struct CID {
|
||||
// byte 0
|
||||
/** Manufacturer ID */
|
||||
unsigned char mid;
|
||||
// byte 1-2
|
||||
/** OEM/Application ID */
|
||||
char oid[2];
|
||||
// byte 3-7
|
||||
/** Product name */
|
||||
char pnm[5];
|
||||
// byte 8
|
||||
/** Product revision least significant digit */
|
||||
unsigned char prv_m : 4;
|
||||
/** Product revision most significant digit */
|
||||
unsigned char prv_n : 4;
|
||||
// byte 9-12
|
||||
/** Product serial number */
|
||||
uint32_t psn;
|
||||
// byte 13
|
||||
/** Manufacturing date year low digit */
|
||||
unsigned char mdt_year_high : 4;
|
||||
/** not used */
|
||||
unsigned char reserved : 4;
|
||||
// byte 14
|
||||
/** Manufacturing date month */
|
||||
unsigned char mdt_month : 4;
|
||||
/** Manufacturing date year low digit */
|
||||
unsigned char mdt_year_low : 4;
|
||||
// byte 15
|
||||
/** not used always 1 */
|
||||
unsigned char always1 : 1;
|
||||
/** CRC7 checksum */
|
||||
unsigned char crc : 7;
|
||||
} __attribute__((packed)) cid_t;
|
||||
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class CSDV1
|
||||
* \brief CSD register for version 1.00 cards .
|
||||
*/
|
||||
typedef struct CSDV1 {
|
||||
// byte 0
|
||||
unsigned char reserved1 : 6;
|
||||
unsigned char csd_ver : 2;
|
||||
// byte 1
|
||||
unsigned char taac;
|
||||
// byte 2
|
||||
unsigned char nsac;
|
||||
// byte 3
|
||||
unsigned char tran_speed;
|
||||
// byte 4
|
||||
unsigned char ccc_high;
|
||||
// byte 5
|
||||
unsigned char read_bl_len : 4;
|
||||
unsigned char ccc_low : 4;
|
||||
// byte 6
|
||||
unsigned char c_size_high : 2;
|
||||
unsigned char reserved2 : 2;
|
||||
unsigned char dsr_imp : 1;
|
||||
unsigned char read_blk_misalign : 1;
|
||||
unsigned char write_blk_misalign : 1;
|
||||
unsigned char read_bl_partial : 1;
|
||||
// byte 7
|
||||
unsigned char c_size_mid;
|
||||
// byte 8
|
||||
unsigned char vdd_r_curr_max : 3;
|
||||
unsigned char vdd_r_curr_min : 3;
|
||||
unsigned char c_size_low : 2;
|
||||
// byte 9
|
||||
unsigned char c_size_mult_high : 2;
|
||||
unsigned char vdd_w_cur_max : 3;
|
||||
unsigned char vdd_w_curr_min : 3;
|
||||
// byte 10
|
||||
unsigned char sector_size_high : 6;
|
||||
unsigned char erase_blk_en : 1;
|
||||
unsigned char c_size_mult_low : 1;
|
||||
// byte 11
|
||||
unsigned char wp_grp_size : 7;
|
||||
unsigned char sector_size_low : 1;
|
||||
// byte 12
|
||||
unsigned char write_bl_len_high : 2;
|
||||
unsigned char r2w_factor : 3;
|
||||
unsigned char reserved3 : 2;
|
||||
unsigned char wp_grp_enable : 1;
|
||||
// byte 13
|
||||
unsigned char reserved4 : 5;
|
||||
unsigned char write_partial : 1;
|
||||
unsigned char write_bl_len_low : 2;
|
||||
// byte 14
|
||||
unsigned char reserved5: 2;
|
||||
unsigned char file_format : 2;
|
||||
unsigned char tmp_write_protect : 1;
|
||||
unsigned char perm_write_protect : 1;
|
||||
unsigned char copy : 1;
|
||||
/** Indicates the file format on the card */
|
||||
unsigned char file_format_grp : 1;
|
||||
// byte 15
|
||||
unsigned char always1 : 1;
|
||||
unsigned char crc : 7;
|
||||
} __attribute__((packed)) csd1_t;
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class CSDV2
|
||||
* \brief CSD register for version 2.00 cards.
|
||||
*/
|
||||
typedef struct CSDV2 {
|
||||
// byte 0
|
||||
unsigned char reserved1 : 6;
|
||||
unsigned char csd_ver : 2;
|
||||
// byte 1
|
||||
/** fixed to 0X0E */
|
||||
unsigned char taac;
|
||||
// byte 2
|
||||
/** fixed to 0 */
|
||||
unsigned char nsac;
|
||||
// byte 3
|
||||
unsigned char tran_speed;
|
||||
// byte 4
|
||||
unsigned char ccc_high;
|
||||
// byte 5
|
||||
/** This field is fixed to 9h, which indicates READ_BL_LEN=512 Byte */
|
||||
unsigned char read_bl_len : 4;
|
||||
unsigned char ccc_low : 4;
|
||||
// byte 6
|
||||
/** not used */
|
||||
unsigned char reserved2 : 4;
|
||||
unsigned char dsr_imp : 1;
|
||||
/** fixed to 0 */
|
||||
unsigned char read_blk_misalign : 1;
|
||||
/** fixed to 0 */
|
||||
unsigned char write_blk_misalign : 1;
|
||||
/** fixed to 0 - no partial read */
|
||||
unsigned char read_bl_partial : 1;
|
||||
// byte 7
|
||||
/** high part of card size */
|
||||
unsigned char c_size_high : 6;
|
||||
/** not used */
|
||||
unsigned char reserved3 : 2;
|
||||
// byte 8
|
||||
/** middle part of card size */
|
||||
unsigned char c_size_mid;
|
||||
// byte 9
|
||||
/** low part of card size */
|
||||
unsigned char c_size_low;
|
||||
// byte 10
|
||||
/** sector size is fixed at 64 KB */
|
||||
unsigned char sector_size_high : 6;
|
||||
/** fixed to 1 - erase single is supported */
|
||||
unsigned char erase_blk_en : 1;
|
||||
/** not used */
|
||||
unsigned char reserved4 : 1;
|
||||
// byte 11
|
||||
unsigned char wp_grp_size : 7;
|
||||
/** sector size is fixed at 64 KB */
|
||||
unsigned char sector_size_low : 1;
|
||||
// byte 12
|
||||
/** write_bl_len fixed for 512 byte blocks */
|
||||
unsigned char write_bl_len_high : 2;
|
||||
/** fixed value of 2 */
|
||||
unsigned char r2w_factor : 3;
|
||||
/** not used */
|
||||
unsigned char reserved5 : 2;
|
||||
/** fixed value of 0 - no write protect groups */
|
||||
unsigned char wp_grp_enable : 1;
|
||||
// byte 13
|
||||
unsigned char reserved6 : 5;
|
||||
/** always zero - no partial block read*/
|
||||
unsigned char write_partial : 1;
|
||||
/** write_bl_len fixed for 512 byte blocks */
|
||||
unsigned char write_bl_len_low : 2;
|
||||
// byte 14
|
||||
unsigned char reserved7: 2;
|
||||
/** Do not use always 0 */
|
||||
unsigned char file_format : 2;
|
||||
unsigned char tmp_write_protect : 1;
|
||||
unsigned char perm_write_protect : 1;
|
||||
unsigned char copy : 1;
|
||||
/** Do not use always 0 */
|
||||
unsigned char file_format_grp : 1;
|
||||
// byte 15
|
||||
/** not used always 1 */
|
||||
unsigned char always1 : 1;
|
||||
/** checksum */
|
||||
unsigned char crc : 7;
|
||||
} __attribute__((packed)) csd2_t;
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class csd_t
|
||||
* \brief Union of old and new style CSD register.
|
||||
*/
|
||||
union csd_t {
|
||||
csd1_t v1;
|
||||
csd2_t v2;
|
||||
};
|
||||
//-----------------------------------------------------------------------------
|
||||
inline uint32_t sdCardCapacity(csd_t* csd) {
|
||||
if (csd->v1.csd_ver == 0) {
|
||||
uint8_t read_bl_len = csd->v1.read_bl_len;
|
||||
uint16_t c_size = (csd->v1.c_size_high << 10)
|
||||
| (csd->v1.c_size_mid << 2) | csd->v1.c_size_low;
|
||||
uint8_t c_size_mult = (csd->v1.c_size_mult_high << 1)
|
||||
| csd->v1.c_size_mult_low;
|
||||
return (uint32_t)(c_size + 1) << (c_size_mult + read_bl_len - 7);
|
||||
} else if (csd->v2.csd_ver == 1) {
|
||||
uint32_t c_size = 0X10000L * csd->v2.c_size_high + 0X100L
|
||||
* (uint32_t)csd->v2.c_size_mid + csd->v2.c_size_low;
|
||||
return (c_size + 1) << 10;
|
||||
} else {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
#endif // SdInfo_h
|
670
Repetier-Firmware 1.0.3/Repetier/src/SdFat/SdCard/SdSpiCard.cpp
Normal file
670
Repetier-Firmware 1.0.3/Repetier/src/SdFat/SdCard/SdSpiCard.cpp
Normal file
@ -0,0 +1,670 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#include "../../../Repetier.h"
|
||||
#include "SdSpiCard.h"
|
||||
// debug trace macro
|
||||
#define SD_TRACE(m, b)
|
||||
// #define SD_TRACE(m, b) Serial.print(m);Serial.println(b);
|
||||
#define SD_CS_DBG(m)
|
||||
// #define SD_CS_DBG(m) Serial.println(F(m));
|
||||
//==============================================================================
|
||||
#if USE_SD_CRC
|
||||
// CRC functions
|
||||
//------------------------------------------------------------------------------
|
||||
static uint8_t CRC7(const uint8_t* data, uint8_t n) {
|
||||
uint8_t crc = 0;
|
||||
for (uint8_t i = 0; i < n; i++) {
|
||||
uint8_t d = data[i];
|
||||
for (uint8_t j = 0; j < 8; j++) {
|
||||
crc <<= 1;
|
||||
if ((d & 0x80) ^ (crc & 0x80)) {
|
||||
crc ^= 0x09;
|
||||
}
|
||||
d <<= 1;
|
||||
}
|
||||
}
|
||||
return (crc << 1) | 1;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
#if USE_SD_CRC == 1
|
||||
// Shift based CRC-CCITT
|
||||
// uses the x^16,x^12,x^5,x^1 polynomial.
|
||||
static uint16_t CRC_CCITT(const uint8_t* data, size_t n) {
|
||||
uint16_t crc = 0;
|
||||
for (size_t i = 0; i < n; i++) {
|
||||
crc = (uint8_t)(crc >> 8) | (crc << 8);
|
||||
crc ^= data[i];
|
||||
crc ^= (uint8_t)(crc & 0xff) >> 4;
|
||||
crc ^= crc << 12;
|
||||
crc ^= (crc & 0xff) << 5;
|
||||
}
|
||||
return crc;
|
||||
}
|
||||
#elif USE_SD_CRC > 1 // CRC_CCITT
|
||||
//------------------------------------------------------------------------------
|
||||
// Table based CRC-CCITT
|
||||
// uses the x^16,x^12,x^5,x^1 polynomial.
|
||||
#ifdef __AVR__
|
||||
static const uint16_t crctab[] PROGMEM = {
|
||||
#else // __AVR__
|
||||
static const uint16_t crctab[] = {
|
||||
#endif // __AVR__
|
||||
0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7,
|
||||
0x8108, 0x9129, 0xA14A, 0xB16B, 0xC18C, 0xD1AD, 0xE1CE, 0xF1EF,
|
||||
0x1231, 0x0210, 0x3273, 0x2252, 0x52B5, 0x4294, 0x72F7, 0x62D6,
|
||||
0x9339, 0x8318, 0xB37B, 0xA35A, 0xD3BD, 0xC39C, 0xF3FF, 0xE3DE,
|
||||
0x2462, 0x3443, 0x0420, 0x1401, 0x64E6, 0x74C7, 0x44A4, 0x5485,
|
||||
0xA56A, 0xB54B, 0x8528, 0x9509, 0xE5EE, 0xF5CF, 0xC5AC, 0xD58D,
|
||||
0x3653, 0x2672, 0x1611, 0x0630, 0x76D7, 0x66F6, 0x5695, 0x46B4,
|
||||
0xB75B, 0xA77A, 0x9719, 0x8738, 0xF7DF, 0xE7FE, 0xD79D, 0xC7BC,
|
||||
0x48C4, 0x58E5, 0x6886, 0x78A7, 0x0840, 0x1861, 0x2802, 0x3823,
|
||||
0xC9CC, 0xD9ED, 0xE98E, 0xF9AF, 0x8948, 0x9969, 0xA90A, 0xB92B,
|
||||
0x5AF5, 0x4AD4, 0x7AB7, 0x6A96, 0x1A71, 0x0A50, 0x3A33, 0x2A12,
|
||||
0xDBFD, 0xCBDC, 0xFBBF, 0xEB9E, 0x9B79, 0x8B58, 0xBB3B, 0xAB1A,
|
||||
0x6CA6, 0x7C87, 0x4CE4, 0x5CC5, 0x2C22, 0x3C03, 0x0C60, 0x1C41,
|
||||
0xEDAE, 0xFD8F, 0xCDEC, 0xDDCD, 0xAD2A, 0xBD0B, 0x8D68, 0x9D49,
|
||||
0x7E97, 0x6EB6, 0x5ED5, 0x4EF4, 0x3E13, 0x2E32, 0x1E51, 0x0E70,
|
||||
0xFF9F, 0xEFBE, 0xDFDD, 0xCFFC, 0xBF1B, 0xAF3A, 0x9F59, 0x8F78,
|
||||
0x9188, 0x81A9, 0xB1CA, 0xA1EB, 0xD10C, 0xC12D, 0xF14E, 0xE16F,
|
||||
0x1080, 0x00A1, 0x30C2, 0x20E3, 0x5004, 0x4025, 0x7046, 0x6067,
|
||||
0x83B9, 0x9398, 0xA3FB, 0xB3DA, 0xC33D, 0xD31C, 0xE37F, 0xF35E,
|
||||
0x02B1, 0x1290, 0x22F3, 0x32D2, 0x4235, 0x5214, 0x6277, 0x7256,
|
||||
0xB5EA, 0xA5CB, 0x95A8, 0x8589, 0xF56E, 0xE54F, 0xD52C, 0xC50D,
|
||||
0x34E2, 0x24C3, 0x14A0, 0x0481, 0x7466, 0x6447, 0x5424, 0x4405,
|
||||
0xA7DB, 0xB7FA, 0x8799, 0x97B8, 0xE75F, 0xF77E, 0xC71D, 0xD73C,
|
||||
0x26D3, 0x36F2, 0x0691, 0x16B0, 0x6657, 0x7676, 0x4615, 0x5634,
|
||||
0xD94C, 0xC96D, 0xF90E, 0xE92F, 0x99C8, 0x89E9, 0xB98A, 0xA9AB,
|
||||
0x5844, 0x4865, 0x7806, 0x6827, 0x18C0, 0x08E1, 0x3882, 0x28A3,
|
||||
0xCB7D, 0xDB5C, 0xEB3F, 0xFB1E, 0x8BF9, 0x9BD8, 0xABBB, 0xBB9A,
|
||||
0x4A75, 0x5A54, 0x6A37, 0x7A16, 0x0AF1, 0x1AD0, 0x2AB3, 0x3A92,
|
||||
0xFD2E, 0xED0F, 0xDD6C, 0xCD4D, 0xBDAA, 0xAD8B, 0x9DE8, 0x8DC9,
|
||||
0x7C26, 0x6C07, 0x5C64, 0x4C45, 0x3CA2, 0x2C83, 0x1CE0, 0x0CC1,
|
||||
0xEF1F, 0xFF3E, 0xCF5D, 0xDF7C, 0xAF9B, 0xBFBA, 0x8FD9, 0x9FF8,
|
||||
0x6E17, 0x7E36, 0x4E55, 0x5E74, 0x2E93, 0x3EB2, 0x0ED1, 0x1EF0
|
||||
};
|
||||
static uint16_t CRC_CCITT(const uint8_t* data, size_t n) {
|
||||
uint16_t crc = 0;
|
||||
for (size_t i = 0; i < n; i++) {
|
||||
#ifdef __AVR__
|
||||
crc = pgm_read_word(&crctab[(crc >> 8 ^ data[i]) & 0XFF]) ^ (crc << 8);
|
||||
#else // __AVR__
|
||||
crc = crctab[(crc >> 8 ^ data[i]) & 0XFF] ^ (crc << 8);
|
||||
#endif // __AVR__
|
||||
}
|
||||
return crc;
|
||||
}
|
||||
#endif // CRC_CCITT
|
||||
#endif // USE_SD_CRC
|
||||
//==============================================================================
|
||||
// SdSpiCard member functions
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdSpiCard::begin(SdSpiDriver* spi, uint8_t csPin, SPISettings settings) {
|
||||
m_spiActive = false;
|
||||
m_errorCode = SD_CARD_ERROR_NONE;
|
||||
m_type = 0;
|
||||
m_spiDriver = spi;
|
||||
uint16_t t0 = curTimeMS();
|
||||
uint32_t arg;
|
||||
|
||||
m_spiDriver->begin(csPin);
|
||||
m_spiDriver->setSpiSettings(SD_SCK_HZ(250000));
|
||||
spiStart();
|
||||
|
||||
// must supply min of 74 clock cycles with CS high.
|
||||
spiUnselect();
|
||||
for (uint8_t i = 0; i < 10; i++) {
|
||||
spiSend(0XFF);
|
||||
}
|
||||
spiSelect();
|
||||
// command to go idle in SPI mode
|
||||
while (cardCommand(CMD0, 0) != R1_IDLE_STATE) {
|
||||
if (isTimedOut(t0, SD_INIT_TIMEOUT)) {
|
||||
error(SD_CARD_ERROR_CMD0);
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
#if USE_SD_CRC
|
||||
if (cardCommand(CMD59, 1) != R1_IDLE_STATE) {
|
||||
error(SD_CARD_ERROR_CMD59);
|
||||
goto fail;
|
||||
}
|
||||
#endif // USE_SD_CRC
|
||||
// check SD version
|
||||
while (1) {
|
||||
if (cardCommand(CMD8, 0x1AA) == (R1_ILLEGAL_COMMAND | R1_IDLE_STATE)) {
|
||||
type(SD_CARD_TYPE_SD1);
|
||||
break;
|
||||
}
|
||||
for (uint8_t i = 0; i < 4; i++) {
|
||||
m_status = spiReceive();
|
||||
}
|
||||
if (m_status == 0XAA) {
|
||||
type(SD_CARD_TYPE_SD2);
|
||||
break;
|
||||
}
|
||||
if (isTimedOut(t0, SD_INIT_TIMEOUT)) {
|
||||
error(SD_CARD_ERROR_CMD8);
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
// initialize card and send host supports SDHC if SD2
|
||||
arg = type() == SD_CARD_TYPE_SD2 ? 0X40000000 : 0;
|
||||
|
||||
while (cardAcmd(ACMD41, arg) != R1_READY_STATE) {
|
||||
// check for timeout
|
||||
if (isTimedOut(t0, SD_INIT_TIMEOUT)) {
|
||||
error(SD_CARD_ERROR_ACMD41);
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
// if SD2 read OCR register to check for SDHC card
|
||||
if (type() == SD_CARD_TYPE_SD2) {
|
||||
if (cardCommand(CMD58, 0)) {
|
||||
error(SD_CARD_ERROR_CMD58);
|
||||
goto fail;
|
||||
}
|
||||
if ((spiReceive() & 0XC0) == 0XC0) {
|
||||
type(SD_CARD_TYPE_SDHC);
|
||||
}
|
||||
// Discard rest of ocr - contains allowed voltage range.
|
||||
for (uint8_t i = 0; i < 3; i++) {
|
||||
spiReceive();
|
||||
}
|
||||
}
|
||||
spiStop();
|
||||
m_spiDriver->setSpiSettings(settings);
|
||||
return true;
|
||||
|
||||
fail:
|
||||
spiStop();
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// send command and return error code. Return zero for OK
|
||||
uint8_t SdSpiCard::cardCommand(uint8_t cmd, uint32_t arg) {
|
||||
// select card
|
||||
if (!m_spiActive) {
|
||||
spiStart();
|
||||
}
|
||||
// wait if busy
|
||||
waitNotBusy(SD_WRITE_TIMEOUT);
|
||||
|
||||
#if USE_SD_CRC
|
||||
// form message
|
||||
uint8_t buf[6];
|
||||
buf[0] = (uint8_t)0x40U | cmd;
|
||||
buf[1] = (uint8_t)(arg >> 24U);
|
||||
buf[2] = (uint8_t)(arg >> 16U);
|
||||
buf[3] = (uint8_t)(arg >> 8U);
|
||||
buf[4] = (uint8_t)arg;
|
||||
|
||||
// add CRC
|
||||
buf[5] = CRC7(buf, 5);
|
||||
|
||||
// send message
|
||||
spiSend(buf, 6);
|
||||
#else // USE_SD_CRC
|
||||
// send command
|
||||
spiSend(cmd | 0x40);
|
||||
|
||||
// send argument
|
||||
uint8_t* pa = reinterpret_cast<uint8_t*>(&arg);
|
||||
for (int8_t i = 3; i >= 0; i--) {
|
||||
spiSend(pa[i]);
|
||||
}
|
||||
|
||||
// send CRC - correct for CMD0 with arg zero or CMD8 with arg 0X1AA
|
||||
spiSend(cmd == CMD0 ? 0X95 : 0X87);
|
||||
#endif // USE_SD_CRC
|
||||
|
||||
// skip stuff byte for stop read
|
||||
if (cmd == CMD12) {
|
||||
spiReceive();
|
||||
}
|
||||
|
||||
// wait for response
|
||||
for (uint8_t i = 0; ((m_status = spiReceive()) & 0X80) && i != 0XFF; i++) {
|
||||
}
|
||||
return m_status;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
uint32_t SdSpiCard::cardSize() {
|
||||
csd_t csd;
|
||||
return readCSD(&csd) ? sdCardCapacity(&csd) : 0;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdSpiCard::erase(uint32_t firstBlock, uint32_t lastBlock) {
|
||||
csd_t csd;
|
||||
if (!readCSD(&csd)) {
|
||||
goto fail;
|
||||
}
|
||||
// check for single block erase
|
||||
if (!csd.v1.erase_blk_en) {
|
||||
// erase size mask
|
||||
uint8_t m = (csd.v1.sector_size_high << 1) | csd.v1.sector_size_low;
|
||||
if ((firstBlock & m) != 0 || ((lastBlock + 1) & m) != 0) {
|
||||
// error card can't erase specified area
|
||||
error(SD_CARD_ERROR_ERASE_SINGLE_BLOCK);
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
if (m_type != SD_CARD_TYPE_SDHC) {
|
||||
firstBlock <<= 9;
|
||||
lastBlock <<= 9;
|
||||
}
|
||||
if (cardCommand(CMD32, firstBlock)
|
||||
|| cardCommand(CMD33, lastBlock)
|
||||
|| cardCommand(CMD38, 0)) {
|
||||
error(SD_CARD_ERROR_ERASE);
|
||||
goto fail;
|
||||
}
|
||||
if (!waitNotBusy(SD_ERASE_TIMEOUT)) {
|
||||
error(SD_CARD_ERROR_ERASE_TIMEOUT);
|
||||
goto fail;
|
||||
}
|
||||
spiStop();
|
||||
return true;
|
||||
|
||||
fail:
|
||||
spiStop();
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdSpiCard::eraseSingleBlockEnable() {
|
||||
csd_t csd;
|
||||
return readCSD(&csd) ? csd.v1.erase_blk_en : false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdSpiCard::isBusy() {
|
||||
bool rtn = true;
|
||||
bool spiActive = m_spiActive;
|
||||
if (!spiActive) {
|
||||
spiStart();
|
||||
}
|
||||
for (uint8_t i = 0; i < 8; i++) {
|
||||
if (0XFF == spiReceive()) {
|
||||
rtn = false;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (!spiActive) {
|
||||
spiStop();
|
||||
}
|
||||
return rtn;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdSpiCard::isTimedOut(uint16_t startMS, uint16_t timeoutMS) {
|
||||
#if WDT_YIELD_TIME_MICROS
|
||||
static uint32_t last;
|
||||
if ((micros() - last) > WDT_YIELD_TIME_MICROS) {
|
||||
SysCall::yield();
|
||||
last = micros();
|
||||
}
|
||||
#endif // WDT_YIELD_TIME_MICROS
|
||||
return (curTimeMS() - startMS) > timeoutMS;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdSpiCard::readBlock(uint32_t blockNumber, uint8_t* dst) {
|
||||
SD_TRACE("RB", blockNumber);
|
||||
// use address if not SDHC card
|
||||
if (type() != SD_CARD_TYPE_SDHC) {
|
||||
blockNumber <<= 9;
|
||||
}
|
||||
if (cardCommand(CMD17, blockNumber)) {
|
||||
error(SD_CARD_ERROR_CMD17);
|
||||
goto fail;
|
||||
}
|
||||
if (!readData(dst, 512)) {
|
||||
goto fail;
|
||||
}
|
||||
spiStop();
|
||||
return true;
|
||||
|
||||
fail:
|
||||
spiStop();
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdSpiCard::readBlocks(uint32_t block, uint8_t* dst, size_t count) {
|
||||
if (!readStart(block)) {
|
||||
return false;
|
||||
}
|
||||
for (uint16_t b = 0; b < count; b++, dst += 512) {
|
||||
if (!readData(dst, 512)) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return readStop();
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdSpiCard::readData(uint8_t* dst) {
|
||||
return readData(dst, 512);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdSpiCard::readData(uint8_t* dst, size_t count) {
|
||||
#if USE_SD_CRC
|
||||
uint16_t crc;
|
||||
#endif // USE_SD_CRC
|
||||
// wait for start block token
|
||||
uint16_t t0 = curTimeMS();
|
||||
while ((m_status = spiReceive()) == 0XFF) {
|
||||
if (isTimedOut(t0, SD_READ_TIMEOUT)) {
|
||||
error(SD_CARD_ERROR_READ_TIMEOUT);
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
if (m_status != DATA_START_BLOCK) {
|
||||
error(SD_CARD_ERROR_READ);
|
||||
goto fail;
|
||||
}
|
||||
// transfer data
|
||||
if ((m_status = spiReceive(dst, count))) {
|
||||
error(SD_CARD_ERROR_DMA);
|
||||
goto fail;
|
||||
}
|
||||
|
||||
#if USE_SD_CRC
|
||||
// get crc
|
||||
crc = (spiReceive() << 8) | spiReceive();
|
||||
if (crc != CRC_CCITT(dst, count)) {
|
||||
error(SD_CARD_ERROR_READ_CRC);
|
||||
goto fail;
|
||||
}
|
||||
#else
|
||||
// discard crc
|
||||
spiReceive();
|
||||
spiReceive();
|
||||
#endif // USE_SD_CRC
|
||||
return true;
|
||||
|
||||
fail:
|
||||
spiStop();
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdSpiCard::readOCR(uint32_t* ocr) {
|
||||
uint8_t* p = reinterpret_cast<uint8_t*>(ocr);
|
||||
if (cardCommand(CMD58, 0)) {
|
||||
error(SD_CARD_ERROR_CMD58);
|
||||
goto fail;
|
||||
}
|
||||
for (uint8_t i = 0; i < 4; i++) {
|
||||
p[3 - i] = spiReceive();
|
||||
}
|
||||
|
||||
spiStop();
|
||||
return true;
|
||||
|
||||
fail:
|
||||
spiStop();
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** read CID or CSR register */
|
||||
bool SdSpiCard::readRegister(uint8_t cmd, void* buf) {
|
||||
uint8_t* dst = reinterpret_cast<uint8_t*>(buf);
|
||||
if (cardCommand(cmd, 0)) {
|
||||
error(SD_CARD_ERROR_READ_REG);
|
||||
goto fail;
|
||||
}
|
||||
if (!readData(dst, 16)) {
|
||||
goto fail;
|
||||
}
|
||||
spiStop();
|
||||
return true;
|
||||
|
||||
fail:
|
||||
spiStop();
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdSpiCard::readStart(uint32_t blockNumber) {
|
||||
SD_TRACE("RS", blockNumber);
|
||||
if (type() != SD_CARD_TYPE_SDHC) {
|
||||
blockNumber <<= 9;
|
||||
}
|
||||
if (cardCommand(CMD18, blockNumber)) {
|
||||
error(SD_CARD_ERROR_CMD18);
|
||||
goto fail;
|
||||
}
|
||||
// spiStop();
|
||||
return true;
|
||||
|
||||
fail:
|
||||
spiStop();
|
||||
return false;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdSpiCard::readStatus(uint8_t* status) {
|
||||
// retrun is R2 so read extra status byte.
|
||||
if (cardAcmd(ACMD13, 0) || spiReceive()) {
|
||||
error(SD_CARD_ERROR_ACMD13);
|
||||
goto fail;
|
||||
}
|
||||
if (!readData(status, 64)) {
|
||||
goto fail;
|
||||
}
|
||||
spiStop();
|
||||
return true;
|
||||
|
||||
fail:
|
||||
spiStop();
|
||||
return false;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
void SdSpiCard::spiStart() {
|
||||
if (!m_spiActive) {
|
||||
spiActivate();
|
||||
spiSelect();
|
||||
m_spiActive = true;
|
||||
}
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
void SdSpiCard::spiStop() {
|
||||
if (m_spiActive) {
|
||||
spiUnselect();
|
||||
spiSend(0XFF);
|
||||
spiDeactivate();
|
||||
m_spiActive = false;
|
||||
}
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdSpiCard::readStop() {
|
||||
if (cardCommand(CMD12, 0)) {
|
||||
error(SD_CARD_ERROR_CMD12);
|
||||
goto fail;
|
||||
}
|
||||
spiStop();
|
||||
return true;
|
||||
|
||||
fail:
|
||||
spiStop();
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// wait for card to go not busy
|
||||
bool SdSpiCard::waitNotBusy(uint16_t timeoutMS) {
|
||||
uint16_t t0 = curTimeMS();
|
||||
#if WDT_YIELD_TIME_MICROS
|
||||
// Call isTimedOut first to insure yield is called.
|
||||
while (!isTimedOut(t0, timeoutMS)) {
|
||||
if (spiReceive() == 0XFF) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
#else // WDT_YIELD_TIME_MICROS
|
||||
// Check not busy first since yield is not called in isTimedOut.
|
||||
while (spiReceive() != 0XFF) {
|
||||
if (isTimedOut(t0, timeoutMS)) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
#endif // WDT_YIELD_TIME_MICROS
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdSpiCard::writeBlock(uint32_t blockNumber, const uint8_t* src) {
|
||||
SD_TRACE("WB", blockNumber);
|
||||
// use address if not SDHC card
|
||||
if (type() != SD_CARD_TYPE_SDHC) {
|
||||
blockNumber <<= 9;
|
||||
}
|
||||
if (cardCommand(CMD24, blockNumber)) {
|
||||
error(SD_CARD_ERROR_CMD24);
|
||||
goto fail;
|
||||
}
|
||||
if (!writeData(DATA_START_BLOCK, src)) {
|
||||
goto fail;
|
||||
}
|
||||
|
||||
#if CHECK_FLASH_PROGRAMMING
|
||||
// wait for flash programming to complete
|
||||
if (!waitNotBusy(SD_WRITE_TIMEOUT)) {
|
||||
error(SD_CARD_ERROR_WRITE_TIMEOUT);
|
||||
goto fail;
|
||||
}
|
||||
// response is r2 so get and check two bytes for nonzero
|
||||
if (cardCommand(CMD13, 0) || spiReceive()) {
|
||||
error(SD_CARD_ERROR_CMD13);
|
||||
goto fail;
|
||||
}
|
||||
#endif // CHECK_PROGRAMMING
|
||||
|
||||
spiStop();
|
||||
return true;
|
||||
|
||||
fail:
|
||||
spiStop();
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdSpiCard::writeBlocks(uint32_t block, const uint8_t* src, size_t count) {
|
||||
if (!writeStart(block)) {
|
||||
goto fail;
|
||||
}
|
||||
for (size_t b = 0; b < count; b++, src += 512) {
|
||||
if (!writeData(src)) {
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
return writeStop();
|
||||
|
||||
fail:
|
||||
spiStop();
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdSpiCard::writeData(const uint8_t* src) {
|
||||
// wait for previous write to finish
|
||||
if (!waitNotBusy(SD_WRITE_TIMEOUT)) {
|
||||
error(SD_CARD_ERROR_WRITE_TIMEOUT);
|
||||
goto fail;
|
||||
}
|
||||
if (!writeData(WRITE_MULTIPLE_TOKEN, src)) {
|
||||
goto fail;
|
||||
}
|
||||
return true;
|
||||
|
||||
fail:
|
||||
spiStop();
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// send one block of data for write block or write multiple blocks
|
||||
bool SdSpiCard::writeData(uint8_t token, const uint8_t* src) {
|
||||
#if USE_SD_CRC
|
||||
uint16_t crc = CRC_CCITT(src, 512);
|
||||
#else // USE_SD_CRC
|
||||
uint16_t crc = 0XFFFF;
|
||||
#endif // USE_SD_CRC
|
||||
spiSend(token);
|
||||
spiSend(src, 512);
|
||||
spiSend(crc >> 8);
|
||||
spiSend(crc & 0XFF);
|
||||
|
||||
m_status = spiReceive();
|
||||
if ((m_status & DATA_RES_MASK) != DATA_RES_ACCEPTED) {
|
||||
error(SD_CARD_ERROR_WRITE);
|
||||
goto fail;
|
||||
}
|
||||
return true;
|
||||
|
||||
fail:
|
||||
spiStop();
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdSpiCard::writeStart(uint32_t blockNumber) {
|
||||
// use address if not SDHC card
|
||||
if (type() != SD_CARD_TYPE_SDHC) {
|
||||
blockNumber <<= 9;
|
||||
}
|
||||
if (cardCommand(CMD25, blockNumber)) {
|
||||
error(SD_CARD_ERROR_CMD25);
|
||||
goto fail;
|
||||
}
|
||||
return true;
|
||||
|
||||
fail:
|
||||
spiStop();
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdSpiCard::writeStart(uint32_t blockNumber, uint32_t eraseCount) {
|
||||
SD_TRACE("WS", blockNumber);
|
||||
// send pre-erase count
|
||||
if (cardAcmd(ACMD23, eraseCount)) {
|
||||
error(SD_CARD_ERROR_ACMD23);
|
||||
goto fail;
|
||||
}
|
||||
// use address if not SDHC card
|
||||
if (type() != SD_CARD_TYPE_SDHC) {
|
||||
blockNumber <<= 9;
|
||||
}
|
||||
if (cardCommand(CMD25, blockNumber)) {
|
||||
error(SD_CARD_ERROR_CMD25);
|
||||
goto fail;
|
||||
}
|
||||
return true;
|
||||
|
||||
fail:
|
||||
spiStop();
|
||||
return false;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
bool SdSpiCard::writeStop() {
|
||||
if (!waitNotBusy(SD_WRITE_TIMEOUT)) {
|
||||
goto fail;
|
||||
}
|
||||
spiSend(STOP_TRAN_TOKEN);
|
||||
spiStop();
|
||||
return true;
|
||||
|
||||
fail:
|
||||
error(SD_CARD_ERROR_STOP_TRAN);
|
||||
spiStop();
|
||||
return false;
|
||||
}
|
373
Repetier-Firmware 1.0.3/Repetier/src/SdFat/SdCard/SdSpiCard.h
Normal file
373
Repetier-Firmware 1.0.3/Repetier/src/SdFat/SdCard/SdSpiCard.h
Normal file
@ -0,0 +1,373 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef SdSpiCard_h
|
||||
#define SdSpiCard_h
|
||||
/**
|
||||
* \file
|
||||
* \brief SdSpiCard class for V2 SD/SDHC cards
|
||||
*/
|
||||
#include <stddef.h>
|
||||
#include "../SysCall.h"
|
||||
#include "SdInfo.h"
|
||||
#include "../FatLib/BaseBlockDriver.h"
|
||||
#include "../SpiDriver/SdSpiDriver.h"
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class SdSpiCard
|
||||
* \brief Raw access to SD and SDHC flash memory cards via SPI protocol.
|
||||
*/
|
||||
#if ENABLE_EXTENDED_TRANSFER_CLASS || ENABLE_SDIO_CLASS
|
||||
class SdSpiCard : public BaseBlockDriver {
|
||||
#else // ENABLE_EXTENDED_TRANSFER_CLASS || ENABLE_SDIO_CLASS
|
||||
class SdSpiCard {
|
||||
#endif // ENABLE_EXTENDED_TRANSFER_CLASS || ENABLE_SDIO_CLASS
|
||||
public:
|
||||
/** Construct an instance of SdSpiCard. */
|
||||
SdSpiCard() : m_errorCode(SD_CARD_ERROR_INIT_NOT_CALLED), m_type(0) {}
|
||||
/** Initialize the SD card.
|
||||
* \param[in] spi SPI driver for card.
|
||||
* \param[in] csPin card chip select pin.
|
||||
* \param[in] spiSettings SPI speed, mode, and bit order.
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool begin(SdSpiDriver* spi, uint8_t csPin, SPISettings spiSettings);
|
||||
/**
|
||||
* Determine the size of an SD flash memory card.
|
||||
*
|
||||
* \return The number of 512 byte data blocks in the card
|
||||
* or zero if an error occurs.
|
||||
*/
|
||||
uint32_t cardSize();
|
||||
/** Erase a range of blocks.
|
||||
*
|
||||
* \param[in] firstBlock The address of the first block in the range.
|
||||
* \param[in] lastBlock The address of the last block in the range.
|
||||
*
|
||||
* \note This function requests the SD card to do a flash erase for a
|
||||
* range of blocks. The data on the card after an erase operation is
|
||||
* either 0 or 1, depends on the card vendor. The card must support
|
||||
* single block erase.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool erase(uint32_t firstBlock, uint32_t lastBlock);
|
||||
/** Determine if card supports single block erase.
|
||||
*
|
||||
* \return true is returned if single block erase is supported.
|
||||
* false is returned if single block erase is not supported.
|
||||
*/
|
||||
bool eraseSingleBlockEnable();
|
||||
/**
|
||||
* Set SD error code.
|
||||
* \param[in] code value for error code.
|
||||
*/
|
||||
void error(uint8_t code) {
|
||||
m_errorCode = code;
|
||||
}
|
||||
/**
|
||||
* \return code for the last error. See SdInfo.h for a list of error codes.
|
||||
*/
|
||||
int errorCode() const {
|
||||
return m_errorCode;
|
||||
}
|
||||
/** \return error data for last error. */
|
||||
int errorData() const {
|
||||
return m_status;
|
||||
}
|
||||
/**
|
||||
* Check for busy. MISO low indicates the card is busy.
|
||||
*
|
||||
* \return true if busy else false.
|
||||
*/
|
||||
bool isBusy();
|
||||
/**
|
||||
* Read a 512 byte block from an SD card.
|
||||
*
|
||||
* \param[in] lba Logical block to be read.
|
||||
* \param[out] dst Pointer to the location that will receive the data.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool readBlock(uint32_t lba, uint8_t* dst);
|
||||
/**
|
||||
* Read multiple 512 byte blocks from an SD card.
|
||||
*
|
||||
* \param[in] lba Logical block to be read.
|
||||
* \param[in] nb Number of blocks to be read.
|
||||
* \param[out] dst Pointer to the location that will receive the data.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool readBlocks(uint32_t lba, uint8_t* dst, size_t nb);
|
||||
/**
|
||||
* Read a card's CID register. The CID contains card identification
|
||||
* information such as Manufacturer ID, Product name, Product serial
|
||||
* number and Manufacturing date.
|
||||
*
|
||||
* \param[out] cid pointer to area for returned data.
|
||||
*
|
||||
* \return true for success or false for failure.
|
||||
*/
|
||||
bool readCID(cid_t* cid) {
|
||||
return readRegister(CMD10, cid);
|
||||
}
|
||||
/**
|
||||
* Read a card's CSD register. The CSD contains Card-Specific Data that
|
||||
* provides information regarding access to the card's contents.
|
||||
*
|
||||
* \param[out] csd pointer to area for returned data.
|
||||
*
|
||||
* \return true for success or false for failure.
|
||||
*/
|
||||
bool readCSD(csd_t* csd) {
|
||||
return readRegister(CMD9, csd);
|
||||
}
|
||||
/** Read one data block in a multiple block read sequence
|
||||
*
|
||||
* \param[out] dst Pointer to the location for the data to be read.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool readData(uint8_t *dst);
|
||||
/** Read OCR register.
|
||||
*
|
||||
* \param[out] ocr Value of OCR register.
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool readOCR(uint32_t* ocr);
|
||||
/** Start a read multiple blocks sequence.
|
||||
*
|
||||
* \param[in] blockNumber Address of first block in sequence.
|
||||
*
|
||||
* \note This function is used with readData() and readStop() for optimized
|
||||
* multiple block reads. SPI chipSelect must be low for the entire sequence.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool readStart(uint32_t blockNumber);
|
||||
/** Return the 64 byte card status
|
||||
* \param[out] status location for 64 status bytes.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool readStatus(uint8_t* status);
|
||||
/** End a read multiple blocks sequence.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool readStop();
|
||||
/** \return success if sync successful. Not for user apps. */
|
||||
bool syncBlocks() {return true;}
|
||||
/** Return the card type: SD V1, SD V2 or SDHC
|
||||
* \return 0 - SD V1, 1 - SD V2, or 3 - SDHC.
|
||||
*/
|
||||
int type() const {
|
||||
return m_type;
|
||||
}
|
||||
/**
|
||||
* Writes a 512 byte block to an SD card.
|
||||
*
|
||||
* \param[in] lba Logical block to be written.
|
||||
* \param[in] src Pointer to the location of the data to be written.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool writeBlock(uint32_t lba, const uint8_t* src);
|
||||
/**
|
||||
* Write multiple 512 byte blocks to an SD card.
|
||||
*
|
||||
* \param[in] lba Logical block to be written.
|
||||
* \param[in] nb Number of blocks to be written.
|
||||
* \param[in] src Pointer to the location of the data to be written.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool writeBlocks(uint32_t lba, const uint8_t* src, size_t nb);
|
||||
/** Write one data block in a multiple block write sequence.
|
||||
* \param[in] src Pointer to the location of the data to be written.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool writeData(const uint8_t* src);
|
||||
/** Start a write multiple blocks sequence.
|
||||
*
|
||||
* \param[in] blockNumber Address of first block in sequence.
|
||||
*
|
||||
* \note This function is used with writeData() and writeStop()
|
||||
* for optimized multiple block writes.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool writeStart(uint32_t blockNumber);
|
||||
|
||||
/** Start a write multiple blocks sequence with pre-erase.
|
||||
*
|
||||
* \param[in] blockNumber Address of first block in sequence.
|
||||
* \param[in] eraseCount The number of blocks to be pre-erased.
|
||||
*
|
||||
* \note This function is used with writeData() and writeStop()
|
||||
* for optimized multiple block writes.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool writeStart(uint32_t blockNumber, uint32_t eraseCount);
|
||||
/** End a write multiple blocks sequence.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool writeStop();
|
||||
/** Set CS low and activate the card. */
|
||||
void spiStart();
|
||||
/** Set CS high and deactivate the card. */
|
||||
void spiStop();
|
||||
|
||||
private:
|
||||
// private functions
|
||||
uint8_t cardAcmd(uint8_t cmd, uint32_t arg) {
|
||||
cardCommand(CMD55, 0);
|
||||
return cardCommand(cmd, arg);
|
||||
}
|
||||
uint8_t cardCommand(uint8_t cmd, uint32_t arg);
|
||||
bool isTimedOut(uint16_t startMS, uint16_t timeoutMS);
|
||||
bool readData(uint8_t* dst, size_t count);
|
||||
bool readRegister(uint8_t cmd, void* buf);
|
||||
|
||||
void type(uint8_t value) {
|
||||
m_type = value;
|
||||
}
|
||||
|
||||
bool waitNotBusy(uint16_t timeoutMS);
|
||||
bool writeData(uint8_t token, const uint8_t* src);
|
||||
|
||||
//---------------------------------------------------------------------------
|
||||
// functions defined in SdSpiDriver.h
|
||||
void spiActivate() {
|
||||
m_spiDriver->activate();
|
||||
}
|
||||
void spiDeactivate() {
|
||||
m_spiDriver->deactivate();
|
||||
}
|
||||
uint8_t spiReceive() {
|
||||
return m_spiDriver->receive();
|
||||
}
|
||||
uint8_t spiReceive(uint8_t* buf, size_t n) {
|
||||
return m_spiDriver->receive(buf, n);
|
||||
}
|
||||
void spiSend(uint8_t data) {
|
||||
m_spiDriver->send(data);
|
||||
}
|
||||
void spiSend(const uint8_t* buf, size_t n) {
|
||||
m_spiDriver->send(buf, n);
|
||||
}
|
||||
void spiSelect() {
|
||||
m_spiDriver->select();
|
||||
}
|
||||
void spiUnselect() {
|
||||
m_spiDriver->unselect();
|
||||
}
|
||||
uint8_t m_errorCode;
|
||||
SdSpiDriver *m_spiDriver;
|
||||
bool m_spiActive;
|
||||
uint8_t m_status;
|
||||
uint8_t m_type;
|
||||
};
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class SdSpiCardEX
|
||||
* \brief Extended SD I/O block driver.
|
||||
*/
|
||||
class SdSpiCardEX : public SdSpiCard {
|
||||
public:
|
||||
/** Initialize the SD card
|
||||
*
|
||||
* \param[in] spi SPI driver.
|
||||
* \param[in] csPin Card chip select pin number.
|
||||
* \param[in] spiSettings SPI speed, mode, and bit order.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool begin(SdSpiDriver* spi, uint8_t csPin, SPISettings spiSettings) {
|
||||
m_curState = IDLE_STATE;
|
||||
return SdSpiCard::begin(spi, csPin, spiSettings);
|
||||
}
|
||||
/**
|
||||
* Read a 512 byte block from an SD card.
|
||||
*
|
||||
* \param[in] block Logical block to be read.
|
||||
* \param[out] dst Pointer to the location that will receive the data.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool readBlock(uint32_t block, uint8_t* dst);
|
||||
/** End multi-block transfer and go to idle state.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool syncBlocks();
|
||||
/**
|
||||
* Writes a 512 byte block to an SD card.
|
||||
*
|
||||
* \param[in] block Logical block to be written.
|
||||
* \param[in] src Pointer to the location of the data to be written.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool writeBlock(uint32_t block, const uint8_t* src);
|
||||
/**
|
||||
* Read multiple 512 byte blocks from an SD card.
|
||||
*
|
||||
* \param[in] block Logical block to be read.
|
||||
* \param[in] nb Number of blocks to be read.
|
||||
* \param[out] dst Pointer to the location that will receive the data.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool readBlocks(uint32_t block, uint8_t* dst, size_t nb);
|
||||
/**
|
||||
* Write multiple 512 byte blocks to an SD card.
|
||||
*
|
||||
* \param[in] block Logical block to be written.
|
||||
* \param[in] nb Number of blocks to be written.
|
||||
* \param[in] src Pointer to the location of the data to be written.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool writeBlocks(uint32_t block, const uint8_t* src, size_t nb);
|
||||
|
||||
private:
|
||||
static const uint32_t IDLE_STATE = 0;
|
||||
static const uint32_t READ_STATE = 1;
|
||||
static const uint32_t WRITE_STATE = 2;
|
||||
uint32_t m_curBlock;
|
||||
uint8_t m_curState;
|
||||
};
|
||||
#endif // SdSpiCard_h
|
@ -0,0 +1,95 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#include "../../../Repetier.h"
|
||||
#include "SdSpiCard.h"
|
||||
bool SdSpiCardEX::readBlock(uint32_t block, uint8_t* dst) {
|
||||
if (m_curState != READ_STATE || block != m_curBlock) {
|
||||
if (!syncBlocks()) {
|
||||
return false;
|
||||
}
|
||||
if (!SdSpiCard::readStart(block)) {
|
||||
return false;
|
||||
}
|
||||
m_curBlock = block;
|
||||
m_curState = READ_STATE;
|
||||
}
|
||||
if (!SdSpiCard::readData(dst)) {
|
||||
return false;
|
||||
}
|
||||
m_curBlock++;
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdSpiCardEX::readBlocks(uint32_t block, uint8_t* dst, size_t nb) {
|
||||
for (size_t i = 0; i < nb; i++) {
|
||||
if (!readBlock(block + i, dst + i * 512UL)) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdSpiCardEX::syncBlocks() {
|
||||
if (m_curState == READ_STATE) {
|
||||
m_curState = IDLE_STATE;
|
||||
if (!SdSpiCard::readStop()) {
|
||||
return false;
|
||||
}
|
||||
} else if (m_curState == WRITE_STATE) {
|
||||
m_curState = IDLE_STATE;
|
||||
if (!SdSpiCard::writeStop()) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdSpiCardEX::writeBlock(uint32_t block, const uint8_t* src) {
|
||||
if (m_curState != WRITE_STATE || m_curBlock != block) {
|
||||
if (!syncBlocks()) {
|
||||
return false;
|
||||
}
|
||||
if (!SdSpiCard::writeStart(block)) {
|
||||
return false;
|
||||
}
|
||||
m_curBlock = block;
|
||||
m_curState = WRITE_STATE;
|
||||
}
|
||||
if (!SdSpiCard::writeData(src)) {
|
||||
return false;
|
||||
}
|
||||
m_curBlock++;
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdSpiCardEX::writeBlocks(uint32_t block,
|
||||
const uint8_t* src, size_t nb) {
|
||||
for (size_t i = 0; i < nb; i++) {
|
||||
if (!writeBlock(block + i, src + i * 512UL)) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
301
Repetier-Firmware 1.0.3/Repetier/src/SdFat/SdCard/SdioCard.h
Normal file
301
Repetier-Firmware 1.0.3/Repetier/src/SdFat/SdCard/SdioCard.h
Normal file
@ -0,0 +1,301 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef SdioCard_h
|
||||
#define SdioCard_h
|
||||
#include "../SysCall.h"
|
||||
#include "../BlockDriver.h"
|
||||
/**
|
||||
* \class SdioCard
|
||||
* \brief Raw SDIO access to SD and SDHC flash memory cards.
|
||||
*/
|
||||
class SdioCard : public BaseBlockDriver {
|
||||
public:
|
||||
/** Initialize the SD card.
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool begin();
|
||||
/**
|
||||
* Determine the size of an SD flash memory card.
|
||||
*
|
||||
* \return The number of 512 byte data blocks in the card
|
||||
* or zero if an error occurs.
|
||||
*/
|
||||
uint32_t cardSize();
|
||||
/** Erase a range of blocks.
|
||||
*
|
||||
* \param[in] firstBlock The address of the first block in the range.
|
||||
* \param[in] lastBlock The address of the last block in the range.
|
||||
*
|
||||
* \note This function requests the SD card to do a flash erase for a
|
||||
* range of blocks. The data on the card after an erase operation is
|
||||
* either 0 or 1, depends on the card vendor. The card must support
|
||||
* single block erase.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool erase(uint32_t firstBlock, uint32_t lastBlock);
|
||||
/**
|
||||
* \return code for the last error. See SdInfo.h for a list of error codes.
|
||||
*/
|
||||
uint8_t errorCode();
|
||||
/** \return error data for last error. */
|
||||
uint32_t errorData();
|
||||
/** \return error line for last error. Tmp function for debug. */
|
||||
uint32_t errorLine();
|
||||
/**
|
||||
* Check for busy with CMD13.
|
||||
*
|
||||
* \return true if busy else false.
|
||||
*/
|
||||
bool isBusy();
|
||||
/** \return the SD clock frequency in kHz. */
|
||||
uint32_t kHzSdClk();
|
||||
/**
|
||||
* Read a 512 byte block from an SD card.
|
||||
*
|
||||
* \param[in] lba Logical block to be read.
|
||||
* \param[out] dst Pointer to the location that will receive the data.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool readBlock(uint32_t lba, uint8_t* dst);
|
||||
/**
|
||||
* Read multiple 512 byte blocks from an SD card.
|
||||
*
|
||||
* \param[in] lba Logical block to be read.
|
||||
* \param[in] nb Number of blocks to be read.
|
||||
* \param[out] dst Pointer to the location that will receive the data.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool readBlocks(uint32_t lba, uint8_t* dst, size_t nb);
|
||||
/**
|
||||
* Read a card's CID register. The CID contains card identification
|
||||
* information such as Manufacturer ID, Product name, Product serial
|
||||
* number and Manufacturing date.
|
||||
*
|
||||
* \param[out] cid pointer to area for returned data.
|
||||
*
|
||||
* \return true for success or false for failure.
|
||||
*/
|
||||
bool readCID(void* cid);
|
||||
/**
|
||||
* Read a card's CSD register. The CSD contains Card-Specific Data that
|
||||
* provides information regarding access to the card's contents.
|
||||
*
|
||||
* \param[out] csd pointer to area for returned data.
|
||||
*
|
||||
* \return true for success or false for failure.
|
||||
*/
|
||||
bool readCSD(void* csd);
|
||||
/** Read one data block in a multiple block read sequence
|
||||
*
|
||||
* \param[out] dst Pointer to the location for the data to be read.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool readData(uint8_t *dst);
|
||||
/** Read OCR register.
|
||||
*
|
||||
* \param[out] ocr Value of OCR register.
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool readOCR(uint32_t* ocr);
|
||||
/** Start a read multiple blocks sequence.
|
||||
*
|
||||
* \param[in] lba Address of first block in sequence.
|
||||
*
|
||||
* \note This function is used with readData() and readStop() for optimized
|
||||
* multiple block reads. SPI chipSelect must be low for the entire sequence.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool readStart(uint32_t lba);
|
||||
/** Start a read multiple blocks sequence.
|
||||
*
|
||||
* \param[in] lba Address of first block in sequence.
|
||||
* \param[in] count Maximum block count.
|
||||
* \note This function is used with readData() and readStop() for optimized
|
||||
* multiple block reads. SPI chipSelect must be low for the entire sequence.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool readStart(uint32_t lba, uint32_t count);
|
||||
/** End a read multiple blocks sequence.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool readStop();
|
||||
/** \return success if sync successful. Not for user apps. */
|
||||
bool syncBlocks();
|
||||
/** Return the card type: SD V1, SD V2 or SDHC
|
||||
* \return 0 - SD V1, 1 - SD V2, or 3 - SDHC.
|
||||
*/
|
||||
uint8_t type();
|
||||
/**
|
||||
* Writes a 512 byte block to an SD card.
|
||||
*
|
||||
* \param[in] lba Logical block to be written.
|
||||
* \param[in] src Pointer to the location of the data to be written.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool writeBlock(uint32_t lba, const uint8_t* src);
|
||||
/**
|
||||
* Write multiple 512 byte blocks to an SD card.
|
||||
*
|
||||
* \param[in] lba Logical block to be written.
|
||||
* \param[in] nb Number of blocks to be written.
|
||||
* \param[in] src Pointer to the location of the data to be written.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool writeBlocks(uint32_t lba, const uint8_t* src, size_t nb);
|
||||
/** Write one data block in a multiple block write sequence.
|
||||
* \param[in] src Pointer to the location of the data to be written.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool writeData(const uint8_t* src);
|
||||
/** Start a write multiple blocks sequence.
|
||||
*
|
||||
* \param[in] lba Address of first block in sequence.
|
||||
*
|
||||
* \note This function is used with writeData() and writeStop()
|
||||
* for optimized multiple block writes.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool writeStart(uint32_t lba);
|
||||
/** Start a write multiple blocks sequence.
|
||||
*
|
||||
* \param[in] lba Address of first block in sequence.
|
||||
* \param[in] count Maximum block count.
|
||||
* \note This function is used with writeData() and writeStop()
|
||||
* for optimized multiple block writes.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool writeStart(uint32_t lba, uint32_t count);
|
||||
|
||||
/** End a write multiple blocks sequence.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool writeStop();
|
||||
};
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class SdioCardEX
|
||||
* \brief Extended SD I/O block driver.
|
||||
*/
|
||||
class SdioCardEX : public SdioCard {
|
||||
public:
|
||||
/** Initialize the SD card
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool begin() {
|
||||
m_curState = IDLE_STATE;
|
||||
return SdioCard::begin();
|
||||
}
|
||||
/** Erase a range of blocks.
|
||||
*
|
||||
* \param[in] firstBlock The address of the first block in the range.
|
||||
* \param[in] lastBlock The address of the last block in the range.
|
||||
*
|
||||
* \note This function requests the SD card to do a flash erase for a
|
||||
* range of blocks. The data on the card after an erase operation is
|
||||
* either 0 or 1, depends on the card vendor. The card must support
|
||||
* single block erase.
|
||||
*
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool erase(uint32_t firstBlock, uint32_t lastBlock) {
|
||||
return syncBlocks() && SdioCard::erase(firstBlock, lastBlock);
|
||||
}
|
||||
/**
|
||||
* Read a 512 byte block from an SD card.
|
||||
*
|
||||
* \param[in] block Logical block to be read.
|
||||
* \param[out] dst Pointer to the location that will receive the data.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool readBlock(uint32_t block, uint8_t* dst);
|
||||
/** End multi-block transfer and go to idle state.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool syncBlocks();
|
||||
/**
|
||||
* Writes a 512 byte block to an SD card.
|
||||
*
|
||||
* \param[in] block Logical block to be written.
|
||||
* \param[in] src Pointer to the location of the data to be written.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool writeBlock(uint32_t block, const uint8_t* src);
|
||||
/**
|
||||
* Read multiple 512 byte blocks from an SD card.
|
||||
*
|
||||
* \param[in] block Logical block to be read.
|
||||
* \param[in] nb Number of blocks to be read.
|
||||
* \param[out] dst Pointer to the location that will receive the data.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool readBlocks(uint32_t block, uint8_t* dst, size_t nb);
|
||||
/**
|
||||
* Write multiple 512 byte blocks to an SD card.
|
||||
*
|
||||
* \param[in] block Logical block to be written.
|
||||
* \param[in] nb Number of blocks to be written.
|
||||
* \param[in] src Pointer to the location of the data to be written.
|
||||
* \return The value true is returned for success and
|
||||
* the value false is returned for failure.
|
||||
*/
|
||||
bool writeBlocks(uint32_t block, const uint8_t* src, size_t nb);
|
||||
|
||||
private:
|
||||
static const uint32_t IDLE_STATE = 0;
|
||||
static const uint32_t READ_STATE = 1;
|
||||
static const uint32_t WRITE_STATE = 2;
|
||||
uint32_t m_curLba;
|
||||
uint32_t m_limitLba;
|
||||
uint8_t m_curState;
|
||||
};
|
||||
#endif // SdioCard_h
|
109
Repetier-Firmware 1.0.3/Repetier/src/SdFat/SdCard/SdioCardEX.cpp
Normal file
109
Repetier-Firmware 1.0.3/Repetier/src/SdFat/SdCard/SdioCardEX.cpp
Normal file
@ -0,0 +1,109 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#include "../../../Repetier.h"
|
||||
#include "SdioCard.h"
|
||||
|
||||
// limit of K66 due to errata KINETIS_K_0N65N.
|
||||
const uint32_t MAX_SDHC_COUNT = 0XFFFF;
|
||||
|
||||
// Max RU is 1024 blocks.
|
||||
const uint32_t RU_MASK = 0X03FF;
|
||||
|
||||
bool SdioCardEX::readBlock(uint32_t lba, uint8_t* dst) {
|
||||
if (m_curState != READ_STATE || lba != m_curLba) {
|
||||
if (!syncBlocks()) {
|
||||
return false;
|
||||
}
|
||||
m_limitLba = (lba + MAX_SDHC_COUNT) & ~RU_MASK;
|
||||
if (!SdioCard::readStart(lba, m_limitLba - lba)) {
|
||||
return false;
|
||||
}
|
||||
m_curLba = lba;
|
||||
m_curState = READ_STATE;
|
||||
}
|
||||
if (!SdioCard::readData(dst)) {
|
||||
return false;
|
||||
}
|
||||
m_curLba++;
|
||||
if (m_curLba >= m_limitLba) {
|
||||
m_curState = IDLE_STATE;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdioCardEX::readBlocks(uint32_t lba, uint8_t* dst, size_t nb) {
|
||||
for (size_t i = 0; i < nb; i++) {
|
||||
if (!readBlock(lba + i, dst + i * 512UL)) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdioCardEX::syncBlocks() {
|
||||
if (m_curState == READ_STATE) {
|
||||
m_curState = IDLE_STATE;
|
||||
if (!SdioCard::readStop()) {
|
||||
return false;
|
||||
}
|
||||
} else if (m_curState == WRITE_STATE) {
|
||||
m_curState = IDLE_STATE;
|
||||
if (!SdioCard::writeStop()) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdioCardEX::writeBlock(uint32_t lba, const uint8_t* src) {
|
||||
if (m_curState != WRITE_STATE || m_curLba != lba) {
|
||||
if (!syncBlocks()) {
|
||||
return false;
|
||||
}
|
||||
m_limitLba = (lba + MAX_SDHC_COUNT) & ~RU_MASK;
|
||||
if (!SdioCard::writeStart(lba, m_limitLba - lba)) {
|
||||
return false;
|
||||
}
|
||||
m_curLba = lba;
|
||||
m_curState = WRITE_STATE;
|
||||
}
|
||||
if (!SdioCard::writeData(src)) {
|
||||
return false;
|
||||
}
|
||||
m_curLba++;
|
||||
if (m_curLba >= m_limitLba) {
|
||||
m_curState = IDLE_STATE;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdioCardEX::writeBlocks(uint32_t lba, const uint8_t* src, size_t nb) {
|
||||
for (size_t i = 0; i < nb; i++) {
|
||||
if (!writeBlock(lba + i, src + i * 512UL)) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
768
Repetier-Firmware 1.0.3/Repetier/src/SdFat/SdCard/SdioTeensy.cpp
Normal file
768
Repetier-Firmware 1.0.3/Repetier/src/SdFat/SdCard/SdioTeensy.cpp
Normal file
@ -0,0 +1,768 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#include "../../../Repetier.h"
|
||||
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)
|
||||
#include "SdioCard.h"
|
||||
//==============================================================================
|
||||
#define SDHC_PROCTL_DTW_4BIT 0x01
|
||||
const uint32_t FIFO_WML = 16;
|
||||
const uint32_t CMD8_RETRIES = 10;
|
||||
const uint32_t BUSY_TIMEOUT_MICROS = 500000;
|
||||
//==============================================================================
|
||||
const uint32_t SDHC_IRQSTATEN_MASK = SDHC_IRQSTATEN_DMAESEN | SDHC_IRQSTATEN_AC12ESEN | SDHC_IRQSTATEN_DEBESEN | SDHC_IRQSTATEN_DCESEN | SDHC_IRQSTATEN_DTOESEN | SDHC_IRQSTATEN_CIESEN | SDHC_IRQSTATEN_CEBESEN | SDHC_IRQSTATEN_CCESEN | SDHC_IRQSTATEN_CTOESEN | SDHC_IRQSTATEN_DINTSEN | SDHC_IRQSTATEN_TCSEN | SDHC_IRQSTATEN_CCSEN;
|
||||
|
||||
const uint32_t SDHC_IRQSTAT_CMD_ERROR = SDHC_IRQSTAT_CIE | SDHC_IRQSTAT_CEBE | SDHC_IRQSTAT_CCE | SDHC_IRQSTAT_CTOE;
|
||||
|
||||
const uint32_t SDHC_IRQSTAT_DATA_ERROR = SDHC_IRQSTAT_AC12E | SDHC_IRQSTAT_DEBE | SDHC_IRQSTAT_DCE | SDHC_IRQSTAT_DTOE;
|
||||
|
||||
const uint32_t SDHC_IRQSTAT_ERROR = SDHC_IRQSTAT_DMAE | SDHC_IRQSTAT_CMD_ERROR | SDHC_IRQSTAT_DATA_ERROR;
|
||||
|
||||
const uint32_t SDHC_IRQSIGEN_MASK = SDHC_IRQSIGEN_DMAEIEN | SDHC_IRQSIGEN_AC12EIEN | SDHC_IRQSIGEN_DEBEIEN | SDHC_IRQSIGEN_DCEIEN | SDHC_IRQSIGEN_DTOEIEN | SDHC_IRQSIGEN_CIEIEN | SDHC_IRQSIGEN_CEBEIEN | SDHC_IRQSIGEN_CCEIEN | SDHC_IRQSIGEN_CTOEIEN | SDHC_IRQSIGEN_TCIEN;
|
||||
//=============================================================================
|
||||
const uint32_t CMD_RESP_NONE = SDHC_XFERTYP_RSPTYP(0);
|
||||
|
||||
const uint32_t CMD_RESP_R1 = SDHC_XFERTYP_CICEN | SDHC_XFERTYP_CCCEN | SDHC_XFERTYP_RSPTYP(2);
|
||||
|
||||
const uint32_t CMD_RESP_R1b = SDHC_XFERTYP_CICEN | SDHC_XFERTYP_CCCEN | SDHC_XFERTYP_RSPTYP(3);
|
||||
|
||||
const uint32_t CMD_RESP_R2 = SDHC_XFERTYP_CCCEN | SDHC_XFERTYP_RSPTYP(1);
|
||||
|
||||
const uint32_t CMD_RESP_R3 = SDHC_XFERTYP_RSPTYP(2);
|
||||
|
||||
const uint32_t CMD_RESP_R6 = CMD_RESP_R1;
|
||||
|
||||
const uint32_t CMD_RESP_R7 = CMD_RESP_R1;
|
||||
|
||||
const uint32_t DATA_READ = SDHC_XFERTYP_DTDSEL | SDHC_XFERTYP_DPSEL;
|
||||
|
||||
const uint32_t DATA_READ_DMA = DATA_READ | SDHC_XFERTYP_DMAEN;
|
||||
|
||||
const uint32_t DATA_READ_MULTI_DMA = DATA_READ_DMA | SDHC_XFERTYP_MSBSEL | SDHC_XFERTYP_AC12EN | SDHC_XFERTYP_BCEN;
|
||||
|
||||
const uint32_t DATA_READ_MULTI_PGM = DATA_READ | SDHC_XFERTYP_MSBSEL | SDHC_XFERTYP_BCEN | SDHC_XFERTYP_AC12EN;
|
||||
|
||||
const uint32_t DATA_WRITE_DMA = SDHC_XFERTYP_DPSEL | SDHC_XFERTYP_DMAEN;
|
||||
|
||||
const uint32_t DATA_WRITE_MULTI_DMA = DATA_WRITE_DMA | SDHC_XFERTYP_MSBSEL | SDHC_XFERTYP_AC12EN | SDHC_XFERTYP_BCEN;
|
||||
|
||||
const uint32_t DATA_WRITE_MULTI_PGM = SDHC_XFERTYP_DPSEL | SDHC_XFERTYP_MSBSEL | SDHC_XFERTYP_BCEN | SDHC_XFERTYP_AC12EN;
|
||||
|
||||
const uint32_t ACMD6_XFERTYP = SDHC_XFERTYP_CMDINX(ACMD6) | CMD_RESP_R1;
|
||||
|
||||
const uint32_t ACMD41_XFERTYP = SDHC_XFERTYP_CMDINX(ACMD41) | CMD_RESP_R3;
|
||||
|
||||
const uint32_t CMD0_XFERTYP = SDHC_XFERTYP_CMDINX(CMD0) | CMD_RESP_NONE;
|
||||
|
||||
const uint32_t CMD2_XFERTYP = SDHC_XFERTYP_CMDINX(CMD2) | CMD_RESP_R2;
|
||||
|
||||
const uint32_t CMD3_XFERTYP = SDHC_XFERTYP_CMDINX(CMD3) | CMD_RESP_R6;
|
||||
|
||||
const uint32_t CMD6_XFERTYP = SDHC_XFERTYP_CMDINX(CMD6) | CMD_RESP_R1 | DATA_READ_DMA;
|
||||
|
||||
const uint32_t CMD7_XFERTYP = SDHC_XFERTYP_CMDINX(CMD7) | CMD_RESP_R1b;
|
||||
|
||||
const uint32_t CMD8_XFERTYP = SDHC_XFERTYP_CMDINX(CMD8) | CMD_RESP_R7;
|
||||
|
||||
const uint32_t CMD9_XFERTYP = SDHC_XFERTYP_CMDINX(CMD9) | CMD_RESP_R2;
|
||||
|
||||
const uint32_t CMD10_XFERTYP = SDHC_XFERTYP_CMDINX(CMD10) | CMD_RESP_R2;
|
||||
|
||||
const uint32_t CMD12_XFERTYP = SDHC_XFERTYP_CMDINX(CMD12) | CMD_RESP_R1b | SDHC_XFERTYP_CMDTYP(3);
|
||||
|
||||
const uint32_t CMD13_XFERTYP = SDHC_XFERTYP_CMDINX(CMD13) | CMD_RESP_R1;
|
||||
|
||||
const uint32_t CMD17_DMA_XFERTYP = SDHC_XFERTYP_CMDINX(CMD17) | CMD_RESP_R1 | DATA_READ_DMA;
|
||||
|
||||
const uint32_t CMD18_DMA_XFERTYP = SDHC_XFERTYP_CMDINX(CMD18) | CMD_RESP_R1 | DATA_READ_MULTI_DMA;
|
||||
|
||||
const uint32_t CMD18_PGM_XFERTYP = SDHC_XFERTYP_CMDINX(CMD18) | CMD_RESP_R1 | DATA_READ_MULTI_PGM;
|
||||
|
||||
const uint32_t CMD24_DMA_XFERTYP = SDHC_XFERTYP_CMDINX(CMD24) | CMD_RESP_R1 | DATA_WRITE_DMA;
|
||||
|
||||
const uint32_t CMD25_DMA_XFERTYP = SDHC_XFERTYP_CMDINX(CMD25) | CMD_RESP_R1 | DATA_WRITE_MULTI_DMA;
|
||||
|
||||
const uint32_t CMD25_PGM_XFERTYP = SDHC_XFERTYP_CMDINX(CMD25) | CMD_RESP_R1 | DATA_WRITE_MULTI_PGM;
|
||||
|
||||
const uint32_t CMD32_XFERTYP = SDHC_XFERTYP_CMDINX(CMD32) | CMD_RESP_R1;
|
||||
|
||||
const uint32_t CMD33_XFERTYP = SDHC_XFERTYP_CMDINX(CMD33) | CMD_RESP_R1;
|
||||
|
||||
const uint32_t CMD38_XFERTYP = SDHC_XFERTYP_CMDINX(CMD38) | CMD_RESP_R1b;
|
||||
|
||||
const uint32_t CMD55_XFERTYP = SDHC_XFERTYP_CMDINX(CMD55) | CMD_RESP_R1;
|
||||
|
||||
//=============================================================================
|
||||
static bool cardCommand(uint32_t xfertyp, uint32_t arg);
|
||||
static void enableGPIO(bool enable);
|
||||
static void enableDmaIrs();
|
||||
static void initSDHC();
|
||||
static bool isBusyCMD13();
|
||||
static bool isBusyCommandComplete();
|
||||
static bool isBusyCommandInhibit();
|
||||
static bool readReg16(uint32_t xfertyp, void* data);
|
||||
static void setSdclk(uint32_t kHzMax);
|
||||
static bool yieldTimeout(bool (*fcn)());
|
||||
static bool waitDmaStatus();
|
||||
static bool waitTimeout(bool (*fcn)());
|
||||
//-----------------------------------------------------------------------------
|
||||
static bool (*m_busyFcn)() = 0;
|
||||
static bool m_initDone = false;
|
||||
static bool m_version2;
|
||||
static bool m_highCapacity;
|
||||
static uint8_t m_errorCode = SD_CARD_ERROR_INIT_NOT_CALLED;
|
||||
static uint32_t m_errorLine = 0;
|
||||
static uint32_t m_rca;
|
||||
static volatile bool m_dmaBusy = false;
|
||||
static volatile uint32_t m_irqstat;
|
||||
static uint32_t m_sdClkKhz = 0;
|
||||
static uint32_t m_ocr;
|
||||
static cid_t m_cid;
|
||||
static csd_t m_csd;
|
||||
//=============================================================================
|
||||
#define USE_DEBUG_MODE 0
|
||||
#if USE_DEBUG_MODE
|
||||
#define DBG_IRQSTAT() \
|
||||
if (SDHC_IRQSTAT) { \
|
||||
Serial.print(__LINE__); \
|
||||
Serial.print(" IRQSTAT "); \
|
||||
Serial.println(SDHC_IRQSTAT, HEX); \
|
||||
}
|
||||
|
||||
static void printRegs(uint32_t line) {
|
||||
Serial.print(line);
|
||||
Serial.print(" PRSSTAT ");
|
||||
Serial.print(SDHC_PRSSTAT, HEX);
|
||||
Serial.print(" PROCTL ");
|
||||
Serial.print(SDHC_PROCTL, HEX);
|
||||
Serial.print(" IRQSTAT ");
|
||||
Serial.print(SDHC_IRQSTAT, HEX);
|
||||
Serial.print(" m_irqstat ");
|
||||
Serial.println(m_irqstat, HEX);
|
||||
}
|
||||
#else // USE_DEBUG_MODE
|
||||
#define DBG_IRQSTAT()
|
||||
#endif // USE_DEBUG_MODE
|
||||
//=============================================================================
|
||||
// Error function and macro.
|
||||
#define sdError(code) setSdErrorCode(code, __LINE__)
|
||||
inline bool setSdErrorCode(uint8_t code, uint32_t line) {
|
||||
m_errorCode = code;
|
||||
m_errorLine = line;
|
||||
return false; // setSdErrorCode
|
||||
}
|
||||
//=============================================================================
|
||||
// ISR
|
||||
void sdhc_isr() {
|
||||
SDHC_IRQSIGEN = 0;
|
||||
m_irqstat = SDHC_IRQSTAT;
|
||||
SDHC_IRQSTAT = m_irqstat;
|
||||
m_dmaBusy = false;
|
||||
}
|
||||
//=============================================================================
|
||||
// Static functions.
|
||||
static bool cardAcmd(uint32_t rca, uint32_t xfertyp, uint32_t arg) {
|
||||
return cardCommand(CMD55_XFERTYP, rca) && cardCommand(xfertyp, arg);
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
static bool cardCommand(uint32_t xfertyp, uint32_t arg) {
|
||||
DBG_IRQSTAT();
|
||||
if (waitTimeout(isBusyCommandInhibit)) {
|
||||
return false; // Caller will set errorCode.
|
||||
}
|
||||
SDHC_CMDARG = arg;
|
||||
SDHC_XFERTYP = xfertyp;
|
||||
if (waitTimeout(isBusyCommandComplete)) {
|
||||
return false; // Caller will set errorCode.
|
||||
}
|
||||
m_irqstat = SDHC_IRQSTAT;
|
||||
SDHC_IRQSTAT = m_irqstat;
|
||||
|
||||
return (m_irqstat & SDHC_IRQSTAT_CC) && !(m_irqstat & SDHC_IRQSTAT_CMD_ERROR);
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
static bool cardCMD6(uint32_t arg, uint8_t* status) {
|
||||
// CMD6 returns 64 bytes.
|
||||
if (waitTimeout(isBusyCMD13)) {
|
||||
return sdError(SD_CARD_ERROR_CMD13);
|
||||
}
|
||||
enableDmaIrs();
|
||||
SDHC_DSADDR = (uint32_t)status;
|
||||
SDHC_CMDARG = arg;
|
||||
SDHC_BLKATTR = SDHC_BLKATTR_BLKCNT(1) | SDHC_BLKATTR_BLKSIZE(64);
|
||||
SDHC_IRQSIGEN = SDHC_IRQSIGEN_MASK;
|
||||
SDHC_XFERTYP = CMD6_XFERTYP;
|
||||
|
||||
if (!waitDmaStatus()) {
|
||||
return sdError(SD_CARD_ERROR_CMD6);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
static void enableGPIO(bool enable) {
|
||||
const uint32_t PORT_CLK = PORT_PCR_MUX(4) | PORT_PCR_DSE;
|
||||
const uint32_t PORT_CMD_DATA = PORT_CLK | PORT_PCR_PS | PORT_PCR_PE;
|
||||
|
||||
PORTE_PCR0 = enable ? PORT_CMD_DATA : 0; // SDHC_D1
|
||||
PORTE_PCR1 = enable ? PORT_CMD_DATA : 0; // SDHC_D0
|
||||
PORTE_PCR2 = enable ? PORT_CLK : 0; // SDHC_CLK
|
||||
PORTE_PCR3 = enable ? PORT_CMD_DATA : 0; // SDHC_CMD
|
||||
PORTE_PCR4 = enable ? PORT_CMD_DATA : 0; // SDHC_D3
|
||||
PORTE_PCR5 = enable ? PORT_CMD_DATA : 0; // SDHC_D2
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
static void enableDmaIrs() {
|
||||
m_dmaBusy = true;
|
||||
m_irqstat = 0;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
static void initSDHC() {
|
||||
#ifdef HAS_KINETIS_MPU
|
||||
// Allow SDHC Bus Master access.
|
||||
MPU_RGDAAC0 |= 0x0C000000;
|
||||
#endif
|
||||
// Enable SDHC clock.
|
||||
SIM_SCGC3 |= SIM_SCGC3_SDHC;
|
||||
|
||||
// Disable GPIO clock.
|
||||
enableGPIO(false);
|
||||
|
||||
// Reset SDHC. Use default Water Mark Level of 16.
|
||||
SDHC_SYSCTL = SDHC_SYSCTL_RSTA;
|
||||
while (SDHC_SYSCTL & SDHC_SYSCTL_RSTA) {
|
||||
}
|
||||
// Set initial SCK rate.
|
||||
setSdclk(400);
|
||||
|
||||
enableGPIO(true);
|
||||
|
||||
// Enable desired IRQSTAT bits.
|
||||
SDHC_IRQSTATEN = SDHC_IRQSTATEN_MASK;
|
||||
|
||||
NVIC_SET_PRIORITY(IRQ_SDHC, 6 * 16);
|
||||
NVIC_ENABLE_IRQ(IRQ_SDHC);
|
||||
|
||||
// Send 80 clocks to card.
|
||||
SDHC_SYSCTL |= SDHC_SYSCTL_INITA;
|
||||
while (SDHC_SYSCTL & SDHC_SYSCTL_INITA) {
|
||||
}
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
static bool isBusyCMD13() {
|
||||
if (!cardCommand(CMD13_XFERTYP, m_rca)) {
|
||||
// Caller will timeout.
|
||||
return true;
|
||||
}
|
||||
return !(SDHC_CMDRSP0 & CARD_STATUS_READY_FOR_DATA);
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
static bool isBusyCommandComplete() {
|
||||
return !(SDHC_IRQSTAT & (SDHC_IRQSTAT_CC | SDHC_IRQSTAT_CMD_ERROR));
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
static bool isBusyCommandInhibit() {
|
||||
return SDHC_PRSSTAT & SDHC_PRSSTAT_CIHB;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
static bool isBusyDMA() {
|
||||
return m_dmaBusy;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
static bool isBusyFifoRead() {
|
||||
return !(SDHC_PRSSTAT & SDHC_PRSSTAT_BREN);
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
static bool isBusyFifoWrite() {
|
||||
return !(SDHC_PRSSTAT & SDHC_PRSSTAT_BWEN);
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
static bool isBusyTransferComplete() {
|
||||
return !(SDHC_IRQSTAT & (SDHC_IRQSTAT_TC | SDHC_IRQSTAT_ERROR));
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
static bool rdWrBlocks(uint32_t xfertyp,
|
||||
uint32_t lba, uint8_t* buf, size_t n) {
|
||||
if ((3 & (uint32_t)buf) || n == 0) {
|
||||
return sdError(SD_CARD_ERROR_DMA);
|
||||
}
|
||||
if (yieldTimeout(isBusyCMD13)) {
|
||||
return sdError(SD_CARD_ERROR_CMD13);
|
||||
}
|
||||
enableDmaIrs();
|
||||
SDHC_DSADDR = (uint32_t)buf;
|
||||
SDHC_CMDARG = m_highCapacity ? lba : 512 * lba;
|
||||
SDHC_BLKATTR = SDHC_BLKATTR_BLKCNT(n) | SDHC_BLKATTR_BLKSIZE(512);
|
||||
SDHC_IRQSIGEN = SDHC_IRQSIGEN_MASK;
|
||||
SDHC_XFERTYP = xfertyp;
|
||||
|
||||
return waitDmaStatus();
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
// Read 16 byte CID or CSD register.
|
||||
static bool readReg16(uint32_t xfertyp, void* data) {
|
||||
uint8_t* d = reinterpret_cast<uint8_t*>(data);
|
||||
if (!cardCommand(xfertyp, m_rca)) {
|
||||
return false; // Caller will set errorCode.
|
||||
}
|
||||
uint32_t sr[] = { SDHC_CMDRSP0, SDHC_CMDRSP1, SDHC_CMDRSP2, SDHC_CMDRSP3 };
|
||||
for (int i = 0; i < 15; i++) {
|
||||
d[14 - i] = sr[i / 4] >> 8 * (i % 4);
|
||||
}
|
||||
d[15] = 0;
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
static void setSdclk(uint32_t kHzMax) {
|
||||
const uint32_t DVS_LIMIT = 0X10;
|
||||
const uint32_t SDCLKFS_LIMIT = 0X100;
|
||||
uint32_t dvs = 1;
|
||||
uint32_t sdclkfs = 1;
|
||||
uint32_t maxSdclk = 1000 * kHzMax;
|
||||
|
||||
while ((F_CPU / (sdclkfs * DVS_LIMIT) > maxSdclk) && (sdclkfs < SDCLKFS_LIMIT)) {
|
||||
sdclkfs <<= 1;
|
||||
}
|
||||
while ((F_CPU / (sdclkfs * dvs) > maxSdclk) && (dvs < DVS_LIMIT)) {
|
||||
dvs++;
|
||||
}
|
||||
m_sdClkKhz = F_CPU / (1000 * sdclkfs * dvs);
|
||||
sdclkfs >>= 1;
|
||||
dvs--;
|
||||
|
||||
// Disable SDHC clock.
|
||||
SDHC_SYSCTL &= ~SDHC_SYSCTL_SDCLKEN;
|
||||
|
||||
// Change dividers.
|
||||
uint32_t sysctl = SDHC_SYSCTL & ~(SDHC_SYSCTL_DTOCV_MASK | SDHC_SYSCTL_DVS_MASK | SDHC_SYSCTL_SDCLKFS_MASK);
|
||||
|
||||
SDHC_SYSCTL = sysctl | SDHC_SYSCTL_DTOCV(0x0E) | SDHC_SYSCTL_DVS(dvs)
|
||||
| SDHC_SYSCTL_SDCLKFS(sdclkfs);
|
||||
|
||||
// Wait until the SDHC clock is stable.
|
||||
while (!(SDHC_PRSSTAT & SDHC_PRSSTAT_SDSTB)) {
|
||||
}
|
||||
// Enable the SDHC clock.
|
||||
SDHC_SYSCTL |= SDHC_SYSCTL_SDCLKEN;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
static bool transferStop() {
|
||||
DBG_IRQSTAT();
|
||||
|
||||
if (!cardCommand(CMD12_XFERTYP, 0)) {
|
||||
return sdError(SD_CARD_ERROR_CMD12);
|
||||
}
|
||||
if (yieldTimeout(isBusyCMD13)) {
|
||||
return sdError(SD_CARD_ERROR_CMD13);
|
||||
}
|
||||
// Save registers before reset DAT lines.
|
||||
uint32_t irqsststen = SDHC_IRQSTATEN;
|
||||
uint32_t proctl = SDHC_PROCTL & ~SDHC_PROCTL_SABGREQ;
|
||||
|
||||
// Do reset to clear CDIHB. Should be a better way!
|
||||
SDHC_SYSCTL |= SDHC_SYSCTL_RSTD;
|
||||
|
||||
// Restore registers.
|
||||
SDHC_IRQSTATEN = irqsststen;
|
||||
SDHC_PROCTL = proctl;
|
||||
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
// Return true if timeout occurs.
|
||||
static bool yieldTimeout(bool (*fcn)()) {
|
||||
m_busyFcn = fcn;
|
||||
uint32_t m = micros();
|
||||
while (fcn()) {
|
||||
if ((micros() - m) > BUSY_TIMEOUT_MICROS) {
|
||||
m_busyFcn = 0;
|
||||
return true;
|
||||
}
|
||||
yield();
|
||||
}
|
||||
m_busyFcn = 0;
|
||||
return false; // Caller will set errorCode.
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
static bool waitDmaStatus() {
|
||||
if (yieldTimeout(isBusyDMA)) {
|
||||
return false; // Caller will set errorCode.
|
||||
}
|
||||
return (m_irqstat & SDHC_IRQSTAT_TC) && !(m_irqstat & SDHC_IRQSTAT_ERROR);
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
// Return true if timeout occurs.
|
||||
static bool waitTimeout(bool (*fcn)()) {
|
||||
uint32_t m = micros();
|
||||
while (fcn()) {
|
||||
if ((micros() - m) > BUSY_TIMEOUT_MICROS) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false; // Caller will set errorCode.
|
||||
}
|
||||
//=============================================================================
|
||||
bool SdioCard::begin() {
|
||||
uint32_t kHzSdClk;
|
||||
uint32_t arg;
|
||||
m_initDone = false;
|
||||
m_errorCode = SD_CARD_ERROR_NONE;
|
||||
m_highCapacity = false;
|
||||
m_version2 = false;
|
||||
|
||||
// initialize controller.
|
||||
initSDHC();
|
||||
|
||||
if (!cardCommand(CMD0_XFERTYP, 0)) {
|
||||
return sdError(SD_CARD_ERROR_CMD0);
|
||||
}
|
||||
// Try several times for case of reset delay.
|
||||
for (uint32_t i = 0; i < CMD8_RETRIES; i++) {
|
||||
if (cardCommand(CMD8_XFERTYP, 0X1AA)) {
|
||||
if (SDHC_CMDRSP0 != 0X1AA) {
|
||||
return sdError(SD_CARD_ERROR_CMD8);
|
||||
}
|
||||
m_version2 = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
arg = m_version2 ? 0X40300000 : 0x00300000;
|
||||
uint32_t m = micros();
|
||||
do {
|
||||
if (!cardAcmd(0, ACMD41_XFERTYP, arg) || ((micros() - m) > BUSY_TIMEOUT_MICROS)) {
|
||||
return sdError(SD_CARD_ERROR_ACMD41);
|
||||
}
|
||||
} while ((SDHC_CMDRSP0 & 0x80000000) == 0);
|
||||
|
||||
m_ocr = SDHC_CMDRSP0;
|
||||
if (SDHC_CMDRSP0 & 0x40000000) {
|
||||
// Is high capacity.
|
||||
m_highCapacity = true;
|
||||
}
|
||||
if (!cardCommand(CMD2_XFERTYP, 0)) {
|
||||
return sdError(SD_CARD_ERROR_CMD2);
|
||||
}
|
||||
if (!cardCommand(CMD3_XFERTYP, 0)) {
|
||||
return sdError(SD_CARD_ERROR_CMD3);
|
||||
}
|
||||
m_rca = SDHC_CMDRSP0 & 0xFFFF0000;
|
||||
|
||||
if (!readReg16(CMD9_XFERTYP, &m_csd)) {
|
||||
return sdError(SD_CARD_ERROR_CMD9);
|
||||
}
|
||||
if (!readReg16(CMD10_XFERTYP, &m_cid)) {
|
||||
return sdError(SD_CARD_ERROR_CMD10);
|
||||
}
|
||||
if (!cardCommand(CMD7_XFERTYP, m_rca)) {
|
||||
return sdError(SD_CARD_ERROR_CMD7);
|
||||
}
|
||||
// Set card to bus width four.
|
||||
if (!cardAcmd(m_rca, ACMD6_XFERTYP, 2)) {
|
||||
return sdError(SD_CARD_ERROR_ACMD6);
|
||||
}
|
||||
// Set SDHC to bus width four.
|
||||
SDHC_PROCTL &= ~SDHC_PROCTL_DTW_MASK;
|
||||
SDHC_PROCTL |= SDHC_PROCTL_DTW(SDHC_PROCTL_DTW_4BIT);
|
||||
|
||||
SDHC_WML = SDHC_WML_RDWML(FIFO_WML) | SDHC_WML_WRWML(FIFO_WML);
|
||||
|
||||
// Determine if High Speed mode is supported and set frequency.
|
||||
uint8_t status[64];
|
||||
if (cardCMD6(0X00FFFFFF, status) && (2 & status[13]) && cardCMD6(0X80FFFFF1, status) && (status[16] & 0XF) == 1) {
|
||||
kHzSdClk = 50000;
|
||||
} else {
|
||||
kHzSdClk = 25000;
|
||||
}
|
||||
// disable GPIO
|
||||
enableGPIO(false);
|
||||
|
||||
// Set the SDHC SCK frequency.
|
||||
setSdclk(kHzSdClk);
|
||||
|
||||
// enable GPIO
|
||||
enableGPIO(true);
|
||||
m_initDone = true;
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
uint32_t SdioCard::cardSize() {
|
||||
return sdCardCapacity(&m_csd);
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdioCard::erase(uint32_t firstBlock, uint32_t lastBlock) {
|
||||
// check for single block erase
|
||||
if (!m_csd.v1.erase_blk_en) {
|
||||
// erase size mask
|
||||
uint8_t m = (m_csd.v1.sector_size_high << 1) | m_csd.v1.sector_size_low;
|
||||
if ((firstBlock & m) != 0 || ((lastBlock + 1) & m) != 0) {
|
||||
// error card can't erase specified area
|
||||
return sdError(SD_CARD_ERROR_ERASE_SINGLE_BLOCK);
|
||||
}
|
||||
}
|
||||
if (!m_highCapacity) {
|
||||
firstBlock <<= 9;
|
||||
lastBlock <<= 9;
|
||||
}
|
||||
if (!cardCommand(CMD32_XFERTYP, firstBlock)) {
|
||||
return sdError(SD_CARD_ERROR_CMD32);
|
||||
}
|
||||
if (!cardCommand(CMD33_XFERTYP, lastBlock)) {
|
||||
return sdError(SD_CARD_ERROR_CMD33);
|
||||
}
|
||||
if (!cardCommand(CMD38_XFERTYP, 0)) {
|
||||
return sdError(SD_CARD_ERROR_CMD38);
|
||||
}
|
||||
if (waitTimeout(isBusyCMD13)) {
|
||||
return sdError(SD_CARD_ERROR_ERASE_TIMEOUT);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
uint8_t SdioCard::errorCode() {
|
||||
return m_errorCode;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
uint32_t SdioCard::errorData() {
|
||||
return m_irqstat;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
uint32_t SdioCard::errorLine() {
|
||||
return m_errorLine;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdioCard::isBusy() {
|
||||
return m_busyFcn ? m_busyFcn() : m_initDone && isBusyCMD13();
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
uint32_t SdioCard::kHzSdClk() {
|
||||
return m_sdClkKhz;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdioCard::readBlock(uint32_t lba, uint8_t* buf) {
|
||||
uint8_t aligned[512];
|
||||
|
||||
uint8_t* ptr = (uint32_t)buf & 3 ? aligned : buf;
|
||||
|
||||
if (!rdWrBlocks(CMD17_DMA_XFERTYP, lba, ptr, 1)) {
|
||||
return sdError(SD_CARD_ERROR_CMD18);
|
||||
}
|
||||
if (ptr != buf) {
|
||||
memcpy(buf, aligned, 512);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdioCard::readBlocks(uint32_t lba, uint8_t* buf, size_t n) {
|
||||
if ((uint32_t)buf & 3) {
|
||||
for (size_t i = 0; i < n; i++, lba++, buf += 512) {
|
||||
if (!readBlock(lba, buf)) {
|
||||
return false; // readBlock will set errorCode.
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
if (!rdWrBlocks(CMD18_DMA_XFERTYP, lba, buf, n)) {
|
||||
return sdError(SD_CARD_ERROR_CMD18);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdioCard::readCID(void* cid) {
|
||||
memcpy(cid, &m_cid, 16);
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdioCard::readCSD(void* csd) {
|
||||
memcpy(csd, &m_csd, 16);
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdioCard::readData(uint8_t* dst) {
|
||||
DBG_IRQSTAT();
|
||||
uint32_t* p32 = reinterpret_cast<uint32_t*>(dst);
|
||||
|
||||
if (!(SDHC_PRSSTAT & SDHC_PRSSTAT_RTA)) {
|
||||
SDHC_PROCTL &= ~SDHC_PROCTL_SABGREQ;
|
||||
if ((SDHC_BLKATTR & 0XFFFF0000) == 0X10000) {
|
||||
// Don't stop at block gap if last block. Allows auto CMD12.
|
||||
SDHC_PROCTL |= SDHC_PROCTL_CREQ;
|
||||
} else {
|
||||
noInterrupts();
|
||||
SDHC_PROCTL |= SDHC_PROCTL_CREQ;
|
||||
SDHC_PROCTL |= SDHC_PROCTL_SABGREQ;
|
||||
interrupts();
|
||||
}
|
||||
}
|
||||
if (waitTimeout(isBusyFifoRead)) {
|
||||
return sdError(SD_CARD_ERROR_READ_FIFO);
|
||||
}
|
||||
for (uint32_t iw = 0; iw < 512 / (4 * FIFO_WML); iw++) {
|
||||
while (0 == (SDHC_PRSSTAT & SDHC_PRSSTAT_BREN)) {
|
||||
}
|
||||
for (uint32_t i = 0; i < FIFO_WML; i++) {
|
||||
p32[i] = SDHC_DATPORT;
|
||||
}
|
||||
p32 += FIFO_WML;
|
||||
}
|
||||
if (waitTimeout(isBusyTransferComplete)) {
|
||||
return sdError(SD_CARD_ERROR_READ_TIMEOUT);
|
||||
}
|
||||
m_irqstat = SDHC_IRQSTAT;
|
||||
SDHC_IRQSTAT = m_irqstat;
|
||||
return (m_irqstat & SDHC_IRQSTAT_TC) && !(m_irqstat & SDHC_IRQSTAT_ERROR);
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdioCard::readOCR(uint32_t* ocr) {
|
||||
*ocr = m_ocr;
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdioCard::readStart(uint32_t lba) {
|
||||
// K66/K65 Errata - SDHC: Does not support Infinite Block Transfer Mode.
|
||||
return sdError(SD_CARD_ERROR_FUNCTION_NOT_SUPPORTED);
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
// SDHC will do Auto CMD12 after count blocks.
|
||||
bool SdioCard::readStart(uint32_t lba, uint32_t count) {
|
||||
DBG_IRQSTAT();
|
||||
if (count > 0XFFFF) {
|
||||
return sdError(SD_CARD_ERROR_READ_START);
|
||||
}
|
||||
if (yieldTimeout(isBusyCMD13)) {
|
||||
return sdError(SD_CARD_ERROR_CMD13);
|
||||
}
|
||||
if (count > 1) {
|
||||
SDHC_PROCTL |= SDHC_PROCTL_SABGREQ;
|
||||
}
|
||||
SDHC_BLKATTR = SDHC_BLKATTR_BLKCNT(count) | SDHC_BLKATTR_BLKSIZE(512);
|
||||
if (!cardCommand(CMD18_PGM_XFERTYP, m_highCapacity ? lba : 512 * lba)) {
|
||||
return sdError(SD_CARD_ERROR_CMD18);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdioCard::readStop() {
|
||||
return transferStop();
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdioCard::syncBlocks() {
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
uint8_t SdioCard::type() {
|
||||
return m_version2 ? m_highCapacity ? SD_CARD_TYPE_SDHC : SD_CARD_TYPE_SD2 : SD_CARD_TYPE_SD1;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdioCard::writeBlock(uint32_t lba, const uint8_t* buf) {
|
||||
uint8_t* ptr;
|
||||
uint8_t aligned[512];
|
||||
if (3 & (uint32_t)buf) {
|
||||
ptr = aligned;
|
||||
memcpy(aligned, buf, 512);
|
||||
} else {
|
||||
ptr = const_cast<uint8_t*>(buf);
|
||||
}
|
||||
if (!rdWrBlocks(CMD24_DMA_XFERTYP, lba, ptr, 1)) {
|
||||
return sdError(SD_CARD_ERROR_CMD24);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdioCard::writeBlocks(uint32_t lba, const uint8_t* buf, size_t n) {
|
||||
uint8_t* ptr = const_cast<uint8_t*>(buf);
|
||||
if (3 & (uint32_t)ptr) {
|
||||
for (size_t i = 0; i < n; i++, lba++, ptr += 512) {
|
||||
if (!writeBlock(lba, ptr)) {
|
||||
return false; // writeBlock will set errorCode.
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
if (!rdWrBlocks(CMD25_DMA_XFERTYP, lba, ptr, n)) {
|
||||
return sdError(SD_CARD_ERROR_CMD25);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdioCard::writeData(const uint8_t* src) {
|
||||
DBG_IRQSTAT();
|
||||
const uint32_t* p32 = reinterpret_cast<const uint32_t*>(src);
|
||||
|
||||
if (!(SDHC_PRSSTAT & SDHC_PRSSTAT_WTA)) {
|
||||
SDHC_PROCTL &= ~SDHC_PROCTL_SABGREQ;
|
||||
// Don't stop at block gap if last block. Allows auto CMD12.
|
||||
if ((SDHC_BLKATTR & 0XFFFF0000) == 0X10000) {
|
||||
SDHC_PROCTL |= SDHC_PROCTL_CREQ;
|
||||
} else {
|
||||
SDHC_PROCTL |= SDHC_PROCTL_CREQ;
|
||||
SDHC_PROCTL |= SDHC_PROCTL_SABGREQ;
|
||||
}
|
||||
}
|
||||
if (waitTimeout(isBusyFifoWrite)) {
|
||||
return sdError(SD_CARD_ERROR_WRITE_FIFO);
|
||||
}
|
||||
for (uint32_t iw = 0; iw < 512 / (4 * FIFO_WML); iw++) {
|
||||
while (0 == (SDHC_PRSSTAT & SDHC_PRSSTAT_BWEN)) {
|
||||
}
|
||||
for (uint32_t i = 0; i < FIFO_WML; i++) {
|
||||
SDHC_DATPORT = p32[i];
|
||||
}
|
||||
p32 += FIFO_WML;
|
||||
}
|
||||
if (waitTimeout(isBusyTransferComplete)) {
|
||||
return sdError(SD_CARD_ERROR_WRITE_TIMEOUT);
|
||||
}
|
||||
m_irqstat = SDHC_IRQSTAT;
|
||||
SDHC_IRQSTAT = m_irqstat;
|
||||
return (m_irqstat & SDHC_IRQSTAT_TC) && !(m_irqstat & SDHC_IRQSTAT_ERROR);
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdioCard::writeStart(uint32_t lba) {
|
||||
// K66/K65 Errata - SDHC: Does not support Infinite Block Transfer Mode.
|
||||
return sdError(SD_CARD_ERROR_FUNCTION_NOT_SUPPORTED);
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
// SDHC will do Auto CMD12 after count blocks.
|
||||
bool SdioCard::writeStart(uint32_t lba, uint32_t count) {
|
||||
if (count > 0XFFFF) {
|
||||
return sdError(SD_CARD_ERROR_WRITE_START);
|
||||
}
|
||||
DBG_IRQSTAT();
|
||||
if (yieldTimeout(isBusyCMD13)) {
|
||||
return sdError(SD_CARD_ERROR_CMD13);
|
||||
}
|
||||
if (count > 1) {
|
||||
SDHC_PROCTL |= SDHC_PROCTL_SABGREQ;
|
||||
}
|
||||
SDHC_BLKATTR = SDHC_BLKATTR_BLKCNT(count) | SDHC_BLKATTR_BLKSIZE(512);
|
||||
|
||||
if (!cardCommand(CMD25_PGM_XFERTYP, m_highCapacity ? lba : 512 * lba)) {
|
||||
return sdError(SD_CARD_ERROR_CMD25);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
bool SdioCard::writeStop() {
|
||||
return transferStop();
|
||||
}
|
||||
#endif // defined(__MK64FX512__) || defined(__MK66FX1M0__)
|
428
Repetier-Firmware 1.0.3/Repetier/src/SdFat/SdFat.h
Normal file
428
Repetier-Firmware 1.0.3/Repetier/src/SdFat/SdFat.h
Normal file
@ -0,0 +1,428 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef SdFat_h
|
||||
#define SdFat_h
|
||||
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wunused-variable"
|
||||
#pragma GCC diagnostic ignored "-Wunused-parameter"
|
||||
/**
|
||||
* \file
|
||||
* \brief SdFat class
|
||||
*/
|
||||
#include "SysCall.h"
|
||||
#include "BlockDriver.h"
|
||||
#include "FatLib/FatLib.h"
|
||||
#include "SdCard/SdioCard.h"
|
||||
#if INCLUDE_SDIOS
|
||||
#include "sdios.h"
|
||||
#endif // INCLUDE_SDIOS
|
||||
//------------------------------------------------------------------------------
|
||||
/** SdFat version */
|
||||
#define SD_FAT_VERSION "1.0.7"
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class SdBaseFile
|
||||
* \brief Class for backward compatibility.
|
||||
*/
|
||||
class SdBaseFile : public FatFile {
|
||||
public:
|
||||
SdBaseFile() {}
|
||||
/** Create a file object and open it in the current working directory.
|
||||
*
|
||||
* \param[in] path A path for a file to be opened.
|
||||
*
|
||||
* \param[in] oflag Values for \a oflag are constructed by a
|
||||
* bitwise-inclusive OR of open flags. see
|
||||
* FatFile::open(FatFile*, const char*, uint8_t).
|
||||
*/
|
||||
SdBaseFile(const char* path, uint8_t oflag)
|
||||
: FatFile(path, oflag) {}
|
||||
};
|
||||
//-----------------------------------------------------------------------------
|
||||
#if ENABLE_ARDUINO_FEATURES
|
||||
/**
|
||||
* \class SdFile
|
||||
* \brief Class for backward compatibility.
|
||||
*/
|
||||
class SdFile : public PrintFile {
|
||||
public:
|
||||
SdFile() {}
|
||||
/** Create a file object and open it in the current working directory.
|
||||
*
|
||||
* \param[in] path A path for a file to be opened.
|
||||
*
|
||||
* \param[in] oflag Values for \a oflag are constructed by a
|
||||
* bitwise-inclusive OR of open flags. see
|
||||
* FatFile::open(FatFile*, const char*, uint8_t).
|
||||
*/
|
||||
SdFile(const char* path, uint8_t oflag)
|
||||
: PrintFile(path, oflag) {}
|
||||
};
|
||||
#endif // #if ENABLE_ARDUINO_FEATURES
|
||||
//-----------------------------------------------------------------------------
|
||||
/**
|
||||
* \class SdFileSystem
|
||||
* \brief Virtual base class for %SdFat library.
|
||||
*/
|
||||
template <class SdDriverClass>
|
||||
class SdFileSystem : public FatFileSystem {
|
||||
public:
|
||||
/** Initialize file system.
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool begin() {
|
||||
return FatFileSystem::begin(&m_card);
|
||||
}
|
||||
/** \return Pointer to SD card object */
|
||||
SdDriverClass* card() {
|
||||
m_card.syncBlocks();
|
||||
return &m_card;
|
||||
}
|
||||
/** %Print any SD error code to Serial and halt. */
|
||||
void errorHalt() {
|
||||
errorPrint();
|
||||
SysCall::halt();
|
||||
}
|
||||
/** %Print msg, any SD error code and halt.
|
||||
*
|
||||
* \param[in] msg Message to print.
|
||||
*/
|
||||
void errorHalt(char const* msg) {
|
||||
errorHalt(msg);
|
||||
}
|
||||
/** %Print any SD error code to Serial */
|
||||
void errorPrint() {
|
||||
if (!cardErrorCode()) {
|
||||
return;
|
||||
}
|
||||
Com::printF(PSTR("SD errorCode: 0X"));
|
||||
Com::print((int32_t)cardErrorCode());
|
||||
Com::printF(PSTR(",0X"));
|
||||
Com::print((int32_t)cardErrorData());
|
||||
Com::println();
|
||||
}
|
||||
/** %Print msg, any SD error code.
|
||||
*
|
||||
* \param[in] msg Message to print.
|
||||
*/
|
||||
void errorPrint(const char* msg) {
|
||||
Com::printF(PSTR("error: "));
|
||||
Com::printFLN(msg);
|
||||
errorPrint();
|
||||
}
|
||||
/** %Print any SD error code and halt. */
|
||||
void initErrorHalt() {
|
||||
initErrorPrint();
|
||||
SysCall::halt();
|
||||
}
|
||||
/**Print message, error details, and halt after begin() fails.
|
||||
*
|
||||
* \param[in] msg Message to print.
|
||||
*/
|
||||
void initErrorHalt(char const* msg) {
|
||||
initErrorHalt(msg);
|
||||
}
|
||||
|
||||
/** Print error details after begin() fails. */
|
||||
void initErrorPrint() {
|
||||
if (cardErrorCode()) {
|
||||
Com::printFLN(PSTR("Can't access SD card. Do not reformat."));
|
||||
if (cardErrorCode() == SD_CARD_ERROR_CMD0) {
|
||||
Com::printFLN(PSTR("No card, wrong chip select pin, or SPI problem?"));
|
||||
}
|
||||
errorPrint();
|
||||
} else if (vol()->fatType() == 0) {
|
||||
Com::printFLN(PSTR("Invalid format, reformat SD."));
|
||||
} else if (!vwd()->isOpen()) {
|
||||
Com::printFLN(PSTR("Can't open root directory."));
|
||||
} else {
|
||||
Com::printFLN(PSTR("No error found."));
|
||||
}
|
||||
}
|
||||
/**Print message and error details and halt after begin() fails.
|
||||
*
|
||||
* \param[in] msg Message to print.
|
||||
*/
|
||||
void initErrorPrint(char const* msg) {
|
||||
Com::printFLN(msg);
|
||||
initErrorPrint();
|
||||
}
|
||||
#if defined(ARDUINO) || defined(DOXYGEN)
|
||||
/** %Print msg, any SD error code, and halt.
|
||||
*
|
||||
* \param[in] msg Message to print.
|
||||
*/
|
||||
void errorHalt(const __FlashStringHelper* msg) {
|
||||
errorPrint(reinterpret_cast<const char*>(msg));
|
||||
SysCall::halt();
|
||||
}
|
||||
|
||||
/** %Print msg, any SD error code.
|
||||
*
|
||||
* \param[in] msg Message to print.
|
||||
*/
|
||||
void errorPrint(const __FlashStringHelper* msg) {
|
||||
Com::printF(PSTR("error: "));
|
||||
Com::printFLN(reinterpret_cast<const char*>(msg));
|
||||
errorPrint();
|
||||
}
|
||||
/**Print message, error details, and halt after begin() fails.
|
||||
*
|
||||
* \param[in] msg Message to print.
|
||||
*/
|
||||
void initErrorHalt(const __FlashStringHelper* msg) {
|
||||
Com::printFLN(reinterpret_cast<const char*>(msg));
|
||||
initErrorHalt();
|
||||
}
|
||||
/**Print message and error details and halt after begin() fails.
|
||||
*
|
||||
* \param[in] msg Message to print.
|
||||
*/
|
||||
void initErrorPrint(const __FlashStringHelper* msg) {
|
||||
Com::printFLN(reinterpret_cast<const char*>(msg));
|
||||
initErrorPrint();
|
||||
}
|
||||
#endif // defined(ARDUINO) || defined(DOXYGEN)
|
||||
/** \return The card error code */
|
||||
uint8_t cardErrorCode() {
|
||||
return m_card.errorCode();
|
||||
}
|
||||
/** \return the card error data */
|
||||
uint32_t cardErrorData() {
|
||||
return m_card.errorData();
|
||||
}
|
||||
|
||||
protected:
|
||||
SdDriverClass m_card;
|
||||
};
|
||||
//==============================================================================
|
||||
/**
|
||||
* \class SdFat
|
||||
* \brief Main file system class for %SdFat library.
|
||||
*/
|
||||
class SdFat : public SdFileSystem<SdSpiCard> {
|
||||
public:
|
||||
#if IMPLEMENT_SPI_PORT_SELECTION || defined(DOXYGEN)
|
||||
SdFat() {
|
||||
m_spi.setPort(0);
|
||||
}
|
||||
/** Constructor with SPI port selection.
|
||||
* \param[in] spiPort SPI port number.
|
||||
*/
|
||||
explicit SdFat(uint8_t spiPort) {
|
||||
m_spi.setPort(spiPort);
|
||||
}
|
||||
#endif // IMPLEMENT_SPI_PORT_SELECTION
|
||||
/** Initialize SD card and file system.
|
||||
*
|
||||
* \param[in] csPin SD card chip select pin.
|
||||
* \param[in] spiSettings SPI speed, mode, and bit order.
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool begin(uint8_t csPin = SS, SPISettings spiSettings = SPI_FULL_SPEED) {
|
||||
return m_card.begin(&m_spi, csPin, spiSettings) && SdFileSystem::begin();
|
||||
}
|
||||
/** Initialize SD card for diagnostic use only.
|
||||
*
|
||||
* \param[in] csPin SD card chip select pin.
|
||||
* \param[in] settings SPI speed, mode, and bit order.
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool cardBegin(uint8_t csPin = SS, SPISettings settings = SPI_FULL_SPEED) {
|
||||
return m_card.begin(&m_spi, csPin, settings);
|
||||
}
|
||||
/** Initialize file system for diagnostic use only.
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool fsBegin() {
|
||||
return FatFileSystem::begin(card());
|
||||
}
|
||||
|
||||
private:
|
||||
SdFatSpiDriver m_spi;
|
||||
};
|
||||
//==============================================================================
|
||||
#if ENABLE_SDIO_CLASS || defined(DOXYGEN)
|
||||
/**
|
||||
* \class SdFatSdio
|
||||
* \brief SdFat class using SDIO.
|
||||
*/
|
||||
class SdFatSdio : public SdFileSystem<SdioCard> {
|
||||
public:
|
||||
/** Initialize SD card and file system.
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool begin() {
|
||||
return m_card.begin() && SdFileSystem::begin();
|
||||
}
|
||||
/** Initialize SD card for diagnostic use only.
|
||||
*
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool cardBegin() {
|
||||
return m_card.begin();
|
||||
}
|
||||
/** Initialize file system for diagnostic use only.
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool fsBegin() {
|
||||
return SdFileSystem::begin();
|
||||
}
|
||||
};
|
||||
#if ENABLE_SDIOEX_CLASS || defined(DOXYGEN)
|
||||
//-----------------------------------------------------------------------------
|
||||
/**
|
||||
* \class SdFatSdioEX
|
||||
* \brief SdFat class using SDIO.
|
||||
*/
|
||||
class SdFatSdioEX : public SdFileSystem<SdioCardEX> {
|
||||
public:
|
||||
/** Initialize SD card and file system.
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool begin() {
|
||||
return m_card.begin() && SdFileSystem::begin();
|
||||
}
|
||||
/** \return Pointer to SD card object */
|
||||
SdioCardEX* card() {
|
||||
return &m_card;
|
||||
}
|
||||
/** Initialize SD card for diagnostic use only.
|
||||
*
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool cardBegin() {
|
||||
return m_card.begin();
|
||||
}
|
||||
/** Initialize file system for diagnostic use only.
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool fsBegin() {
|
||||
return SdFileSystem::begin();
|
||||
}
|
||||
};
|
||||
#endif // ENABLE_SDIOEX_CLASS || defined(DOXYGEN)
|
||||
#endif // ENABLE_SDIO_CLASS || defined(DOXYGEN)
|
||||
//=============================================================================
|
||||
#if ENABLE_SOFTWARE_SPI_CLASS || defined(DOXYGEN)
|
||||
/**
|
||||
* \class SdFatSoftSpi
|
||||
* \brief SdFat class using software SPI.
|
||||
*/
|
||||
template <uint8_t MisoPin, uint8_t MosiPin, uint8_t SckPin>
|
||||
class SdFatSoftSpi : public SdFileSystem<SdSpiCard> {
|
||||
public:
|
||||
/** Initialize SD card and file system.
|
||||
*
|
||||
* \param[in] csPin SD card chip select pin.
|
||||
* \param[in] spiSettings ignored for software SPI..
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool begin(uint8_t csPin = SS, SPISettings spiSettings = SPI_FULL_SPEED) {
|
||||
return m_card.begin(&m_spi, csPin, spiSettings) && SdFileSystem::begin();
|
||||
}
|
||||
|
||||
private:
|
||||
SdSpiSoftDriver<MisoPin, MosiPin, SckPin> m_spi;
|
||||
};
|
||||
#endif // #if ENABLE_SOFTWARE_SPI_CLASS || defined(DOXYGEN)
|
||||
//==============================================================================
|
||||
#if ENABLE_EXTENDED_TRANSFER_CLASS || defined(DOXYGEN)
|
||||
/**
|
||||
* \class SdFatEX
|
||||
* \brief SdFat class with extended SD I/O.
|
||||
*/
|
||||
class SdFatEX : public SdFileSystem<SdSpiCardEX> {
|
||||
public:
|
||||
#if IMPLEMENT_SPI_PORT_SELECTION || defined(DOXYGEN)
|
||||
SdFatEX() {
|
||||
m_spi.setPort(0);
|
||||
}
|
||||
/** Constructor with SPI port selection.
|
||||
* \param[in] spiPort SPI port number.
|
||||
*/
|
||||
explicit SdFatEX(uint8_t spiPort) {
|
||||
m_spi.setPort(spiPort);
|
||||
}
|
||||
#endif // IMPLEMENT_SPI_PORT_SELECTION
|
||||
/** Initialize SD card and file system.
|
||||
*
|
||||
* \param[in] csPin SD card chip select pin.
|
||||
* \param[in] spiSettings SPI speed, mode, and bit order.
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool begin(uint8_t csPin = SS, SPISettings spiSettings = SPI_FULL_SPEED) {
|
||||
return m_card.begin(&m_spi, csPin, spiSettings) && SdFileSystem::begin();
|
||||
}
|
||||
|
||||
private:
|
||||
SdFatSpiDriver m_spi;
|
||||
};
|
||||
//==============================================================================
|
||||
#if ENABLE_SOFTWARE_SPI_CLASS || defined(DOXYGEN)
|
||||
/**
|
||||
* \class SdFatSoftSpiEX
|
||||
* \brief SdFat class using software SPI and extended SD I/O.
|
||||
*/
|
||||
template <uint8_t MisoPin, uint8_t MosiPin, uint8_t SckPin>
|
||||
class SdFatSoftSpiEX : public SdFileSystem<SdSpiCardEX> {
|
||||
public:
|
||||
/** Initialize SD card and file system.
|
||||
*
|
||||
* \param[in] csPin SD card chip select pin.
|
||||
* \param[in] spiSettings ignored for software SPI.
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool begin(uint8_t csPin = SS, SPISettings spiSettings = SPI_FULL_SPEED) {
|
||||
return m_card.begin(&m_spi, csPin, spiSettings) && SdFileSystem::begin();
|
||||
}
|
||||
|
||||
private:
|
||||
SdSpiSoftDriver<MisoPin, MosiPin, SckPin> m_spi;
|
||||
};
|
||||
#endif // #if ENABLE_SOFTWARE_SPI_CLASS || defined(DOXYGEN)
|
||||
#endif // ENABLE_EXTENDED_TRANSFER_CLASS || defined(DOXYGEN)
|
||||
//=============================================================================
|
||||
/**
|
||||
* \class Sd2Card
|
||||
* \brief Raw access to SD and SDHC card using default SPI library.
|
||||
*/
|
||||
class Sd2Card : public SdSpiCard {
|
||||
public:
|
||||
/** Initialize the SD card.
|
||||
* \param[in] csPin SD chip select pin.
|
||||
* \param[in] settings SPI speed, mode, and bit order.
|
||||
* \return true for success else false.
|
||||
*/
|
||||
bool begin(uint8_t csPin = SS, SPISettings settings = SD_SCK_MHZ(50)) {
|
||||
return SdSpiCard::begin(&m_spi, csPin, settings);
|
||||
}
|
||||
|
||||
private:
|
||||
SdFatSpiDriver m_spi;
|
||||
};
|
||||
#pragma GCC diagnostic pop
|
||||
#endif // SdFat_h
|
216
Repetier-Firmware 1.0.3/Repetier/src/SdFat/SdFatConfig.h
Normal file
216
Repetier-Firmware 1.0.3/Repetier/src/SdFat/SdFatConfig.h
Normal file
@ -0,0 +1,216 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
/**
|
||||
* \file
|
||||
* \brief configuration definitions
|
||||
*/
|
||||
#ifndef SdFatConfig_h
|
||||
#define SdFatConfig_h
|
||||
#include <Arduino.h>
|
||||
#include <stdint.h>
|
||||
#ifdef __AVR__
|
||||
#include <avr/io.h>
|
||||
#endif // __AVR__
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Set INCLUDE_SDIOS nonzero to include sdios.h in SdFat.h.
|
||||
* sdios.h provides C++ style IO Streams.
|
||||
*/
|
||||
#define INCLUDE_SDIOS 1
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Set USE_LONG_FILE_NAMES nonzero to use long file names (LFN).
|
||||
* Long File Name are limited to a maximum length of 255 characters.
|
||||
*
|
||||
* This implementation allows 7-bit characters in the range
|
||||
* 0X20 to 0X7E except the following characters are not allowed:
|
||||
*
|
||||
* < (less than)
|
||||
* > (greater than)
|
||||
* : (colon)
|
||||
* " (double quote)
|
||||
* / (forward slash)
|
||||
* \ (backslash)
|
||||
* | (vertical bar or pipe)
|
||||
* ? (question mark)
|
||||
* * (asterisk)
|
||||
*
|
||||
*/
|
||||
#define USE_LONG_FILE_NAMES 1
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* If the symbol ENABLE_EXTENDED_TRANSFER_CLASS is nonzero, the class SdFatEX
|
||||
* will be defined. If the symbol ENABLE_SOFTWARE_SPI_CLASS is also nonzero,
|
||||
* the class SdFatSoftSpiEX will be defined.
|
||||
*
|
||||
* These classes used extended multi-block SD I/O for better performance.
|
||||
* the SPI bus may not be shared with other devices in this mode.
|
||||
*/
|
||||
#define ENABLE_EXTENDED_TRANSFER_CLASS 0
|
||||
//-----------------------------------------------------------------------------
|
||||
/**
|
||||
* If the symbol USE_STANDARD_SPI_LIBRARY is nonzero, the classes SdFat and
|
||||
* SdFatEX use the standard Arduino SPI.h library. If USE_STANDARD_SPI_LIBRARY
|
||||
* is zero, an optimized custom SPI driver is used if it exists.
|
||||
*/
|
||||
#define USE_STANDARD_SPI_LIBRARY 0
|
||||
//-----------------------------------------------------------------------------
|
||||
/**
|
||||
* If the symbol ENABLE_SOFTWARE_SPI_CLASS is nonzero, the class SdFatSoftSpi
|
||||
* will be defined. If ENABLE_EXTENDED_TRANSFER_CLASS is also nonzero,
|
||||
* the class SdFatSoftSpiEX will be defined.
|
||||
*/
|
||||
#ifndef ENABLE_SOFTWARE_SPI_CLASS
|
||||
#define ENABLE_SOFTWARE_SPI_CLASS 0
|
||||
#endif
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* If CHECK_FLASH_PROGRAMMING is zero, overlap of single sector flash
|
||||
* programming and other operations will be allowed for faster write
|
||||
* performance.
|
||||
*
|
||||
* Some cards will not sleep in low power mode unless CHECK_FLASH_PROGRAMMING
|
||||
* is non-zero.
|
||||
*/
|
||||
#define CHECK_FLASH_PROGRAMMING 1
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Set MAINTAIN_FREE_CLUSTER_COUNT nonzero to keep the count of free clusters
|
||||
* updated. This will increase the speed of the freeClusterCount() call
|
||||
* after the first call. Extra flash will be required.
|
||||
*/
|
||||
#define MAINTAIN_FREE_CLUSTER_COUNT 0
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* To enable SD card CRC checking set USE_SD_CRC nonzero.
|
||||
*
|
||||
* Set USE_SD_CRC to 1 to use a smaller CRC-CCITT function. This function
|
||||
* is slower for AVR but may be fast for ARM and other processors.
|
||||
*
|
||||
* Set USE_SD_CRC to 2 to used a larger table driven CRC-CCITT function. This
|
||||
* function is faster for AVR but may be slower for ARM and other processors.
|
||||
*/
|
||||
#define USE_SD_CRC 0
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Handle Watchdog Timer for WiFi modules.
|
||||
*
|
||||
* Yield will be called before accessing the SPI bus if it has been more
|
||||
* than WDT_YIELD_TIME_MICROS microseconds since the last yield call by SdFat.
|
||||
*/
|
||||
#if defined(PLATFORM_ID) || defined(ESP8266)
|
||||
// If Particle device or ESP8266 call yield.
|
||||
#define WDT_YIELD_TIME_MICROS 100000
|
||||
#else
|
||||
#define WDT_YIELD_TIME_MICROS 0
|
||||
#endif
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Set FAT12_SUPPORT nonzero to enable use if FAT12 volumes.
|
||||
* FAT12 has not been well tested and requires additional flash.
|
||||
*/
|
||||
#define FAT12_SUPPORT 0
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Set DESTRUCTOR_CLOSES_FILE nonzero to close a file in its destructor.
|
||||
*
|
||||
* Causes use of lots of heap in ARM.
|
||||
*/
|
||||
#define DESTRUCTOR_CLOSES_FILE 0
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Call flush for endl if ENDL_CALLS_FLUSH is nonzero
|
||||
*
|
||||
* The standard for iostreams is to call flush. This is very costly for
|
||||
* SdFat. Each call to flush causes 2048 bytes of I/O to the SD.
|
||||
*
|
||||
* SdFat has a single 512 byte buffer for SD I/O so it must write the current
|
||||
* data block to the SD, read the directory block from the SD, update the
|
||||
* directory entry, write the directory block to the SD and read the data
|
||||
* block back into the buffer.
|
||||
*
|
||||
* The SD flash memory controller is not designed for this many rewrites
|
||||
* so performance may be reduced by more than a factor of 100.
|
||||
*
|
||||
* If ENDL_CALLS_FLUSH is zero, you must call flush and/or close to force
|
||||
* all data to be written to the SD.
|
||||
*/
|
||||
#define ENDL_CALLS_FLUSH 0
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Set USE_SEPARATE_FAT_CACHE nonzero to use a second 512 byte cache
|
||||
* for FAT table entries. This improves performance for large writes
|
||||
* that are not a multiple of 512 bytes.
|
||||
*/
|
||||
#ifdef __arm__
|
||||
#define USE_SEPARATE_FAT_CACHE 1
|
||||
#else // __arm__
|
||||
#define USE_SEPARATE_FAT_CACHE 0
|
||||
#endif // __arm__
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Set USE_MULTI_BLOCK_IO nonzero to use multi-block SD read/write.
|
||||
*
|
||||
* Don't use mult-block read/write on small AVR boards.
|
||||
*/
|
||||
#if defined(RAMEND) && RAMEND < 3000
|
||||
#define USE_MULTI_BLOCK_IO 0
|
||||
#else // RAMEND
|
||||
#define USE_MULTI_BLOCK_IO 1
|
||||
#endif // RAMEND
|
||||
//-----------------------------------------------------------------------------
|
||||
/** Enable SDIO driver if available. */
|
||||
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)
|
||||
#define ENABLE_SDIO_CLASS 1
|
||||
#define ENABLE_SDIOEX_CLASS 1
|
||||
#else // ENABLE_SDIO_CLASS
|
||||
#define ENABLE_SDIO_CLASS 0
|
||||
#endif // ENABLE_SDIO_CLASS
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Determine the default SPI configuration.
|
||||
*/
|
||||
#if defined(__STM32F1__) || defined(__STM32F4__)
|
||||
// has multiple SPI ports
|
||||
#define SD_HAS_CUSTOM_SPI 2
|
||||
#elif defined(__AVR__) \
|
||||
|| defined(__SAM3X8E__) || defined(__SAM3X8H__) \
|
||||
|| (defined(__arm__) && defined(CORE_TEENSY)) \
|
||||
|| defined(ESP8266)
|
||||
#define SD_HAS_CUSTOM_SPI 1
|
||||
#else // SD_HAS_CUSTOM_SPI
|
||||
// Use standard SPI library.
|
||||
#define SD_HAS_CUSTOM_SPI 0
|
||||
#endif // SD_HAS_CUSTOM_SPI
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* Check if API to select HW SPI port is needed.
|
||||
*/
|
||||
#if (USE_STANDARD_SPI_LIBRARY || SD_HAS_CUSTOM_SPI < 2)
|
||||
#define IMPLEMENT_SPI_PORT_SELECTION 0
|
||||
#else // USE_STANDARD_SPI_LIBRARY
|
||||
#define IMPLEMENT_SPI_PORT_SELECTION 1
|
||||
#endif // USE_STANDARD_SPI_LIBRARY
|
||||
#endif // SdFatConfig_h
|
@ -0,0 +1,386 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
/**
|
||||
* @file
|
||||
* @brief Fast Digital Pin functions
|
||||
*
|
||||
* @defgroup digitalPin Fast Pin I/O
|
||||
* @details Fast Digital I/O functions and template class.
|
||||
* @{
|
||||
*/
|
||||
#ifndef DigitalPin_h
|
||||
#define DigitalPin_h
|
||||
#if defined(__AVR__) || defined(DOXYGEN)
|
||||
#include <avr/io.h>
|
||||
/** GpioPinMap type */
|
||||
struct GpioPinMap_t {
|
||||
volatile uint8_t* pin; /**< address of PIN for this pin */
|
||||
volatile uint8_t* ddr; /**< address of DDR for this pin */
|
||||
volatile uint8_t* port; /**< address of PORT for this pin */
|
||||
uint8_t mask; /**< bit mask for this pin */
|
||||
};
|
||||
|
||||
/** Initializer macro. */
|
||||
#define GPIO_PIN(reg, bit) {&PIN##reg, &DDR##reg, &PORT##reg, 1 << bit}
|
||||
|
||||
// Include pin map for current board.
|
||||
#include "boards/GpioPinMap.h"
|
||||
//------------------------------------------------------------------------------
|
||||
/** generate bad pin number error */
|
||||
void badPinNumber(void)
|
||||
__attribute__((error("Pin number is too large or not a constant")));
|
||||
//------------------------------------------------------------------------------
|
||||
/** Check for valid pin number
|
||||
* @param[in] pin Number of pin to be checked.
|
||||
*/
|
||||
static inline __attribute__((always_inline))
|
||||
void badPinCheck(uint8_t pin) {
|
||||
if (!__builtin_constant_p(pin) || pin >= NUM_DIGITAL_PINS) {
|
||||
badPinNumber();
|
||||
}
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** DDR register address
|
||||
* @param[in] pin Arduino pin number
|
||||
* @return register address
|
||||
*/
|
||||
static inline __attribute__((always_inline))
|
||||
volatile uint8_t* ddrReg(uint8_t pin) {
|
||||
badPinCheck(pin);
|
||||
return GpioPinMap[pin].ddr;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Bit mask for pin
|
||||
* @param[in] pin Arduino pin number
|
||||
* @return mask
|
||||
*/
|
||||
static inline __attribute__((always_inline))
|
||||
uint8_t pinMask(uint8_t pin) {
|
||||
badPinCheck(pin);
|
||||
return GpioPinMap[pin].mask;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** PIN register address
|
||||
* @param[in] pin Arduino pin number
|
||||
* @return register address
|
||||
*/
|
||||
static inline __attribute__((always_inline))
|
||||
volatile uint8_t* pinReg(uint8_t pin) {
|
||||
badPinCheck(pin);
|
||||
return GpioPinMap[pin].pin;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** PORT register address
|
||||
* @param[in] pin Arduino pin number
|
||||
* @return register address
|
||||
*/
|
||||
static inline __attribute__((always_inline))
|
||||
volatile uint8_t* portReg(uint8_t pin) {
|
||||
badPinCheck(pin);
|
||||
return GpioPinMap[pin].port;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Fast write helper.
|
||||
* @param[in] address I/O register address
|
||||
* @param[in] mask bit mask for pin
|
||||
* @param[in] level value for bit
|
||||
*/
|
||||
static inline __attribute__((always_inline))
|
||||
void fastBitWriteSafe(volatile uint8_t* address, uint8_t mask, bool level) {
|
||||
uint8_t s;
|
||||
if (address > reinterpret_cast<uint8_t*>(0X3F)) {
|
||||
s = SREG;
|
||||
cli();
|
||||
}
|
||||
if (level) {
|
||||
*address |= mask;
|
||||
} else {
|
||||
*address &= ~mask;
|
||||
}
|
||||
if (address > reinterpret_cast<uint8_t*>(0X3F)) {
|
||||
SREG = s;
|
||||
}
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Read pin value.
|
||||
* @param[in] pin Arduino pin number
|
||||
* @return value read
|
||||
*/
|
||||
static inline __attribute__((always_inline))
|
||||
bool fastDigitalRead(uint8_t pin) {
|
||||
return *pinReg(pin) & pinMask(pin);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Toggle a pin.
|
||||
* @param[in] pin Arduino pin number
|
||||
*
|
||||
* If the pin is in output mode toggle the pin level.
|
||||
* If the pin is in input mode toggle the state of the 20K pullup.
|
||||
*/
|
||||
static inline __attribute__((always_inline))
|
||||
void fastDigitalToggle(uint8_t pin) {
|
||||
if (pinReg(pin) > reinterpret_cast<uint8_t*>(0X3F)) {
|
||||
// must write bit to high address port
|
||||
*pinReg(pin) = pinMask(pin);
|
||||
} else {
|
||||
// will compile to sbi and PIN register will not be read.
|
||||
*pinReg(pin) |= pinMask(pin);
|
||||
}
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Set pin value.
|
||||
* @param[in] pin Arduino pin number
|
||||
* @param[in] level value to write
|
||||
*/
|
||||
static inline __attribute__((always_inline))
|
||||
void fastDigitalWrite(uint8_t pin, bool level) {
|
||||
fastBitWriteSafe(portReg(pin), pinMask(pin), level);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Write the DDR register.
|
||||
* @param[in] pin Arduino pin number
|
||||
* @param[in] level value to write
|
||||
*/
|
||||
static inline __attribute__((always_inline))
|
||||
void fastDdrWrite(uint8_t pin, bool level) {
|
||||
fastBitWriteSafe(ddrReg(pin), pinMask(pin), level);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Set pin mode.
|
||||
* @param[in] pin Arduino pin number
|
||||
* @param[in] mode INPUT, OUTPUT, or INPUT_PULLUP.
|
||||
*
|
||||
* The internal pullup resistors will be enabled if mode is INPUT_PULLUP
|
||||
* and disabled if the mode is INPUT.
|
||||
*/
|
||||
static inline __attribute__((always_inline))
|
||||
void fastPinMode(uint8_t pin, uint8_t mode) {
|
||||
fastDdrWrite(pin, mode == OUTPUT);
|
||||
if (mode != OUTPUT) {
|
||||
fastDigitalWrite(pin, mode == INPUT_PULLUP);
|
||||
}
|
||||
}
|
||||
#else // defined(__AVR__)
|
||||
#if defined(CORE_TEENSY)
|
||||
//------------------------------------------------------------------------------
|
||||
/** read pin value
|
||||
* @param[in] pin Arduino pin number
|
||||
* @return value read
|
||||
*/
|
||||
static inline __attribute__((always_inline))
|
||||
bool fastDigitalRead(uint8_t pin) {
|
||||
return *portInputRegister(pin);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Set pin value
|
||||
* @param[in] pin Arduino pin number
|
||||
* @param[in] level value to write
|
||||
*/
|
||||
static inline __attribute__((always_inline))
|
||||
void fastDigitalWrite(uint8_t pin, bool value) {
|
||||
if (value) {
|
||||
*portSetRegister(pin) = 1;
|
||||
} else {
|
||||
*portClearRegister(pin) = 1;
|
||||
}
|
||||
}
|
||||
#elif defined(__SAM3X8E__) || defined(__SAM3X8H__)
|
||||
//------------------------------------------------------------------------------
|
||||
/** read pin value
|
||||
* @param[in] pin Arduino pin number
|
||||
* @return value read
|
||||
*/
|
||||
static inline __attribute__((always_inline))
|
||||
bool fastDigitalRead(uint8_t pin) {
|
||||
return g_APinDescription[pin].pPort->PIO_PDSR & g_APinDescription[pin].ulPin;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Set pin value
|
||||
* @param[in] pin Arduino pin number
|
||||
* @param[in] level value to write
|
||||
*/
|
||||
static inline __attribute__((always_inline))
|
||||
void fastDigitalWrite(uint8_t pin, bool value) {
|
||||
if (value) {
|
||||
g_APinDescription[pin].pPort->PIO_SODR = g_APinDescription[pin].ulPin;
|
||||
} else {
|
||||
g_APinDescription[pin].pPort->PIO_CODR = g_APinDescription[pin].ulPin;
|
||||
}
|
||||
}
|
||||
#elif defined(ESP8266)
|
||||
//------------------------------------------------------------------------------
|
||||
/** Set pin value
|
||||
* @param[in] pin Arduino pin number
|
||||
* @param[in] val value to write
|
||||
*/
|
||||
static inline __attribute__((always_inline))
|
||||
void fastDigitalWrite(uint8_t pin, uint8_t val) {
|
||||
if (pin < 16) {
|
||||
if (val) {
|
||||
GPOS = (1 << pin);
|
||||
} else {
|
||||
GPOC = (1 << pin);
|
||||
}
|
||||
} else if (pin == 16) {
|
||||
if (val) {
|
||||
GP16O |= 1;
|
||||
} else {
|
||||
GP16O &= ~1;
|
||||
}
|
||||
}
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Read pin value
|
||||
* @param[in] pin Arduino pin number
|
||||
* @return value read
|
||||
*/
|
||||
static inline __attribute__((always_inline))
|
||||
bool fastDigitalRead(uint8_t pin) {
|
||||
if (pin < 16) {
|
||||
return GPIP(pin);
|
||||
} else if (pin == 16) {
|
||||
return GP16I & 0x01;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
#else // CORE_TEENSY
|
||||
//------------------------------------------------------------------------------
|
||||
inline void fastDigitalWrite(uint8_t pin, bool value) {
|
||||
digitalWrite(pin, value);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
inline bool fastDigitalRead(uint8_t pin) {
|
||||
return digitalRead(pin);
|
||||
}
|
||||
#endif // CORE_TEENSY
|
||||
//------------------------------------------------------------------------------
|
||||
inline void fastDigitalToggle(uint8_t pin) {
|
||||
fastDigitalWrite(pin, !fastDigitalRead(pin));
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
inline void fastPinMode(uint8_t pin, uint8_t mode) {
|
||||
pinMode(pin, mode);
|
||||
}
|
||||
#endif // __AVR__
|
||||
//------------------------------------------------------------------------------
|
||||
/** set pin configuration
|
||||
* @param[in] pin Arduino pin number
|
||||
* @param[in] mode mode INPUT or OUTPUT.
|
||||
* @param[in] level If mode is output, set level high/low.
|
||||
* If mode is input, enable or disable the pin's 20K pullup.
|
||||
*/
|
||||
#define fastPinConfig(pin, mode, level)\
|
||||
{fastPinMode(pin, mode); fastDigitalWrite(pin, level);}
|
||||
//==============================================================================
|
||||
/**
|
||||
* @class DigitalPin
|
||||
* @brief Fast digital port I/O
|
||||
*/
|
||||
template<uint8_t PinNumber>
|
||||
class DigitalPin {
|
||||
public:
|
||||
//----------------------------------------------------------------------------
|
||||
/** Constructor */
|
||||
DigitalPin() {}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Asignment operator.
|
||||
* @param[in] value If true set the pin's level high else set the
|
||||
* pin's level low.
|
||||
*
|
||||
* @return This DigitalPin instance.
|
||||
*/
|
||||
inline DigitalPin & operator = (bool value) __attribute__((always_inline)) {
|
||||
write(value);
|
||||
return *this;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Parenthesis operator.
|
||||
* @return Pin's level
|
||||
*/
|
||||
inline operator bool () const __attribute__((always_inline)) {
|
||||
return read();
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Set pin configuration.
|
||||
* @param[in] mode: INPUT or OUTPUT.
|
||||
* @param[in] level If mode is OUTPUT, set level high/low.
|
||||
* If mode is INPUT, enable or disable the pin's 20K pullup.
|
||||
*/
|
||||
inline __attribute__((always_inline))
|
||||
void config(uint8_t mode, bool level) {
|
||||
fastPinConfig(PinNumber, mode, level);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/**
|
||||
* Set pin level high if output mode or enable 20K pullup if input mode.
|
||||
*/
|
||||
inline __attribute__((always_inline))
|
||||
void high() {write(true);}
|
||||
//----------------------------------------------------------------------------
|
||||
/**
|
||||
* Set pin level low if output mode or disable 20K pullup if input mode.
|
||||
*/
|
||||
inline __attribute__((always_inline))
|
||||
void low() {write(false);}
|
||||
//----------------------------------------------------------------------------
|
||||
/**
|
||||
* Set pin mode.
|
||||
* @param[in] mode: INPUT, OUTPUT, or INPUT_PULLUP.
|
||||
*
|
||||
* The internal pullup resistors will be enabled if mode is INPUT_PULLUP
|
||||
* and disabled if the mode is INPUT.
|
||||
*/
|
||||
inline __attribute__((always_inline))
|
||||
void mode(uint8_t mode) {
|
||||
fastPinMode(PinNumber, mode);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** @return Pin's level. */
|
||||
inline __attribute__((always_inline))
|
||||
bool read() const {
|
||||
return fastDigitalRead(PinNumber);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Toggle a pin.
|
||||
*
|
||||
* If the pin is in output mode toggle the pin's level.
|
||||
* If the pin is in input mode toggle the state of the 20K pullup.
|
||||
*/
|
||||
inline __attribute__((always_inline))
|
||||
void toggle() {
|
||||
fastDigitalToggle(PinNumber);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Write the pin's level.
|
||||
* @param[in] value If true set the pin's level high else set the
|
||||
* pin's level low.
|
||||
*/
|
||||
inline __attribute__((always_inline))
|
||||
void write(bool value) {
|
||||
fastDigitalWrite(PinNumber, value);
|
||||
}
|
||||
};
|
||||
#endif // DigitalPin_h
|
||||
/** @} */
|
@ -0,0 +1,79 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef SdSpiBaseDriver_h
|
||||
#define SdSpiBaseDriver_h
|
||||
/**
|
||||
* \class SdSpiBaseDriver
|
||||
* \brief SPI base driver.
|
||||
*/
|
||||
class SdSpiBaseDriver {
|
||||
public:
|
||||
/** Set SPI options for access to SD/SDHC cards.
|
||||
*
|
||||
*/
|
||||
virtual void activate() = 0;
|
||||
/** Initialize the SPI bus.
|
||||
*
|
||||
* \param[in] chipSelectPin SD card chip select pin.
|
||||
*/
|
||||
virtual void begin(uint8_t chipSelectPin) = 0;
|
||||
/**
|
||||
* End SPI transaction.
|
||||
*/
|
||||
virtual void deactivate() = 0;
|
||||
/** Receive a byte.
|
||||
*
|
||||
* \return The byte.
|
||||
*/
|
||||
virtual uint8_t receive() = 0;
|
||||
/** Receive multiple bytes.
|
||||
*
|
||||
* \param[out] buf Buffer to receive the data.
|
||||
* \param[in] n Number of bytes to receive.
|
||||
*
|
||||
* \return Zero for no error or nonzero error code.
|
||||
*/
|
||||
virtual uint8_t receive(uint8_t* buf, size_t n) = 0;
|
||||
/** Send a byte.
|
||||
*
|
||||
* \param[in] data Byte to send
|
||||
*/
|
||||
virtual void send(uint8_t data) = 0;
|
||||
/** Send multiple bytes.
|
||||
*
|
||||
* \param[in] buf Buffer for data to be sent.
|
||||
* \param[in] n Number of bytes to send.
|
||||
*/
|
||||
virtual void send(const uint8_t* buf, size_t n) = 0;
|
||||
/** Set CS low. */
|
||||
virtual void select() = 0;
|
||||
/** Save SPI settings.
|
||||
* \param[in] spiSettings SPI speed, mode, and bit order.
|
||||
*/
|
||||
virtual void setSpiSettings(SPISettings spiSettings) = 0;
|
||||
/** Set CS high. */
|
||||
virtual void unselect() = 0;
|
||||
};
|
||||
#endif // SdSpiBaseDriver_h
|
@ -0,0 +1,369 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
/**
|
||||
* \file
|
||||
* \brief SpiDriver classes
|
||||
*/
|
||||
#ifndef SdSpiDriver_h
|
||||
#define SdSpiDriver_h
|
||||
#include <Arduino.h>
|
||||
#include "SPI.h"
|
||||
#include "SdSpiBaseDriver.h"
|
||||
#include "../SdFatConfig.h"
|
||||
//-----------------------------------------------------------------------------
|
||||
/** SDCARD_SPI is defined if board has built-in SD card socket */
|
||||
#ifndef SDCARD_SPI
|
||||
#define SDCARD_SPI SPI
|
||||
#endif // SDCARD_SPI
|
||||
//-----------------------------------------------------------------------------
|
||||
/**
|
||||
* \class SdSpiLibDriver
|
||||
* \brief SdSpiLibDriver - use standard SPI library.
|
||||
*/
|
||||
#if ENABLE_SOFTWARE_SPI_CLASS
|
||||
class SdSpiLibDriver : public SdSpiBaseDriver {
|
||||
#else // ENABLE_SOFTWARE_SPI_CLASS
|
||||
class SdSpiLibDriver {
|
||||
#endif // ENABLE_SOFTWARE_SPI_CLASS
|
||||
public:
|
||||
/** Activate SPI hardware. */
|
||||
void activate() {
|
||||
SDCARD_SPI.beginTransaction(m_spiSettings);
|
||||
}
|
||||
/** Deactivate SPI hardware. */
|
||||
void deactivate() {
|
||||
SDCARD_SPI.endTransaction();
|
||||
}
|
||||
/** Initialize the SPI bus.
|
||||
*
|
||||
* \param[in] csPin SD card chip select pin.
|
||||
*/
|
||||
void begin(uint8_t csPin) {
|
||||
m_csPin = csPin;
|
||||
digitalWrite(csPin, HIGH);
|
||||
pinMode(csPin, OUTPUT);
|
||||
SDCARD_SPI.begin();
|
||||
}
|
||||
/** Receive a byte.
|
||||
*
|
||||
* \return The byte.
|
||||
*/
|
||||
uint8_t receive() {
|
||||
return SDCARD_SPI.transfer( 0XFF);
|
||||
}
|
||||
/** Receive multiple bytes.
|
||||
*
|
||||
* \param[out] buf Buffer to receive the data.
|
||||
* \param[in] n Number of bytes to receive.
|
||||
*
|
||||
* \return Zero for no error or nonzero error code.
|
||||
*/
|
||||
uint8_t receive(uint8_t* buf, size_t n) {
|
||||
for (size_t i = 0; i < n; i++) {
|
||||
buf[i] = SDCARD_SPI.transfer(0XFF);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
/** Send a byte.
|
||||
*
|
||||
* \param[in] data Byte to send
|
||||
*/
|
||||
void send(uint8_t data) {
|
||||
SDCARD_SPI.transfer(data);
|
||||
}
|
||||
/** Send multiple bytes.
|
||||
*
|
||||
* \param[in] buf Buffer for data to be sent.
|
||||
* \param[in] n Number of bytes to send.
|
||||
*/
|
||||
void send(const uint8_t* buf, size_t n) {
|
||||
for (size_t i = 0; i < n; i++) {
|
||||
SDCARD_SPI.transfer(buf[i]);
|
||||
}
|
||||
}
|
||||
/** Set CS low. */
|
||||
void select() {
|
||||
digitalWrite(m_csPin, LOW);
|
||||
}
|
||||
/** Save SPISettings.
|
||||
*
|
||||
* \param[in] spiSettings SPI speed, mode, and byte order.
|
||||
*/
|
||||
void setSpiSettings(SPISettings spiSettings) {
|
||||
m_spiSettings = spiSettings;
|
||||
}
|
||||
/** Set CS high. */
|
||||
void unselect() {
|
||||
digitalWrite(m_csPin, HIGH);
|
||||
}
|
||||
|
||||
private:
|
||||
SPISettings m_spiSettings;
|
||||
uint8_t m_csPin;
|
||||
};
|
||||
//-----------------------------------------------------------------------------
|
||||
/**
|
||||
* \class SdSpiAltDriver
|
||||
* \brief Optimized SPI class for access to SD and SDHC flash memory cards.
|
||||
*/
|
||||
#if ENABLE_SOFTWARE_SPI_CLASS
|
||||
class SdSpiAltDriver : public SdSpiBaseDriver {
|
||||
#else // ENABLE_SOFTWARE_SPI_CLASS
|
||||
class SdSpiAltDriver {
|
||||
#endif // ENABLE_SOFTWARE_SPI_CLASS
|
||||
public:
|
||||
/** Activate SPI hardware. */
|
||||
void activate();
|
||||
/** Deactivate SPI hardware. */
|
||||
void deactivate();
|
||||
/** Initialize the SPI bus.
|
||||
*
|
||||
* \param[in] csPin SD card chip select pin.
|
||||
*/
|
||||
void begin(uint8_t csPin);
|
||||
/** Receive a byte.
|
||||
*
|
||||
* \return The byte.
|
||||
*/
|
||||
uint8_t receive();
|
||||
/** Receive multiple bytes.
|
||||
*
|
||||
* \param[out] buf Buffer to receive the data.
|
||||
* \param[in] n Number of bytes to receive.
|
||||
*
|
||||
* \return Zero for no error or nonzero error code.
|
||||
*/
|
||||
uint8_t receive(uint8_t* buf, size_t n);
|
||||
/** Send a byte.
|
||||
*
|
||||
* \param[in] data Byte to send
|
||||
*/
|
||||
void send(uint8_t data);
|
||||
/** Send multiple bytes.
|
||||
*
|
||||
* \param[in] buf Buffer for data to be sent.
|
||||
* \param[in] n Number of bytes to send.
|
||||
*/
|
||||
void send(const uint8_t* buf, size_t n);
|
||||
/** Set CS low. */
|
||||
void select() {
|
||||
digitalWrite(m_csPin, LOW);
|
||||
}
|
||||
/** Save SPISettings.
|
||||
*
|
||||
* \param[in] spiSettings SPI speed, mode, and byte order.
|
||||
*/
|
||||
void setSpiSettings(SPISettings spiSettings) {
|
||||
m_spiSettings = spiSettings;
|
||||
}
|
||||
/** Set CS high. */
|
||||
void unselect() {
|
||||
digitalWrite(m_csPin, HIGH);
|
||||
}
|
||||
#if IMPLEMENT_SPI_PORT_SELECTION || defined(DOXYGEN)
|
||||
/** Set SPI port number.
|
||||
* \param[in] portNumber Hardware SPI port number.
|
||||
*/
|
||||
void setPort(uint8_t portNumber);
|
||||
|
||||
private:
|
||||
SPIClass* m_spi;
|
||||
#else // IMPLEMENT_SPI_PORT_SELECTION
|
||||
private:
|
||||
#endif // IMPLEMENT_SPI_PORT_SELECTION
|
||||
SPISettings m_spiSettings;
|
||||
uint8_t m_csPin;
|
||||
};
|
||||
//------------------------------------------------------------------------------
|
||||
#if ENABLE_SOFTWARE_SPI_CLASS || defined(DOXYGEN)
|
||||
#ifdef ARDUINO
|
||||
#include "SoftSPI.h"
|
||||
#elif defined(PLATFORM_ID) // Only defined if a Particle device
|
||||
#include "SoftSPIParticle.h"
|
||||
#endif // ARDUINO
|
||||
/**
|
||||
* \class SdSpiSoftDriver
|
||||
* \brief Software SPI class for access to SD and SDHC flash memory cards.
|
||||
*/
|
||||
template<uint8_t MisoPin, uint8_t MosiPin, uint8_t SckPin>
|
||||
class SdSpiSoftDriver : public SdSpiBaseDriver {
|
||||
public:
|
||||
/** Dummy activate SPI hardware for software SPI */
|
||||
void activate() {}
|
||||
/** Dummy deactivate SPI hardware for software SPI */
|
||||
void deactivate() {}
|
||||
/** Initialize the SPI bus.
|
||||
*
|
||||
* \param[in] csPin SD card chip select pin.
|
||||
*/
|
||||
void begin(uint8_t csPin) {
|
||||
m_csPin = csPin;
|
||||
pinMode(m_csPin, OUTPUT);
|
||||
digitalWrite(m_csPin, HIGH);
|
||||
m_spi.begin();
|
||||
}
|
||||
/** Receive a byte.
|
||||
*
|
||||
* \return The byte.
|
||||
*/
|
||||
uint8_t receive() {
|
||||
return m_spi.receive();
|
||||
}
|
||||
/** Receive multiple bytes.
|
||||
*
|
||||
* \param[out] buf Buffer to receive the data.
|
||||
* \param[in] n Number of bytes to receive.
|
||||
*
|
||||
* \return Zero for no error or nonzero error code.
|
||||
*/
|
||||
uint8_t receive(uint8_t* buf, size_t n) {
|
||||
for (size_t i = 0; i < n; i++) {
|
||||
buf[i] = receive();
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
/** Send a byte.
|
||||
*
|
||||
* \param[in] data Byte to send
|
||||
*/
|
||||
void send(uint8_t data) {
|
||||
m_spi.send(data);
|
||||
}
|
||||
/** Send multiple bytes.
|
||||
*
|
||||
* \param[in] buf Buffer for data to be sent.
|
||||
* \param[in] n Number of bytes to send.
|
||||
*/
|
||||
void send(const uint8_t* buf , size_t n) {
|
||||
for (size_t i = 0; i < n; i++) {
|
||||
send(buf[i]);
|
||||
}
|
||||
}
|
||||
/** Set CS low. */
|
||||
void select() {
|
||||
digitalWrite(m_csPin, LOW);
|
||||
}
|
||||
/** Save SPISettings.
|
||||
*
|
||||
* \param[in] spiSettings SPI speed, mode, and byte order.
|
||||
*/
|
||||
void setSpiSettings(SPISettings spiSettings) {
|
||||
(void)spiSettings;
|
||||
}
|
||||
/** Set CS high. */
|
||||
void unselect() {
|
||||
digitalWrite(m_csPin, HIGH);
|
||||
}
|
||||
|
||||
private:
|
||||
uint8_t m_csPin;
|
||||
SoftSPI<MisoPin, MosiPin, SckPin, 0> m_spi;
|
||||
};
|
||||
#endif // ENABLE_SOFTWARE_SPI_CLASS || defined(DOXYGEN)
|
||||
//-----------------------------------------------------------------------------
|
||||
// Choose SPI driver for SdFat and SdFatEX classes.
|
||||
#if USE_STANDARD_SPI_LIBRARY || !SD_HAS_CUSTOM_SPI
|
||||
/** SdFat uses Arduino library SPI. */
|
||||
typedef SdSpiLibDriver SdFatSpiDriver;
|
||||
#else // USE_STANDARD_SPI_LIBRARY || !SD_HAS_CUSTOM_SPI
|
||||
/** SdFat uses custom fast SPI. */
|
||||
typedef SdSpiAltDriver SdFatSpiDriver;
|
||||
#endif // USE_STANDARD_SPI_LIBRARY || !SD_HAS_CUSTOM_SPI
|
||||
|
||||
/** typedef for for SdSpiCard class. */
|
||||
#if ENABLE_SOFTWARE_SPI_CLASS
|
||||
// Need virtual driver.
|
||||
typedef SdSpiBaseDriver SdSpiDriver;
|
||||
#else // ENABLE_SOFTWARE_SPI_CLASS
|
||||
// Don't need virtual driver.
|
||||
typedef SdFatSpiDriver SdSpiDriver;
|
||||
#endif // ENABLE_SOFTWARE_SPI_CLASS
|
||||
//=============================================================================
|
||||
// Use of in-line for AVR to save flash.
|
||||
#ifdef __AVR__
|
||||
//------------------------------------------------------------------------------
|
||||
inline void SdSpiAltDriver::begin(uint8_t csPin) {
|
||||
m_csPin = csPin;
|
||||
pinMode(m_csPin, OUTPUT);
|
||||
digitalWrite(m_csPin, HIGH);
|
||||
SPI.begin();
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
inline void SdSpiAltDriver::activate() {
|
||||
SPI.beginTransaction(m_spiSettings);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
inline void SdSpiAltDriver::deactivate() {
|
||||
SPI.endTransaction();
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
inline uint8_t SdSpiAltDriver::receive() {
|
||||
SPDR = 0XFF;
|
||||
while (!(SPSR & (1 << SPIF))) {}
|
||||
return SPDR;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
inline uint8_t SdSpiAltDriver::receive(uint8_t* buf, size_t n) {
|
||||
if (n-- == 0) {
|
||||
return 0;
|
||||
}
|
||||
SPDR = 0XFF;
|
||||
for (size_t i = 0; i < n; i++) {
|
||||
while (!(SPSR & (1 << SPIF))) {}
|
||||
uint8_t b = SPDR;
|
||||
SPDR = 0XFF;
|
||||
buf[i] = b;
|
||||
}
|
||||
while (!(SPSR & (1 << SPIF))) {}
|
||||
buf[n] = SPDR;
|
||||
return 0;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
inline void SdSpiAltDriver::send(uint8_t data) {
|
||||
SPDR = data;
|
||||
while (!(SPSR & (1 << SPIF))) {}
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
inline void SdSpiAltDriver::send(const uint8_t* buf , size_t n) {
|
||||
if (n == 0) {
|
||||
return;
|
||||
}
|
||||
SPDR = buf[0];
|
||||
if (n > 1) {
|
||||
uint8_t b = buf[1];
|
||||
size_t i = 2;
|
||||
while (1) {
|
||||
while (!(SPSR & (1 << SPIF))) {}
|
||||
SPDR = b;
|
||||
if (i == n) {
|
||||
break;
|
||||
}
|
||||
b = buf[i++];
|
||||
}
|
||||
}
|
||||
while (!(SPSR & (1 << SPIF))) {}
|
||||
}
|
||||
#endif // __AVR__
|
||||
#endif // SdSpiDriver_h
|
@ -0,0 +1,93 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#if defined(ESP8266)
|
||||
#include "SdSpiDriver.h"
|
||||
//------------------------------------------------------------------------------
|
||||
/** Initialize the SPI bus.
|
||||
*
|
||||
* \param[in] chipSelectPin SD card chip select pin.
|
||||
*/
|
||||
void SdSpiAltDriver::begin(uint8_t csPin) {
|
||||
m_csPin = csPin;
|
||||
pinMode(m_csPin, OUTPUT);
|
||||
digitalWrite(m_csPin, HIGH);
|
||||
SPI.begin();
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Set SPI options for access to SD/SDHC cards.
|
||||
*
|
||||
*/
|
||||
void SdSpiAltDriver::activate() {
|
||||
SPI.beginTransaction(m_spiSettings);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void SdSpiAltDriver::deactivate() {
|
||||
// Note: endTransaction is an empty function on ESP8266.
|
||||
SPI.endTransaction();
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Receive a byte.
|
||||
*
|
||||
* \return The byte.
|
||||
*/
|
||||
uint8_t SdSpiAltDriver::receive() {
|
||||
return SPI.transfer(0XFF);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Receive multiple bytes.
|
||||
*
|
||||
* \param[out] buf Buffer to receive the data.
|
||||
* \param[in] n Number of bytes to receive.
|
||||
*
|
||||
* \return Zero for no error or nonzero error code.
|
||||
*/
|
||||
uint8_t SdSpiAltDriver::receive(uint8_t* buf, size_t n) {
|
||||
// Works without 32-bit alignment of buf.
|
||||
SPI.transferBytes(0, buf, n);
|
||||
return 0;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Send a byte.
|
||||
*
|
||||
* \param[in] b Byte to send
|
||||
*/
|
||||
void SdSpiAltDriver::send(uint8_t b) {
|
||||
SPI.transfer(b);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Send multiple bytes.
|
||||
*
|
||||
* \param[in] buf Buffer for data to be sent.
|
||||
* \param[in] n Number of bytes to send.
|
||||
*/
|
||||
void SdSpiAltDriver::send(const uint8_t* buf , size_t n) {
|
||||
// Adjust to 32-bit alignment.
|
||||
while ((reinterpret_cast<uintptr_t>(buf) & 0X3) && n) {
|
||||
SPI.transfer(*buf++);
|
||||
n--;
|
||||
}
|
||||
SPI.transferBytes(const_cast<uint8_t*>(buf), 0, n);
|
||||
}
|
||||
#endif // defined(ESP8266)
|
@ -0,0 +1,222 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wunused-variable"
|
||||
#pragma GCC diagnostic ignored "-Wunused-parameter"
|
||||
|
||||
#include "../../../Repetier.h"
|
||||
#include "SdSpiDriver.h"
|
||||
#if defined(__SAM3X8E__) || defined(__SAM3X8H__)
|
||||
/** Use SAM3X DMAC if nonzero */
|
||||
#define USE_SAM3X_DMAC 1
|
||||
/** Use extra Bus Matrix arbitration fix if nonzero */
|
||||
#define USE_SAM3X_BUS_MATRIX_FIX 0
|
||||
/** Time in ms for DMA receive timeout */
|
||||
#define SAM3X_DMA_TIMEOUT 100
|
||||
/** chip select register number */
|
||||
#define SPI_CHIP_SEL 3
|
||||
/** DMAC receive channel */
|
||||
#define SPI_DMAC_RX_CH 1
|
||||
/** DMAC transmit channel */
|
||||
#define SPI_DMAC_TX_CH 0
|
||||
/** DMAC Channel HW Interface Number for SPI TX. */
|
||||
#define SPI_TX_IDX 1
|
||||
/** DMAC Channel HW Interface Number for SPI RX. */
|
||||
#define SPI_RX_IDX 2
|
||||
//------------------------------------------------------------------------------
|
||||
/** Disable DMA Controller. */
|
||||
static void dmac_disable() {
|
||||
DMAC->DMAC_EN &= (~DMAC_EN_ENABLE);
|
||||
}
|
||||
/** Enable DMA Controller. */
|
||||
static void dmac_enable() {
|
||||
DMAC->DMAC_EN = DMAC_EN_ENABLE;
|
||||
}
|
||||
/** Disable DMA Channel. */
|
||||
static void dmac_channel_disable(uint32_t ul_num) {
|
||||
DMAC->DMAC_CHDR = DMAC_CHDR_DIS0 << ul_num;
|
||||
}
|
||||
/** Enable DMA Channel. */
|
||||
static void dmac_channel_enable(uint32_t ul_num) {
|
||||
DMAC->DMAC_CHER = DMAC_CHER_ENA0 << ul_num;
|
||||
}
|
||||
/** Poll for transfer complete. */
|
||||
static bool dmac_channel_transfer_done(uint32_t ul_num) {
|
||||
return (DMAC->DMAC_CHSR & (DMAC_CHSR_ENA0 << ul_num)) ? false : true;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void SdSpiAltDriver::begin(uint8_t csPin) {
|
||||
m_csPin = csPin;
|
||||
pinMode(m_csPin, OUTPUT);
|
||||
digitalWrite(m_csPin, HIGH);
|
||||
SPI.begin();
|
||||
#if USE_SAM3X_DMAC
|
||||
pmc_enable_periph_clk(ID_DMAC);
|
||||
dmac_disable();
|
||||
DMAC->DMAC_GCFG = DMAC_GCFG_ARB_CFG_FIXED;
|
||||
dmac_enable();
|
||||
#if USE_SAM3X_BUS_MATRIX_FIX
|
||||
MATRIX->MATRIX_WPMR = 0x4d415400;
|
||||
MATRIX->MATRIX_MCFG[1] = 1;
|
||||
MATRIX->MATRIX_MCFG[2] = 1;
|
||||
MATRIX->MATRIX_SCFG[0] = 0x01000010;
|
||||
MATRIX->MATRIX_SCFG[1] = 0x01000010;
|
||||
MATRIX->MATRIX_SCFG[7] = 0x01000010;
|
||||
#endif // USE_SAM3X_BUS_MATRIX_FIX
|
||||
#endif // USE_SAM3X_DMAC
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// start RX DMA
|
||||
static void spiDmaRX(uint8_t* dst, uint16_t count) {
|
||||
dmac_channel_disable(SPI_DMAC_RX_CH);
|
||||
DMAC->DMAC_CH_NUM[SPI_DMAC_RX_CH].DMAC_SADDR = (uint32_t)&SPI0->SPI_RDR;
|
||||
DMAC->DMAC_CH_NUM[SPI_DMAC_RX_CH].DMAC_DADDR = (uint32_t)dst;
|
||||
DMAC->DMAC_CH_NUM[SPI_DMAC_RX_CH].DMAC_DSCR = 0;
|
||||
DMAC->DMAC_CH_NUM[SPI_DMAC_RX_CH].DMAC_CTRLA = count | DMAC_CTRLA_SRC_WIDTH_BYTE | DMAC_CTRLA_DST_WIDTH_BYTE;
|
||||
DMAC->DMAC_CH_NUM[SPI_DMAC_RX_CH].DMAC_CTRLB = DMAC_CTRLB_SRC_DSCR | DMAC_CTRLB_DST_DSCR | DMAC_CTRLB_FC_PER2MEM_DMA_FC | DMAC_CTRLB_SRC_INCR_FIXED | DMAC_CTRLB_DST_INCR_INCREMENTING;
|
||||
DMAC->DMAC_CH_NUM[SPI_DMAC_RX_CH].DMAC_CFG = DMAC_CFG_SRC_PER(SPI_RX_IDX) | DMAC_CFG_SRC_H2SEL | DMAC_CFG_SOD | DMAC_CFG_FIFOCFG_ASAP_CFG;
|
||||
dmac_channel_enable(SPI_DMAC_RX_CH);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// start TX DMA
|
||||
static void spiDmaTX(const uint8_t* src, uint16_t count) {
|
||||
static uint8_t ff = 0XFF;
|
||||
uint32_t src_incr = DMAC_CTRLB_SRC_INCR_INCREMENTING;
|
||||
if (!src) {
|
||||
src = &ff;
|
||||
src_incr = DMAC_CTRLB_SRC_INCR_FIXED;
|
||||
}
|
||||
dmac_channel_disable(SPI_DMAC_TX_CH);
|
||||
DMAC->DMAC_CH_NUM[SPI_DMAC_TX_CH].DMAC_SADDR = (uint32_t)src;
|
||||
DMAC->DMAC_CH_NUM[SPI_DMAC_TX_CH].DMAC_DADDR = (uint32_t)&SPI0->SPI_TDR;
|
||||
DMAC->DMAC_CH_NUM[SPI_DMAC_TX_CH].DMAC_DSCR = 0;
|
||||
DMAC->DMAC_CH_NUM[SPI_DMAC_TX_CH].DMAC_CTRLA = count | DMAC_CTRLA_SRC_WIDTH_BYTE | DMAC_CTRLA_DST_WIDTH_BYTE;
|
||||
|
||||
DMAC->DMAC_CH_NUM[SPI_DMAC_TX_CH].DMAC_CTRLB = DMAC_CTRLB_SRC_DSCR | DMAC_CTRLB_DST_DSCR | DMAC_CTRLB_FC_MEM2PER_DMA_FC | src_incr | DMAC_CTRLB_DST_INCR_FIXED;
|
||||
|
||||
DMAC->DMAC_CH_NUM[SPI_DMAC_TX_CH].DMAC_CFG = DMAC_CFG_DST_PER(SPI_TX_IDX) | DMAC_CFG_DST_H2SEL | DMAC_CFG_SOD | DMAC_CFG_FIFOCFG_ALAP_CFG;
|
||||
|
||||
dmac_channel_enable(SPI_DMAC_TX_CH);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
// initialize SPI controller
|
||||
void SdSpiAltDriver::activate() {
|
||||
SPI.beginTransaction(m_spiSettings);
|
||||
|
||||
Spi* pSpi = SPI0;
|
||||
// Save the divisor
|
||||
uint32_t scbr = pSpi->SPI_CSR[SPI_CHIP_SEL] & 0XFF00;
|
||||
// Disable SPI
|
||||
pSpi->SPI_CR = SPI_CR_SPIDIS;
|
||||
// reset SPI
|
||||
pSpi->SPI_CR = SPI_CR_SWRST;
|
||||
// no mode fault detection, set master mode
|
||||
pSpi->SPI_MR = SPI_PCS(SPI_CHIP_SEL) | SPI_MR_MODFDIS | SPI_MR_MSTR;
|
||||
// mode 0, 8-bit,
|
||||
pSpi->SPI_CSR[SPI_CHIP_SEL] = scbr | SPI_CSR_CSAAT | SPI_CSR_NCPHA;
|
||||
// enable SPI
|
||||
pSpi->SPI_CR |= SPI_CR_SPIEN;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void SdSpiAltDriver::deactivate() {
|
||||
SPI.endTransaction();
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
static inline uint8_t spiTransfer(uint8_t b) {
|
||||
Spi* pSpi = SPI0;
|
||||
|
||||
pSpi->SPI_TDR = b;
|
||||
while ((pSpi->SPI_SR & SPI_SR_RDRF) == 0) {
|
||||
}
|
||||
b = pSpi->SPI_RDR;
|
||||
return b;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** SPI receive a byte */
|
||||
uint8_t SdSpiAltDriver::receive() {
|
||||
return spiTransfer(0XFF);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** SPI receive multiple bytes */
|
||||
uint8_t SdSpiAltDriver::receive(uint8_t* buf, size_t n) {
|
||||
Spi* pSpi = SPI0;
|
||||
int rtn = 0;
|
||||
#if USE_SAM3X_DMAC
|
||||
// clear overrun error
|
||||
uint32_t s = pSpi->SPI_SR;
|
||||
|
||||
spiDmaRX(buf, n);
|
||||
spiDmaTX(0, n);
|
||||
|
||||
uint32_t m = millis();
|
||||
while (!dmac_channel_transfer_done(SPI_DMAC_RX_CH)) {
|
||||
if ((millis() - m) > SAM3X_DMA_TIMEOUT) {
|
||||
dmac_channel_disable(SPI_DMAC_RX_CH);
|
||||
dmac_channel_disable(SPI_DMAC_TX_CH);
|
||||
rtn = 2;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (pSpi->SPI_SR & SPI_SR_OVRES) {
|
||||
rtn |= 1;
|
||||
}
|
||||
#else // USE_SAM3X_DMAC
|
||||
for (size_t i = 0; i < n; i++) {
|
||||
pSpi->SPI_TDR = 0XFF;
|
||||
while ((pSpi->SPI_SR & SPI_SR_RDRF) == 0) {
|
||||
}
|
||||
buf[i] = pSpi->SPI_RDR;
|
||||
}
|
||||
#endif // USE_SAM3X_DMAC
|
||||
return rtn;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** SPI send a byte */
|
||||
void SdSpiAltDriver::send(uint8_t b) {
|
||||
spiTransfer(b);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void SdSpiAltDriver::send(const uint8_t* buf, size_t n) {
|
||||
Spi* pSpi = SPI0;
|
||||
#if USE_SAM3X_DMAC
|
||||
spiDmaTX(buf, n);
|
||||
while (!dmac_channel_transfer_done(SPI_DMAC_TX_CH)) {
|
||||
}
|
||||
#else // #if USE_SAM3X_DMAC
|
||||
while ((pSpi->SPI_SR & SPI_SR_TXEMPTY) == 0) {
|
||||
}
|
||||
for (size_t i = 0; i < n; i++) {
|
||||
pSpi->SPI_TDR = buf[i];
|
||||
while ((pSpi->SPI_SR & SPI_SR_TDRE) == 0) {
|
||||
}
|
||||
}
|
||||
#endif // #if USE_SAM3X_DMAC
|
||||
while ((pSpi->SPI_SR & SPI_SR_TXEMPTY) == 0) {
|
||||
}
|
||||
// leave RDR empty
|
||||
uint8_t b = pSpi->SPI_RDR;
|
||||
}
|
||||
#endif // defined(__SAM3X8E__) || defined(__SAM3X8H__)
|
||||
#pragma GCC diagnostic pop
|
@ -0,0 +1,131 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#if defined(__STM32F1__) || defined(__STM32F4__)
|
||||
#include "../../../Repetier.h"
|
||||
#include "SdSpiDriver.h"
|
||||
#if defined(__STM32F1__)
|
||||
#define USE_STM32_DMA 1
|
||||
#elif defined(__STM32F4__)
|
||||
#define USE_STM32_DMA 1
|
||||
#else // defined(__STM32F1__)
|
||||
#error Unknown STM32 type
|
||||
#endif // defined(__STM32F1__)
|
||||
//------------------------------------------------------------------------------
|
||||
static SPIClass m_SPI1(1);
|
||||
#if BOARD_NR_SPI >= 2
|
||||
static SPIClass m_SPI2(2);
|
||||
#endif // BOARD_NR_SPI >= 2
|
||||
#if BOARD_NR_SPI >= 3
|
||||
static SPIClass m_SPI3(3);
|
||||
#endif // BOARD_NR_SPI >= 3
|
||||
#if BOARD_NR_SPI > 3
|
||||
#error BOARD_NR_SPI too large
|
||||
#endif
|
||||
//------------------------------------------------------------------------------
|
||||
/** Set SPI options for access to SD/SDHC cards.
|
||||
*
|
||||
* \param[in] divisor SCK clock divider relative to the APB1 or APB2 clock.
|
||||
*/
|
||||
void SdSpiAltDriver::activate() {
|
||||
m_spi->beginTransaction(m_spiSettings);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Initialize the SPI bus.
|
||||
*
|
||||
* \param[in] chipSelectPin SD card chip select pin.
|
||||
*/
|
||||
void SdSpiAltDriver::begin(uint8_t csPin) {
|
||||
m_csPin = csPin;
|
||||
pinMode(m_csPin, OUTPUT);
|
||||
digitalWrite(m_csPin, HIGH);
|
||||
m_spi->begin();
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* End SPI transaction.
|
||||
*/
|
||||
void SdSpiAltDriver::deactivate() {
|
||||
m_spi->endTransaction();
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Receive a byte.
|
||||
*
|
||||
* \return The byte.
|
||||
*/
|
||||
uint8_t SdSpiAltDriver::receive() {
|
||||
return m_spi->transfer(0XFF);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Receive multiple bytes.
|
||||
*
|
||||
* \param[out] buf Buffer to receive the data.
|
||||
* \param[in] n Number of bytes to receive.
|
||||
*
|
||||
* \return Zero for no error or nonzero error code.
|
||||
*/
|
||||
uint8_t SdSpiAltDriver::receive(uint8_t* buf, size_t n) {
|
||||
#if USE_STM32_DMA
|
||||
return m_spi->dmaTransfer(0, buf, n);
|
||||
#else // USE_STM32_DMA
|
||||
m_spi->read(buf, n);
|
||||
return 0;
|
||||
#endif // USE_STM32_DMA
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Send a byte.
|
||||
*
|
||||
* \param[in] b Byte to send
|
||||
*/
|
||||
void SdSpiAltDriver::send(uint8_t b) {
|
||||
m_spi->transfer(b);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** Send multiple bytes.
|
||||
*
|
||||
* \param[in] buf Buffer for data to be sent.
|
||||
* \param[in] n Number of bytes to send.
|
||||
*/
|
||||
void SdSpiAltDriver::send(const uint8_t* buf, size_t n) {
|
||||
#if USE_STM32_DMA
|
||||
m_spi->dmaTransfer(const_cast<uint8*>(buf), 0, n);
|
||||
#else // USE_STM32_DMA
|
||||
m_spi->write(const_cast<uint8*>(buf), n);
|
||||
#endif // USE_STM32_DMA
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void SdSpiAltDriver::setPort(uint8_t portNumber) {
|
||||
m_spi = &m_SPI1;
|
||||
#if BOARD_NR_SPI >= 2
|
||||
if (portNumber == 2) {
|
||||
m_spi = &m_SPI2;
|
||||
}
|
||||
#endif // BOARD_NR_SPI >= 2
|
||||
#if BOARD_NR_SPI >= 3
|
||||
if (portNumber == 3) {
|
||||
m_spi = &m_SPI3;
|
||||
}
|
||||
#endif // BOARD_NR_SPI >= 2
|
||||
}
|
||||
#endif // defined(__STM32F1__) || defined(__STM32F4__)
|
@ -0,0 +1,244 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#include "../../../Repetier.h"
|
||||
#include "SdSpiDriver.h"
|
||||
#if defined(__arm__) && defined(CORE_TEENSY)
|
||||
// SPI definitions
|
||||
#include "kinetis.h"
|
||||
|
||||
//------------------------------------------------------------------------------
|
||||
void SdSpiAltDriver::activate() {
|
||||
SPI.beginTransaction(m_spiSettings);
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void SdSpiAltDriver::begin(uint8_t chipSelectPin) {
|
||||
m_csPin = chipSelectPin;
|
||||
pinMode(m_csPin, OUTPUT);
|
||||
digitalWrite(m_csPin, HIGH);
|
||||
SPI.begin();
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
void SdSpiAltDriver::deactivate() {
|
||||
SPI.endTransaction();
|
||||
}
|
||||
//==============================================================================
|
||||
#ifdef KINETISK
|
||||
|
||||
// use 16-bit frame if SPI_USE_8BIT_FRAME is zero
|
||||
#define SPI_USE_8BIT_FRAME 0
|
||||
// Limit initial fifo to three entries to avoid fifo overrun
|
||||
#define SPI_INITIAL_FIFO_DEPTH 3
|
||||
// define some symbols that are not in mk20dx128.h
|
||||
#ifndef SPI_SR_RXCTR
|
||||
#define SPI_SR_RXCTR 0XF0
|
||||
#endif // SPI_SR_RXCTR
|
||||
#ifndef SPI_PUSHR_CONT
|
||||
#define SPI_PUSHR_CONT 0X80000000
|
||||
#endif // SPI_PUSHR_CONT
|
||||
#ifndef SPI_PUSHR_CTAS
|
||||
#define SPI_PUSHR_CTAS(n) (((n)&7) << 28)
|
||||
#endif // SPI_PUSHR_CTAS
|
||||
//------------------------------------------------------------------------------
|
||||
/** SPI receive a byte */
|
||||
uint8_t SdSpiAltDriver::receive() {
|
||||
SPI0_MCR |= SPI_MCR_CLR_RXF;
|
||||
SPI0_SR = SPI_SR_TCF;
|
||||
SPI0_PUSHR = 0xFF;
|
||||
while (!(SPI0_SR & SPI_SR_TCF)) {
|
||||
}
|
||||
return SPI0_POPR;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** SPI receive multiple bytes */
|
||||
uint8_t SdSpiAltDriver::receive(uint8_t* buf, size_t n) {
|
||||
// clear any data in RX FIFO
|
||||
SPI0_MCR = SPI_MCR_MSTR | SPI_MCR_CLR_RXF | SPI_MCR_PCSIS(0x1F);
|
||||
#if SPI_USE_8BIT_FRAME
|
||||
// initial number of bytes to push into TX FIFO
|
||||
int nf = n < SPI_INITIAL_FIFO_DEPTH ? n : SPI_INITIAL_FIFO_DEPTH;
|
||||
for (int i = 0; i < nf; i++) {
|
||||
SPI0_PUSHR = 0XFF;
|
||||
}
|
||||
// limit for pushing dummy data into TX FIFO
|
||||
uint8_t* limit = buf + n - nf;
|
||||
while (buf < limit) {
|
||||
while (!(SPI0_SR & SPI_SR_RXCTR)) {
|
||||
}
|
||||
SPI0_PUSHR = 0XFF;
|
||||
*buf++ = SPI0_POPR;
|
||||
}
|
||||
// limit for rest of RX data
|
||||
limit += nf;
|
||||
while (buf < limit) {
|
||||
while (!(SPI0_SR & SPI_SR_RXCTR)) {
|
||||
}
|
||||
*buf++ = SPI0_POPR;
|
||||
}
|
||||
#else // SPI_USE_8BIT_FRAME
|
||||
// use 16 bit frame to avoid TD delay between frames
|
||||
// get one byte if n is odd
|
||||
if (n & 1) {
|
||||
*buf++ = receive();
|
||||
n--;
|
||||
}
|
||||
// initial number of words to push into TX FIFO
|
||||
int nf = n / 2 < SPI_INITIAL_FIFO_DEPTH ? n / 2 : SPI_INITIAL_FIFO_DEPTH;
|
||||
for (int i = 0; i < nf; i++) {
|
||||
SPI0_PUSHR = SPI_PUSHR_CONT | SPI_PUSHR_CTAS(1) | 0XFFFF;
|
||||
}
|
||||
uint8_t* limit = buf + n - 2 * nf;
|
||||
while (buf < limit) {
|
||||
while (!(SPI0_SR & SPI_SR_RXCTR)) {
|
||||
}
|
||||
SPI0_PUSHR = SPI_PUSHR_CONT | SPI_PUSHR_CTAS(1) | 0XFFFF;
|
||||
uint16_t w = SPI0_POPR;
|
||||
*buf++ = w >> 8;
|
||||
*buf++ = w & 0XFF;
|
||||
}
|
||||
// limit for rest of RX data
|
||||
limit += 2 * nf;
|
||||
while (buf < limit) {
|
||||
while (!(SPI0_SR & SPI_SR_RXCTR)) {
|
||||
}
|
||||
uint16_t w = SPI0_POPR;
|
||||
*buf++ = w >> 8;
|
||||
*buf++ = w & 0XFF;
|
||||
}
|
||||
#endif // SPI_USE_8BIT_FRAME
|
||||
return 0;
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** SPI send a byte */
|
||||
void SdSpiAltDriver::send(uint8_t b) {
|
||||
SPI0_MCR |= SPI_MCR_CLR_RXF;
|
||||
SPI0_SR = SPI_SR_TCF;
|
||||
SPI0_PUSHR = b;
|
||||
while (!(SPI0_SR & SPI_SR_TCF)) {
|
||||
}
|
||||
}
|
||||
//------------------------------------------------------------------------------
|
||||
/** SPI send multiple bytes */
|
||||
void SdSpiAltDriver::send(const uint8_t* buf, size_t n) {
|
||||
// clear any data in RX FIFO
|
||||
SPI0_MCR = SPI_MCR_MSTR | SPI_MCR_CLR_RXF | SPI_MCR_PCSIS(0x1F);
|
||||
#if SPI_USE_8BIT_FRAME
|
||||
// initial number of bytes to push into TX FIFO
|
||||
int nf = n < SPI_INITIAL_FIFO_DEPTH ? n : SPI_INITIAL_FIFO_DEPTH;
|
||||
// limit for pushing data into TX fifo
|
||||
const uint8_t* limit = buf + n;
|
||||
for (int i = 0; i < nf; i++) {
|
||||
SPI0_PUSHR = *buf++;
|
||||
}
|
||||
// write data to TX FIFO
|
||||
while (buf < limit) {
|
||||
while (!(SPI0_SR & SPI_SR_RXCTR)) {
|
||||
}
|
||||
SPI0_PUSHR = *buf++;
|
||||
SPI0_POPR;
|
||||
}
|
||||
// wait for data to be sent
|
||||
while (nf) {
|
||||
while (!(SPI0_SR & SPI_SR_RXCTR)) {
|
||||
}
|
||||
SPI0_POPR;
|
||||
nf--;
|
||||
}
|
||||
#else // SPI_USE_8BIT_FRAME
|
||||
// use 16 bit frame to avoid TD delay between frames
|
||||
// send one byte if n is odd
|
||||
if (n & 1) {
|
||||
send(*buf++);
|
||||
n--;
|
||||
}
|
||||
// initial number of words to push into TX FIFO
|
||||
int nf = n / 2 < SPI_INITIAL_FIFO_DEPTH ? n / 2 : SPI_INITIAL_FIFO_DEPTH;
|
||||
// limit for pushing data into TX fifo
|
||||
const uint8_t* limit = buf + n;
|
||||
for (int i = 0; i < nf; i++) {
|
||||
uint16_t w = (*buf++) << 8;
|
||||
w |= *buf++;
|
||||
SPI0_PUSHR = SPI_PUSHR_CONT | SPI_PUSHR_CTAS(1) | w;
|
||||
}
|
||||
// write data to TX FIFO
|
||||
while (buf < limit) {
|
||||
uint16_t w = *buf++ << 8;
|
||||
w |= *buf++;
|
||||
while (!(SPI0_SR & SPI_SR_RXCTR)) {
|
||||
}
|
||||
SPI0_PUSHR = SPI_PUSHR_CONT | SPI_PUSHR_CTAS(1) | w;
|
||||
SPI0_POPR;
|
||||
}
|
||||
// wait for data to be sent
|
||||
while (nf) {
|
||||
while (!(SPI0_SR & SPI_SR_RXCTR)) {
|
||||
}
|
||||
SPI0_POPR;
|
||||
nf--;
|
||||
}
|
||||
#endif // SPI_USE_8BIT_FRAME
|
||||
}
|
||||
#else // KINETISK
|
||||
//==============================================================================
|
||||
// Use standard SPI library if not KINETISK
|
||||
//------------------------------------------------------------------------------
|
||||
/** Receive a byte.
|
||||
*
|
||||
* \return The byte.
|
||||
*/
|
||||
uint8_t SdSpiAltDriver::receive() {
|
||||
return SPI.transfer(0XFF);
|
||||
}
|
||||
/** Receive multiple bytes.
|
||||
*
|
||||
* \param[out] buf Buffer to receive the data.
|
||||
* \param[in] n Number of bytes to receive.
|
||||
*
|
||||
* \return Zero for no error or nonzero error code.
|
||||
*/
|
||||
uint8_t SdSpiAltDriver::receive(uint8_t* buf, size_t n) {
|
||||
for (size_t i = 0; i < n; i++) {
|
||||
buf[i] = SPI.transfer(0XFF);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
/** Send a byte.
|
||||
*
|
||||
* \param[in] b Byte to send
|
||||
*/
|
||||
void SdSpiAltDriver::send(uint8_t b) {
|
||||
SPI.transfer(b);
|
||||
}
|
||||
/** Send multiple bytes.
|
||||
*
|
||||
* \param[in] buf Buffer for data to be sent.
|
||||
* \param[in] n Number of bytes to send.
|
||||
*/
|
||||
void SdSpiAltDriver::send(const uint8_t* buf, size_t n) {
|
||||
for (size_t i = 0; i < n; i++) {
|
||||
SPI.transfer(buf[i]);
|
||||
}
|
||||
}
|
||||
#endif // KINETISK
|
||||
#endif // defined(__arm__) && defined(CORE_TEENSY)
|
167
Repetier-Firmware 1.0.3/Repetier/src/SdFat/SpiDriver/SoftSPI.h
Normal file
167
Repetier-Firmware 1.0.3/Repetier/src/SdFat/SpiDriver/SoftSPI.h
Normal file
@ -0,0 +1,167 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
/**
|
||||
* @file
|
||||
* @brief Software SPI.
|
||||
*
|
||||
* @defgroup softSPI Software SPI
|
||||
* @details Software SPI Template Class.
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef SoftSPI_h
|
||||
#define SoftSPI_h
|
||||
#include "DigitalPin.h"
|
||||
//------------------------------------------------------------------------------
|
||||
/** Nop for timing. */
|
||||
#define nop asm volatile ("nop\n\t")
|
||||
//------------------------------------------------------------------------------
|
||||
/** Pin Mode for MISO is input.*/
|
||||
#define MISO_MODE INPUT
|
||||
/** Pullups disabled for MISO are disabled. */
|
||||
#define MISO_LEVEL false
|
||||
/** Pin Mode for MOSI is output.*/
|
||||
#define MOSI_MODE OUTPUT
|
||||
/** Pin Mode for SCK is output. */
|
||||
#define SCK_MODE OUTPUT
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* @class SoftSPI
|
||||
* @brief Fast software SPI.
|
||||
*/
|
||||
template<uint8_t MisoPin, uint8_t MosiPin, uint8_t SckPin, uint8_t Mode = 0>
|
||||
class SoftSPI {
|
||||
public:
|
||||
//----------------------------------------------------------------------------
|
||||
/** Initialize SoftSPI pins. */
|
||||
void begin() {
|
||||
fastPinConfig(MisoPin, MISO_MODE, MISO_LEVEL);
|
||||
fastPinConfig(MosiPin, MOSI_MODE, !MODE_CPHA(Mode));
|
||||
fastPinConfig(SckPin, SCK_MODE, MODE_CPOL(Mode));
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Soft SPI receive byte.
|
||||
* @return Data byte received.
|
||||
*/
|
||||
inline __attribute__((always_inline))
|
||||
uint8_t receive() {
|
||||
uint8_t data = 0;
|
||||
receiveBit(7, &data);
|
||||
receiveBit(6, &data);
|
||||
receiveBit(5, &data);
|
||||
receiveBit(4, &data);
|
||||
receiveBit(3, &data);
|
||||
receiveBit(2, &data);
|
||||
receiveBit(1, &data);
|
||||
receiveBit(0, &data);
|
||||
return data;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Soft SPI send byte.
|
||||
* @param[in] data Data byte to send.
|
||||
*/
|
||||
inline __attribute__((always_inline))
|
||||
void send(uint8_t data) {
|
||||
sendBit(7, data);
|
||||
sendBit(6, data);
|
||||
sendBit(5, data);
|
||||
sendBit(4, data);
|
||||
sendBit(3, data);
|
||||
sendBit(2, data);
|
||||
sendBit(1, data);
|
||||
sendBit(0, data);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
/** Soft SPI transfer byte.
|
||||
* @param[in] txData Data byte to send.
|
||||
* @return Data byte received.
|
||||
*/
|
||||
inline __attribute__((always_inline))
|
||||
uint8_t transfer(uint8_t txData) {
|
||||
uint8_t rxData = 0;
|
||||
transferBit(7, &rxData, txData);
|
||||
transferBit(6, &rxData, txData);
|
||||
transferBit(5, &rxData, txData);
|
||||
transferBit(4, &rxData, txData);
|
||||
transferBit(3, &rxData, txData);
|
||||
transferBit(2, &rxData, txData);
|
||||
transferBit(1, &rxData, txData);
|
||||
transferBit(0, &rxData, txData);
|
||||
return rxData;
|
||||
}
|
||||
|
||||
private:
|
||||
//----------------------------------------------------------------------------
|
||||
inline __attribute__((always_inline))
|
||||
bool MODE_CPHA(uint8_t mode) {return (mode & 1) != 0;}
|
||||
inline __attribute__((always_inline))
|
||||
bool MODE_CPOL(uint8_t mode) {return (mode & 2) != 0;}
|
||||
inline __attribute__((always_inline))
|
||||
void receiveBit(uint8_t bit, uint8_t* data) {
|
||||
if (MODE_CPHA(Mode)) {
|
||||
fastDigitalWrite(SckPin, !MODE_CPOL(Mode));
|
||||
}
|
||||
nop;
|
||||
nop;
|
||||
fastDigitalWrite(SckPin,
|
||||
MODE_CPHA(Mode) ? MODE_CPOL(Mode) : !MODE_CPOL(Mode));
|
||||
if (fastDigitalRead(MisoPin)) *data |= 1 << bit;
|
||||
if (!MODE_CPHA(Mode)) {
|
||||
fastDigitalWrite(SckPin, MODE_CPOL(Mode));
|
||||
}
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
inline __attribute__((always_inline))
|
||||
void sendBit(uint8_t bit, uint8_t data) {
|
||||
if (MODE_CPHA(Mode)) {
|
||||
fastDigitalWrite(SckPin, !MODE_CPOL(Mode));
|
||||
}
|
||||
fastDigitalWrite(MosiPin, data & (1 << bit));
|
||||
fastDigitalWrite(SckPin,
|
||||
MODE_CPHA(Mode) ? MODE_CPOL(Mode) : !MODE_CPOL(Mode));
|
||||
nop;
|
||||
nop;
|
||||
if (!MODE_CPHA(Mode)) {
|
||||
fastDigitalWrite(SckPin, MODE_CPOL(Mode));
|
||||
}
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
inline __attribute__((always_inline))
|
||||
void transferBit(uint8_t bit, uint8_t* rxData, uint8_t txData) {
|
||||
if (MODE_CPHA(Mode)) {
|
||||
fastDigitalWrite(SckPin, !MODE_CPOL(Mode));
|
||||
}
|
||||
fastDigitalWrite(MosiPin, txData & (1 << bit));
|
||||
fastDigitalWrite(SckPin,
|
||||
MODE_CPHA(Mode) ? MODE_CPOL(Mode) : !MODE_CPOL(Mode));
|
||||
if (fastDigitalRead(MisoPin)) *rxData |= 1 << bit;
|
||||
if (!MODE_CPHA(Mode)) {
|
||||
fastDigitalWrite(SckPin, MODE_CPOL(Mode));
|
||||
}
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
};
|
||||
#endif // SoftSPI_h
|
||||
/** @} */
|
@ -0,0 +1,37 @@
|
||||
#ifndef AvrDevelopersGpioPinMap_h
|
||||
#define AvrDevelopersGpioPinMap_h
|
||||
static const GpioPinMap_t GpioPinMap[] = {
|
||||
GPIO_PIN(B, 0), // D0
|
||||
GPIO_PIN(B, 1), // D1
|
||||
GPIO_PIN(B, 2), // D2
|
||||
GPIO_PIN(B, 3), // D3
|
||||
GPIO_PIN(B, 4), // D4
|
||||
GPIO_PIN(B, 5), // D5
|
||||
GPIO_PIN(B, 6), // D6
|
||||
GPIO_PIN(B, 7), // D7
|
||||
GPIO_PIN(D, 0), // D8
|
||||
GPIO_PIN(D, 1), // D9
|
||||
GPIO_PIN(D, 2), // D10
|
||||
GPIO_PIN(D, 3), // D11
|
||||
GPIO_PIN(D, 4), // D12
|
||||
GPIO_PIN(D, 5), // D13
|
||||
GPIO_PIN(D, 6), // D14
|
||||
GPIO_PIN(D, 7), // D15
|
||||
GPIO_PIN(C, 0), // D16
|
||||
GPIO_PIN(C, 1), // D17
|
||||
GPIO_PIN(C, 2), // D18
|
||||
GPIO_PIN(C, 3), // D19
|
||||
GPIO_PIN(C, 4), // D20
|
||||
GPIO_PIN(C, 5), // D21
|
||||
GPIO_PIN(C, 6), // D22
|
||||
GPIO_PIN(C, 7), // D23
|
||||
GPIO_PIN(A, 7), // D24
|
||||
GPIO_PIN(A, 6), // D25
|
||||
GPIO_PIN(A, 5), // D26
|
||||
GPIO_PIN(A, 4), // D27
|
||||
GPIO_PIN(A, 3), // D28
|
||||
GPIO_PIN(A, 2), // D29
|
||||
GPIO_PIN(A, 1), // D30
|
||||
GPIO_PIN(A, 0) // D31
|
||||
};
|
||||
#endif // AvrDevelopersGpioPinMap_h
|
@ -0,0 +1,37 @@
|
||||
#ifndef BobuinoGpioPinMap_h
|
||||
#define BobuinoGpioPinMap_h
|
||||
static const GpioPinMap_t GpioPinMap[] = {
|
||||
GPIO_PIN(B, 0), // D0
|
||||
GPIO_PIN(B, 1), // D1
|
||||
GPIO_PIN(B, 2), // D2
|
||||
GPIO_PIN(B, 3), // D3
|
||||
GPIO_PIN(B, 4), // D4
|
||||
GPIO_PIN(B, 5), // D5
|
||||
GPIO_PIN(B, 6), // D6
|
||||
GPIO_PIN(B, 7), // D7
|
||||
GPIO_PIN(D, 0), // D8
|
||||
GPIO_PIN(D, 1), // D9
|
||||
GPIO_PIN(D, 2), // D10
|
||||
GPIO_PIN(D, 3), // D11
|
||||
GPIO_PIN(D, 4), // D12
|
||||
GPIO_PIN(D, 5), // D13
|
||||
GPIO_PIN(D, 6), // D14
|
||||
GPIO_PIN(D, 7), // D15
|
||||
GPIO_PIN(C, 0), // D16
|
||||
GPIO_PIN(C, 1), // D17
|
||||
GPIO_PIN(C, 2), // D18
|
||||
GPIO_PIN(C, 3), // D19
|
||||
GPIO_PIN(C, 4), // D20
|
||||
GPIO_PIN(C, 5), // D21
|
||||
GPIO_PIN(C, 6), // D22
|
||||
GPIO_PIN(C, 7), // D23
|
||||
GPIO_PIN(A, 0), // D24
|
||||
GPIO_PIN(A, 1), // D25
|
||||
GPIO_PIN(A, 2), // D26
|
||||
GPIO_PIN(A, 3), // D27
|
||||
GPIO_PIN(A, 4), // D28
|
||||
GPIO_PIN(A, 5), // D29
|
||||
GPIO_PIN(A, 6), // D30
|
||||
GPIO_PIN(A, 7) // D31
|
||||
};
|
||||
#endif // BobuinoGpioPinMap_h
|
@ -0,0 +1,45 @@
|
||||
#ifndef GpioPinMap_h
|
||||
#define GpioPinMap_h
|
||||
#if defined(__AVR_ATmega168__)\
|
||||
||defined(__AVR_ATmega168P__)\
|
||||
||defined(__AVR_ATmega328P__)
|
||||
// 168 and 328 Arduinos
|
||||
#include "UnoGpioPinMap.h"
|
||||
#elif defined(__AVR_ATmega1280__)\
|
||||
|| defined(__AVR_ATmega2560__)
|
||||
// Mega ADK
|
||||
#include "MegaGpioPinMap.h"
|
||||
#elif defined(__AVR_ATmega32U4__)
|
||||
#ifdef CORE_TEENSY
|
||||
#include "Teensy2GpioPinMap.h"
|
||||
#else // CORE_TEENSY
|
||||
// Leonardo or Yun
|
||||
#include "LeonardoGpioPinMap.h"
|
||||
#endif // CORE_TEENSY
|
||||
#elif defined(__AVR_AT90USB646__)\
|
||||
|| defined(__AVR_AT90USB1286__)
|
||||
// Teensy++ 1.0 & 2.0
|
||||
#include "Teensy2ppGpioPinMap.h"
|
||||
#elif defined(__AVR_ATmega1284P__)\
|
||||
|| defined(__AVR_ATmega1284__)\
|
||||
|| defined(__AVR_ATmega644P__)\
|
||||
|| defined(__AVR_ATmega644__)\
|
||||
|| defined(__AVR_ATmega64__)\
|
||||
|| defined(__AVR_ATmega32__)\
|
||||
|| defined(__AVR_ATmega324__)\
|
||||
|| defined(__AVR_ATmega16__)
|
||||
#ifdef ARDUINO_1284P_AVR_DEVELOPERS
|
||||
#include "AvrDevelopersGpioPinMap.h"
|
||||
#elif defined(BOBUINO_PINOUT) || defined(ARDUINO_1284P_BOBUINO)
|
||||
#include "BobuinoGpioPinMap.h"
|
||||
#elif defined(ARDUINO_1284P_SLEEPINGBEAUTY)
|
||||
#include "SleepingBeautyGpioPinMap.h"
|
||||
#elif defined(STANDARD_PINOUT) || defined(ARDUINO_1284P_STANDARD)
|
||||
#include "Standard1284GpioPinMap.h"
|
||||
#else // ARDUINO_1284P_AVR_DEVELOPERS
|
||||
#error Undefined variant 1284, 644, 324
|
||||
#endif // ARDUINO_1284P_AVR_DEVELOPERS
|
||||
#else // 1284P, 1284, 644
|
||||
#error Unknown board type.
|
||||
#endif // end all boards
|
||||
#endif // GpioPinMap_h
|
@ -0,0 +1,35 @@
|
||||
#ifndef LeonardoGpioPinMap_h
|
||||
#define LeonardoGpioPinMap_h
|
||||
static const GpioPinMap_t GpioPinMap[] = {
|
||||
GPIO_PIN(D, 2), // D0
|
||||
GPIO_PIN(D, 3), // D1
|
||||
GPIO_PIN(D, 1), // D2
|
||||
GPIO_PIN(D, 0), // D3
|
||||
GPIO_PIN(D, 4), // D4
|
||||
GPIO_PIN(C, 6), // D5
|
||||
GPIO_PIN(D, 7), // D6
|
||||
GPIO_PIN(E, 6), // D7
|
||||
GPIO_PIN(B, 4), // D8
|
||||
GPIO_PIN(B, 5), // D9
|
||||
GPIO_PIN(B, 6), // D10
|
||||
GPIO_PIN(B, 7), // D11
|
||||
GPIO_PIN(D, 6), // D12
|
||||
GPIO_PIN(C, 7), // D13
|
||||
GPIO_PIN(B, 3), // D14
|
||||
GPIO_PIN(B, 1), // D15
|
||||
GPIO_PIN(B, 2), // D16
|
||||
GPIO_PIN(B, 0), // D17
|
||||
GPIO_PIN(F, 7), // D18
|
||||
GPIO_PIN(F, 6), // D19
|
||||
GPIO_PIN(F, 5), // D20
|
||||
GPIO_PIN(F, 4), // D21
|
||||
GPIO_PIN(F, 1), // D22
|
||||
GPIO_PIN(F, 0), // D23
|
||||
GPIO_PIN(D, 4), // D24
|
||||
GPIO_PIN(D, 7), // D25
|
||||
GPIO_PIN(B, 4), // D26
|
||||
GPIO_PIN(B, 5), // D27
|
||||
GPIO_PIN(B, 6), // D28
|
||||
GPIO_PIN(D, 6) // D29
|
||||
};
|
||||
#endif // LeonardoGpioPinMap_h
|
@ -0,0 +1,75 @@
|
||||
#ifndef MegaGpioPinMap_h
|
||||
#define MegaGpioPinMap_h
|
||||
static const GpioPinMap_t GpioPinMap[] = {
|
||||
GPIO_PIN(E, 0), // D0
|
||||
GPIO_PIN(E, 1), // D1
|
||||
GPIO_PIN(E, 4), // D2
|
||||
GPIO_PIN(E, 5), // D3
|
||||
GPIO_PIN(G, 5), // D4
|
||||
GPIO_PIN(E, 3), // D5
|
||||
GPIO_PIN(H, 3), // D6
|
||||
GPIO_PIN(H, 4), // D7
|
||||
GPIO_PIN(H, 5), // D8
|
||||
GPIO_PIN(H, 6), // D9
|
||||
GPIO_PIN(B, 4), // D10
|
||||
GPIO_PIN(B, 5), // D11
|
||||
GPIO_PIN(B, 6), // D12
|
||||
GPIO_PIN(B, 7), // D13
|
||||
GPIO_PIN(J, 1), // D14
|
||||
GPIO_PIN(J, 0), // D15
|
||||
GPIO_PIN(H, 1), // D16
|
||||
GPIO_PIN(H, 0), // D17
|
||||
GPIO_PIN(D, 3), // D18
|
||||
GPIO_PIN(D, 2), // D19
|
||||
GPIO_PIN(D, 1), // D20
|
||||
GPIO_PIN(D, 0), // D21
|
||||
GPIO_PIN(A, 0), // D22
|
||||
GPIO_PIN(A, 1), // D23
|
||||
GPIO_PIN(A, 2), // D24
|
||||
GPIO_PIN(A, 3), // D25
|
||||
GPIO_PIN(A, 4), // D26
|
||||
GPIO_PIN(A, 5), // D27
|
||||
GPIO_PIN(A, 6), // D28
|
||||
GPIO_PIN(A, 7), // D29
|
||||
GPIO_PIN(C, 7), // D30
|
||||
GPIO_PIN(C, 6), // D31
|
||||
GPIO_PIN(C, 5), // D32
|
||||
GPIO_PIN(C, 4), // D33
|
||||
GPIO_PIN(C, 3), // D34
|
||||
GPIO_PIN(C, 2), // D35
|
||||
GPIO_PIN(C, 1), // D36
|
||||
GPIO_PIN(C, 0), // D37
|
||||
GPIO_PIN(D, 7), // D38
|
||||
GPIO_PIN(G, 2), // D39
|
||||
GPIO_PIN(G, 1), // D40
|
||||
GPIO_PIN(G, 0), // D41
|
||||
GPIO_PIN(L, 7), // D42
|
||||
GPIO_PIN(L, 6), // D43
|
||||
GPIO_PIN(L, 5), // D44
|
||||
GPIO_PIN(L, 4), // D45
|
||||
GPIO_PIN(L, 3), // D46
|
||||
GPIO_PIN(L, 2), // D47
|
||||
GPIO_PIN(L, 1), // D48
|
||||
GPIO_PIN(L, 0), // D49
|
||||
GPIO_PIN(B, 3), // D50
|
||||
GPIO_PIN(B, 2), // D51
|
||||
GPIO_PIN(B, 1), // D52
|
||||
GPIO_PIN(B, 0), // D53
|
||||
GPIO_PIN(F, 0), // D54
|
||||
GPIO_PIN(F, 1), // D55
|
||||
GPIO_PIN(F, 2), // D56
|
||||
GPIO_PIN(F, 3), // D57
|
||||
GPIO_PIN(F, 4), // D58
|
||||
GPIO_PIN(F, 5), // D59
|
||||
GPIO_PIN(F, 6), // D60
|
||||
GPIO_PIN(F, 7), // D61
|
||||
GPIO_PIN(K, 0), // D62
|
||||
GPIO_PIN(K, 1), // D63
|
||||
GPIO_PIN(K, 2), // D64
|
||||
GPIO_PIN(K, 3), // D65
|
||||
GPIO_PIN(K, 4), // D66
|
||||
GPIO_PIN(K, 5), // D67
|
||||
GPIO_PIN(K, 6), // D68
|
||||
GPIO_PIN(K, 7) // D69
|
||||
};
|
||||
#endif // MegaGpioPinMap_h
|
@ -0,0 +1,37 @@
|
||||
#ifndef SleepingBeautyGpioPinMap_h
|
||||
#define SleepingBeautyGpioPinMap_h
|
||||
static const GpioPinMap_t GpioPinMap[] = {
|
||||
GPIO_PIN(D, 0), // D0
|
||||
GPIO_PIN(D, 1), // D1
|
||||
GPIO_PIN(D, 2), // D2
|
||||
GPIO_PIN(D, 3), // D3
|
||||
GPIO_PIN(B, 0), // D4
|
||||
GPIO_PIN(B, 1), // D5
|
||||
GPIO_PIN(B, 2), // D6
|
||||
GPIO_PIN(B, 3), // D7
|
||||
GPIO_PIN(D, 6), // D8
|
||||
GPIO_PIN(D, 5), // D9
|
||||
GPIO_PIN(B, 4), // D10
|
||||
GPIO_PIN(B, 5), // D11
|
||||
GPIO_PIN(B, 6), // D12
|
||||
GPIO_PIN(B, 7), // D13
|
||||
GPIO_PIN(C, 7), // D14
|
||||
GPIO_PIN(C, 6), // D15
|
||||
GPIO_PIN(A, 5), // D16
|
||||
GPIO_PIN(A, 4), // D17
|
||||
GPIO_PIN(A, 3), // D18
|
||||
GPIO_PIN(A, 2), // D19
|
||||
GPIO_PIN(A, 1), // D20
|
||||
GPIO_PIN(A, 0), // D21
|
||||
GPIO_PIN(D, 4), // D22
|
||||
GPIO_PIN(D, 7), // D23
|
||||
GPIO_PIN(C, 2), // D24
|
||||
GPIO_PIN(C, 3), // D25
|
||||
GPIO_PIN(C, 4), // D26
|
||||
GPIO_PIN(C, 5), // D27
|
||||
GPIO_PIN(C, 1), // D28
|
||||
GPIO_PIN(C, 0), // D29
|
||||
GPIO_PIN(A, 6), // D30
|
||||
GPIO_PIN(A, 7) // D31
|
||||
};
|
||||
#endif // SleepingBeautyGpioPinMap_h
|
@ -0,0 +1,37 @@
|
||||
#ifndef Standard1284GpioPinMap_h
|
||||
#define Standard1284GpioPinMap_h
|
||||
static const GpioPinMap_t GpioPinMap[] = {
|
||||
GPIO_PIN(B, 0), // D0
|
||||
GPIO_PIN(B, 1), // D1
|
||||
GPIO_PIN(B, 2), // D2
|
||||
GPIO_PIN(B, 3), // D3
|
||||
GPIO_PIN(B, 4), // D4
|
||||
GPIO_PIN(B, 5), // D5
|
||||
GPIO_PIN(B, 6), // D6
|
||||
GPIO_PIN(B, 7), // D7
|
||||
GPIO_PIN(D, 0), // D8
|
||||
GPIO_PIN(D, 1), // D9
|
||||
GPIO_PIN(D, 2), // D10
|
||||
GPIO_PIN(D, 3), // D11
|
||||
GPIO_PIN(D, 4), // D12
|
||||
GPIO_PIN(D, 5), // D13
|
||||
GPIO_PIN(D, 6), // D14
|
||||
GPIO_PIN(D, 7), // D15
|
||||
GPIO_PIN(C, 0), // D16
|
||||
GPIO_PIN(C, 1), // D17
|
||||
GPIO_PIN(C, 2), // D18
|
||||
GPIO_PIN(C, 3), // D19
|
||||
GPIO_PIN(C, 4), // D20
|
||||
GPIO_PIN(C, 5), // D21
|
||||
GPIO_PIN(C, 6), // D22
|
||||
GPIO_PIN(C, 7), // D23
|
||||
GPIO_PIN(A, 0), // D24
|
||||
GPIO_PIN(A, 1), // D25
|
||||
GPIO_PIN(A, 2), // D26
|
||||
GPIO_PIN(A, 3), // D27
|
||||
GPIO_PIN(A, 4), // D28
|
||||
GPIO_PIN(A, 5), // D29
|
||||
GPIO_PIN(A, 6), // D30
|
||||
GPIO_PIN(A, 7) // D31
|
||||
};
|
||||
#endif // Standard1284GpioPinMap_h
|
@ -0,0 +1,30 @@
|
||||
#ifndef Teensy2GpioPinMap_h
|
||||
#define Teensy2GpioPinMap_h
|
||||
static const GpioPinMap_t GpioPinMap[] = {
|
||||
GPIO_PIN(B, 0), // D0
|
||||
GPIO_PIN(B, 1), // D1
|
||||
GPIO_PIN(B, 2), // D2
|
||||
GPIO_PIN(B, 3), // D3
|
||||
GPIO_PIN(B, 7), // D4
|
||||
GPIO_PIN(D, 0), // D5
|
||||
GPIO_PIN(D, 1), // D6
|
||||
GPIO_PIN(D, 2), // D7
|
||||
GPIO_PIN(D, 3), // D8
|
||||
GPIO_PIN(C, 6), // D9
|
||||
GPIO_PIN(C, 7), // D10
|
||||
GPIO_PIN(D, 6), // D11
|
||||
GPIO_PIN(D, 7), // D12
|
||||
GPIO_PIN(B, 4), // D13
|
||||
GPIO_PIN(B, 5), // D14
|
||||
GPIO_PIN(B, 6), // D15
|
||||
GPIO_PIN(F, 7), // D16
|
||||
GPIO_PIN(F, 6), // D17
|
||||
GPIO_PIN(F, 5), // D18
|
||||
GPIO_PIN(F, 4), // D19
|
||||
GPIO_PIN(F, 1), // D20
|
||||
GPIO_PIN(F, 0), // D21
|
||||
GPIO_PIN(D, 4), // D22
|
||||
GPIO_PIN(D, 5), // D23
|
||||
GPIO_PIN(E, 6), // D24
|
||||
};
|
||||
#endif // Teensy2GpioPinMap_h
|
@ -0,0 +1,51 @@
|
||||
#ifndef Teensypp2GpioPinMap_h
|
||||
#define Teensypp2GpioPinMap_h
|
||||
static const GpioPinMap_t GpioPinMap[] = {
|
||||
GPIO_PIN(D, 0), // D0
|
||||
GPIO_PIN(D, 1), // D1
|
||||
GPIO_PIN(D, 2), // D2
|
||||
GPIO_PIN(D, 3), // D3
|
||||
GPIO_PIN(D, 4), // D4
|
||||
GPIO_PIN(D, 5), // D5
|
||||
GPIO_PIN(D, 6), // D6
|
||||
GPIO_PIN(D, 7), // D7
|
||||
GPIO_PIN(E, 0), // D8
|
||||
GPIO_PIN(E, 1), // D9
|
||||
GPIO_PIN(C, 0), // D10
|
||||
GPIO_PIN(C, 1), // D11
|
||||
GPIO_PIN(C, 2), // D12
|
||||
GPIO_PIN(C, 3), // D13
|
||||
GPIO_PIN(C, 4), // D14
|
||||
GPIO_PIN(C, 5), // D15
|
||||
GPIO_PIN(C, 6), // D16
|
||||
GPIO_PIN(C, 7), // D17
|
||||
GPIO_PIN(E, 6), // D18
|
||||
GPIO_PIN(E, 7), // D19
|
||||
GPIO_PIN(B, 0), // D20
|
||||
GPIO_PIN(B, 1), // D21
|
||||
GPIO_PIN(B, 2), // D22
|
||||
GPIO_PIN(B, 3), // D23
|
||||
GPIO_PIN(B, 4), // D24
|
||||
GPIO_PIN(B, 5), // D25
|
||||
GPIO_PIN(B, 6), // D26
|
||||
GPIO_PIN(B, 7), // D27
|
||||
GPIO_PIN(A, 0), // D28
|
||||
GPIO_PIN(A, 1), // D29
|
||||
GPIO_PIN(A, 2), // D30
|
||||
GPIO_PIN(A, 3), // D31
|
||||
GPIO_PIN(A, 4), // D32
|
||||
GPIO_PIN(A, 5), // D33
|
||||
GPIO_PIN(A, 6), // D34
|
||||
GPIO_PIN(A, 7), // D35
|
||||
GPIO_PIN(E, 4), // D36
|
||||
GPIO_PIN(E, 5), // D37
|
||||
GPIO_PIN(F, 0), // D38
|
||||
GPIO_PIN(F, 1), // D39
|
||||
GPIO_PIN(F, 2), // D40
|
||||
GPIO_PIN(F, 3), // D41
|
||||
GPIO_PIN(F, 4), // D42
|
||||
GPIO_PIN(F, 5), // D43
|
||||
GPIO_PIN(F, 6), // D44
|
||||
GPIO_PIN(F, 7), // D45
|
||||
};
|
||||
#endif // Teensypp2GpioPinMap_h
|
@ -0,0 +1,25 @@
|
||||
#ifndef UnoGpioPinMap_h
|
||||
#define UnoGpioPinMap_h
|
||||
static const GpioPinMap_t GpioPinMap[] = {
|
||||
GPIO_PIN(D, 0), // D0
|
||||
GPIO_PIN(D, 1), // D1
|
||||
GPIO_PIN(D, 2), // D2
|
||||
GPIO_PIN(D, 3), // D3
|
||||
GPIO_PIN(D, 4), // D4
|
||||
GPIO_PIN(D, 5), // D5
|
||||
GPIO_PIN(D, 6), // D6
|
||||
GPIO_PIN(D, 7), // D7
|
||||
GPIO_PIN(B, 0), // D8
|
||||
GPIO_PIN(B, 1), // D9
|
||||
GPIO_PIN(B, 2), // D10
|
||||
GPIO_PIN(B, 3), // D11
|
||||
GPIO_PIN(B, 4), // D12
|
||||
GPIO_PIN(B, 5), // D13
|
||||
GPIO_PIN(C, 0), // D14
|
||||
GPIO_PIN(C, 1), // D15
|
||||
GPIO_PIN(C, 2), // D16
|
||||
GPIO_PIN(C, 3), // D17
|
||||
GPIO_PIN(C, 4), // D18
|
||||
GPIO_PIN(C, 5) // D19
|
||||
};
|
||||
#endif // UnoGpioPinMap_h
|
88
Repetier-Firmware 1.0.3/Repetier/src/SdFat/SysCall.h
Normal file
88
Repetier-Firmware 1.0.3/Repetier/src/SdFat/SysCall.h
Normal file
@ -0,0 +1,88 @@
|
||||
/**
|
||||
* Copyright (c) 20011-2017 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef SysCall_h
|
||||
#define SysCall_h
|
||||
/**
|
||||
* \file
|
||||
* \brief SysCall class
|
||||
*/
|
||||
#if defined(ARDUINO)
|
||||
#include <Arduino.h>
|
||||
#include <SPI.h>
|
||||
#elif defined(PLATFORM_ID) // Only defined if a Particle device
|
||||
#include "application.h"
|
||||
#else // defined(ARDUINO)
|
||||
#error "Unknown system"
|
||||
#endif // defined(ARDUINO)
|
||||
//-----------------------------------------------------------------------------
|
||||
#ifdef ESP8266
|
||||
// undefine F macro if ESP8266.
|
||||
#undef F
|
||||
#endif // ESP8266
|
||||
//-----------------------------------------------------------------------------
|
||||
#ifndef F
|
||||
/** Define macro for strings stored in flash. */
|
||||
#define F(str) (str)
|
||||
#endif // F
|
||||
//-----------------------------------------------------------------------------
|
||||
/** \return the time in milliseconds. */
|
||||
inline uint16_t curTimeMS() {
|
||||
return millis();
|
||||
}
|
||||
//-----------------------------------------------------------------------------
|
||||
/**
|
||||
* \class SysCall
|
||||
* \brief SysCall - Class to wrap system calls.
|
||||
*/
|
||||
class SysCall {
|
||||
public:
|
||||
/** Halt execution of this thread. */
|
||||
static void halt() {
|
||||
while (1) {
|
||||
yield();
|
||||
}
|
||||
}
|
||||
/** Yield to other threads. */
|
||||
static void yield();
|
||||
};
|
||||
|
||||
#if defined(ESP8266)
|
||||
inline void SysCall::yield() {
|
||||
// Avoid ESP8266 bug
|
||||
delay(0);
|
||||
}
|
||||
#elif defined(ARDUINO)
|
||||
inline void SysCall::yield() {
|
||||
// Use the external Arduino yield() function.
|
||||
::yield();
|
||||
}
|
||||
#elif defined(PLATFORM_ID) // Only defined if a Particle device
|
||||
inline void SysCall::yield() {
|
||||
Particle.process();
|
||||
}
|
||||
#else // ESP8266
|
||||
inline void SysCall::yield() {}
|
||||
#endif // ESP8266
|
||||
#endif // SysCall_h
|
33
Repetier-Firmware 1.0.3/Repetier/src/SdFat/sdios.h
Normal file
33
Repetier-Firmware 1.0.3/Repetier/src/SdFat/sdios.h
Normal file
@ -0,0 +1,33 @@
|
||||
/**
|
||||
* Copyright (c) 2011-2018 Bill Greiman
|
||||
* This file is part of the SdFat library for SD memory cards.
|
||||
*
|
||||
* MIT License
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included
|
||||
* in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
|
||||
* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
#ifndef sdios_h
|
||||
#define sdios_h
|
||||
/**
|
||||
* \file
|
||||
* \brief C++ IO Streams features.
|
||||
*/
|
||||
#include "FatLib/fstream.h"
|
||||
#include "FatLib/ArduinoStream.h"
|
||||
#endif // sdios_h
|
10903
Repetier-Firmware 1.0.3/Repetier/u8glib_ex.h
Normal file
10903
Repetier-Firmware 1.0.3/Repetier/u8glib_ex.h
Normal file
File diff suppressed because it is too large
Load Diff
4157
Repetier-Firmware 1.0.3/Repetier/ui.cpp
Normal file
4157
Repetier-Firmware 1.0.3/Repetier/ui.cpp
Normal file
File diff suppressed because it is too large
Load Diff
676
Repetier-Firmware 1.0.3/Repetier/ui.h
Normal file
676
Repetier-Firmware 1.0.3/Repetier/ui.h
Normal file
@ -0,0 +1,676 @@
|
||||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware 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.
|
||||
|
||||
Repetier-Firmware 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 Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
|
||||
#ifndef _ui_h
|
||||
#define _ui_h
|
||||
|
||||
//#include "gcode.h"
|
||||
|
||||
#define NO_DISPLAY 0
|
||||
#define DISPLAY_4BIT 1
|
||||
#define DISPLAY_8BIT 2
|
||||
#define DISPLAY_I2C 3
|
||||
#define DISPLAY_ARDUINO_LIB 4
|
||||
#define DISPLAY_U8G 5
|
||||
#define DISPLAY_GAMEDUINO2 6
|
||||
#define DISPLAY_SR 7
|
||||
|
||||
/**
|
||||
What display type do you use?
|
||||
0 = No display
|
||||
1 = LCD Display with 4 bit data bus
|
||||
2 = LCD Display with 8 bit data bus (currently not implemented, fallback to 1)
|
||||
3 = LCD Display with I2C connection, 4 bit mode
|
||||
4 = Use the slower LiquiedCrystal library bundled with arduino.
|
||||
IMPORTANT: You need to uncomment the LiquidCrystal include in Repetier.pde for it to work.
|
||||
If you have Sanguino and want to use the library, you need to have Arduino 023 or older. (13.04.2012)
|
||||
5 = U8G supported display
|
||||
6 = Gameduino2 display
|
||||
7 = LCD Display via shift register (2 or 3 wire connection: DATA/EN, CLOCK, ENABLE/-1)
|
||||
*/
|
||||
|
||||
// ----------------------------------------------------------------------------
|
||||
// Action codes
|
||||
// 1-999 : Autorepeat
|
||||
// 1000-1999 : Execute
|
||||
// 2000-2999 : Write code
|
||||
// 4000-4999 : Show menu
|
||||
// 5000-5999 : Wizard pages
|
||||
// Add UI_ACTION_TOPMENU to show a menu as top menu
|
||||
// Add UI_ACTION_NO_AUTORETURN to prevent auto return to start display
|
||||
// ----------------------------------------------------------------------------
|
||||
|
||||
#define UI_ACTION_TOPMENU 8192
|
||||
#define UI_ACTION_NO_AUTORETURN 16384
|
||||
|
||||
#define UI_ACTION_NEXT 1
|
||||
#define UI_ACTION_PREVIOUS 2
|
||||
|
||||
#define UI_ACTION_X_UP 100
|
||||
#define UI_ACTION_X_DOWN 101
|
||||
#define UI_ACTION_Y_UP 102
|
||||
#define UI_ACTION_Y_DOWN 103
|
||||
#define UI_ACTION_Z_UP 104
|
||||
#define UI_ACTION_Z_DOWN 105
|
||||
#define UI_ACTION_EXTRUDER_UP 106
|
||||
#define UI_ACTION_EXTRUDER_DOWN 107
|
||||
#define UI_ACTION_EXTRUDER_TEMP_UP 108
|
||||
#define UI_ACTION_EXTRUDER_TEMP_DOWN 109
|
||||
#define UI_ACTION_HEATED_BED_UP 110
|
||||
#define UI_ACTION_HEATED_BED_DOWN 111
|
||||
#define UI_ACTION_FAN_UP 112
|
||||
#define UI_ACTION_FAN_DOWN 113
|
||||
// 700-999 reserved for custom events.
|
||||
|
||||
|
||||
#define UI_ACTION_DUMMY 10000
|
||||
#define UI_ACTION_BACK 1000
|
||||
#define UI_ACTION_OK 1001
|
||||
#define UI_ACTION_MENU_UP 1002
|
||||
#define UI_ACTION_TOP_MENU 1003
|
||||
#define UI_ACTION_EMERGENCY_STOP 1004
|
||||
#define UI_ACTION_XPOSITION 1005
|
||||
#define UI_ACTION_YPOSITION 1006
|
||||
#define UI_ACTION_ZPOSITION 1007
|
||||
#define UI_ACTION_EPOSITION 1008
|
||||
#define UI_ACTION_BED_TEMP 1009
|
||||
#define UI_ACTION_EXTRUDER_TEMP 1010
|
||||
#define UI_ACTION_SD_DELETE 1012
|
||||
#define UI_ACTION_SD_PRINT 1013
|
||||
#define UI_ACTION_SD_PAUSE 1014
|
||||
#define UI_ACTION_SD_CONTINUE 1015
|
||||
#define UI_ACTION_SD_UNMOUNT 1016
|
||||
#define UI_ACTION_SD_MOUNT 1017
|
||||
#define UI_ACTION_XPOSITION_FAST 1018
|
||||
#define UI_ACTION_YPOSITION_FAST 1019
|
||||
#define UI_ACTION_ZPOSITION_FAST 1020
|
||||
#define UI_ACTION_HOME_ALL 1021
|
||||
#define UI_ACTION_HOME_X 1022
|
||||
#define UI_ACTION_HOME_Y 1023
|
||||
#define UI_ACTION_HOME_Z 1024
|
||||
#define UI_ACTION_STORE_EEPROM 1030
|
||||
#define UI_ACTION_LOAD_EEPROM 1031
|
||||
#define UI_ACTION_PRINT_ACCEL_X 1032
|
||||
#define UI_ACTION_PRINT_ACCEL_Y 1033
|
||||
#define UI_ACTION_PRINT_ACCEL_Z 1034
|
||||
#define UI_ACTION_MOVE_ACCEL_X 1035
|
||||
#define UI_ACTION_MOVE_ACCEL_Y 1036
|
||||
#define UI_ACTION_MOVE_ACCEL_Z 1037
|
||||
#define UI_ACTION_MAX_JERK 1038
|
||||
#define UI_ACTION_MAX_ZJERK 1039
|
||||
#define UI_ACTION_BAUDRATE 1040
|
||||
#define UI_ACTION_HOMING_FEEDRATE_X 1041
|
||||
#define UI_ACTION_HOMING_FEEDRATE_Y 1042
|
||||
#define UI_ACTION_HOMING_FEEDRATE_Z 1043
|
||||
#define UI_ACTION_MAX_FEEDRATE_X 1044
|
||||
#define UI_ACTION_MAX_FEEDRATE_Y 1045
|
||||
#define UI_ACTION_MAX_FEEDRATE_Z 1046
|
||||
#define UI_ACTION_STEPS_X 1047
|
||||
#define UI_ACTION_STEPS_Y 1048
|
||||
#define UI_ACTION_STEPS_Z 1049
|
||||
#define UI_ACTION_FAN_OFF 1050
|
||||
#define UI_ACTION_FAN_25 1051
|
||||
#define UI_ACTION_FAN_50 1052
|
||||
#define UI_ACTION_FAN_75 1053
|
||||
#define UI_ACTION_FAN_FULL 1054
|
||||
#define UI_ACTION_FEEDRATE_MULTIPLY 1055
|
||||
#define UI_ACTION_STEPPER_INACTIVE 1056
|
||||
|
||||
#define UI_ACTION_PID_PGAIN 1058
|
||||
#define UI_ACTION_PID_IGAIN 1059
|
||||
#define UI_ACTION_PID_DGAIN 1060
|
||||
#define UI_ACTION_DRIVE_MIN 1061
|
||||
#define UI_ACTION_DRIVE_MAX 1062
|
||||
#define UI_ACTION_X_OFFSET 1063
|
||||
#define UI_ACTION_Y_OFFSET 1064
|
||||
#define UI_ACTION_EXTR_STEPS 1065
|
||||
#define UI_ACTION_EXTR_ACCELERATION 1066
|
||||
#define UI_ACTION_EXTR_MAX_FEEDRATE 1067
|
||||
#define UI_ACTION_EXTR_START_FEEDRATE 1068
|
||||
#define UI_ACTION_EXTR_HEATMANAGER 1069
|
||||
#define UI_ACTION_EXTR_WATCH_PERIOD 1070
|
||||
#define UI_ACTION_PID_MAX 1071
|
||||
#define UI_ACTION_ADVANCE_K 1072
|
||||
#define UI_ACTION_SET_ORIGIN 1073
|
||||
|
||||
#define UI_ACTION_POWER 1078
|
||||
#define UI_ACTION_PREHEAT_SINGLE 1079
|
||||
#define UI_ACTION_COOLDOWN 1080
|
||||
#define UI_ACTION_HEATED_BED_OFF 1081
|
||||
#define UI_ACTION_EXTRUDER0_OFF 1082
|
||||
#define UI_ACTION_EXTRUDER1_OFF 1083
|
||||
#define UI_ACTION_EXTRUDER2_OFF 1084
|
||||
#define UI_ACTION_EXTRUDER3_OFF 1085
|
||||
#define UI_ACTION_EXTRUDER4_OFF 1086
|
||||
#define UI_ACTION_EXTRUDER5_OFF 1087
|
||||
#define UI_ACTION_OPS_OFF 1088
|
||||
#define UI_ACTION_OPS_CLASSIC 1089
|
||||
#define UI_ACTION_OPS_FAST 1090
|
||||
#define UI_ACTION_DISABLE_STEPPER 1091
|
||||
#define UI_ACTION_RESET_EXTRUDER 1092
|
||||
#define UI_ACTION_EXTRUDER_RELATIVE 1093
|
||||
#define UI_ACTION_ADVANCE_L 1094
|
||||
#define UI_ACTION_PREHEAT_ALL 1095
|
||||
#define UI_ACTION_FLOWRATE_MULTIPLY 1096
|
||||
#define UI_ACTION_KILL 1097
|
||||
#define UI_ACTION_RESET 1098
|
||||
#define UI_ACTION_PAUSE 1099
|
||||
#define UI_ACTION_EXTR_WAIT_RETRACT_TEMP 1100
|
||||
#define UI_ACTION_EXTR_WAIT_RETRACT_UNITS 1101
|
||||
#define UI_ACTION_WRITE_DEBUG 1105
|
||||
#define UI_ACTION_FANSPEED 1106
|
||||
#define UI_ACTION_LIGHTS_ONOFF 1107
|
||||
#define UI_ACTION_SD_STOP 1108
|
||||
#define UI_ACTION_ZPOSITION_NOTEST 1109
|
||||
#define UI_ACTION_ZPOSITION_FAST_NOTEST 1110
|
||||
#define UI_ACTION_Z_BABYSTEPS 1111
|
||||
#define UI_ACTION_MAX_INACTIVE 1112
|
||||
#define UI_ACTION_TEMP_DEFECT 1113
|
||||
#define UI_ACTION_BED_HEATMANAGER 1114
|
||||
#define UI_ACTION_BED_PGAIN 1115
|
||||
#define UI_ACTION_BED_IGAIN 1116
|
||||
#define UI_ACTION_BED_DGAIN 1117
|
||||
#define UI_ACTION_BED_DRIVE_MIN 1118
|
||||
#define UI_ACTION_BED_DRIVE_MAX 1119
|
||||
#define UI_ACTION_BED_MAX 1120
|
||||
#define UI_ACTION_HEATED_BED_TEMP 1121
|
||||
#define UI_ACTION_EXTRUDER0_TEMP 1122
|
||||
#define UI_ACTION_EXTRUDER1_TEMP 1123
|
||||
#define UI_ACTION_EXTRUDER2_TEMP 1124
|
||||
#define UI_ACTION_EXTRUDER3_TEMP 1125
|
||||
#define UI_ACTION_EXTRUDER4_TEMP 1126
|
||||
#define UI_ACTION_EXTRUDER5_TEMP 1127
|
||||
#define UI_ACTION_SELECT_EXTRUDER0 1128
|
||||
#define UI_ACTION_SELECT_EXTRUDER1 1129
|
||||
#define UI_ACTION_SELECT_EXTRUDER2 1130
|
||||
#define UI_ACTION_SELECT_EXTRUDER3 1131
|
||||
#define UI_ACTION_SELECT_EXTRUDER4 1132
|
||||
#define UI_ACTION_SELECT_EXTRUDER5 1133
|
||||
#define UI_DITTO_0 1134
|
||||
#define UI_DITTO_1 1135
|
||||
#define UI_DITTO_2 1136
|
||||
#define UI_DITTO_3 1137
|
||||
|
||||
#define UI_ACTION_DEBUG_ECHO 1150
|
||||
#define UI_ACTION_DEBUG_INFO 1151
|
||||
#define UI_ACTION_DEBUG_ERROR 1152
|
||||
#define UI_ACTION_DEBUG_DRYRUN 1153
|
||||
#define UI_ACTION_DEBUG_ENDSTOP 1154
|
||||
|
||||
#define UI_ACTION_SD_PRI_PAU_CONT 1200
|
||||
#define UI_ACTION_FAN_SUSPEND 1201
|
||||
#define UI_ACTION_AUTOLEVEL_ONOFF 1202
|
||||
#define UI_ACTION_SERVOPOS 1203
|
||||
#define UI_ACTION_IGNORE_M106 1204
|
||||
|
||||
#define UI_ACTION_KAPTON 1205
|
||||
#define UI_ACTION_BLUETAPE 1206
|
||||
#define UI_ACTION_NOCOATING 1207
|
||||
#define UI_ACTION_PETTAPE 1208
|
||||
#define UI_ACTION_GLUESTICK 1209
|
||||
#define UI_ACTION_RESET_MATRIX 1210
|
||||
#define UI_ACTION_CALIBRATE 1211
|
||||
#define UI_ACTION_BED_LED_CHANGE 1212
|
||||
#define UI_ACTION_COATING_CUSTOM 1213
|
||||
#define UI_ACTION_BUILDTAK 1214
|
||||
|
||||
#define UI_ACTION_CONTINUE 1220
|
||||
#define UI_ACTION_STOP 1221
|
||||
#define UI_ACTION_STOP_CONFIRMED 1222
|
||||
#define UI_ACTION_FAN2SPEED 1223
|
||||
#define UI_ACTION_AUTOLEVEL 1224
|
||||
#define UI_ACTION_MEASURE_DISTORTION 1225
|
||||
#define UI_ACTION_TOGGLE_DISTORTION 1226
|
||||
#define UI_ACTION_MESSAGE 1227
|
||||
#define UI_ACTION_STATE 1228
|
||||
#define UI_ACTION_AUTOLEVEL2 1229
|
||||
#define UI_ACTION_MEASURE_DISTORTION2 1230
|
||||
#define UI_ACTION_BED_PREHEAT 1231
|
||||
#define UI_ACTION_EXT0_PREHEAT 1232
|
||||
#define UI_ACTION_EXT1_PREHEAT 1233
|
||||
#define UI_ACTION_EXT2_PREHEAT 1234
|
||||
#define UI_ACTION_EXT3_PREHEAT 1235
|
||||
#define UI_ACTION_EXT4_PREHEAT 1236
|
||||
#define UI_ACTION_EXT5_PREHEAT 1237
|
||||
#define UI_ACTION_MEASURE_ZPROBE_HEIGHT 1238
|
||||
#define UI_ACTION_MEASURE_ZPROBE_HEIGHT2 1239
|
||||
#define UI_ACTION_MEASURE_ZP_REALZ 1240
|
||||
#define UI_ACTION_Z_OFFSET 1241
|
||||
#define UI_ACTION_TOGGLE_JAMCONTROL 1242
|
||||
#define UI_ACTION_RESET_EEPROM 1243
|
||||
|
||||
// 1500-1699 reserved for custom actions
|
||||
|
||||
// 1700-1956 language selectors
|
||||
|
||||
#define UI_ACTION_LANGUAGE_EN 1700
|
||||
#define UI_ACTION_LANGUAGE_DE 1701
|
||||
#define UI_ACTION_LANGUAGE_NL 1702
|
||||
#define UI_ACTION_LANGUAGE_PT 1703
|
||||
#define UI_ACTION_LANGUAGE_IT 1704
|
||||
#define UI_ACTION_LANGUAGE_ES 1705
|
||||
#define UI_ACTION_LANGUAGE_SE 1706
|
||||
#define UI_ACTION_LANGUAGE_FR 1707
|
||||
#define UI_ACTION_LANGUAGE_CZ 1708
|
||||
#define UI_ACTION_LANGUAGE_PL 1709
|
||||
#define UI_ACTION_LANGUAGE_TR 1710
|
||||
#define UI_ACTION_LANGUAGE_FI 1711
|
||||
|
||||
#define UI_ACTION_MENU_XPOS 4000
|
||||
#define UI_ACTION_MENU_YPOS 4001
|
||||
#define UI_ACTION_MENU_ZPOS 4002
|
||||
#define UI_ACTION_MENU_XPOSFAST 4003
|
||||
#define UI_ACTION_MENU_YPOSFAST 4004
|
||||
#define UI_ACTION_MENU_ZPOSFAST 4005
|
||||
#define UI_ACTION_MENU_SDCARD 4006
|
||||
#define UI_ACTION_MENU_QUICKSETTINGS 4007
|
||||
#define UI_ACTION_MENU_EXTRUDER 4008
|
||||
#define UI_ACTION_MENU_POSITIONS 4009
|
||||
//#define UI_ACTION_SHOW_MEASUREMENT 4010
|
||||
//#define UI_ACTION_RESET_MEASUREMENT 4011
|
||||
#define UI_ACTION_SET_MEASURED_ORIGIN 4012
|
||||
#define UI_ACTION_SET_P1 4013
|
||||
#define UI_ACTION_SET_P2 4014
|
||||
#define UI_ACTION_SET_P3 4015
|
||||
#define UI_ACTION_CALC_LEVEL 4016
|
||||
#define UI_ACTION_XOFF 4020
|
||||
#define UI_ACTION_YOFF 4021
|
||||
#define UI_ACTION_ZOFF 4022
|
||||
|
||||
#define UI_ACTION_SHOW_USERMENU1 4101
|
||||
#define UI_ACTION_SHOW_USERMENU2 4102
|
||||
#define UI_ACTION_SHOW_USERMENU3 4103
|
||||
#define UI_ACTION_SHOW_USERMENU4 4104
|
||||
#define UI_ACTION_SHOW_USERMENU5 4105
|
||||
#define UI_ACTION_SHOW_USERMENU6 4106
|
||||
#define UI_ACTION_SHOW_USERMENU7 4107
|
||||
#define UI_ACTION_SHOW_USERMENU8 4108
|
||||
#define UI_ACTION_SHOW_USERMENU9 4109
|
||||
#define UI_ACTION_SHOW_USERMENU10 4110
|
||||
|
||||
#define UI_ACTION_WIZARD_FILAMENTCHANGE 5000
|
||||
#define UI_ACTION_WIZARD_JAM_REHEAT 5001
|
||||
#define UI_ACTION_WIZARD_JAM_WAITHEAT 5002
|
||||
#define UI_ACTION_WIZARD_JAM_EOF 5003
|
||||
|
||||
// Load basic language definition to make sure all values are defined
|
||||
//#include "uilang.h"
|
||||
|
||||
#define UI_MENU_TYPE_INFO 0
|
||||
#define UI_MENU_TYPE_FILE_SELECTOR 1
|
||||
#define UI_MENU_TYPE_SUBMENU 2
|
||||
#define UI_MENU_TYPE_MODIFICATION_MENU 3
|
||||
#define UI_MENU_TYPE_WIZARD 5
|
||||
|
||||
struct UIMenuEntry_s {
|
||||
const char *text; // Menu text
|
||||
uint8_t entryType; // 0 = Info, 1 = Headline, 2 = sub menu ref, 3 = direct action command, 4 = modify action command,
|
||||
unsigned int action; // must be int so it gets 32 bit on arm!
|
||||
uint16_t filter; // allows dynamic menu filtering based on Printer::menuMode bits set.
|
||||
uint16_t nofilter; // Hide if one of these bits are set
|
||||
int translation; // Translation id
|
||||
bool showEntry() const;
|
||||
} ;
|
||||
typedef const UIMenuEntry_s UIMenuEntry;
|
||||
|
||||
struct UIMenu_s {
|
||||
// 0 = info page
|
||||
// 1 = file selector
|
||||
// 2 = sub menu
|
||||
// 3 = modification menu
|
||||
// 5 = Wizard menu
|
||||
// +128 = sticky -> no autoreturn to main menuü after timeout
|
||||
uint8_t menuType;
|
||||
int id; // Type of modification
|
||||
int numEntries;
|
||||
const UIMenuEntry * const * entries;
|
||||
};
|
||||
typedef const UIMenu_s UIMenu;
|
||||
|
||||
extern const int8_t encoder_table[16] PROGMEM ;
|
||||
|
||||
//#ifdef COMPILE_I2C_DRIVER
|
||||
|
||||
/*************************************************************************
|
||||
Title: C include file for the I2C master interface
|
||||
(i2cmaster.S or twimaster.c)
|
||||
Author: Peter Fleury <pfleury@gmx.ch> http://jump.to/fleury
|
||||
File: $Id: i2cmaster.h,v 1.10 2005/03/06 22:39:57 Peter Exp $
|
||||
Software: AVR-GCC 3.4.3 / avr-libc 1.2.3
|
||||
Target: any AVR device
|
||||
Usage: see Doxygen manual
|
||||
**************************************************************************/
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//extern const int matrixActions[] PROGMEM;
|
||||
// Key codes
|
||||
#define UI_KEYS_INIT_CLICKENCODER_LOW(pinA,pinB) SET_INPUT(pinA);SET_INPUT(pinB); PULLUP(pinA,HIGH);PULLUP(pinB,HIGH);
|
||||
#define UI_KEYS_INIT_BUTTON_LOW(pin) SET_INPUT(pin);PULLUP(pin,HIGH);
|
||||
#define UI_KEYS_INIT_CLICKENCODER_HIGH(pinA,pinB) SET_INPUT(pinA);SET_INPUT(pinB); PULLUP(pinA,LOW);PULLUP(pinB,LOW);
|
||||
#define UI_KEYS_INIT_BUTTON_HIGH(pin) SET_INPUT(pin);PULLUP(pin,LOW);
|
||||
|
||||
#define UI_KEYS_CLICKENCODER_LOW(pinA,pinB) uid.encoderLast = (uid.encoderLast << 2) & 0x0F;if (!READ(pinA)) uid.encoderLast |=2;if (!READ(pinB)) uid.encoderLast |=1; uid.encoderPos += pgm_read_byte(&encoder_table[uid.encoderLast]);
|
||||
#define UI_KEYS_CLICKENCODER_LOW_REV(pinA,pinB) uid.encoderLast = (uid.encoderLast << 2) & 0x0F;if (!READ(pinA)) uid.encoderLast |=2;if (!READ(pinB)) uid.encoderLast |=1; uid.encoderPos -= pgm_read_byte(&encoder_table[uid.encoderLast]);
|
||||
#define UI_KEYS_BUTTON_LOW(pin,action_) if(READ(pin)==0) action=action_;
|
||||
#define UI_KEYS_CLICKENCODER_HIGH(pinA,pinB) uid.encoderLast = (uid.encoderLast << 2) & 0x0F;if (READ(pinA)) uid.encoderLast |=2;if (READ(pinB)) uid.encoderLast |=1; uid.encoderPos += pgm_read_byte(&encoder_table[uid.encoderLast]);
|
||||
#define UI_KEYS_CLICKENCODER_HIGH_REV(pinA,pinB) uid.encoderLast = (uid.encoderLast << 2) & 0x0F;if (READ(pinA)) uid.encoderLast |=2;if (READ(pinB)) uid.encoderLast |=1; uid.encoderPos -= pgm_read_byte(&encoder_table[uid.encoderLast]);
|
||||
#define UI_KEYS_BUTTON_HIGH(pin,action_) if(READ(pin)!=0) action=action_;
|
||||
#define UI_KEYS_INIT_MATRIX(r1,r2,r3,r4,c1,c2,c3,c4) if(c1>=0){SET_INPUT(c1);WRITE(c1,HIGH);}if(c2>=0){SET_INPUT(c2);WRITE(c2,HIGH);}if(c3>=0){SET_INPUT(c3);WRITE(c3,HIGH);}\
|
||||
if(c4>=0) {SET_INPUT(c4);WRITE(c4,HIGH);}if(r1>=0)SET_OUTPUT(r1);if(r2>=0)SET_OUTPUT(r2);if(r3>=0)SET_OUTPUT(r3);if(r4>=0)SET_OUTPUT(r4);\
|
||||
if(r1>=0)WRITE(r1,LOW);if(r2>=0)WRITE(r2,LOW);if(r3>=0)WRITE(r3,LOW);if(r4>=0)WRITE(r4,LOW);
|
||||
// out.print_int_P(PSTR("r4=>c1:"),READ(c1));out.print_int_P(PSTR(" c2:"),READ(c2));out.print_int_P(PSTR(" c3:"),READ(c3));out.println_int_P(PSTR(" c4:"),READ(c4));
|
||||
#define UI_KEYS_MATRIX(r1,r2,r3,r4,c1,c2,c3,c4) {uint8_t r = (c1>=0?READ(c1):1) && (c2>=0?READ(c2):1) && (c3>=0?READ(c3):1) && (c4>=0?READ(c4):1);\
|
||||
if(!r) {\
|
||||
r = 255;\
|
||||
if(r2>=0)WRITE(r2,HIGH);if(r3>=0)WRITE(r3,HIGH);if(r4>=0)WRITE(r4,HIGH);\
|
||||
if(r1>=0) {\
|
||||
asm volatile ("nop\nnop\nnop\nnop\nnop");\
|
||||
if(!((c1>=0?READ(c1):1) && (c2>=0?READ(c2):1) && (c3>=0?READ(c3):1) && (c4>=0?READ(c4):1))) r = 0;\
|
||||
else WRITE(r1,HIGH);\
|
||||
}\
|
||||
if(r==255 && r2>=0) {\
|
||||
WRITE(r2,LOW);asm volatile ("nop\nnop\nnop\nnop\nnop");\
|
||||
if(!((c1>=0?READ(c1):1) && (c2>=0?READ(c2):1) && (c3>=0?READ(c3):1) && (c4>=0?READ(c4):1))) r = 4;\
|
||||
else WRITE(r2,HIGH);\
|
||||
}\
|
||||
if(r==255 && r3>=0) {\
|
||||
WRITE(r3,LOW);asm volatile ("nop\nnop\nnop\nnop\nnop");\
|
||||
if(!((c1>=0?READ(c1):0) && (c2>=0?READ(c2):1) && (c3>=0?READ(c3):1) && (c4>=0?READ(c4):1))) r = 8;\
|
||||
else WRITE(r3,HIGH);\
|
||||
}\
|
||||
if(r==255 && r4>=0) {\
|
||||
WRITE(r4,LOW);asm volatile ("nop\nnop\nnop\nnop\nnop");\
|
||||
if(!((c1>=0?READ(c1):1) && (c2>=0?READ(c2):1) && (c3>=0?READ(c3):1) && (c4>=0?READ(c4):1))) r = 12;\
|
||||
else WRITE(r4,HIGH);\
|
||||
}\
|
||||
if(c2>=0 && !READ(c2)) r+=1;\
|
||||
else if(c3>=0 && !READ(c3)) r+=2;\
|
||||
else if(c4>=0 && !READ(c4)) r+=3;\
|
||||
if(r<16) {action = pgm_read_word(&(matrixActions[r]));}\
|
||||
}if(r1>=0)WRITE(r1,LOW);if(r2>=0)WRITE(r2,LOW);if(r3>=0)WRITE(r3,LOW);if(r4>=0)WRITE(r4,LOW);}
|
||||
// I2C keymask tests
|
||||
#define UI_KEYS_I2C_CLICKENCODER_LOW(pinA,pinB) uid.encoderLast = (uid.encoderLast << 2) & 0x0F;if (!(keymask & pinA)) uid.encoderLast |=2;if (!(keymask & pinB)) uid.encoderLast |=1; uid.encoderPos += pgm_read_byte(&encoder_table[uid.encoderLast]);
|
||||
#define UI_KEYS_I2C_CLICKENCODER_LOW_REV(pinA,pinB) uid.encoderLast = (uid.encoderLast << 2) & 0x0F;if (!(keymask & pinA)) uid.encoderLast |=2;if (!(keymask & pinB)) uid.encoderLast |=1; uid.encoderPos -= pgm_read_byte(&encoder_table[uid.encoderLast]);
|
||||
#define UI_KEYS_I2C_BUTTON_LOW(pin,action_) if((keymask & pin)==0) action=action_;
|
||||
#define UI_KEYS_I2C_CLICKENCODER_HIGH(pinA,pinB) uid.encoderLast = (uid.encoderLast << 2) & 0x0F;if (keymask & pinA) uid.encoderLast |=2;if (keymask & pinB) uid.encoderLast |=1; uid.encoderPos += pgm_read_byte(&encoder_table[uid.encoderLast]);
|
||||
#define UI_KEYS_I2C_CLICKENCODER_HIGH_REV(pinA,pinB) uid.encoderLast = (uid.encoderLast << 2) & 0x0F;if (keymask & pinA) uid.encoderLast |=2;if (keymask & pinB) uid.encoderLast |=1; uid.encoderPos -= pgm_read_byte(&encoder_table[uid.encoderLast]);
|
||||
#define UI_KEYS_I2C_BUTTON_HIGH(pin,action_) if((pin & keymask) != 0) action=action_;
|
||||
|
||||
#define UI_STRING(name,text) const char PROGMEM name[] = text
|
||||
|
||||
#define UI_PAGE6(name,row1,row2,row3,row4,row5,row6) UI_STRING(name ## _1txt,row1);UI_STRING(name ## _2txt,row2);UI_STRING(name ## _3txt,row3);UI_STRING(name ## _4txt,row4);UI_STRING(name ## _5txt,row5);UI_STRING(name ## _6txt,row6);\
|
||||
UIMenuEntry name ## _1 PROGMEM ={name ## _1txt,0,0,0,0,0};\
|
||||
UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,0,0};\
|
||||
UIMenuEntry name ## _3 PROGMEM ={name ## _3txt,0,0,0,0,0};\
|
||||
UIMenuEntry name ## _4 PROGMEM ={name ## _4txt,0,0,0,0,0};\
|
||||
UIMenuEntry name ## _5 PROGMEM ={name ## _5txt,0,0,0,0,0};\
|
||||
UIMenuEntry name ## _6 PROGMEM ={name ## _6txt,0,0,0,0,0};\
|
||||
const UIMenuEntry * const name ## _entries [] PROGMEM = {&name ## _1,&name ## _2,&name ## _3,&name ## _4,&name ## _5,&name ## _6};\
|
||||
const UIMenu name PROGMEM = {0,0,6,name ## _entries};
|
||||
#define UI_PAGE6_T(name,row1,row2,row3,row4,row5,row6) \
|
||||
UIMenuEntry name ## _1 PROGMEM ={0,0,0,0,0,row1};\
|
||||
UIMenuEntry name ## _2 PROGMEM ={0,0,0,0,0,row2};\
|
||||
UIMenuEntry name ## _3 PROGMEM ={0,0,0,0,0,row3};\
|
||||
UIMenuEntry name ## _4 PROGMEM ={0,0,0,0,0,row4};\
|
||||
UIMenuEntry name ## _5 PROGMEM ={0,0,0,0,0,row5};\
|
||||
UIMenuEntry name ## _6 PROGMEM ={0,0,0,0,0,row6};\
|
||||
const UIMenuEntry * const name ## _entries [] PROGMEM = {&name ## _1,&name ## _2,&name ## _3,&name ## _4,&name ## _5,&name ## _6};\
|
||||
const UIMenu name PROGMEM = {0,0,6,name ## _entries};
|
||||
#define UI_PAGE4(name,row1,row2,row3,row4) UI_STRING(name ## _1txt,row1);UI_STRING(name ## _2txt,row2);UI_STRING(name ## _3txt,row3);UI_STRING(name ## _4txt,row4);\
|
||||
UIMenuEntry name ## _1 PROGMEM ={name ## _1txt,0,0,0,0,0};\
|
||||
UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,0,0};\
|
||||
UIMenuEntry name ## _3 PROGMEM ={name ## _3txt,0,0,0,0,0};\
|
||||
UIMenuEntry name ## _4 PROGMEM ={name ## _4txt,0,0,0,0,0};\
|
||||
const UIMenuEntry * const name ## _entries [] PROGMEM = {&name ## _1,&name ## _2,&name ## _3,&name ## _4};\
|
||||
const UIMenu name PROGMEM = {0,0,4,name ## _entries};
|
||||
#define UI_PAGE4_T(name,row1,row2,row3,row4) \
|
||||
UIMenuEntry name ## _1 PROGMEM ={0,0,0,0,0,row1};\
|
||||
UIMenuEntry name ## _2 PROGMEM ={0,0,0,0,0,row2};\
|
||||
UIMenuEntry name ## _3 PROGMEM ={0,0,0,0,0,row3};\
|
||||
UIMenuEntry name ## _4 PROGMEM ={0,0,0,0,0,row4};\
|
||||
const UIMenuEntry * const name ## _entries [] PROGMEM = {&name ## _1,&name ## _2,&name ## _3,&name ## _4};\
|
||||
const UIMenu name PROGMEM = {0,0,4,name ## _entries};
|
||||
#define UI_PAGE2(name,row1,row2) UI_STRING(name ## _1txt,row1);UI_STRING(name ## _2txt,row2);\
|
||||
UIMenuEntry name ## _1 PROGMEM ={name ## _1txt,0,0,0,0,0};\
|
||||
UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,0,0};\
|
||||
const UIMenuEntry * const name ## _entries[] PROGMEM = {&name ## _1,&name ## _2};\
|
||||
const UIMenu name PROGMEM = {0,0,2,name ## _entries};
|
||||
#define UI_PAGE2_T(name,row1,row2) \
|
||||
UIMenuEntry name ## _1 PROGMEM ={0,0,0,0,0,row1};\
|
||||
UIMenuEntry name ## _2 PROGMEM ={0,0,0,0,0,row2};\
|
||||
const UIMenuEntry * const name ## _entries[] PROGMEM = {&name ## _1,&name ## _2};\
|
||||
const UIMenu name PROGMEM = {0,0,2,name ## _entries};
|
||||
#define UI_WIZARD4(name,action,row1,row2,row3,row4) UI_STRING(name ## _1txt,row1);UI_STRING(name ## _2txt,row2);UI_STRING(name ## _3txt,row3);UI_STRING(name ## _4txt,row4);\
|
||||
UIMenuEntry name ## _1 PROGMEM ={name ## _1txt,0,0,0,0,0};\
|
||||
UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,0,0};\
|
||||
UIMenuEntry name ## _3 PROGMEM ={name ## _3txt,0,0,0,0,0};\
|
||||
UIMenuEntry name ## _4 PROGMEM ={name ## _4txt,0,0,0,0,0};\
|
||||
const UIMenuEntry * const name ## _entries [] PROGMEM = {&name ## _1,&name ## _2,&name ## _3,&name ## _4};\
|
||||
const UIMenu name PROGMEM = {5,action,4,name ## _entries};
|
||||
#define UI_WIZARD4_T(name,action,row1,row2,row3,row4) \
|
||||
UIMenuEntry name ## _1 PROGMEM ={0,0,0,0,0,row1};\
|
||||
UIMenuEntry name ## _2 PROGMEM ={0,0,0,0,0,row2};\
|
||||
UIMenuEntry name ## _3 PROGMEM ={0,0,0,0,0,row3};\
|
||||
UIMenuEntry name ## _4 PROGMEM ={0,0,0,0,0,row4};\
|
||||
const UIMenuEntry * const name ## _entries [] PROGMEM = {&name ## _1,&name ## _2,&name ## _3,&name ## _4};\
|
||||
const UIMenu name PROGMEM = {5,action,4,name ## _entries};
|
||||
#define UI_WIZARD5_T(name,action,row1,row2,row3,row4,row5) \
|
||||
UIMenuEntry name ## _1 PROGMEM ={0,0,0,0,0,row1};\
|
||||
UIMenuEntry name ## _2 PROGMEM ={0,0,0,0,0,row2};\
|
||||
UIMenuEntry name ## _3 PROGMEM ={0,0,0,0,0,row3};\
|
||||
UIMenuEntry name ## _4 PROGMEM ={0,0,0,0,0,row4};\
|
||||
UIMenuEntry name ## _5 PROGMEM ={0,0,0,0,0,row5};\
|
||||
const UIMenuEntry * const name ## _entries [] PROGMEM = {&name ## _1,&name ## _2,&name ## _3,&name ## _4,&name ## _5};\
|
||||
const UIMenu name PROGMEM = {5,action,5,name ## _entries};
|
||||
#define UI_WIZARD2(name,action,row1,row2) UI_STRING(name ## _1txt,row1);UI_STRING(name ## _2txt,row2);\
|
||||
UIMenuEntry name ## _1 PROGMEM ={name ## _1txt,0,0,0,0,0};\
|
||||
UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,0,0};\
|
||||
const UIMenuEntry * const name ## _entries[] PROGMEM = {&name ## _1,&name ## _2};\
|
||||
const UIMenu name PROGMEM = {5,action,2,name ## _entries};
|
||||
#define UI_WIZARD2_T(name,action,row1,row2) \
|
||||
UIMenuEntry name ## _1 PROGMEM ={0,0,0,0,0,row1};\
|
||||
UIMenuEntry name ## _2 PROGMEM ={0,0,0,0,0,row2};\
|
||||
const UIMenuEntry * const name ## _entries[] PROGMEM = {&name ## _1,&name ## _2};\
|
||||
const UIMenu name PROGMEM = {5,action,2,name ## _entries};
|
||||
#define UI_MENU_ACTION4C(name,action,rows) UI_MENU_ACTION4(name,action,rows)
|
||||
#define UI_MENU_ACTION2C(name,action,rows) UI_MENU_ACTION2(name,action,rows)
|
||||
#define UI_MENU_ACTION4C_T(name,action,rows) UI_MENU_ACTION4_T(name,action,rows)
|
||||
#define UI_MENU_ACTION2C_T(name,action,rows) UI_MENU_ACTION2_T(name,action,rows)
|
||||
#define UI_MENU_ACTION4(name,action,row1,row2,row3,row4) UI_STRING(name ## _1txt,row1);UI_STRING(name ## _2txt,row2);UI_STRING(name ## _3txt,row3);UI_STRING(name ## _4txt,row4);\
|
||||
UIMenuEntry name ## _1 PROGMEM ={name ## _1txt,0,0,0,0,0};\
|
||||
UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,0,0};\
|
||||
UIMenuEntry name ## _3 PROGMEM ={name ## _3txt,0,0,0,0,0};\
|
||||
UIMenuEntry name ## _4 PROGMEM ={name ## _4txt,0,0,0,0,0};\
|
||||
const UIMenuEntry * const name ## _entries[] PROGMEM = {&name ## _1,&name ## _2,&name ## _3,&name ## _4};\
|
||||
const UIMenu name PROGMEM = {3,action,4,name ## _entries};
|
||||
#define UI_MENU_ACTION4_T(name,action,row1,row2,row3,row4) \
|
||||
UIMenuEntry name ## _1 PROGMEM ={0,0,0,0,0,row1};\
|
||||
UIMenuEntry name ## _2 PROGMEM ={0,0,0,0,0,row2};\
|
||||
UIMenuEntry name ## _3 PROGMEM ={0,0,0,0,0,row3};\
|
||||
UIMenuEntry name ## _4 PROGMEM ={0,0,0,0,0,row4};\
|
||||
const UIMenuEntry * const name ## _entries[] PROGMEM = {&name ## _1,&name ## _2,&name ## _3,&name ## _4};\
|
||||
const UIMenu name PROGMEM = {3,action,4,name ## _entries};
|
||||
#define UI_MENU_ACTION2(name,action,row1,row2) UI_STRING(name ## _1txt,row1);UI_STRING(name ## _2txt,row2);\
|
||||
UIMenuEntry name ## _1 PROGMEM ={name ## _1txt,0,0,0,0,0};\
|
||||
UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,0,0};\
|
||||
const UIMenuEntry * const name ## _entries[] PROGMEM = {&name ## _1,&name ## _2};\
|
||||
const UIMenu name PROGMEM = {3,action,2,name ## _entries};
|
||||
#define UI_MENU_ACTION2_T(name,action,row1,row2) \
|
||||
UIMenuEntry name ## _1 PROGMEM ={0,0,0,0,0,row1};\
|
||||
UIMenuEntry name ## _2 PROGMEM ={0,0,0,0,0,row2};\
|
||||
const UIMenuEntry * const name ## _entries[] PROGMEM = {&name ## _1,&name ## _2};\
|
||||
const UIMenu name PROGMEM = {3,action,2,name ## _entries};
|
||||
#define UI_MENU_HEADLINE(name,text) UI_STRING(name ## _txt,text);UIMenuEntry name PROGMEM = {name ## _txt,1,0,0,0,0};
|
||||
#define UI_MENU_HEADLINE_T(name,text) UIMenuEntry name PROGMEM = {0,1,0,0,0,text};
|
||||
#define UI_MENU_CHANGEACTION(name,row,action) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,4,action,0,0,0};
|
||||
#define UI_MENU_CHANGEACTION_T(name,row,action) UIMenuEntry name PROGMEM = {0,4,action,0,0,row};
|
||||
#define UI_MENU_ACTIONCOMMAND(name,row,action) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,3,action,0,0,0};
|
||||
#define UI_MENU_ACTIONCOMMAND_T(name,rowId,action) UIMenuEntry name PROGMEM = {0,3,action,0,0,rowId};
|
||||
#define UI_MENU_ACTIONSELECTOR(name,row,entries) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,2,(unsigned int)&entries,0,0,0};
|
||||
#define UI_MENU_ACTIONSELECTOR_T(name,row,entries) UIMenuEntry name PROGMEM = {0,2,(unsigned int)&entries,0,0,row};
|
||||
#define UI_MENU_SUBMENU(name,row,entries) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,2,(unsigned int)&entries,0,0,0};
|
||||
#define UI_MENU_SUBMENU_T(name,row,entries) UIMenuEntry name PROGMEM = {0,2,(unsigned int)&entries,0,0,row};
|
||||
#define UI_MENU_WIZARD(name,row,entries) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,5,(unsigned int)&entries,0,0,0};
|
||||
#define UI_MENU_WIZARD_T(name,row,entries) UIMenuEntry name PROGMEM = {0,5,(unsigned int)&entries,0,0,row};
|
||||
#define UI_MENU_CHANGEACTION_FILTER(name,row,action,filter,nofilter) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,4,action,filter,nofilter,0};
|
||||
#define UI_MENU_CHANGEACTION_FILTER_T(name,row,action,filter,nofilter) UIMenuEntry name PROGMEM = {0,4,action,filter,nofilter,row};
|
||||
#define UI_MENU_ACTIONCOMMAND_FILTER(name,row,action,filter,nofilter) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,3,action,filter,nofilter,0};
|
||||
#define UI_MENU_ACTIONCOMMAND_FILTER_T(name,row,action,filter,nofilter) UIMenuEntry name PROGMEM = {0,3,action,filter,nofilter,row};
|
||||
#define UI_MENU_ACTIONSELECTOR_FILTER(name,row,entries,filter,nofilter) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,2,(unsigned int)&entries,filter,nofilter,0};
|
||||
#define UI_MENU_ACTIONSELECTOR_FILTER_T(name,row,entries,filter,nofilter) UIMenuEntry name PROGMEM = {0,2,(unsigned int)&entries,filter,nofilter,row};
|
||||
#define UI_MENU_SUBMENU_FILTER(name,row,entries,filter,nofilter) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,2,(unsigned int)&entries,filter,nofilter,0};
|
||||
#define UI_MENU_SUBMENU_FILTER_T(name,row,entries,filter,nofilter) UIMenuEntry name PROGMEM = {0,2,(unsigned int)&entries,filter,nofilter,row};
|
||||
#define UI_MENU(name,items,itemsCnt) const UIMenuEntry * const name ## _entries[] PROGMEM = items;const UIMenu name PROGMEM = {2,0,itemsCnt,name ## _entries};
|
||||
#define UI_STICKYMENU(name,items,itemsCnt) const UIMenuEntry * const name ## _entries[] PROGMEM = items;const UIMenu name PROGMEM = {2+128,0,itemsCnt,name ## _entries};
|
||||
#define UI_MENU_FILESELECT(name,items,itemsCnt) const UIMenuEntry * const name ## _entries[] PROGMEM = items;const UIMenu name PROGMEM = {1,0,itemsCnt,name ## _entries};
|
||||
|
||||
#if FEATURE_CONTROLLER == CONTROLLER_SMARTRAMPS || FEATURE_CONTROLLER == CONTROLLER_GADGETS3D_SHIELD || FEATURE_CONTROLLER == CONTROLLER_BAM_DICE_DUE || (FEATURE_CONTROLLER == CONTROLLER_REPRAPDISCOUNT_GLCD && MOTHERBOARD != CONTROLLER_FELIX_DUE && MOTHERBOARD != 101 && MOTHERBOARD != 63)
|
||||
#undef SDCARDDETECT
|
||||
#if MOTHERBOARD == 37 || MOTHERBOARD == 414
|
||||
#define SDCARDDETECT ORIG_SDCARDDETECT
|
||||
#else
|
||||
#define SDCARDDETECT 49
|
||||
#endif
|
||||
#undef SDCARDDETECTINVERTED
|
||||
#define SDCARDDETECTINVERTED 0
|
||||
#undef SDSUPPORT
|
||||
#define SDSUPPORT 1
|
||||
#endif
|
||||
|
||||
#if FEATURE_CONTROLLER == CONTROLLER_VIKI2
|
||||
#undef SDCARDDETECT
|
||||
#define SDCARDDETECT -1
|
||||
#undef SDSUPPORT
|
||||
#define SDSUPPORT 1
|
||||
#endif
|
||||
|
||||
#if FEATURE_CONTROLLER == CONTROLLER_RAMBO
|
||||
#undef SDCARDDETECT
|
||||
#define SDCARDDETECT 81
|
||||
#undef SDCARDDETECTINVERTED
|
||||
#define SDCARDDETECTINVERTED 0
|
||||
#undef SDSUPPORT
|
||||
#define SDSUPPORT 1
|
||||
#endif
|
||||
|
||||
|
||||
// Maximum size of a row - if row is larger, text gets scrolled
|
||||
#if defined(UI_DISPLAY_TYPE) && UI_DISPLAY_TYPE == DISPLAY_GAMEDUINO2
|
||||
#define MAX_COLS 50
|
||||
#else
|
||||
#define MAX_COLS 28
|
||||
#endif
|
||||
#define UI_MENU_MAXLEVEL 7
|
||||
|
||||
#define UI_FLAG_FAST_KEY_ACTION 1
|
||||
#define UI_FLAG_SLOW_KEY_ACTION 2
|
||||
#define UI_FLAG_SLOW_ACTION_RUNNING 4
|
||||
#define UI_FLAG_KEY_TEST_RUNNING 8
|
||||
|
||||
class GCode;
|
||||
class UIDisplay {
|
||||
public:
|
||||
volatile uint8_t flags; // 1 = fast key action, 2 = slow key action, 4 = slow action running, 8 = key test running
|
||||
uint8_t col; // current col for buffer pre fill
|
||||
uint8_t menuLevel; // current menu level, 0 = info, 1 = group, 2 = groupdata select, 3 = value change
|
||||
uint16_t menuPos[UI_MENU_MAXLEVEL]; // Positions in menu
|
||||
const UIMenu *menu[UI_MENU_MAXLEVEL]; // Menus active
|
||||
uint16_t menuTop[UI_MENU_MAXLEVEL]; // Top row in menu
|
||||
int8_t shift; // Display shift for scrolling text
|
||||
int pageDelay; // Counter. If 0 page is refreshed if menuLevel is 0.
|
||||
void *errorMsg;
|
||||
uint16_t activeAction; // action for ok/next/previous
|
||||
uint16_t lastAction;
|
||||
uint16_t delayedAction;
|
||||
millis_t lastSwitch; // Last time display switched pages
|
||||
millis_t lastRefresh;
|
||||
uint16_t lastButtonAction;
|
||||
millis_t lastButtonStart;
|
||||
millis_t nextRepeat; // Time of next autorepeat
|
||||
millis_t lastNextPrev; // for increasing speed settings
|
||||
float lastNextAccumul; // Accumulated value
|
||||
unsigned int outputMask; // Output mask for back light, leds etc.
|
||||
int repeatDuration; // Time between to actions if autorepeat is enabled
|
||||
int8_t oldMenuLevel;
|
||||
uint8_t encoderStartScreen;
|
||||
char printCols[MAX_COLS + 1];
|
||||
void addInt(int value, uint8_t digits, char fillChar = ' '); // Print int into printCols
|
||||
void addLong(long value, int8_t digits);
|
||||
inline void addLong(long value) {
|
||||
addLong(value, -11);
|
||||
};
|
||||
void addFloat(float number, char fixdigits, uint8_t digits);
|
||||
inline void addFloat(float number) {
|
||||
addFloat(number, -9, 2);
|
||||
};
|
||||
void addStringP(PGM_P text);
|
||||
void addString(char* text);
|
||||
void addStringOnOff(uint8_t);
|
||||
void addChar(const char c);
|
||||
void addGCode(GCode *code);
|
||||
int okAction(bool allowMoves);
|
||||
bool nextPreviousAction(int16_t next, bool allowMoves);
|
||||
char statusMsg[21];
|
||||
int8_t encoderPos;
|
||||
int8_t encoderLast;
|
||||
UIDisplay();
|
||||
void createChar(uint8_t location, const uint8_t charmap[]);
|
||||
void initialize(); // Initialize display and keys
|
||||
void waitForKey();
|
||||
void printRow(uint8_t r, char *txt, char *txt2, uint8_t changeAtCol); // Print row on display
|
||||
void printRowP(uint8_t r, PGM_P txt);
|
||||
void parse(const char *txt, bool ram); /// Parse output and write to printCols;
|
||||
void refreshPage();
|
||||
int executeAction(unsigned int action, bool allowMoves);
|
||||
void finishAction(unsigned int action);
|
||||
void slowAction(bool allowMoves);
|
||||
void fastAction();
|
||||
void mediumAction();
|
||||
void pushMenu(const UIMenu *men, bool refresh);
|
||||
void popMenu(bool refresh);
|
||||
void showMessage(int id);
|
||||
void adjustMenuPos();
|
||||
void setStatusP(PGM_P txt, bool error = false);
|
||||
void setStatus(const char *txt, bool error = false);
|
||||
inline void setOutputMaskBits(unsigned int bits) {
|
||||
outputMask |= bits;
|
||||
}
|
||||
inline void unsetOutputMaskBits(unsigned int bits) {
|
||||
outputMask &= ~bits;
|
||||
}
|
||||
void updateSDFileCount();
|
||||
void goDir(char *name);
|
||||
bool isDirname(char *name);
|
||||
bool isWizardActive();
|
||||
bool isSticky();
|
||||
void showLanguageSelectionWizard();
|
||||
#if UI_BED_COATING
|
||||
void menuAdjustHeight(const UIMenu *men, float offset);
|
||||
#endif
|
||||
char cwd[SD_MAX_FOLDER_DEPTH * LONG_FILENAME_LENGTH + 2];
|
||||
uint8_t folderLevel;
|
||||
};
|
||||
extern UIDisplay uid;
|
||||
|
||||
|
||||
|
||||
#endif
|
||||
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue
Block a user