AVR RRD works

LPC1768 VIKI2 & RRDFG are working

looks like all SPIs are working

library change

sh1106 locks up

fixed lockup, started I2C SW com

pretty

re-org

restore a few files

make library happy

switched HAL version of rrd

fix travis error

travis error fixes

another travis fix

cleanup

minor update

one more

correct spacing in platformio.ini
This commit is contained in:
Bob-the-Kuhn
2017-11-02 20:57:08 -05:00
parent a34b5a2bfa
commit 0483a7df91
25 changed files with 2711 additions and 369 deletions

View File

@ -0,0 +1,43 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016, 2017 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/>.
*
*/
#ifndef HAL_LCD_DEFINES_H_
#define HAL_LCD_DEFINES_H_
#ifdef ARDUINO_ARCH_SAM
// #include "HAL_DUE/HAL_DUE_LCD_defines.h"
#elif defined(IS_32BIT_TEENSY)
// #include "HAL_TEENSY35_36/HAL_TEENSY_LCD_defines.h"
#elif defined(ARDUINO_ARCH_AVR)
// #include "HAL_AVR/HAL_ARDUINO_LCD_defines.h"
#elif defined(TARGET_LPC1768)
#include "HAL_LPC1768/HAL_LPC1768_LCD_defines.h"
#else
#error "Unsupported Platform!"
#endif
#endif // HAL_LCD_DEFINES_H_

View File

