Added support for the Rambo reprap electronics board. Added Mcodes to set
motor current and microstepping pins.
This commit is contained in:
parent
0e58ef6805
commit
1c1fddc7ac
|
@ -30,9 +30,10 @@
|
||||||
// Ultimaker = 7
|
// Ultimaker = 7
|
||||||
// Teensylu = 8
|
// Teensylu = 8
|
||||||
// Gen3+ =9
|
// Gen3+ =9
|
||||||
|
// Rambo = 301
|
||||||
|
|
||||||
#ifndef MOTHERBOARD
|
#ifndef MOTHERBOARD
|
||||||
#define MOTHERBOARD 7
|
#define MOTHERBOARD 301
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -128,6 +128,20 @@
|
||||||
// if unwanted behavior is observed on a user's machine when running at very slow speeds.
|
// if unwanted behavior is observed on a user's machine when running at very slow speeds.
|
||||||
#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
|
#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
|
||||||
|
|
||||||
|
// MS1 MS2 Stepper Driver Microstepping mode table
|
||||||
|
#define MICROSTEP1 LOW,LOW
|
||||||
|
#define MICROSTEP2 HIGH,LOW
|
||||||
|
#define MICROSTEP4 LOW,HIGH
|
||||||
|
#define MICROSTEP8 HIGH,HIGH
|
||||||
|
#define MICROSTEP16 HIGH,HIGH
|
||||||
|
|
||||||
|
// Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
|
||||||
|
#define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
|
||||||
|
|
||||||
|
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
||||||
|
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
||||||
|
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================Additional Features===========================
|
//=============================Additional Features===========================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
It has preliminary support for Matthew Roberts advance algorithm
|
It has preliminary support for Matthew Roberts advance algorithm
|
||||||
http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
|
http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
|
||||||
*/
|
*/
|
||||||
|
#include <SPI.h>
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
|
|
||||||
#include "ultralcd.h"
|
#include "ultralcd.h"
|
||||||
|
@ -120,6 +120,10 @@
|
||||||
// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
|
// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
|
||||||
// M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
|
// M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
|
||||||
// M503 - print the current settings (from memory not from eeprom)
|
// M503 - print the current settings (from memory not from eeprom)
|
||||||
|
// M907 - Set digital trimpot motor current using axis codes.
|
||||||
|
// M908 - Control digital trimpot directly.
|
||||||
|
// M350 - Set microstepping mode.
|
||||||
|
// M351 - Toggle MS1 MS2 pins directly.
|
||||||
// M999 - Restart after being stopped by error
|
// M999 - Restart after being stopped by error
|
||||||
|
|
||||||
//Stepper Movement Variables
|
//Stepper Movement Variables
|
||||||
|
@ -309,6 +313,8 @@ void setup()
|
||||||
SERIAL_ECHOPGM(STRING_VERSION_CONFIG_H);
|
SERIAL_ECHOPGM(STRING_VERSION_CONFIG_H);
|
||||||
SERIAL_ECHOPGM(MSG_AUTHOR);
|
SERIAL_ECHOPGM(MSG_AUTHOR);
|
||||||
SERIAL_ECHOLNPGM(STRING_CONFIG_H_AUTHOR);
|
SERIAL_ECHOLNPGM(STRING_CONFIG_H_AUTHOR);
|
||||||
|
SERIAL_ECHOPGM("Compiled: ");
|
||||||
|
SERIAL_ECHOLNPGM(__DATE__);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
SERIAL_ECHO_START;
|
SERIAL_ECHO_START;
|
||||||
|
@ -1466,6 +1472,52 @@ void process_commands()
|
||||||
EEPROM_printSettings();
|
EEPROM_printSettings();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
case 907: // Set digital trimpot motor current using axis codes.
|
||||||
|
{
|
||||||
|
#if DIGIPOTSS_PIN > -1
|
||||||
|
for(int i=0;i<=NUM_AXIS;i++) if(code_seen(axis_codes[i])) digipot_current(i,code_value());
|
||||||
|
if(code_seen('B')) digipot_current(4,code_value());
|
||||||
|
if(code_seen('S')) for(int i=0;i<=4;i++) digipot_current(i,code_value());
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
case 908: // Control digital trimpot directly.
|
||||||
|
{
|
||||||
|
#if DIGIPOTSS_PIN > -1
|
||||||
|
uint8_t channel,current;
|
||||||
|
if(code_seen('P')) channel=code_value();
|
||||||
|
if(code_seen('S')) current=code_value();
|
||||||
|
digitalPotWrite(channel, current);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 350: // Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers.
|
||||||
|
{
|
||||||
|
#if X_MS1_PIN > -1
|
||||||
|
if(code_seen('S')) for(int i=0;i<=4;i++) microstep_mode(i,code_value());
|
||||||
|
for(int i=0;i<=NUM_AXIS;i++) if(code_seen(axis_codes[i])) microstep_mode(i,(uint8_t)code_value());
|
||||||
|
if(code_seen('B')) microstep_mode(4,code_value());
|
||||||
|
microstep_readings();
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 351: // Toggle MS1 MS2 pins directly, S# determines MS1 or MS2, X# sets the pin high/low.
|
||||||
|
{
|
||||||
|
#if X_MS1_PIN > -1
|
||||||
|
if(code_seen('S')) switch((int)code_value())
|
||||||
|
{
|
||||||
|
case 1:
|
||||||
|
for(int i=0;i<=NUM_AXIS;i++) if(code_seen(axis_codes[i])) microstep_ms(i,code_value(),-1);
|
||||||
|
if(code_seen('B')) microstep_ms(4,code_value(),-1);
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
for(int i=0;i<=NUM_AXIS;i++) if(code_seen(axis_codes[i])) microstep_ms(i,-1,code_value());
|
||||||
|
if(code_seen('B')) microstep_ms(4,-1,code_value());
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
microstep_readings();
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
break;
|
||||||
case 999: // Restart after being stopped
|
case 999: // Restart after being stopped
|
||||||
Stopped = false;
|
Stopped = false;
|
||||||
gcode_LastN = Stopped_gcode_LastN;
|
gcode_LastN = Stopped_gcode_LastN;
|
||||||
|
|
|
@ -1,6 +1,18 @@
|
||||||
#ifndef PINS_H
|
#ifndef PINS_H
|
||||||
#define PINS_H
|
#define PINS_H
|
||||||
|
|
||||||
|
#define X_MS1_PIN -1
|
||||||
|
#define X_MS2_PIN -1
|
||||||
|
#define Y_MS1_PIN -1
|
||||||
|
#define Y_MS2_PIN -1
|
||||||
|
#define Z_MS1_PIN -1
|
||||||
|
#define Z_MS2_PIN -1
|
||||||
|
#define E0_MS1_PIN -1
|
||||||
|
#define E0_MS2_PIN -1
|
||||||
|
#define E1_MS1_PIN -1
|
||||||
|
#define E1_MS2_PIN -1
|
||||||
|
#define DIGIPOTSS_PIN -1
|
||||||
|
|
||||||
#if MOTHERBOARD == 99
|
#if MOTHERBOARD == 99
|
||||||
#define KNOWN_BOARD 1
|
#define KNOWN_BOARD 1
|
||||||
|
|
||||||
|
@ -1128,6 +1140,76 @@
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if MOTHERBOARD == 301
|
||||||
|
#define KNOWN_BOARD
|
||||||
|
/*****************************************************************
|
||||||
|
* Rambo Pin Assignments
|
||||||
|
******************************************************************/
|
||||||
|
|
||||||
|
#ifndef __AVR_ATmega2560__
|
||||||
|
#error Oops! Make sure you have 'Arduino Mega 2560' selected from the 'Tools -> Boards' menu.
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define X_STEP_PIN 37
|
||||||
|
#define X_DIR_PIN 48
|
||||||
|
#define X_MIN_PIN 12
|
||||||
|
#define X_MAX_PIN 19
|
||||||
|
#define X_ENABLE_PIN 29
|
||||||
|
#define X_MS1_PIN 40
|
||||||
|
#define X_MS2_PIN 41
|
||||||
|
|
||||||
|
#define Y_STEP_PIN 36
|
||||||
|
#define Y_DIR_PIN 49
|
||||||
|
#define Y_MIN_PIN 11
|
||||||
|
#define Y_MAX_PIN 18
|
||||||
|
#define Y_ENABLE_PIN 28
|
||||||
|
#define Y_MS1_PIN 69
|
||||||
|
#define Y_MS2_PIN 39
|
||||||
|
|
||||||
|
#define Z_STEP_PIN 35
|
||||||
|
#define Z_DIR_PIN 47
|
||||||
|
#define Z_MIN_PIN 10
|
||||||
|
#define Z_MAX_PIN 15
|
||||||
|
#define Z_ENABLE_PIN 27
|
||||||
|
#define Z_MS1_PIN 68
|
||||||
|
#define Z_MS2_PIN 67
|
||||||
|
|
||||||
|
#define HEATER_BED_PIN 3
|
||||||
|
#define TEMP_BED_PIN 2
|
||||||
|
|
||||||
|
#define HEATER_0_PIN 9
|
||||||
|
#define TEMP_0_PIN 0
|
||||||
|
|
||||||
|
#define HEATER_1_PIN 7
|
||||||
|
#define TEMP_1_PIN 1
|
||||||
|
|
||||||
|
#define HEATER_2_PIN -1
|
||||||
|
#define TEMP_2_PIN -1
|
||||||
|
|
||||||
|
#define E0_STEP_PIN 34
|
||||||
|
#define E0_DIR_PIN 43
|
||||||
|
#define E0_ENABLE_PIN 26
|
||||||
|
#define E0_MS1_PIN 65
|
||||||
|
#define E0_MS2_PIN 66
|
||||||
|
|
||||||
|
#define E1_STEP_PIN 33
|
||||||
|
#define E1_DIR_PIN 42
|
||||||
|
#define E1_ENABLE_PIN 25
|
||||||
|
#define E1_MS1_PIN 63
|
||||||
|
#define E1_MS2_PIN 64
|
||||||
|
|
||||||
|
#define DIGIPOTSS_PIN 38
|
||||||
|
#define DIGIPOT_CHANNELS {4,5,3,0,1} // X Y Z E0 E1 digipot channels to stepper driver mapping
|
||||||
|
|
||||||
|
#define SDPOWER -1
|
||||||
|
#define SDSS 53
|
||||||
|
#define LED_PIN 13
|
||||||
|
#define FAN_PIN 8
|
||||||
|
#define PS_ON_PIN 4
|
||||||
|
#define KILL_PIN -1
|
||||||
|
#define SUICIDE_PIN -1 //PIN that has to be turned on right after start, to keep power flowing.
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifndef KNOWN_BOARD
|
#ifndef KNOWN_BOARD
|
||||||
#error Unknown MOTHERBOARD value in configuration.h
|
#error Unknown MOTHERBOARD value in configuration.h
|
||||||
|
|
|
@ -28,7 +28,7 @@
|
||||||
#include "ultralcd.h"
|
#include "ultralcd.h"
|
||||||
#include "language.h"
|
#include "language.h"
|
||||||
#include "speed_lookuptable.h"
|
#include "speed_lookuptable.h"
|
||||||
|
#include <SPI.h>
|
||||||
|
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -714,6 +714,9 @@ ISR(TIMER1_COMPA_vect)
|
||||||
|
|
||||||
void st_init()
|
void st_init()
|
||||||
{
|
{
|
||||||
|
digipot_init(); //Initialize Digipot Motor Current
|
||||||
|
microstep_init(); //Initialize Microstepping Pins
|
||||||
|
|
||||||
//Initialize Dir Pins
|
//Initialize Dir Pins
|
||||||
#if X_DIR_PIN > -1
|
#if X_DIR_PIN > -1
|
||||||
SET_OUTPUT(X_DIR_PIN);
|
SET_OUTPUT(X_DIR_PIN);
|
||||||
|
@ -951,3 +954,100 @@ void quickStop()
|
||||||
ENABLE_STEPPER_DRIVER_INTERRUPT();
|
ENABLE_STEPPER_DRIVER_INTERRUPT();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
int digitalPotWrite(int address, int value) // From Arduino DigitalPotControl example
|
||||||
|
{
|
||||||
|
#if DIGIPOTSS_PIN > -1
|
||||||
|
digitalWrite(DIGIPOTSS_PIN,LOW); // take the SS pin low to select the chip
|
||||||
|
SPI.transfer(address); // send in the address and value via SPI:
|
||||||
|
SPI.transfer(value);
|
||||||
|
digitalWrite(DIGIPOTSS_PIN,HIGH); // take the SS pin high to de-select the chip:
|
||||||
|
//delay(10);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void digipot_init() //Initialize Digipot Motor Current
|
||||||
|
{
|
||||||
|
#if DIGIPOTSS_PIN > -1
|
||||||
|
const uint8_t digipot_motor_current[] = DIGIPOT_MOTOR_CURRENT;
|
||||||
|
|
||||||
|
SPI.begin();
|
||||||
|
pinMode(DIGIPOTSS_PIN, OUTPUT);
|
||||||
|
for(int i=0;i<=4;i++)
|
||||||
|
//digitalPotWrite(digipot_ch[i], digipot_motor_current[i]);
|
||||||
|
digipot_current(i,digipot_motor_current[i]);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void digipot_current(uint8_t driver, int current)
|
||||||
|
{
|
||||||
|
#if DIGIPOTSS_PIN > -1
|
||||||
|
const uint8_t digipot_ch[] = DIGIPOT_CHANNELS;
|
||||||
|
digitalPotWrite(digipot_ch[driver], current);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void microstep_init()
|
||||||
|
{
|
||||||
|
#if X_MS1_PIN > -1
|
||||||
|
const uint8_t microstep_modes[] = MICROSTEP_MODES;
|
||||||
|
pinMode(X_MS2_PIN,OUTPUT);
|
||||||
|
pinMode(Y_MS2_PIN,OUTPUT);
|
||||||
|
pinMode(Z_MS2_PIN,OUTPUT);
|
||||||
|
pinMode(E0_MS2_PIN,OUTPUT);
|
||||||
|
pinMode(E1_MS2_PIN,OUTPUT);
|
||||||
|
for(int i=0;i<=4;i++) microstep_mode(i,microstep_modes[i]);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2)
|
||||||
|
{
|
||||||
|
if(ms1 > -1) switch(driver)
|
||||||
|
{
|
||||||
|
case 0: digitalWrite( X_MS1_PIN,ms1); break;
|
||||||
|
case 1: digitalWrite( Y_MS1_PIN,ms1); break;
|
||||||
|
case 2: digitalWrite( Z_MS1_PIN,ms1); break;
|
||||||
|
case 3: digitalWrite(E0_MS1_PIN,ms1); break;
|
||||||
|
case 4: digitalWrite(E1_MS1_PIN,ms1); break;
|
||||||
|
}
|
||||||
|
if(ms2 > -1) switch(driver)
|
||||||
|
{
|
||||||
|
case 0: digitalWrite( X_MS2_PIN,ms2); break;
|
||||||
|
case 1: digitalWrite( Y_MS2_PIN,ms2); break;
|
||||||
|
case 2: digitalWrite( Z_MS2_PIN,ms2); break;
|
||||||
|
case 3: digitalWrite(E0_MS2_PIN,ms2); break;
|
||||||
|
case 4: digitalWrite(E1_MS2_PIN,ms2); break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void microstep_mode(uint8_t driver, uint8_t stepping_mode)
|
||||||
|
{
|
||||||
|
switch(stepping_mode)
|
||||||
|
{
|
||||||
|
case 1: microstep_ms(driver,MICROSTEP1); break;
|
||||||
|
case 2: microstep_ms(driver,MICROSTEP2); break;
|
||||||
|
case 4: microstep_ms(driver,MICROSTEP4); break;
|
||||||
|
case 8: microstep_ms(driver,MICROSTEP8); break;
|
||||||
|
case 16: microstep_ms(driver,MICROSTEP16); break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void microstep_readings()
|
||||||
|
{
|
||||||
|
SERIAL_PROTOCOLPGM("MS1,MS2 Pins\n");
|
||||||
|
SERIAL_PROTOCOLPGM("X: ");
|
||||||
|
SERIAL_PROTOCOL( digitalRead(X_MS1_PIN));
|
||||||
|
SERIAL_PROTOCOLLN( digitalRead(X_MS2_PIN));
|
||||||
|
SERIAL_PROTOCOLPGM("Y: ");
|
||||||
|
SERIAL_PROTOCOL( digitalRead(Y_MS1_PIN));
|
||||||
|
SERIAL_PROTOCOLLN( digitalRead(Y_MS2_PIN));
|
||||||
|
SERIAL_PROTOCOLPGM("Z: ");
|
||||||
|
SERIAL_PROTOCOL( digitalRead(Z_MS1_PIN));
|
||||||
|
SERIAL_PROTOCOLLN( digitalRead(Z_MS2_PIN));
|
||||||
|
SERIAL_PROTOCOLPGM("E0: ");
|
||||||
|
SERIAL_PROTOCOL( digitalRead(E0_MS1_PIN));
|
||||||
|
SERIAL_PROTOCOLLN( digitalRead(E0_MS2_PIN));
|
||||||
|
SERIAL_PROTOCOLPGM("E1: ");
|
||||||
|
SERIAL_PROTOCOL( digitalRead(E1_MS1_PIN));
|
||||||
|
SERIAL_PROTOCOLLN( digitalRead(E1_MS2_PIN));
|
||||||
|
}
|
||||||
|
|
||||||
|
|
|
@ -68,4 +68,13 @@ void finishAndDisableSteppers();
|
||||||
extern block_t *current_block; // A pointer to the block currently being traced
|
extern block_t *current_block; // A pointer to the block currently being traced
|
||||||
|
|
||||||
void quickStop();
|
void quickStop();
|
||||||
|
|
||||||
|
int digitalPotWrite(int address, int value);
|
||||||
|
void microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2);
|
||||||
|
void microstep_mode(uint8_t driver, uint8_t stepping);
|
||||||
|
void digipot_init();
|
||||||
|
void digipot_current(uint8_t driver, int current);
|
||||||
|
void microstep_init();
|
||||||
|
void microstep_readings();
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in a new issue