Skip to content

Commit

Permalink
Откат
Browse files Browse the repository at this point in the history
  • Loading branch information
Malderin committed Oct 13, 2020
1 parent 51c341b commit a873f85
Show file tree
Hide file tree
Showing 58 changed files with 413 additions and 722 deletions.
6 changes: 0 additions & 6 deletions Marlin/Configuration.h
Original file line number Diff line number Diff line change
Expand Up @@ -431,12 +431,6 @@
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100

// Resistor values when using a MAX31865 (sensor -5)
// Sensor value is typically 100 (PT100) or 1000 (PT1000)
// Calibration value is typically 430 ohm for AdaFruit PT100 modules and 4300 ohm for AdaFruit PT1000 modules.
//#define MAX31865_SENSOR_OHMS 100
//#define MAX31865_CALIBRATION_OHMS 430

// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
Expand Down
27 changes: 5 additions & 22 deletions Marlin/Configuration_adv.h
Original file line number Diff line number Diff line change
Expand Up @@ -806,9 +806,11 @@
#define TRAMMING_POINT_NAME_3 "Back-Right"
#define TRAMMING_POINT_NAME_4 "Back-Left"

#define RESTORE_LEVELING_AFTER_G35 // Enable to restore leveling setup after operation
//#define REPORT_TRAMMING_MM // Report Z deviation (mm) for each point relative to the first
//#define ASSISTED_TRAMMING_MENU_ITEM // Add a menu item for Assisted Tramming
// Enable to restore leveling setup after operation
#define RESTORE_LEVELING_AFTER_G35
// Add a menu item for Assisted Tramming
//#define ASSISTED_TRAMMING_MENU_ITEM
/**
* Screw thread:
Expand Down Expand Up @@ -3376,25 +3378,6 @@
//#define JOYSTICK_DEBUG
#endif

/**
* Mechanical Gantry Calibration
* Modern replacement for the Prusa TMC_Z_CALIBRATION.
* Adds capability to work with any adjustable current drivers.
* Implemented as G34 because M915 is deprecated.
*/
//#define MECHANICAL_GANTRY_CALIBRATION
#if ENABLED(MECHANICAL_GANTRY_CALIBRATION)
#define GANTRY_CALIBRATION_CURRENT 600 // Default calibration current in ma
#define GANTRY_CALIBRATION_EXTRA_HEIGHT 15 // Extra distance in mm past Z_###_POS to move
#define GANTRY_CALIBRATION_FEEDRATE 500 // Feedrate for correction move
//#define GANTRY_CALIBRATION_TO_MIN // Enable to calibrate Z in the MIN direction

//#define GANTRY_CALIBRATION_SAFE_POSITION { X_CENTER, Y_CENTER } // Safe position for nozzle
//#define GANTRY_CALIBRATION_XY_PARK_FEEDRATE 3000 // XY Park Feedrate - MMM
//#define GANTRY_CALIBRATION_COMMANDS_PRE ""
#define GANTRY_CALIBRATION_COMMANDS_POST "G28" // G28 highly recommended to ensure an accurate position
#endif