@ -0,0 +1,183 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016, 2017 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/>.
*
*/
// adapted from I2C/master/master.c example
// https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
#if defined(TARGET_LPC1768)
#ifdef __cplusplus
extern "C" {
#endif
#include <lpc17xx_i2c.h>
#include <lpc17xx_pinsel.h>
#include <lpc17xx_libcfg_default.h>
//////////////////////////////////////////////////////////////////////////////////////
// These two routines are exact copies of the lpc17xx_i2c.c routines. Couldn't link to
// to the lpc17xx_i2c.c routines so had to copy them into this file & rename them.
static uint32_t _I2C_Start (LPC_I2C_TypeDef *I2Cx)
{
// Reset STA, STO, SI
I2Cx->I2CONCLR = I2C_I2CONCLR_SIC|I2C_I2CONCLR_STOC|I2C_I2CONCLR_STAC;
// Enter to Master Transmitter mode
I2Cx->I2CONSET = I2C_I2CONSET_STA;
// Wait for complete
while (!(I2Cx->I2CONSET & I2C_I2CONSET_SI));
I2Cx->I2CONCLR = I2C_I2CONCLR_STAC;
return (I2Cx->I2STAT & I2C_STAT_CODE_BITMASK);
}
static void _I2C_Stop (LPC_I2C_TypeDef *I2Cx)
{
/* Make sure start bit is not active */
if (I2Cx->I2CONSET & I2C_I2CONSET_STA)
{
I2Cx->I2CONCLR = I2C_I2CONCLR_STAC;
}
I2Cx->I2CONSET = I2C_I2CONSET_STO|I2C_I2CONSET_AA;
I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
}
//////////////////////////////////////////////////////////////////////////////////////
#define U8G_I2C_OPT_FAST 16 // from u8g.h
#define USEDI2CDEV_M 1
#define I2CDEV_S_ADDR 0x78 // from SSD1306 //actual address is 0x3C - shift left 1 with LSB set to 0 to indicate write
#define BUFFER_SIZE 0x1 // only do single byte transfers with LCDs
#if (USEDI2CDEV_M == 0)
#define I2CDEV_M LPC_I2C0
#elif (USEDI2CDEV_M == 1)
#define I2CDEV_M LPC_I2C1
#elif (USEDI2CDEV_M == 2)
#define I2CDEV_M LPC_I2C2
#else
#error "Master I2C device not defined!"
#endif
PINSEL_CFG_Type PinCfg;
I2C_M_SETUP_Type transferMCfg;
#define I2C_status (LPC_I2C1->I2STAT & I2C_STAT_CODE_BITMASK)
uint8_t u8g_i2c_start(uint8_t sla) { // send slave address and write bit
// Sometimes TX data ACK or NAK status is returned. That mean the start state didn't
// happen which means only the value of the slave address was send. Keep looping until
// the slave address and write bit are actually sent.
do{
_I2C_Stop(I2CDEV_M); // output stop state on I2C bus
_I2C_Start(I2CDEV_M); // output start state on I2C bus
while ((I2C_status != I2C_I2STAT_M_TX_START)
&& (I2C_status != I2C_I2STAT_M_TX_RESTART)
&& (I2C_status != I2C_I2STAT_M_TX_DAT_ACK)
&& (I2C_status != I2C_I2STAT_M_TX_DAT_NACK)); //wait for start to be asserted
LPC_I2C1->I2CONCLR = I2C_I2CONCLR_STAC; // clear start state before tansmitting slave address
LPC_I2C1->I2DAT = I2CDEV_S_ADDR & I2C_I2DAT_BITMASK; // transmit slave address & write bit
LPC_I2C1->I2CONSET = I2C_I2CONSET_AA;
LPC_I2C1->I2CONCLR = I2C_I2CONCLR_SIC;
while ((I2C_status != I2C_I2STAT_M_TX_SLAW_ACK)
&& (I2C_status != I2C_I2STAT_M_TX_SLAW_NACK)
&& (I2C_status != I2C_I2STAT_M_TX_DAT_ACK)
&& (I2C_status != I2C_I2STAT_M_TX_DAT_NACK)); //wait for slaw to finish
}while ( (I2C_status == I2C_I2STAT_M_TX_DAT_ACK) || (I2C_status == I2C_I2STAT_M_TX_DAT_NACK));
return 1;
}
void u8g_i2c_init(uint8_t clock_option) {
/*
* Init I2C pin connect
*/
PinCfg.OpenDrain = 0;
PinCfg.Pinmode = 0;
#if ((USEDI2CDEV_M == 0))
PinCfg.Funcnum = 1;
PinCfg.Pinnum = 27;
PinCfg.Portnum = 0;
PINSEL_ConfigPin(&PinCfg); // SDA0 / D57 AUX-1
PinCfg.Pinnum = 28;
PINSEL_ConfigPin(&PinCfg); // SCL0 / D58 AUX-1
#endif
#if ((USEDI2CDEV_M == 1))
PinCfg.Funcnum = 3;
PinCfg.Pinnum = 0;
PinCfg.Portnum = 0;
PINSEL_ConfigPin(&PinCfg); // SDA1 / D20 SCA
PinCfg.Pinnum = 1;
PINSEL_ConfigPin(&PinCfg); // SCL1 / D21 SCL
#endif
#if ((USEDI2CDEV_M == 2))
PinCfg.Funcnum = 2;
PinCfg.Pinnum = 10;
PinCfg.Portnum = 0;
PINSEL_ConfigPin(&PinCfg); // SDA2 / D38 X_ENABLE_PIN
PinCfg.Pinnum = 11;
PINSEL_ConfigPin(&PinCfg); // SCL2 / D55 X_DIR_PIN
#endif
// Initialize I2C peripheral
I2C_Init(I2CDEV_M, (clock_option & U8G_I2C_OPT_FAST) ? 400000: 100000); // LCD data rates
/* Enable Master I2C operation */
I2C_Cmd(I2CDEV_M, I2C_MASTER_MODE, ENABLE);
u8g_i2c_start(0); // send slave address and write bit
}
volatile extern uint32_t _millis;
uint8_t u8g_i2c_send_byte(uint8_t data) {
#define I2C_TIMEOUT 3
LPC_I2C1->I2DAT = data & I2C_I2DAT_BITMASK; // transmit data
LPC_I2C1->I2CONSET = I2C_I2CONSET_AA;
LPC_I2C1->I2CONCLR = I2C_I2CONCLR_SIC;
uint32_t timeout = _millis + I2C_TIMEOUT;
while ((I2C_status != I2C_I2STAT_M_TX_DAT_ACK) && (I2C_status != I2C_I2STAT_M_TX_DAT_NACK) && (timeout > _millis)); // wait for xmit to finish
// had hangs with SH1106 so added time out - have seen temporary screen corruption when this happens
return 1;
}
void u8g_i2c_stop(void) {
}
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,35 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016, 2017 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/>.
*
*/
#if defined(TARGET_LPC1768)
void u8g_i2c_init(uint8_t options);
uint8_t u8g_i2c_wait(uint8_t mask, uint8_t pos);
uint8_t u8g_i2c_start(uint8_t sla);
uint8_t u8g_i2c_send_byte(uint8_t data);
void u8g_i2c_stop(void);
#endif

View File

@ -0,0 +1,46 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016, 2017 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/>.
*
*/
/**
* LCD delay routines - used by all the drivers.
*
* These are based on the LPC1768 routines.
*
* Couldn't just call exact copies because the overhead resulted in the
* one microsecond delay being about 4uS.
*/
#ifdef __cplusplus
extern "C" {
#endif
void U8g_delay(int msec);
void u8g_MicroDelay(void);
void u8g_10MicroDelay(void);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,116 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016, 2017 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/>.
*
*/
/**
* Low level pin manipulation routines - used by all the drivers.
*
* These are based on the LPC1768 pinMode, digitalRead & digitalWrite routines.
*
* Couldn't just call exact copies because the overhead killed the LCD update speed
* With an intermediate level the softspi was running in the 10-20kHz range which
* resulted in using about about 25% of the CPU's time.
*/
#if defined(TARGET_LPC1768)
#include <LPC17xx.h>
#include <lpc17xx_pinsel.h>
#include "src/core/macros.h"
// #include "pinmapping.h"
#define LPC_PORT_OFFSET (0x0020)
#define LPC_PIN(pin) (1UL << pin)
#define LPC_GPIO(port) ((volatile LPC_GPIO_TypeDef *)(LPC_GPIO0_BASE + LPC_PORT_OFFSET * port))
#define INPUT 0
#define OUTPUT 1
#define INPUT_PULLUP 2
uint8_t LPC1768_PIN_PORT(const uint8_t pin);
uint8_t LPC1768_PIN_PIN(const uint8_t pin);
#ifdef __cplusplus
extern "C" {
#endif
// IO functions
// As defined by Arduino INPUT(0x0), OUPUT(0x1), INPUT_PULLUP(0x2)
void pinMode_LCD(uint8_t pin, uint8_t mode) {
#define LPC1768_PIN_PORT(pin) ((uint8_t)((pin >> 5) & 0b111))
#define LPC1768_PIN_PIN(pin) ((uint8_t)(pin & 0b11111))
PINSEL_CFG_Type config = { LPC1768_PIN_PORT(pin),
LPC1768_PIN_PIN(pin),
PINSEL_FUNC_0,
PINSEL_PINMODE_TRISTATE,
PINSEL_PINMODE_NORMAL };
switch(mode) {
case INPUT:
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
PINSEL_ConfigPin(&config);
break;
case OUTPUT:
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR |= LPC_PIN(LPC1768_PIN_PIN(pin));
PINSEL_ConfigPin(&config);
break;
case INPUT_PULLUP:
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
config.Pinmode = PINSEL_PINMODE_PULLUP;
PINSEL_ConfigPin(&config);
break;
default:
break;
}
}
void u8g_SetPinOutput(uint8_t internal_pin_number) {
pinMode_LCD(internal_pin_number, 1); // OUTPUT
}
void u8g_SetPinInput(uint8_t internal_pin_number) {
pinMode_LCD(internal_pin_number, 0); // INPUT
}
void u8g_SetPinLevel(uint8_t pin, uint8_t pin_status) {
#define LPC1768_PIN_PORT(pin) ((uint8_t)((pin >> 5) & 0b111))
#define LPC1768_PIN_PIN(pin) ((uint8_t)(pin & 0b11111))
if (pin_status)
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOSET = LPC_PIN(LPC1768_PIN_PIN(pin));
else
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOCLR = LPC_PIN(LPC1768_PIN_PIN(pin));
}
uint8_t u8g_GetPinLevel(uint8_t pin) {
#define LPC1768_PIN_PORT(pin) ((uint8_t)((pin >> 5) & 0b111))
#define LPC1768_PIN_PIN(pin) ((uint8_t)(pin & 0b11111))
return (uint32_t)LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOPIN & LPC_PIN(LPC1768_PIN_PIN(pin)) ? 1 : 0;
}
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,47 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016, 2017 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/>.
*
*/
/**
* Low level pin manipulation routines - used by all the drivers.
*
* These are based on the LPC1768 pinMode, digitalRead & digitalWrite routines.
*
* Couldn't just call exact copies because the overhead killed the LCD update speed
* With an intermediate level the softspi was running in the 10-20kHz range which
* resulted in using about about 25% of the CPU's time.
*/
void u8g_SetPinOutput(uint8_t internal_pin_number);
void u8g_SetPinInput(uint8_t internal_pin_number);
void u8g_SetPinLevel(uint8_t pin, uint8_t pin_status);
uint8_t u8g_GetPinLevel(uint8_t pin);

View File

@ -0,0 +1,58 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016, 2017 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/>.
*
*/
/**
* LPC1768 LCD specific defines
*/
#if defined(TARGET_LPC1768)
// pointers to low level routines - must always supply these
// #define U8G_HAL_LINKS
#define HAL_LCD_pin_routines "HAL_LPC1768/HAL_LCD_pin_routines.h"
#define HAL_LCD_I2C_routines "HAL_LPC1768/HAL_LCD_I2C_routines.h"
#define HAL_LCD_delay "HAL_LPC1768/HAL_LCD_delay.h"
// The following are optional depending on the platform.
// definitions of HAL specific com and device drivers.
uint8_t u8g_com_HAL_LPC1768_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr);
uint8_t u8g_com_HAL_LPC1768_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr);
uint8_t u8g_com_HAL_LPC1768_ST7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr);
uint8_t u8g_com_HAL_LPC1768_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr);
uint8_t u8g_com_HAL_LPC1768_ssd_hw_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr);
// connect U8g com generic com names to the desired driver
#define U8G_COM_HW_SPI u8g_com_HAL_LPC1768_hw_spi_fn // use LPC1768 specific hardware SPI routine
#define U8G_COM_SW_SPI u8g_com_HAL_LPC1768_sw_spi_fn // use LPC1768 specific software SPI routine
#define U8G_COM_ST7920_HW_SPI u8g_com_HAL_LPC1768_ST7920_hw_spi_fn
#define U8G_COM_ST7920_SW_SPI u8g_com_HAL_LPC1768_ST7920_sw_spi_fn
#define U8G_COM_SSD_I2C u8g_com_HAL_LPC1768_ssd_hw_i2c_fn
// let these default for now
#define U8G_COM_PARALLEL u8g_com_null_fn
#define U8G_COM_T6963 u8g_com_null_fn
#define U8G_COM_FAST_PARALLEL u8g_com_null_fn
#define U8G_COM_UC_I2C u8g_com_null_fn
#endif

