getFeedrateOverride()

描述
取得进给速率覆写比例。

 

语法

machine.getFeedrateOverride();

 

参数
machine:为 Machine物件。

无参数。

 

回传

double:

进给速率覆写比例

 

范例
machine 进行 G-code 运动时,根据 Encoder 动态调整 feedrate。

1

2

3

4

5

6

7

8

9

10

11

12

13

14

15

16

17

18

19

20

21

22

23

24

25

26

27

28

29

30

31

32

33

34

35

36

37

38

39

40

41

42

43

44

45

46

47

48

49

50

51

52

53

54

55

56

57

58

59

60

61

62

63

64

65

66

67

68

69

70

71

72

73

74

75

76

77

78

79

80

81

82

83

84

85

86

87

88

89

90

91

92

93

94

95

96

97

98

99

100

101

102

103

104

105

106

107

108

109

110

111

112

113

114

115

116

117

118

119

120

121

#include "Motion86.h"

#include "Encoder.h"

#include "SD.h"

 

// 产生机器物件,最多可使用 machine 0~2 三台机器,每台机器三轴。

Machine machine(0);

 

// 步进马达 enable pin。

int EnablePin = 4;

 

// 此 gcode 档案存放于 SD 卡中。

char *filename = "auto.gcode";

File gfile;

char buf[256];

int ptr;

bool working;

 

// 设定预设的进给速度比例。

volatile double FeedrateRatio = 1.0;

 

bool enc_triggered = false;

 

void encoder_callback(int flag);

 

void setup() {

  while (!Serial);

  SD.begin();

 

  // 在此范例中,手摇轮已经被安装上 Enc3。

  Enc3.begin(MODE_AB_PHASE);

  Enc3.setRange(1); // 每次都会触发中断

  Enc3.attachInterrupt(encoder_callback);

 

  pinMode(EnablePin, OUTPUT);

 

  // 若有需要,可以反转运动轴的运动方向。

  // 在此范例中,需要反转 x 轴和 y 轴的方向。

  machine.config_ReverseDirection(AXIS_X);

  machine.config_ReverseDirection(AXIS_Y);

 

  // PPU (pulse per unit) 是一虚拟长度单位,依照不同需求而定。

  // 此例 x 轴的单位长度设定为 80 pulses,对应到实际应用为 1 mm。

  machine.config_PPU(AXIS_X, 80.0);

  machine.config_PPU(AXIS_Y, 80.0);

  machine.config_PPU(AXIS_Z, 1600.0);

 

  // 设定机器运动的软体极限。

  machine.config_PosLimit(AXIS_X, 0, 300);

  machine.config_PosLimit(AXIS_Y, 0, 200);

  machine.config_PosLimit(AXIS_Z, 0, 300);

 

  // 设定用来设定 home 点的极限开关所使用的 pin 脚。

  machine.config_HomePins(2, 7, 8);

 

  // 控制之前,必须启动机器。

  machine.machineOn();

 

  // 启动软体极限。

  machine.enableSoftLimit();

 

  // 设定回到 home 点的进给速率。

  machine.setHomeSpeed(1000, 1000, 200);

 

  // 开启 SD 卡中的 gcode 档案。

  if (SD.exists(filename)) {

    gfile = SD.open(filename);

    working = true;

  } else {

    Serial.print("File not exists: ");

    Serial.println(filename);

    while (1);

  }

 

  // 启动步进马达。

  digitalWrite(EnablePin, LOW);

 

  // 回到由极限开关所定义的 home 点。

  machine.home();

}

 

void loop() {

  // 读取并解析 gcode 档案。

  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;

    }

  }

 

  // 当中断处发时覆写进给速度。

  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) {

  // 进给速度比例应大于 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

feedrateOverride()


 

函式庫參考主頁面

86Duino 参考资料的文本遵循知识共享署名-Creative Commons Attribution-ShareAlike 3.0 License。参考资料中的代码示例已发布到公共领域。