/**
* MAX7219 Debug Matrix
*
Expand Down
4 changes: 2 additions & 2 deletions Marlin/src/HAL/AVR/HAL.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include "watchdog.h"
#include "math.h"

#ifdef IS_AT90USB
#ifdef USBCON
#include <HardwareSerial.h>
#else
#define HardwareSerial_h // Hack to prevent HardwareSerial.h header inclusion
Expand Down Expand Up @@ -81,7 +81,7 @@ typedef int8_t pin_t;
//extern uint8_t MCUSR;

// Serial ports
#ifdef IS_AT90USB
#ifdef USBCON
#define MYSERIAL0 TERN(BLUETOOTH, bluetoothSerial, Serial)
#else
#if !WITHIN(SERIAL_PORT, -1, 3)
Expand Down
6 changes: 3 additions & 3 deletions Marlin/src/HAL/AVR/MarlinSerial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@

#include "../../inc/MarlinConfig.h"

#if !IS_AT90USB && (defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(UBRR2H) || defined(UBRR3H))
#if !defined(USBCON) && (defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(UBRR2H) || defined(UBRR3H))

#include "MarlinSerial.h"
#include "../../MarlinCore.h"
Expand Down Expand Up @@ -792,10 +792,10 @@ MarlinSerial<MarlinSerialCfg<SERIAL_PORT>> customizedSerial1;

#endif

#endif // !IS_AT90USB && (UBRRH || UBRR0H || UBRR1H || UBRR2H || UBRR3H)
#endif // !USBCON && (UBRRH || UBRR0H || UBRR1H || UBRR2H || UBRR3H)

// For AT90USB targets use the UART for BT interfacing
#if BOTH(IS_AT90USB, BLUETOOTH)
#if defined(USBCON) && ENABLED(BLUETOOTH)
HardwareSerial bluetoothSerial;
#endif

Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/AVR/MarlinSerial.h
Original file line number Diff line number Diff line change
Expand Up @@ -327,6 +327,6 @@
#endif

// Use the UART for Bluetooth in AT90USB configurations
#if BOTH(IS_AT90USB, BLUETOOTH)
#if defined(USBCON) && ENABLED(BLUETOOTH)
extern HardwareSerial bluetoothSerial;
#endif
2 changes: 1 addition & 1 deletion Marlin/src/HAL/DUE/fastio/G2_PWM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -154,7 +154,7 @@ void Stepper::digipot_init() {
NVIC_SetPriority(PWM_IRQn, NVIC_EncodePriority(0, 10, 0)); // normal priority for PWM module (can stand some jitter on the Vref signals)
}

void Stepper::set_digipot_current(const uint8_t driver, const int16_t current) {
void Stepper::digipot_current(const uint8_t driver, const int16_t current) {

if (!(PWM->PWM_CH_NUM[0].PWM_CPRD == PWM_PERIOD_US)) digipot_init(); // Init PWM system if needed

Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/HAL.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
#define HAL_ADC_RANGE _BV(HAL_ADC_RESOLUTION)

#ifndef I2C_ADDRESS
#define I2C_ADDRESS(A) uint8_t(A)
#define I2C_ADDRESS(A) (A)
#endif

// Needed for AVR sprintf_P PROGMEM extension
Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/LPC1768/inc/SanityCheck.h
Original file line number Diff line number Diff line change
Expand Up @@ -191,7 +191,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o
//
// Flag any i2c pin conflicts
//
#if ANY(HAS_MOTOR_CURRENT_I2C, HAS_MOTOR_CURRENT_DAC, EXPERIMENTAL_I2CBUS, I2C_POSITION_ENCODERS, PCA9632, I2C_EEPROM)
#if ANY(HAS_I2C_DIGIPOT, DAC_STEPPER_CURRENT, EXPERIMENTAL_I2CBUS, I2C_POSITION_ENCODERS, PCA9632, I2C_EEPROM)
#define USEDI2CDEV_M 1 // <Arduino>/Wire.cpp

#if USEDI2CDEV_M == 0 // P0_27 [D57] (AUX-1) .......... P0_28 [D58] (AUX-1)
Expand Down
6 changes: 1 addition & 5 deletions Marlin/src/HAL/STM32/watchdog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,11 +30,7 @@
#include "watchdog.h"
#include <IWatchdog.h>

void watchdog_init() {
#if DISABLED(DISABLE_WATCHDOG_INIT)
IWatchdog.begin(4000000); // 4 sec timeout
#endif
}
void watchdog_init() { IWatchdog.begin(4000000); } // 4 sec timeout

void HAL_watchdog_refresh() {
IWatchdog.reload();
Expand Down
3 changes: 2 additions & 1 deletion Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@

#if BOTH(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI)

#include "../HAL.h"
#include <U8glib.h>

#undef SPI_SPEED
Expand Down Expand Up @@ -160,5 +161,5 @@ uint8_t u8g_com_HAL_STM32F1_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val,
return 1;
}

#endif // HAS_MARLINUI_U8GLIB && FORCE_SOFT_SPI
#endif // HAS_MARLINUI_U8GLIB
#endif // STM32F1
4 changes: 1 addition & 3 deletions Marlin/src/HAL/STM32F1/watchdog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,9 +52,7 @@ void watchdogSetup() {
* @details The watchdog clock is 40Khz. We need a 4 seconds interval, so use a /256 preescaler and 625 reload value (counts down to 0)
*/
void watchdog_init() {
#if DISABLED(DISABLE_WATCHDOG_INIT)
iwdg_init(IWDG_PRE_256, STM32F1_WD_RELOAD);
#endif
//iwdg_init(IWDG_PRE_256, STM32F1_WD_RELOAD);
}