View File

@ -104,14 +104,14 @@
else if (SPI_speed == 1) { // medium - about 1 MHz
for (int bits = 0; bits < 8; bits++) {
if (b & 0x80) {
for (uint8_t i = 0; i < 8; i++) WRITE(MOSI_PIN, HIGH);
for (uint8_t i = 0; i < 9; i++) WRITE(MOSI_PIN, HIGH);
}
else {
for (uint8_t i = 0; i < 8; i++) WRITE(MOSI_PIN, LOW);
for (uint8_t i = 0; i < 9; i++) WRITE(MOSI_PIN, LOW);
}
b <<= 1;
for (uint8_t i = 0; i < 6; i++) WRITE(SCK_PIN, HIGH);
for (uint8_t i = 0; i < 7; i++) WRITE(SCK_PIN, HIGH);
if (READ(MISO_PIN)) {
b |= 1;

View File

@ -0,0 +1 @@
// blank file needed until I get platformio to update it's copy of U8Glib-HAL

View File

@ -0,0 +1,146 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016, 2017 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/>.
*
*/
/*
based on u8g_com_msp430_hw_spi.c
Universal 8bit Graphics Library
Copyright (c) 2012, olikraus@gmail.com
All rights reserved.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this list
of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice, this
list of conditions and the following disclaimer in the documentation and/or other
materials provided with the distribution.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifdef TARGET_LPC1768
// #include <inttypes.h>
// #include "src/core/macros.h"
// #include "Configuration.h"
#include <lib/u8g.h>
#define SPI_FULL_SPEED 0
#define SPI_HALF_SPEED 1
#define SPI_QUARTER_SPEED 2
#define SPI_EIGHTH_SPEED 3
#define SPI_SIXTEENTH_SPEED 4
#define SPI_SPEED_5 5
#define SPI_SPEED_6 6
void spiBegin();
void spiInit(uint8_t spiRate);
void spiSend(uint8_t b);
void spiSend(const uint8_t* buf, size_t n);
uint8_t u8g_com_HAL_LPC1768_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr)
{
switch(msg)
{
case U8G_COM_MSG_STOP:
break;
case U8G_COM_MSG_INIT:
u8g_SetPILevel(u8g, U8G_PI_CS, 1);
u8g_SetPILevel(u8g, U8G_PI_A0, 1);
u8g_SetPILevel(u8g, U8G_PI_RESET, 1);
u8g_SetPIOutput(u8g, U8G_PI_CS);
u8g_SetPIOutput(u8g, U8G_PI_A0);
u8g_SetPIOutput(u8g, U8G_PI_RESET);
u8g_Delay(5);
spiBegin();
#ifndef SPI_SPEED
#define SPI_SPEED SPI_FULL_SPEED // use same SPI speed as SD card
#endif
spiInit(SPI_SPEED);
break;
case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */
u8g_SetPILevel(u8g, U8G_PI_A0, arg_val);
break;
case U8G_COM_MSG_CHIP_SELECT:
u8g_SetPILevel(u8g, U8G_PI_CS, (arg_val ? 0 : 1));
break;
case U8G_COM_MSG_RESET:
u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val);
break;
case U8G_COM_MSG_WRITE_BYTE:
spiSend((uint8_t)arg_val);
break;
case U8G_COM_MSG_WRITE_SEQ:
{
uint8_t *ptr = (uint8_t*) arg_ptr;
while( arg_val > 0 )
{
spiSend(*ptr++);
arg_val--;
}
}
break;
case U8G_COM_MSG_WRITE_SEQ_P:
{
uint8_t *ptr = (uint8_t*) arg_ptr;
while( arg_val > 0 )
{
spiSend(*ptr++);
arg_val--;
}
}
break;
}
return 1;
}
#endif //TARGET_LPC1768

View File

