Various cleanups ahead of digipot save
This commit is contained in:
parent
ece89bcf7a
commit
3c7bfe798d
|
@ -202,9 +202,9 @@ script:
|
|||
#
|
||||
# Enable COREYX (swapped)
|
||||
#
|
||||
- restore_configs
|
||||
- opt_enable COREYX
|
||||
- build_marlin
|
||||
#- restore_configs
|
||||
#- opt_enable COREYX
|
||||
#- build_marlin
|
||||
#
|
||||
#
|
||||
######## Other Standard LCD/Panels ##############
|
||||
|
|
|
@ -290,8 +290,8 @@ ifeq ($(HARDWARE_VARIANT), Teensy)
|
|||
SRC = wiring.c
|
||||
VPATH += $(ARDUINO_INSTALL_DIR)/hardware/teensy/cores/teensy
|
||||
endif
|
||||
CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp \
|
||||
MarlinSerial.cpp Sd2Card.cpp SdBaseFile.cpp SdFatUtil.cpp \
|
||||
CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp \
|
||||
MarlinSerial.cpp Sd2Card.cpp SdBaseFile.cpp SdFatUtil.cpp \
|
||||
SdFile.cpp SdVolume.cpp planner.cpp stepper.cpp \
|
||||
temperature.cpp cardreader.cpp configuration_store.cpp \
|
||||
watchdog.cpp SPI.cpp servo.cpp Tone.cpp ultralcd.cpp digipot_mcp4451.cpp \
|
||||
|
|
|
@ -9677,10 +9677,13 @@ inline void gcode_M503() {
|
|||
*/
|
||||
inline void gcode_M907() {
|
||||
#if HAS_DIGIPOTSS
|
||||
|
||||
LOOP_XYZE(i) if (parser.seen(axis_codes[i])) stepper.digipot_current(i, parser.value_int());
|
||||
if (parser.seen('B')) stepper.digipot_current(4, parser.value_int());
|
||||
if (parser.seen('S')) for (uint8_t i = 0; i <= 4; i++) stepper.digipot_current(i, parser.value_int());
|
||||
|
||||
#elif HAS_MOTOR_CURRENT_PWM
|
||||
|
||||
#if PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
|
||||
if (parser.seen('X')) stepper.digipot_current(0, parser.value_int());
|
||||
#endif
|
||||
|
@ -9690,13 +9693,16 @@ inline void gcode_M907() {
|
|||
#if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
|
||||
if (parser.seen('E')) stepper.digipot_current(2, parser.value_int());
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#if ENABLED(DIGIPOT_I2C)
|
||||
// this one uses actual amps in floating point
|
||||
LOOP_XYZE(i) if (parser.seen(axis_codes[i])) digipot_i2c_set_current(i, parser.value_float());
|
||||
// for each additional extruder (named B,C,D,E..., channels 4,5,6,7...)
|
||||
for (uint8_t i = NUM_AXIS; i < DIGIPOT_I2C_NUM_CHANNELS; i++) if (parser.seen('B' + i - (NUM_AXIS))) digipot_i2c_set_current(i, parser.value_float());
|
||||
#endif
|
||||
|
||||
#if ENABLED(DAC_STEPPER_CURRENT)
|
||||
if (parser.seen('S')) {
|
||||
const float dac_percent = parser.value_float();
|
||||
|
|
|
@ -74,8 +74,8 @@ block_t* Stepper::current_block = NULL; // A pointer to the block currently bei
|
|||
|
||||
// private:
|
||||
|
||||
unsigned char Stepper::last_direction_bits = 0; // The next stepping-bits to be output
|
||||
unsigned int Stepper::cleaning_buffer_counter = 0;
|
||||
uint8_t Stepper::last_direction_bits = 0; // The next stepping-bits to be output
|
||||
uint16_t Stepper::cleaning_buffer_counter = 0;
|
||||
|
||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||
bool Stepper::locked_z_motor = false;
|
||||
|
@ -1447,11 +1447,11 @@ void Stepper::report_positions() {
|
|||
#if HAS_DIGIPOTSS
|
||||
|
||||
// From Arduino DigitalPotControl example
|
||||
void Stepper::digitalPotWrite(int address, int value) {
|
||||
WRITE(DIGIPOTSS_PIN, LOW); // take the SS pin low to select the chip
|
||||
SPI.transfer(address); // send in the address and value via SPI:
|
||||
void Stepper::digitalPotWrite(const int16_t address, const int16_t value) {
|
||||
WRITE(DIGIPOTSS_PIN, LOW); // Take the SS pin low to select the chip
|
||||
SPI.transfer(address); // Send the address and value via SPI
|
||||
SPI.transfer(value);
|
||||
WRITE(DIGIPOTSS_PIN, HIGH); // take the SS pin high to de-select the chip:
|
||||
WRITE(DIGIPOTSS_PIN, HIGH); // Take the SS pin high to de-select the chip
|
||||
//delay(10);
|
||||
}
|
||||
|
||||
|
@ -1486,21 +1486,24 @@ void Stepper::report_positions() {
|
|||
#endif
|
||||
}
|
||||
|
||||
void Stepper::digipot_current(uint8_t driver, int current) {
|
||||
void Stepper::digipot_current(const uint8_t driver, const int current) {
|
||||
|
||||
#if HAS_DIGIPOTSS
|
||||
|
||||
const uint8_t digipot_ch[] = DIGIPOT_CHANNELS;
|
||||
digitalPotWrite(digipot_ch[driver], current);
|
||||
|
||||
#elif HAS_MOTOR_CURRENT_PWM
|
||||
#define _WRITE_CURRENT_PWM(P) analogWrite(P, 255L * current / (MOTOR_CURRENT_PWM_RANGE))
|
||||
#define _WRITE_CURRENT_PWM(P) analogWrite(MOTOR_CURRENT_PWM_## P ##_PIN, 255L * current / (MOTOR_CURRENT_PWM_RANGE))
|
||||
switch (driver) {
|
||||
#if PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
|
||||
case 0: _WRITE_CURRENT_PWM(MOTOR_CURRENT_PWM_XY_PIN); break;
|
||||
case 0: _WRITE_CURRENT_PWM(XY); break;
|
||||
#endif
|
||||
#if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
|
||||
case 1: _WRITE_CURRENT_PWM(MOTOR_CURRENT_PWM_Z_PIN); break;
|
||||
case 1: _WRITE_CURRENT_PWM(Z); break;
|
||||
#endif
|
||||
#if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
|
||||
case 2: _WRITE_CURRENT_PWM(MOTOR_CURRENT_PWM_E_PIN); break;
|
||||
case 2: _WRITE_CURRENT_PWM(E); break;
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
@ -1550,7 +1553,7 @@ void Stepper::report_positions() {
|
|||
microstep_mode(i, microstep_modes[i]);
|
||||
}
|
||||
|
||||
void Stepper::microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2) {
|
||||
void Stepper::microstep_ms(const uint8_t driver, const int8_t ms1, const int8_t ms2) {
|
||||
if (ms1 >= 0) switch (driver) {
|
||||
case 0: WRITE(X_MS1_PIN, ms1); break;
|
||||
#if HAS_Y_MICROSTEPS
|
||||
|
@ -1601,7 +1604,7 @@ void Stepper::report_positions() {
|
|||
}
|
||||
}
|
||||
|
||||
void Stepper::microstep_mode(uint8_t driver, uint8_t stepping_mode) {
|
||||
void Stepper::microstep_mode(const uint8_t driver, const uint8_t stepping_mode) {
|
||||
switch (stepping_mode) {
|
||||
case 1: microstep_ms(driver, MICROSTEP1); break;
|
||||
case 2: microstep_ms(driver, MICROSTEP2); break;
|
||||
|
|
|
@ -93,8 +93,8 @@ class Stepper {
|
|||
|
||||
private:
|
||||
|
||||
static unsigned char last_direction_bits; // The next stepping-bits to be output
|
||||
static unsigned int cleaning_buffer_counter;
|
||||
static uint8_t last_direction_bits; // The next stepping-bits to be output
|
||||
static uint16_t cleaning_buffer_counter;
|
||||
|
||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||
static bool locked_z_motor, locked_z2_motor;
|
||||
|
@ -243,20 +243,20 @@ class Stepper {
|
|||
static FORCE_INLINE bool motor_direction(AxisEnum axis) { return TEST(last_direction_bits, axis); }
|
||||
|
||||
#if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM
|
||||
static void digitalPotWrite(int address, int value);
|
||||
static void digipot_current(uint8_t driver, int current);
|
||||
static void digitalPotWrite(const int16_t address, const int16_t value);
|
||||
static void digipot_current(const uint8_t driver, const int16_t current);
|
||||
#endif
|
||||
|
||||
#if HAS_MICROSTEPS
|
||||
static void microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2);
|
||||
static void microstep_mode(uint8_t driver, uint8_t stepping);
|
||||
static void microstep_ms(const uint8_t driver, const int8_t ms1, const int8_t ms2);
|
||||
static void microstep_mode(const uint8_t driver, const uint8_t stepping);
|
||||
static void microstep_readings();
|
||||
#endif
|
||||
|
||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||
static FORCE_INLINE void set_homing_flag(bool state) { performing_homing = state; }
|
||||
static FORCE_INLINE void set_z_lock(bool state) { locked_z_motor = state; }
|
||||
static FORCE_INLINE void set_z2_lock(bool state) { locked_z2_motor = state; }
|
||||
static FORCE_INLINE void set_homing_flag(const bool state) { performing_homing = state; }
|
||||
static FORCE_INLINE void set_z_lock(const bool state) { locked_z_motor = state; }
|
||||
static FORCE_INLINE void set_z2_lock(const bool state) { locked_z2_motor = state; }
|
||||
#endif
|
||||
|
||||
#if ENABLED(BABYSTEPPING)
|
||||
|
|
Loading…
Reference in a new issue