#endif // USE_WATCHDOG
Expand Down
12 changes: 6 additions & 6 deletions Marlin/src/MarlinCore.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@
#include "feature/closedloop.h"
#endif

#if HAS_MOTOR_CURRENT_I2C
#if HAS_I2C_DIGIPOT
#include "feature/digipot/digipot.h"
#endif

Expand Down Expand Up @@ -125,7 +125,7 @@
#include "module/servo.h"
#endif

#if ENABLED(HAS_MOTOR_CURRENT_DAC)
#if ENABLED(DAC_STEPPER_CURRENT)
#include "feature/dac/stepper_dac.h"
#endif

Expand Down Expand Up @@ -1137,12 +1137,12 @@ void setup() {
SETUP_RUN(enableStepperDrivers());
#endif

#if HAS_MOTOR_CURRENT_I2C
SETUP_RUN(digipot_i2c.init());
#if HAS_I2C_DIGIPOT
SETUP_RUN(digipot_i2c_init());
#endif

#if ENABLED(HAS_MOTOR_CURRENT_DAC)
SETUP_RUN(stepper_dac.init());
#if ENABLED(DAC_STEPPER_CURRENT)
SETUP_RUN(dac_init());
#endif

#if EITHER(Z_PROBE_SLED, SOLENOID_PROBE) && HAS_SOLENOID_1
Expand Down
50 changes: 24 additions & 26 deletions Marlin/src/feature/dac/dac_mcp4728.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,18 +32,16 @@

#include "../../inc/MarlinConfig.h"

#if ENABLED(HAS_MOTOR_CURRENT_DAC)
#if ENABLED(DAC_STEPPER_CURRENT)

#include "dac_mcp4728.h"

MCP4728 mcp4728;

xyze_uint_t dac_values;
xyze_uint_t mcp4728_values;

/**
* Begin I2C, get current values (input register and eeprom) of mcp4728
*/
void MCP4728::init() {
void mcp4728_init() {
Wire.begin();
Wire.requestFrom(I2C_ADDRESS(DAC_DEV_ADDRESS), uint8_t(24));
while (Wire.available()) {
Expand All @@ -52,46 +50,46 @@ void MCP4728::init() {
loByte = Wire.read();

if (!(deviceID & 0x08))
dac_values[(deviceID & 0x30) >> 4] = word((hiByte & 0x0F), loByte);
mcp4728_values[(deviceID & 0x30) >> 4] = word((hiByte & 0x0F), loByte);
}
}

/**
* Write input resister value to specified channel using fastwrite method.
* Channel : 0-3, Values : 0-4095
*/
uint8_t MCP4728::analogWrite(const uint8_t channel, const uint16_t value) {
dac_values[channel] = value;
return fastWrite();
uint8_t mcp4728_analogWrite(const uint8_t channel, const uint16_t value) {
mcp4728_values[channel] = value;
return mcp4728_fastWrite();
}

/**
* Write all input resistor values to EEPROM using SequencialWrite method.
* This will update both input register and EEPROM value
* This will also write current Vref, PowerDown, Gain settings to EEPROM
*/
uint8_t MCP4728::eepromWrite() {
uint8_t mcp4728_eepromWrite() {
Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS));
Wire.write(SEQWRITE);
LOOP_XYZE(i) {
Wire.write(DAC_STEPPER_VREF << 7 | DAC_STEPPER_GAIN << 4 | highByte(dac_values[i]));
Wire.write(lowByte(dac_values[i]));
Wire.write(DAC_STEPPER_VREF << 7 | DAC_STEPPER_GAIN << 4 | highByte(mcp4728_values[i]));
Wire.write(lowByte(mcp4728_values[i]));
}
return Wire.endTransmission();
}

/**
* Write Voltage reference setting to all input regiters
*/
uint8_t MCP4728::setVref_all(const uint8_t value) {
uint8_t mcp4728_setVref_all(const uint8_t value) {
Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS));
Wire.write(VREFWRITE | (value ? 0x0F : 0x00));
return Wire.endTransmission();
}
/**
* Write Gain setting to all input regiters
*/
uint8_t MCP4728::setGain_all(const uint8_t value) {
uint8_t mcp4728_setGain_all(const uint8_t value) {
Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS));
Wire.write(GAINWRITE | (value ? 0x0F : 0x00));
return Wire.endTransmission();
Expand All @@ -100,55 +98,55 @@ uint8_t MCP4728::setGain_all(const uint8_t value) {
/**
* Return Input Register value
*/
uint16_t MCP4728::getValue(const uint8_t channel) { return dac_values[channel]; }
uint16_t mcp4728_getValue(const uint8_t channel) { return mcp4728_values[channel]; }

#if 0
/**
* Steph: Might be useful in the future
* Return Vout
*/
uint16_t MCP4728::getVout(const uint8_t channel) {
uint16_t mcp4728_getVout(const uint8_t channel) {
const uint32_t vref = 2048,
vOut = (vref * dac_values[channel] * (_DAC_STEPPER_GAIN + 1)) / 4096;
vOut = (vref * mcp4728_values[channel] * (_DAC_STEPPER_GAIN + 1)) / 4096;
return _MIN(vOut, defaultVDD);
}
#endif

/**
* Returns DAC values as a 0-100 percentage of drive strength
*/
uint8_t MCP4728::getDrvPct(const uint8_t channel) { return uint8_t(100.0 * dac_values[channel] / (DAC_STEPPER_MAX) + 0.5); }
uint8_t mcp4728_getDrvPct(const uint8_t channel) { return uint8_t(100.0 * mcp4728_values[channel] / (DAC_STEPPER_MAX) + 0.5); }

/**
* Receives all Drive strengths as 0-100 percent values, updates
* DAC Values array and calls fastwrite to update the DAC.
*/
void MCP4728::setDrvPct(xyze_uint8_t &pct) {
dac_values *= 0.01 * pct * (DAC_STEPPER_MAX);
fastWrite();
void mcp4728_setDrvPct(xyze_uint8_t &pct) {
mcp4728_values *= 0.01 * pct * (DAC_STEPPER_MAX);
mcp4728_fastWrite();
}

/**
* FastWrite input register values - All DAC ouput update. refer to DATASHEET 5.6.1
* DAC Input and PowerDown bits update.
* No EEPROM update
*/
uint8_t MCP4728::fastWrite() {
uint8_t mcp4728_fastWrite() {
Wire.beginTransmission(I2C_ADDRESS(DAC_DEV_ADDRESS));
LOOP_XYZE(i) {
Wire.write(highByte(dac_values[i]));
Wire.write(lowByte(dac_values[i]));
Wire.write(highByte(mcp4728_values[i]));
Wire.write(lowByte(mcp4728_values[i]));
}
return Wire.endTransmission();
}

/**
* Common function for simple general commands
*/
uint8_t MCP4728::simpleCommand(const byte simpleCommand) {
uint8_t mcp4728_simpleCommand(const byte simpleCommand) {
Wire.beginTransmission(I2C_ADDRESS(GENERALCALL));
Wire.write(simpleCommand);
return Wire.endTransmission();
}

#endif // HAS_MOTOR_CURRENT_DAC
#endif // DAC_STEPPER_CURRENT
25 changes: 10 additions & 15 deletions Marlin/src/feature/dac/dac_mcp4728.h
Original file line number Diff line number Diff line change
Expand Up @@ -65,18 +65,13 @@
// DAC_OR_ADDRESS defined in pins_BOARD.h file
#define DAC_DEV_ADDRESS (BASE_ADDR | DAC_OR_ADDRESS)

class MCP4728 {
public:
static void init();
static uint8_t analogWrite(const uint8_t channel, const uint16_t value);
static uint8_t eepromWrite();
static uint8_t setVref_all(const uint8_t value);
static uint8_t setGain_all(const uint8_t value);
static uint16_t getValue(const uint8_t channel);
static uint8_t fastWrite();
static uint8_t simpleCommand(const byte simpleCommand);
static uint8_t getDrvPct(const uint8_t channel);
static void setDrvPct(xyze_uint8_t &pct);
};

extern MCP4728 mcp4728;
void mcp4728_init();
uint8_t mcp4728_analogWrite(const uint8_t channel, const uint16_t value);
uint8_t mcp4728_eepromWrite();
uint8_t mcp4728_setVref_all(const uint8_t value);
uint8_t mcp4728_setGain_all(const uint8_t value);
uint16_t mcp4728_getValue(const uint8_t channel);
uint8_t mcp4728_fastWrite();
uint8_t mcp4728_simpleCommand(const byte simpleCommand);
uint8_t mcp4728_getDrvPct(const uint8_t channel);
void mcp4728_setDrvPct(xyze_uint8_t &pct);
Loading

0 comments on commit a873f85

Please sign in to comment.