@ -0,0 +1,204 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016, 2017 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/>.
*
*/
/*
based on u8g_com_arduino_ssd_i2c.c
com interface for arduino (AND atmega) and the SSDxxxx chip (SOLOMON) variant
I2C protocol
ToDo: Rename this to u8g_com_avr_ssd_i2c.c
Universal 8bit Graphics Library
Copyright (c) 2012, olikraus@gmail.com
All rights reserved.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this list
of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice, this
list of conditions and the following disclaimer in the documentation and/or other
materials provided with the distribution.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
Special pin usage:
U8G_PI_I2C_OPTION additional options
U8G_PI_A0_STATE used to store the last value of the command/data register selection
U8G_PI_SET_A0 1: Signal request to update I2C device with new A0_STATE, 0: Do nothing, A0_STATE matches I2C device
U8G_PI_SCL clock line (NOT USED)
U8G_PI_SDA data line (NOT USED)
U8G_PI_RESET reset line (currently disabled, see below)
Protocol:
SLA, Cmd/Data Selection, Arguments
The command/data register is selected by a special instruction byte, which is sent after SLA
The continue bit is always 0 so that a (re)start is equired for the change from cmd to/data mode
*/
#ifdef TARGET_LPC1768
#include <lib/u8g.h>
#define I2C_SLA (0x3c*2)
//#define I2C_CMD_MODE 0x080
#define I2C_CMD_MODE 0x000
#define I2C_DATA_MODE 0x040
// #define U8G_I2C_OPT_FAST 16
uint8_t u8g_com_ssd_I2C_start_sequence(u8g_t *u8g)
{
/* are we requested to set the a0 state? */
if ( u8g->pin_list[U8G_PI_SET_A0] == 0 )
return 1;
/* setup bus, might be a repeated start */
if ( u8g_i2c_start(I2C_SLA) == 0 )
return 0;
if ( u8g->pin_list[U8G_PI_A0_STATE] == 0 )
{
if ( u8g_i2c_send_byte(I2C_CMD_MODE) == 0 )
return 0;
}
else
{
if ( u8g_i2c_send_byte(I2C_DATA_MODE) == 0 )
return 0;
}
u8g->pin_list[U8G_PI_SET_A0] = 0;
return 1;
}
uint8_t u8g_com_HAL_LPC1768_ssd_hw_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr)
{
switch(msg)
{
case U8G_COM_MSG_INIT:
//u8g_com_arduino_digital_write(u8g, U8G_PI_SCL, HIGH);
//u8g_com_arduino_digital_write(u8g, U8G_PI_SDA, HIGH);
//u8g->pin_list[U8G_PI_A0_STATE] = 0; /* inital RS state: unknown mode */
u8g_i2c_init(u8g->pin_list[U8G_PI_I2C_OPTION]);
u8g_com_ssd_I2C_start_sequence(u8g);
break;
case U8G_COM_MSG_STOP:
break;
case U8G_COM_MSG_RESET:
/* Currently disabled, but it could be enable. Previous restrictions have been removed */
/* u8g_com_arduino_digital_write(u8g, U8G_PI_RESET, arg_val); */
break;
case U8G_COM_MSG_CHIP_SELECT:
u8g->pin_list[U8G_PI_A0_STATE] = 0;
u8g->pin_list[U8G_PI_SET_A0] = 1; /* force a0 to set again, also forces start condition */
if ( arg_val == 0 )
{
/* disable chip, send stop condition */
u8g_i2c_stop();
}
else
{
/* enable, do nothing: any byte writing will trigger the i2c start */
}
break;
case U8G_COM_MSG_WRITE_BYTE:
//u8g->pin_list[U8G_PI_SET_A0] = 1;
// if ( u8g_com_arduino_ssd_start_sequence(u8g) == 0 )
// return u8g_i2c_stop(), 0;
if ( u8g_i2c_send_byte(arg_val) == 0 )
return u8g_i2c_stop(), 0;
// u8g_i2c_stop();
break;
case U8G_COM_MSG_WRITE_SEQ:
//u8g->pin_list[U8G_PI_SET_A0] = 1;
if ( u8g_com_ssd_I2C_start_sequence(u8g) == 0 )
return u8g_i2c_stop(), 0;
{
register uint8_t *ptr = (uint8_t *)arg_ptr;
while( arg_val > 0 )
{
if ( u8g_i2c_send_byte(*ptr++) == 0 )
return u8g_i2c_stop(), 0;
arg_val--;
}
}
// u8g_i2c_stop();
break;
case U8G_COM_MSG_WRITE_SEQ_P:
//u8g->pin_list[U8G_PI_SET_A0] = 1;
if ( u8g_com_ssd_I2C_start_sequence(u8g) == 0 )
return u8g_i2c_stop(), 0;
{
register uint8_t *ptr = (uint8_t *)arg_ptr;
while( arg_val > 0 )
{
if ( u8g_i2c_send_byte(u8g_pgm_read(ptr)) == 0 )
return 0;
ptr++;
arg_val--;
}
}
// u8g_i2c_stop();
break;
case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */
u8g->pin_list[U8G_PI_A0_STATE] = arg_val;
u8g->pin_list[U8G_PI_SET_A0] = 1; /* force a0 to set again */
u8g_i2c_start(0); // send slave address and write bit
if (arg_val)
u8g_i2c_send_byte(0x40); // write to graphics DRAM mode
else
u8g_i2c_send_byte(0x80); //command mode
break;
}
return 1;
}
#endif // TARGET_LPC1768

View File

