committed by
Scott Lahteine
parent
428b67db31
commit
56cec9690a
@ -24,6 +24,10 @@
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "../shared/Delay.h"
|
||||
|
||||
// ------------------------
|
||||
// Serial ports
|
||||
// ------------------------
|
||||
|
||||
MSerialT usb_serial(TERN0(EMERGENCY_PARSER, true));
|
||||
|
||||
// U8glib required functions
|
||||
@ -37,42 +41,21 @@ extern "C" {
|
||||
//************************//
|
||||
|
||||
// return free heap space
|
||||
int freeMemory() {
|
||||
return 0;
|
||||
}
|
||||
int freeMemory() { return 0; }
|
||||
|
||||
// ------------------------
|
||||
// ADC
|
||||
// ------------------------
|
||||
|
||||
void HAL_adc_init() {
|
||||
uint8_t MarlinHAL::active_ch = 0;
|
||||
|
||||
}
|
||||
|
||||
void HAL_adc_enable_channel(const uint8_t ch) {
|
||||
|
||||
}
|
||||
|
||||
uint8_t active_ch = 0;
|
||||
void HAL_adc_start_conversion(const uint8_t ch) {
|
||||
active_ch = ch;
|
||||
}
|
||||
|
||||
bool HAL_adc_finished() {
|
||||
return true;
|
||||
}
|
||||
|
||||
uint16_t HAL_adc_get_result() {
|
||||
pin_t pin = analogInputToDigitalPin(active_ch);
|
||||
uint16_t MarlinHAL::adc_value() {
|
||||
const pin_t pin = analogInputToDigitalPin(active_ch);
|
||||
if (!VALID_PIN(pin)) return 0;
|
||||
uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF);
|
||||
const uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF);
|
||||
return data; // return 10bit value as Marlin expects
|
||||
}
|
||||
|
||||
void HAL_pwm_init() {
|
||||
|
||||
}
|
||||
|
||||
void HAL_reboot() { /* Reset the application state and GPIO */ }
|
||||
void MarlinHAL::reboot() { /* Reset the application state and GPIO */ }
|
||||
|
||||
#endif // __PLAT_LINUX__
|
||||
|
@ -21,34 +21,13 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#define CPU_32_BIT
|
||||
|
||||
#define F_CPU 100000000UL
|
||||
#define SystemCoreClock F_CPU
|
||||
#include <iostream>
|
||||
#include <stdint.h>
|
||||
#include <stdarg.h>
|
||||
|
||||
#undef min
|
||||
#undef max
|
||||
|
||||
#include <algorithm>
|
||||
|
||||
void _printf (const char *format, ...);
|
||||
void _putc(uint8_t c);
|
||||
uint8_t _getc();
|
||||
|
||||
//extern "C" volatile uint32_t _millis;
|
||||
|
||||
//arduino: Print.h
|
||||
#define DEC 10
|
||||
#define HEX 16
|
||||
#define OCT 8
|
||||
#define BIN 2
|
||||
//arduino: binary.h (weird defines)
|
||||
#define B01 1
|
||||
#define B10 2
|
||||
|
||||
#include "hardware/Clock.h"
|
||||
|
||||
#include "../shared/Marduino.h"
|
||||
@ -58,27 +37,56 @@ uint8_t _getc();
|
||||
#include "watchdog.h"
|
||||
#include "serial.h"
|
||||
|
||||
#define SHARED_SERVOS HAS_SERVOS
|
||||
// ------------------------
|
||||
// Defines
|
||||
// ------------------------
|
||||
|
||||
extern MSerialT usb_serial;
|
||||
#define MYSERIAL1 usb_serial
|
||||
#define CPU_32_BIT
|
||||
#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp
|
||||
|
||||
#define F_CPU 100000000UL
|
||||
#define SystemCoreClock F_CPU
|
||||
|
||||
#define DELAY_CYCLES(x) Clock::delayCycles(x)
|
||||
|
||||
#define CPU_ST7920_DELAY_1 600
|
||||
#define CPU_ST7920_DELAY_2 750
|
||||
#define CPU_ST7920_DELAY_3 750
|
||||
|
||||
void _printf(const char *format, ...);
|
||||
void _putc(uint8_t c);
|
||||
uint8_t _getc();
|
||||
|
||||
//arduino: Print.h
|
||||
#define DEC 10
|
||||
#define HEX 16
|
||||
#define OCT 8
|
||||
#define BIN 2
|
||||
//arduino: binary.h (weird defines)
|
||||
#define B01 1
|
||||
#define B10 2
|
||||
|
||||
// ------------------------
|
||||
// Serial ports
|
||||
// ------------------------
|
||||
|
||||
extern MSerialT usb_serial;
|
||||
#define MYSERIAL1 usb_serial
|
||||
|
||||
//
|
||||
// Interrupts
|
||||
//
|
||||
#define CRITICAL_SECTION_START()
|
||||
#define CRITICAL_SECTION_END()
|
||||
#define ISRS_ENABLED()
|
||||
#define ENABLE_ISRS()
|
||||
#define DISABLE_ISRS()
|
||||
|
||||
inline void HAL_init() {}
|
||||
// ADC
|
||||
#define HAL_ADC_VREF 5.0
|
||||
#define HAL_ADC_RESOLUTION 10
|
||||
|
||||
// ------------------------
|
||||
// Class Utilities
|
||||
// ------------------------
|
||||
|
||||
// Utility functions
|
||||
#pragma GCC diagnostic push
|
||||
#if GCC_VERSION <= 50000
|
||||
#pragma GCC diagnostic ignored "-Wunused-function"
|
||||
@ -88,29 +96,66 @@ int freeMemory();
|
||||
|
||||
#pragma GCC diagnostic pop
|
||||
|
||||
// ADC
|
||||
#define HAL_ADC_VREF 5.0
|
||||
#define HAL_ADC_RESOLUTION 10
|
||||
#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch)
|
||||
#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch)
|
||||
#define HAL_READ_ADC() HAL_adc_get_result()
|
||||
#define HAL_ADC_READY() true
|
||||
// ------------------------
|
||||
// MarlinHAL Class
|
||||
// ------------------------
|
||||
|
||||
void HAL_adc_init();
|
||||
void HAL_adc_enable_channel(const uint8_t ch);
|
||||
void HAL_adc_start_conversion(const uint8_t ch);
|
||||
uint16_t HAL_adc_get_result();
|
||||
class MarlinHAL {
|
||||
public:
|
||||
|
||||
// PWM
|
||||
inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
|
||||
// Earliest possible init, before setup()
|
||||
MarlinHAL() {}
|
||||
|
||||
// Reset source
|
||||
inline void HAL_clear_reset_source(void) {}
|
||||
inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; }
|
||||
static void init() {} // Called early in setup()
|
||||
static void init_board() {} // Called less early in setup()
|
||||
static void reboot(); // Reset the application state and GPIO
|
||||
|
||||
void HAL_reboot(); // Reset the application state and GPIO
|
||||
// Interrupts
|
||||
static bool isr_state() { return true; }
|
||||
static void isr_on() {}
|
||||
static void isr_off() {}
|
||||
|
||||
/* ---------------- Delay in cycles */
|
||||
FORCE_INLINE static void DELAY_CYCLES(uint64_t x) {
|
||||
Clock::delayCycles(x);
|
||||
}
|
||||
static void delay_ms(const int ms) { _delay_ms(ms); }
|
||||
|
||||
// Tasks, called from idle()
|
||||
static void idletask() {}
|
||||
|
||||
// Reset
|
||||
static constexpr uint8_t reset_reason = RST_POWER_ON;
|
||||
static uint8_t get_reset_source() { return reset_reason; }
|
||||
static void clear_reset_source() {}
|
||||
|
||||
// Free SRAM
|
||||
static int freeMemory() { return ::freeMemory(); }
|
||||
|
||||
//
|
||||
// ADC Methods
|
||||
//
|
||||
|
||||
static uint8_t active_ch;
|
||||
|
||||
// Called by Temperature::init once at startup
|
||||
static void adc_init() {}
|
||||
|
||||
// Called by Temperature::init for each sensor at startup
|
||||
static void adc_enable(const uint8_t) {}
|
||||
|
||||
// Begin ADC sampling on the given channel
|
||||
static void adc_start(const uint8_t ch) { active_ch = ch; }
|
||||
|
||||
// Is the ADC ready for reading?
|
||||
static bool adc_ready() { return true; }
|
||||
|
||||
// The current value of the ADC register
|
||||
static uint16_t adc_value();
|
||||
|
||||
/**
|
||||
* Set the PWM duty cycle for the pin to the given value.
|
||||
* No option to change the resolution or invert the duty cycle.
|
||||
*/
|
||||
static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
|
||||
analogWrite(pin, v);
|
||||
}
|
||||
|
||||
static void set_pwm_frequency(const pin_t, int) {}
|
||||
};
|
||||
|
@ -31,9 +31,7 @@ void cli() { } // Disable
|
||||
void sei() { } // Enable
|
||||
|
||||
// Time functions
|
||||
void _delay_ms(const int delay_ms) {
|
||||
delay(delay_ms);
|
||||
}
|
||||
void _delay_ms(const int ms) { delay(ms); }
|
||||
|
||||
uint32_t millis() {
|
||||
return (uint32_t)Clock::millis();
|
||||
|
@ -59,10 +59,9 @@ typedef uint8_t byte;
|
||||
#endif
|
||||
|
||||
#define sq(v) ((v) * (v))
|
||||
#define square(v) sq(v)
|
||||
#define constrain(value, arg_min, arg_max) ((value) < (arg_min) ? (arg_min) :((value) > (arg_max) ? (arg_max) : (value)))
|
||||
|
||||
//Interrupts
|
||||
// Interrupts
|
||||
void cli(); // Disable
|
||||
void sei(); // Enable
|
||||
void attachInterrupt(uint32_t pin, void (*callback)(), uint32_t mode);
|
||||
@ -74,8 +73,8 @@ extern "C" {
|
||||
}
|
||||
|
||||
// Time functions
|
||||
extern "C" void delay(const int milis);
|
||||
void _delay_ms(const int delay);
|
||||
extern "C" void delay(const int ms);
|
||||
void _delay_ms(const int ms);
|
||||
void delayMicroseconds(unsigned long);
|
||||
uint32_t millis();
|
||||
|
||||
|
@ -92,5 +92,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num);
|
||||
void HAL_timer_disable_interrupt(const uint8_t timer_num);
|
||||
bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
|
||||
|
||||
#define HAL_timer_isr_prologue(T)
|
||||
#define HAL_timer_isr_epilogue(T)
|
||||
#define HAL_timer_isr_prologue(T) NOOP
|
||||
#define HAL_timer_isr_epilogue(T) NOOP
|
||||
|
Reference in New Issue
Block a user