Machine.getFeedrateOverride()

[Motion86]

Description

The feed rate overwrite ratio is obtained.

Syntax

machine.getFeedrateOverride();

Parameters

machine: Machine object.

No parameter.

Returns

double:

Feed rate overwrite ratio.

Example

When the machine performs G-code movement, the feedrate is adjusted according to the Encoder dynamics.

#include "Motion86.h"
#include "Encoder.h"
#include "SD.h"
 
// Generate machine objects, up to machine 0~2 three machines, each machine three axes. 
Machine machine(0);
 
// Stepper motor enable pin.
int EnablePin = 4;
 
// This gcode file is stored in the SD card.
char *filename = "auto.gcode";
File gfile;
char buf[256];
int ptr;
bool working;
 
// Set the default feedrate ratio.
volatile double FeedrateRatio = 1.0;
 
bool enc_triggered = false;
 
void encoder_callback(int flag);
 
void setup() {
  while (!Serial);
  SD.begin();
 
  // In this example, the hand crank has been installed with Enc3.
  Enc3.begin(MODE_AB_PHASE);
  Enc3.setRange(1); // Interrupt will be triggered every time
  Enc3.attachInterrupt(encoder_callback);
 
  pinMode(EnablePin, OUTPUT);
 
  // If necessary, the motion direction of the motion axis can be reversed.
  // In this example, the direction of x-axis and y-axis should be reversed.
  machine.config_ReverseDirection(AXIS_X);
  machine.config_ReverseDirection(AXIS_Y);
 
  // PPU (pulse per unit) is a virtual length unit, depending on different requirements.
  // In this example, the unit length of x-axis is set to 80 pulses, which corresponds to 1 mm in real application.
  machine.config_PPU(AXIS_X, 80.0);
  machine.config_PPU(AXIS_Y, 80.0);
  machine.config_PPU(AXIS_Z, 1600.0);
 
  // Set the software limit for the machine motion.
  machine.config_PosLimit(AXIS_X, 0, 300);
  machine.config_PosLimit(AXIS_Y, 0, 200);
  machine.config_PosLimit(AXIS_Z, 0, 300);
 
  // Set the pin used to set the limit switch for the home point.
  machine.config_HomePins(2, 7, 8);
 
  // Before controlling, the machine must be started.
  machine.machineOn();
 
  // Enable the software limits.
  machine.enableSoftLimit();
 
  // Set the feed rate back to the home point.
  machine.setHomeSpeed(1000, 1000, 200);
 
  // Open the gcode file in the SD card
  if (SD.exists(filename)) {
    gfile = SD.open(filename);
    working = true;
  } else {
    Serial.print("File does not exist: ");
    Serial.println(filename);
    while (1);
  }
 
  // Start the stepper motor.
  digitalWrite(EnablePin, LOW);
 
  // Return to the home point defined by the limit switch.
  machine.home();
home(); }
 
void loop() {
  // Read and parse the gcode file.
  if (working && !machine.isCmdBufferFull()) {
    ptr = 0;
    while (gfile.available()) {
      buf[ptr] = gfile.read();
      if (buf[ptr] == '\n') {
        buf[ptr + 1] = '\0';
        machine.gcode(buf);
        break;
      } else {
        ptr ++;
      }
    }
    if (!gfile.available())
    {
      Serial.println("GCODE FINISH");
      gfile.close();
      working = false;
    }
  }
 
  // Overwrite the feed rate when it is interrupted.
  if (enc_triggered) {
    if (FeedrateRatio > 2.0) FeedrateRatio = 2.0;
    if (FeedrateRatio < 0.1) FeedrateRatio = 0.1;
    machine.feedrateOverride(FeedrateRatio);
    enc_triggered = false;
    Serial.print("FeedrateRatio = ");
    Serial.println(machine.getFeedrateOverride());
  }
}
 
void encoder_callback(int flag) {
  // The feedrate ratio should be greater than 0.
  if (flag == INTR_OVERFLOW && FeedrateRatio < 2.0)
    FeedrateRatio += 0.01;
  else if (flag == INTR_UNDERFLOW && FeedrateRatio > 0.0)
    FeedrateRatio -= 0.01;
  enc_triggered = true;
}

See also


Libraries Reference Home

The text of the 86Duino reference is a modification of the Arduino reference and is licensed under a Creative Commons Attribution-ShareAlike 3.0 License. Code samples in the reference are released into the public domain.

Leave a Comment

Scroll to Top