@ -0,0 +1,283 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016, 2017 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/>.
*
*/
/* based on U8G2 code
u8x8_byte.c
Universal 8bit Graphics Library (https://github.com/olikraus/u8g2/)
Copyright (c) 2016, olikraus@gmail.com
All rights reserved.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this list
of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice, this
list of conditions and the following disclaimer in the documentation and/or other
materials provided with the distribution.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*
software i2c,
ignores ACK response (which is anyway not provided by some displays)
also does not allow reading from the device
*/
#ifdef TARGET_LPC1768
#include <lib/u8g.h>
void delayMicroseconds(uint32_t us);
//void pinMode(int16_t pin, uint8_t mode);
//void digitalWrite(int16_t pin, uint8_t pin_status);
#define I2C_SLA (0x3c*2)
//#define I2C_CMD_MODE 0x080
#define I2C_CMD_MODE 0x000
#define I2C_DATA_MODE 0x040
//static uint8_t I2C_speed; // 3 - 400KHz, 13 - 100KHz
//#define SPEED_400KHz 3
//#define SPEED_100KHz 13
// #define U8G_I2C_OPT_FAST 16
uint8_t SCL_pin_HAL_LPC1768_sw_I2C, SCL_port_HAL_LPC1768_sw_I2C, SDA_pin_HAL_LPC1768_sw_I2C, SDA_port_HAL_LPC1768_sw_I2C;
#define SPI_SPEED 2 //20: 200KHz 5:750KHz 2:3-4MHz
uint8_t u8g_i2c_send_byte_sw(uint8_t data) {
{
for (uint8_t i = 0; i < 9; i++) { // 1 extra bit for the ack/nak
if (val & 0x80)
for (uint8_t j = 0; j < SPI_SPEED; j++) {
LPC_GPIO(SDA_port_HAL_LPC1768_sw_I2C)->FIOSET = LPC_PIN(SDA_pin_HAL_LPC1768_sw_I2C);
LPC_GPIO(SDA_port_HAL_LPC1768_sw_I2C)->FIOSET = LPC_PIN(SDA_pin_HAL_LPC1768_sw_I2C);
LPC_GPIO(SDA_port_HAL_LPC1768_sw_I2C)->FIOSET = LPC_PIN(SDA_pin_HAL_LPC1768_sw_I2C);
}
else
for (uint8_t j = 0; j < SPI_SPEED; j++) {
LPC_GPIO(SDA_port_HAL_LPC1768_sw_I2C)->FIOCLR = LPC_PIN(SDA_pin_HAL_LPC1768_sw_I2C);
LPC_GPIO(SDA_port_HAL_LPC1768_sw_I2C)->FIOCLR = LPC_PIN(SDA_pin_HAL_LPC1768_sw_I2C);
LPC_GPIO(SDA_port_HAL_LPC1768_sw_I2C)->FIOCLR = LPC_PIN(SDA_pin_HAL_LPC1768_sw_I2C);
}
for (uint8_t j = 0; j < SPI_SPEED; j++) {
LPC_GPIO(SCL_port_HAL_LPC1768_sw_I2C)->FIOSET = LPC_PIN(SCL_pin_HAL_LPC1768_sw_I2C);
LPC_GPIO(SCL_port_HAL_LPC1768_sw_I2C)->FIOSET = LPC_PIN(SCL_pin_HAL_LPC1768_sw_I2C);
LPC_GPIO(SCL_port_HAL_LPC1768_sw_I2C)->FIOSET = LPC_PIN(SCL_pin_HAL_LPC1768_sw_I2C);
LPC_GPIO(SCL_port_HAL_LPC1768_sw_I2C)->FIOSET = LPC_PIN(SCL_pin_HAL_LPC1768_sw_I2C);
LPC_GPIO(SCL_port_HAL_LPC1768_sw_I2C)->FIOSET = LPC_PIN(SCL_pin_HAL_LPC1768_sw_I2C);
}
for (uint8_t j = 0; j < SPI_SPEED; j++) {
LPC_GPIO(SCL_port_HAL_LPC1768_sw_I2C)->FIOCLR = LPC_PIN(SCL_pin_HAL_LPC1768_sw_I2C);
LPC_GPIO(SCL_port_HAL_LPC1768_sw_I2C)->FIOCLR = LPC_PIN(SCL_pin_HAL_LPC1768_sw_I2C);
}
val = val << 1;
}
return 1;
}
uint8_t u8g_i2c_start_sw(uint8_t sla) { // assert start condition and then send slave address with write bit
{
/* send the start condition, both lines go from 1 to 0 */
LPC_GPIO(SDA_port_HAL_LPC1768_sw_I2C)->FIOCLR = LPC_PIN(SDA_pin_HAL_LPC1768_sw_I2C);
LPC_GPIO(SCL_port_HAL_LPC1768_sw_I2C)->FIOCLR = LPC_PIN(SCL_pin_HAL_LPC1768_sw_I2C);
delayMicroseconds(2);
LPC_GPIO(SCL_port_HAL_LPC1768_sw_I2C)->FIOSET = LPC_PIN(SCL_pin_HAL_LPC1768_sw_I2C);
delayMicroseconds(2);
LPC_GPIO(SDA_port_HAL_LPC1768_sw_I2C)->FIOSET = LPC_PIN(SDA_pin_HAL_LPC1768_sw_I2C);
delayMicroseconds(2);
LPC_GPIO(SDA_port_HAL_LPC1768_sw_I2C)->FIOCLR = LPC_PIN(SDA_pin_HAL_LPC1768_sw_I2C);
delayMicroseconds(2);
LPC_GPIO(SCL_port_HAL_LPC1768_sw_I2C)->FIOCLR = LPC_PIN(SCL_pin_HAL_LPC1768_sw_I2C);
u8g_i2c_send_byte_sw(I2C_SLA); // send slave address with write bit
}
void u8g_i2c_stop_sw(void) {
}
void u8g_i2c_init_sw(uint8_t clock_option) {
u8g_i2c_start(0); // send slave address and write bit
}
uint8_t u8g_com_ssd_I2C_start_sequence_sw(u8g_t *u8g)
{
/* are we requested to set the a0 state? */
if ( u8g->pin_list[U8G_PI_SET_A0] == 0 )
return 1;
/* setup bus, might be a repeated start */
if ( u8g_i2c_start(I2C_SLA) == 0 )
return 0;
if ( u8g->pin_list[U8G_PI_A0_STATE] == 0 )
{
if ( u8g_i2c_send_byte(I2C_CMD_MODE) == 0 )
return 0;
}
else
{
if ( u8g_i2c_send_byte(I2C_DATA_MODE) == 0 )
return 0;
}
u8g->pin_list[U8G_PI_SET_A0] = 0;
return 1;
}
uint8_t u8g_com_HAL_LPC1768_ssd_sw_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr)
{
switch(msg)
{
case U8G_COM_MSG_INIT:
#define LPC1768_PIN_PORT(pin) ((uint8_t)((pin >> 5) & 0b111))
#define LPC1768_PIN_PIN(pin) ((uint8_t)(pin & 0b11111))
SCL_pin_HAL_LPC1768_sw_I2C = LPC1768_PIN_PIN(u8g->pin_list[U8G_PI_SCL]);
SCL_port_HAL_LPC1768_sw_I2C = LPC1768_PIN_PORT(u8g->pin_list[U8G_PI_SCL]);
SDA_pin_HAL_LPC1768_sw_I2C = LPC1768_PIN_PIN(u8g->pin_list[U8G_PI_SDA]);
SDA_port_HAL_LPC1768_sw_I2C = LPC1768_PIN_PORT(u8g->pin_list[U8G_PI_SDA]);
// As defined by Arduino INPUT(0x0), OUPUT(0x1), INPUT_PULLUP(0x2)
#define OUPUT 0x1
u8g_SetPIOutput(u8g, U8G_PI_SCL);
u8g_SetPIOutput(u8g, U8G_PI_SDA);
if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_CS]) u8g_SetPIOutput(u8g, U8G_PI_CS);
if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_A0]) u8g_SetPIOutput(u8g, U8G_PI_A0);
if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPIOutput(u8g, U8G_PI_RESET);
//u8g_com_arduino_digital_write(u8g, U8G_PI_SCL, HIGH);
//u8g_com_arduino_digital_write(u8g, U8G_PI_SDA, HIGH);
//u8g->pin_list[U8G_PI_A0_STATE] = 0; /* inital RS state: unknown mode */
u8g_i2c_init_sw(u8g->pin_list[U8G_PI_I2C_OPTION]);
u8g_com_ssd_I2C_start_sequence_sw((u8g);
break;
case U8G_COM_MSG_STOP:
break;
case U8G_COM_MSG_RESET:
break;
case U8G_COM_MSG_CHIP_SELECT:
u8g->pin_list[U8G_PI_A0_STATE] = 0;
u8g->pin_list[U8G_PI_SET_A0] = 1; /* force a0 to set again, also forces start condition */
if ( arg_val == 0 )
{
/* disable chip, send stop condition */
u8g_i2c_stop_sw();
}
else
{
/* enable, do nothing: any byte writing will trigger the i2c start */
}
break;
case U8G_COM_MSG_WRITE_BYTE:
//u8g->pin_list[U8G_PI_SET_A0] = 1;
// if ( u8g_com_arduino_ssd_start_sequence(u8g) == 0 )
// return u8g_i2c_stop(), 0;
if ( u8g_i2c_send_byte_sw(arg_val) == 0 )
return u8g_i2c_stop_sw(), 0;
// u8g_i2c_stop();
break;
case U8G_COM_MSG_WRITE_SEQ:
//u8g->pin_list[U8G_PI_SET_A0] = 1;
if ( u8g_com_ssd_I2C_start_sequence_sw(u8g) == 0 )
return u8g_i2c_stop_sw(), 0;
{
register uint8_t *ptr = (uint8_t *)arg_ptr;
while( arg_val > 0 )
{
if ( u8g_i2c_send_byte_sw(*ptr++) == 0 )
return u8g_i2c_stop_sw(), 0;
arg_val--;
}
}
// u8g_i2c_stop();
break;
case U8G_COM_MSG_WRITE_SEQ_P:
//u8g->pin_list[U8G_PI_SET_A0] = 1;
if ( u8g_com_ssd_I2C_start_sequence_sw(u8g) == 0 )
return u8g_i2c_stop_sw(), 0;
{
register uint8_t *ptr = (uint8_t *)arg_ptr;
while( arg_val > 0 )
{
if ( u8g_i2c_send_byte_sw(u8g_pgm_read(ptr)) == 0 )
return 0;
ptr++;
arg_val--;
}
}
// u8g_i2c_stop();
break;
case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */
u8g->pin_list[U8G_PI_A0_STATE] = arg_val;
u8g->pin_list[U8G_PI_SET_A0] = 1; /* force a0 to set again */
u8g_i2c_start_sw(0); // send slave address and write bit
if (arg_val)
u8g_i2c_send_byte_sw(0x40); // write to graphics DRAM mode
else
u8g_i2c_send_byte_sw(0x80); //command mode
break;
}
return 1;
}
#endif // TARGET_LPC1768

