Merge pull request #4159 from thinkyhead/rc_rigidbot_diff
Rigidbot V2 support - has MCP4728 digipot
This commit is contained in:
commit
ee876dcd7a
@ -40,6 +40,7 @@
|
||||
#define BOARD_RAMPS_13_SF 38 // RAMPS 1.3 (Power outputs: Spindle, Controller Fan)
|
||||
#define BOARD_FELIX2 37 // Felix 2.0+ Electronics Board (RAMPS like)
|
||||
#define BOARD_RIGIDBOARD 42 // Invent-A-Part RigidBoard
|
||||
#define BOARD_RIGIDBOARD_V2 52 // Invent-A-Part RigidBoard V2
|
||||
#define BOARD_RAMPS_14_EFB 43 // RAMPS 1.4 (Power outputs: Hotend, Fan, Bed)
|
||||
#define BOARD_RAMPS_14_EEB 44 // RAMPS 1.4 (Power outputs: Hotend0, Hotend1, Bed)
|
||||
#define BOARD_RAMPS_14_EFF 45 // RAMPS 1.4 (Power outputs: Hotend, Fan0, Fan1)
|
||||
|
@ -43,9 +43,9 @@ void mcp4728_init() {
|
||||
Wire.begin();
|
||||
Wire.requestFrom(int(DAC_DEV_ADDRESS), 24);
|
||||
while(Wire.available()) {
|
||||
int deviceID = Wire.receive();
|
||||
int hiByte = Wire.receive();
|
||||
int loByte = Wire.receive();
|
||||
int deviceID = Wire.read();
|
||||
int hiByte = Wire.read();
|
||||
int loByte = Wire.read();
|
||||
|
||||
int isEEPROM = (deviceID & 0B00001000) >> 3;
|
||||
int channel = (deviceID & 0B00110000) >> 4;
|
||||
@ -70,10 +70,10 @@ uint8_t mcp4728_analogWrite(uint8_t channel, uint16_t value) {
|
||||
*/
|
||||
uint8_t mcp4728_eepromWrite() {
|
||||
Wire.beginTransmission(DAC_DEV_ADDRESS);
|
||||
Wire.send(SEQWRITE);
|
||||
Wire.write(SEQWRITE);
|
||||
for (uint8_t channel=0; channel <= 3; channel++) {
|
||||
Wire.send(DAC_STEPPER_VREF << 7 | 0 << 5 | DAC_STEPPER_GAIN << 4 | highByte(mcp4728_values[channel]));
|
||||
Wire.send(lowByte(mcp4728_values[channel]));
|
||||
Wire.write(DAC_STEPPER_VREF << 7 | 0 << 5 | DAC_STEPPER_GAIN << 4 | highByte(mcp4728_values[channel]));
|
||||
Wire.write(lowByte(mcp4728_values[channel]));
|
||||
}
|
||||
return Wire.endTransmission();
|
||||
}
|
||||
@ -83,7 +83,7 @@ uint8_t mcp4728_eepromWrite() {
|
||||
*/
|
||||
uint8_t mcp4728_setVref_all(uint8_t value) {
|
||||
Wire.beginTransmission(DAC_DEV_ADDRESS);
|
||||
Wire.send(VREFWRITE | value << 3 | value << 2 | value << 1 | value);
|
||||
Wire.write(VREFWRITE | value << 3 | value << 2 | value << 1 | value);
|
||||
return Wire.endTransmission();
|
||||
}
|
||||
/**
|
||||
@ -91,7 +91,7 @@ uint8_t mcp4728_setVref_all(uint8_t value) {
|
||||
*/
|
||||
uint8_t mcp4728_setGain_all(uint8_t value) {
|
||||
Wire.beginTransmission(DAC_DEV_ADDRESS);
|
||||
Wire.send(GAINWRITE | value << 3 | value << 2 | value << 1 | value);
|
||||
Wire.write(GAINWRITE | value << 3 | value << 2 | value << 1 | value);
|
||||
return Wire.endTransmission();
|
||||
}
|
||||
|
||||
@ -120,8 +120,8 @@ uint16_t mcp4728_getVout(uint8_t channel) {
|
||||
uint8_t mcp4728_fastWrite() {
|
||||
Wire.beginTransmission(DAC_DEV_ADDRESS);
|
||||
for (uint8_t channel=0; channel <= 3; channel++) {
|
||||
Wire.send(highByte(mcp4728_values[channel]));
|
||||
Wire.send(lowByte(mcp4728_values[channel]));
|
||||
Wire.write(highByte(mcp4728_values[channel]));
|
||||
Wire.write(lowByte(mcp4728_values[channel]));
|
||||
}
|
||||
return Wire.endTransmission();
|
||||
}
|
||||
@ -131,7 +131,7 @@ uint8_t mcp4728_fastWrite() {
|
||||
*/
|
||||
uint8_t mcp4728_simpleCommand(byte simpleCommand) {
|
||||
Wire.beginTransmission(GENERALCALL);
|
||||
Wire.send(simpleCommand);
|
||||
Wire.write(simpleCommand);
|
||||
return Wire.endTransmission();
|
||||
}
|
||||
|
||||
|
@ -31,9 +31,7 @@
|
||||
#include "Configuration_adv.h"
|
||||
|
||||
#if ENABLED(DAC_STEPPER_CURRENT)
|
||||
#include "WProgram.h"
|
||||
#include "Wire.h"
|
||||
//#include <Wire.h>
|
||||
|
||||
#define defaultVDD 5000
|
||||
#define BASE_ADDR 0x60
|
||||
@ -50,7 +48,9 @@
|
||||
#define GAINWRITE 0B11000000
|
||||
|
||||
// This is taken from the original lib, makes it easy to edit if needed
|
||||
#define DAC_DEV_ADDRESS (BASE_ADDR | 0x00)
|
||||
// DAC_OR_ADDRESS defined in pins_BOARD.h file
|
||||
#define DAC_DEV_ADDRESS (BASE_ADDR | DAC_OR_ADDRESS)
|
||||
|
||||
|
||||
void mcp4728_init();
|
||||
uint8_t mcp4728_analogWrite(uint8_t channel, uint16_t value);
|
||||
|
@ -117,8 +117,11 @@
|
||||
|
||||
// The following define selects which electronics board you have.
|
||||
// Please choose the name from boards.h that matches your setup
|
||||
// for Rigidbot version 1 : #define MOTHERBOARD BOARD_RIGIDBOARD
|
||||
// for Rigidbot Version 2 : #define MOTHERBOARD BOARD_RIGIDBOARD_V2
|
||||
|
||||
#ifndef MOTHERBOARD
|
||||
#define MOTHERBOARD BOARD_RIGIDBOARD
|
||||
#define MOTHERBOARD BOARD_RIGIDBOARD_V2
|
||||
#endif
|
||||
|
||||
// Optional custom name for your RepStrap or other custom machine
|
||||
|
@ -129,6 +129,8 @@
|
||||
#include "pins_MKS_BASE.h"
|
||||
#elif MB(RIGIDBOARD)
|
||||
#include "pins_RIGIDBOARD.h"
|
||||
#elif MB(RIGIDBOARD_V2)
|
||||
#include "pins_RIGIDBOARD_V2.h"
|
||||
#elif MB(MEGACONTROLLER)
|
||||
#include "pins_MEGACONTROLLER.h"
|
||||
#elif MB(BQ_ZUM_MEGA_3D)
|
||||
|
@ -89,6 +89,7 @@
|
||||
#define DAC_STEPPER_MAX 3520
|
||||
#define DAC_STEPPER_VREF 1 //internal Vref, gain 1x = 2.048V
|
||||
#define DAC_STEPPER_GAIN 0
|
||||
#define DAC_OR_ADDRESS 0x00
|
||||
|
||||
#if DISABLED(SDSUPPORT)
|
||||
// these pins are defined in the SD library if building with SD support
|
||||
|
40
Marlin/pins_RIGIDBOARD_V2.h
Normal file
40
Marlin/pins_RIGIDBOARD_V2.h
Normal file
@ -0,0 +1,40 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* RIGIDBOARD V2 Arduino Mega with RAMPS v1.4 pin assignments
|
||||
*/
|
||||
|
||||
#include "pins_RIGIDBOARD.h"
|
||||
|
||||
// I2C based DAC like on the Printrboard REVF
|
||||
#define DAC_STEPPER_CURRENT
|
||||
// Channels available for DAC, For Rigidboard there are 4
|
||||
#define DAC_STEPPER_ORDER {0,1,2,3}
|
||||
|
||||
#define DAC_STEPPER_SENSE 0.11
|
||||
#define DAC_STEPPER_ADDRESS 0
|
||||
#define DAC_STEPPER_MAX 5000
|
||||
#define DAC_STEPPER_VREF 1 //internal Vref, gain 1x = 2.048V
|
||||
#define DAC_STEPPER_GAIN 0
|
||||
#define DAC_DISABLE_PIN 42 // set low to enable DAC
|
||||
#define DAC_OR_ADDRESS 0x01
|
@ -51,6 +51,11 @@
|
||||
const uint8_t dac_order[NUM_AXIS] = DAC_STEPPER_ORDER;
|
||||
|
||||
int dac_init() {
|
||||
#if PIN_EXISTS(DAC_DISABLE)
|
||||
pinMode(DAC_DISABLE_PIN, OUTPUT);
|
||||
digitalWrite(DAC_DISABLE_PIN, LOW); // set pin low to enable DAC
|
||||
#endif
|
||||
|
||||
mcp4728_init();
|
||||
|
||||
if (mcp4728_simpleCommand(RESET)) return -1;
|
||||
|
Loading…
Reference in New Issue
Block a user