View File

@ -0,0 +1,164 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016, 2017 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/>.
*
*/
/*
based on u8g_com_LPC1768_st7920_hw_spi.c
Universal 8bit Graphics Library
Copyright (c) 2011, olikraus@gmail.com
All rights reserved.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this list
of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice, this
list of conditions and the following disclaimer in the documentation and/or other
materials provided with the distribution.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifdef TARGET_LPC1768
// #include <inttypes.h>
// #include "src/core/macros.h"
// #include "Configuration.h"
#include <lib/u8g.h>
#define SPI_FULL_SPEED 0
#define SPI_HALF_SPEED 1
#define SPI_QUARTER_SPEED 2
#define SPI_EIGHTH_SPEED 3
#define SPI_SIXTEENTH_SPEED 4
#define SPI_SPEED_5 5
#define SPI_SPEED_6 6
void spiBegin();
void spiInit(uint8_t spiRate);
void spiSend(uint8_t b);
void spiSend(const uint8_t* buf, size_t n);
static uint8_t rs_last_state = 255;
static void u8g_com_LPC1768_st7920_write_byte_hw_spi(uint8_t rs, uint8_t val)
{
uint8_t i;
if ( rs != rs_last_state) { // time to send a command/data byte
rs_last_state = rs;
if ( rs == 0 )
/* command */
spiSend(0x0f8);
else
/* data */
spiSend(0x0fa);
for( i = 0; i < 4; i++ ) // give the controller some time to process the data
u8g_10MicroDelay(); // 2 is bad, 3 is OK, 4 is safe
}
spiSend(val & 0x0f0);
spiSend(val << 4);
}
uint8_t u8g_com_HAL_LPC1768_ST7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr)
{
switch(msg)
{
case U8G_COM_MSG_INIT:
u8g_SetPILevel(u8g, U8G_PI_CS, 0);
u8g_SetPIOutput(u8g, U8G_PI_CS);
u8g_Delay(5);
spiBegin();
spiInit(SPI_EIGHTH_SPEED); // ST7920 max speed is about 1.1 MHz
u8g->pin_list[U8G_PI_A0_STATE] = 0; /* inital RS state: command mode */
break;
case U8G_COM_MSG_STOP:
break;
case U8G_COM_MSG_RESET:
u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val);
break;
case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */
u8g->pin_list[U8G_PI_A0_STATE] = arg_val;
break;
case U8G_COM_MSG_CHIP_SELECT:
u8g_SetPILevel(u8g, U8G_PI_CS, arg_val); //note: the st7920 has an active high chip select
break;
case U8G_COM_MSG_WRITE_BYTE:
u8g_com_LPC1768_st7920_write_byte_hw_spi(u8g->pin_list[U8G_PI_A0_STATE], arg_val);
break;
case U8G_COM_MSG_WRITE_SEQ:
{
uint8_t *ptr = (uint8_t*) arg_ptr;
while( arg_val > 0 )
{
u8g_com_LPC1768_st7920_write_byte_hw_spi(u8g->pin_list[U8G_PI_A0_STATE], *ptr++);
arg_val--;
}
}
break;
case U8G_COM_MSG_WRITE_SEQ_P:
{
uint8_t *ptr = (uint8_t*) arg_ptr;
while( arg_val > 0 )
{
u8g_com_LPC1768_st7920_write_byte_hw_spi(u8g->pin_list[U8G_PI_A0_STATE], *ptr++);
arg_val--;
}
}
break;
}
return 1;
}
#endif // TARGET_LPC1768

View File

@ -0,0 +1,198 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016, 2017 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/>.
*
*/
/*
based on u8g_com_st7920_hw_spi.c
Universal 8bit Graphics Library
Copyright (c) 2011, olikraus@gmail.com
All rights reserved.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this list
of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice, this
list of conditions and the following disclaimer in the documentation and/or other
materials provided with the distribution.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifdef TARGET_LPC1768
#include <lib/u8g.h>
#include <lpc17xx_pinsel.h>
#define LPC_PORT_OFFSET (0x0020)
#define LPC_PIN(pin) (1UL << pin)
#define LPC_GPIO(port) ((volatile LPC_GPIO_TypeDef *)(LPC_GPIO0_BASE + LPC_PORT_OFFSET * port))
uint8_t SCK_pin_ST7920_HAL, SCK_port_ST7920_HAL, MOSI_pin_ST7920_HAL_HAL, MOSI_port_ST7920_HAL;
#define SPI_SPEED 4 //20: 200KHz 5:750KHz 4:1MHz 3:1.5MHz 2:3-4MHz
static void spiSend_sw(uint8_t val)
{
for (uint8_t i = 0; i < 8; i++) {
if (val & 0x80)
for (uint8_t j = 0; j < SPI_SPEED; j++) {
LPC_GPIO(MOSI_port_ST7920_HAL)->FIOSET = LPC_PIN(MOSI_pin_ST7920_HAL_HAL);
LPC_GPIO(MOSI_port_ST7920_HAL)->FIOSET = LPC_PIN(MOSI_pin_ST7920_HAL_HAL);
LPC_GPIO(MOSI_port_ST7920_HAL)->FIOSET = LPC_PIN(MOSI_pin_ST7920_HAL_HAL);
}
else
for (uint8_t j = 0; j < SPI_SPEED; j++) {
LPC_GPIO(MOSI_port_ST7920_HAL)->FIOCLR = LPC_PIN(MOSI_pin_ST7920_HAL_HAL);
LPC_GPIO(MOSI_port_ST7920_HAL)->FIOCLR = LPC_PIN(MOSI_pin_ST7920_HAL_HAL);
LPC_GPIO(MOSI_port_ST7920_HAL)->FIOCLR = LPC_PIN(MOSI_pin_ST7920_HAL_HAL);
}
for (uint8_t j = 0; j < SPI_SPEED; j++) {
LPC_GPIO(SCK_port_ST7920_HAL)->FIOSET = LPC_PIN(SCK_pin_ST7920_HAL);
LPC_GPIO(SCK_port_ST7920_HAL)->FIOSET = LPC_PIN(SCK_pin_ST7920_HAL);
LPC_GPIO(SCK_port_ST7920_HAL)->FIOSET = LPC_PIN(SCK_pin_ST7920_HAL);
LPC_GPIO(SCK_port_ST7920_HAL)->FIOSET = LPC_PIN(SCK_pin_ST7920_HAL);
LPC_GPIO(SCK_port_ST7920_HAL)->FIOSET = LPC_PIN(SCK_pin_ST7920_HAL);
}
for (uint8_t j = 0; j < SPI_SPEED; j++) {
LPC_GPIO(SCK_port_ST7920_HAL)->FIOCLR = LPC_PIN(SCK_pin_ST7920_HAL);
LPC_GPIO(SCK_port_ST7920_HAL)->FIOCLR = LPC_PIN(SCK_pin_ST7920_HAL);
}
val = val << 1;
}
}
static uint8_t rs_last_state = 255;
static void u8g_com_LPC1768_st7920_write_byte_sw_spi(uint8_t rs, uint8_t val)
{
uint8_t i;
if ( rs != rs_last_state) { // time to send a command/data byte
rs_last_state = rs;
if ( rs == 0 )
/* command */
spiSend_sw(0x0f8);
else
/* data */
spiSend_sw(0x0fa);
for( i = 0; i < 4; i++ ) // give the controller some time to process the data
u8g_10MicroDelay(); // 2 is bad, 3 is OK, 4 is safe
}
spiSend_sw(val & 0x0f0);
spiSend_sw(val << 4);
}
uint8_t u8g_com_HAL_LPC1768_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr)
{
switch(msg)
{
case U8G_COM_MSG_INIT:
#define LPC1768_PIN_PORT(pin) ((uint8_t)((pin >> 5) & 0b111))
#define LPC1768_PIN_PIN(pin) ((uint8_t)(pin & 0b11111))
SCK_pin_ST7920_HAL = LPC1768_PIN_PIN(u8g->pin_list[U8G_PI_SCK]);
SCK_port_ST7920_HAL = LPC1768_PIN_PORT(u8g->pin_list[U8G_PI_SCK]);
MOSI_pin_ST7920_HAL_HAL = LPC1768_PIN_PIN(u8g->pin_list[U8G_PI_MOSI]);
MOSI_port_ST7920_HAL = LPC1768_PIN_PORT(u8g->pin_list[U8G_PI_MOSI]);
u8g_SetPILevel(u8g, U8G_PI_CS, 0);
u8g_SetPIOutput(u8g, U8G_PI_CS);
u8g_SetPILevel(u8g, U8G_PI_SCK, 0);
u8g_SetPIOutput(u8g, U8G_PI_SCK);
u8g_SetPILevel(u8g, U8G_PI_MOSI, 0);
u8g_SetPIOutput(u8g, U8G_PI_MOSI);
u8g_Delay(5);
u8g->pin_list[U8G_PI_A0_STATE] = 0; /* inital RS state: command mode */
break;
case U8G_COM_MSG_STOP:
break;
case U8G_COM_MSG_RESET:
if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val);
break;
case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */
u8g->pin_list[U8G_PI_A0_STATE] = arg_val;
break;
case U8G_COM_MSG_CHIP_SELECT:
if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_CS]) u8g_SetPILevel(u8g, U8G_PI_CS, arg_val); //note: the st7920 has an active high chip select
break;
case U8G_COM_MSG_WRITE_BYTE:
u8g_com_LPC1768_st7920_write_byte_sw_spi(u8g->pin_list[U8G_PI_A0_STATE], arg_val);
break;
case U8G_COM_MSG_WRITE_SEQ:
{
uint8_t *ptr = (uint8_t*) arg_ptr;
while( arg_val > 0 )
{
u8g_com_LPC1768_st7920_write_byte_sw_spi(u8g->pin_list[U8G_PI_A0_STATE], *ptr++);
arg_val--;
}
}
break;
case U8G_COM_MSG_WRITE_SEQ_P:
{
uint8_t *ptr = (uint8_t*) arg_ptr;
while( arg_val > 0 )
{
u8g_com_LPC1768_st7920_write_byte_sw_spi(u8g->pin_list[U8G_PI_A0_STATE], *ptr++);
arg_val--;
}
}
break;
}
return 1;
}
#endif //TARGET_LPC1768

View File

@ -0,0 +1,184 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016, 2017 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/>.
*
*/
/*
adapted from u8g_com_std_sw_spi.c
Universal 8bit Graphics Library
Copyright (c) 2015, olikraus@gmail.com
All rights reserved.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this list
of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice, this
list of conditions and the following disclaimer in the documentation and/or other
materials provided with the distribution.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#if defined (TARGET_LPC1768)
#include <lib/u8g.h>
#include <U8glib.h>
#include <lpc17xx_pinsel.h>
#define LPC_PORT_OFFSET (0x0020)
#define LPC_PIN(pin) (1UL << pin)
#define LPC_GPIO(port) ((volatile LPC_GPIO_TypeDef *)(LPC_GPIO0_BASE + LPC_PORT_OFFSET * port))
void delayMicroseconds(uint32_t us);
void pinMode(int16_t pin, uint8_t mode);
void digitalWrite(int16_t pin, uint8_t pin_status);
uint8_t SCK_pin, SCK_port, MOSI_pin, MOSI_port;
#define SPI_SPEED 2 //20: 200KHz 5:750KHz 2:3-4MHz
static void u8g_sw_spi_HAL_LPC1768_shift_out(uint8_t dataPin, uint8_t clockPin, uint8_t val)
{
for (uint8_t i = 0; i < 8; i++) {
if (val & 0x80)
for (uint8_t j = 0; j < SPI_SPEED; j++) {
LPC_GPIO(MOSI_port)->FIOSET = LPC_PIN(MOSI_pin);
LPC_GPIO(MOSI_port)->FIOSET = LPC_PIN(MOSI_pin);
LPC_GPIO(MOSI_port)->FIOSET = LPC_PIN(MOSI_pin);
}
else
for (uint8_t j = 0; j < SPI_SPEED; j++) {
LPC_GPIO(MOSI_port)->FIOCLR = LPC_PIN(MOSI_pin);
LPC_GPIO(MOSI_port)->FIOCLR = LPC_PIN(MOSI_pin);
LPC_GPIO(MOSI_port)->FIOCLR = LPC_PIN(MOSI_pin);
}
for (uint8_t j = 0; j < SPI_SPEED; j++) {
LPC_GPIO(SCK_port)->FIOSET = LPC_PIN(SCK_pin);
LPC_GPIO(SCK_port)->FIOSET = LPC_PIN(SCK_pin);
LPC_GPIO(SCK_port)->FIOSET = LPC_PIN(SCK_pin);
LPC_GPIO(SCK_port)->FIOSET = LPC_PIN(SCK_pin);
LPC_GPIO(SCK_port)->FIOSET = LPC_PIN(SCK_pin);
}
for (uint8_t j = 0; j < SPI_SPEED; j++) {
LPC_GPIO(SCK_port)->FIOCLR = LPC_PIN(SCK_pin);
LPC_GPIO(SCK_port)->FIOCLR = LPC_PIN(SCK_pin);
}
val = val << 1;
}
}
uint8_t u8g_com_HAL_LPC1768_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr)
{
switch(msg)
{
case U8G_COM_MSG_INIT:
#define LPC1768_PIN_PORT(pin) ((uint8_t)((pin >> 5) & 0b111))
#define LPC1768_PIN_PIN(pin) ((uint8_t)(pin & 0b11111))
SCK_pin = LPC1768_PIN_PIN(u8g->pin_list[U8G_PI_SCK]);
SCK_port = LPC1768_PIN_PORT(u8g->pin_list[U8G_PI_SCK]);
MOSI_pin = LPC1768_PIN_PIN(u8g->pin_list[U8G_PI_MOSI]);
MOSI_port = LPC1768_PIN_PORT(u8g->pin_list[U8G_PI_MOSI]);
// As defined by Arduino INPUT(0x0), OUPUT(0x1), INPUT_PULLUP(0x2)
#define OUPUT 0x1
pinMode(u8g->pin_list[U8G_PI_SCK], OUPUT);
pinMode(u8g->pin_list[U8G_PI_MOSI], OUPUT);
pinMode(u8g->pin_list[U8G_PI_CS], OUPUT);
pinMode(u8g->pin_list[U8G_PI_A0], OUPUT);
if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) pinMode(u8g->pin_list[U8G_PI_RESET], OUPUT);
digitalWrite(u8g->pin_list[U8G_PI_SCK], 0);
digitalWrite(u8g->pin_list[U8G_PI_MOSI], 0);
break;
case U8G_COM_MSG_STOP:
break;
case U8G_COM_MSG_RESET:
digitalWrite(u8g->pin_list[U8G_PI_RESET], arg_val);
break;
case U8G_COM_MSG_CHIP_SELECT:
digitalWrite(u8g->pin_list[U8G_PI_CS], !arg_val);
break;
case U8G_COM_MSG_WRITE_BYTE:
u8g_sw_spi_HAL_LPC1768_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], arg_val);
break;
case U8G_COM_MSG_WRITE_SEQ:
{
uint8_t *ptr = (uint8_t *)arg_ptr;
while( arg_val > 0 )
{
u8g_sw_spi_HAL_LPC1768_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], *ptr++);
arg_val--;
}
}
break;
case U8G_COM_MSG_WRITE_SEQ_P:
{
uint8_t *ptr = (uint8_t *)arg_ptr;
while( arg_val > 0 )
{
u8g_sw_spi_HAL_LPC1768_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], u8g_pgm_read(ptr));
ptr++;
arg_val--;
}
}
break;
case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */
digitalWrite(u8g->pin_list[U8G_PI_A0], arg_val);
break;
}
return 1;
}
#endif // TARGET_LPC1768