CFLAGS += $(COMMON)
CFLAGS += -gdwarf-2 -std=gnu99 -Wall -DF_CPU=$(CLOCK)UL -Os -funsigned-char
CFLAGS += -funsigned-bitfields -fpack-struct -fshort-enums
-CFLAGS += -MD -MP -MT $(*F).o -MF build/dep/$(@F).d
+CFLAGS += -MD -MP -MT $@ -MF build/dep/$(@F).d
# Linker flags
LDFLAGS += $(COMMON) -Wl,-u,vfprintf -lprintf_flt -lm -Wl,-Map=$(PROJECT).map
#include "hardware.h"
#include "util.h"
#include "xio.h" // for serial queue flush
-/*
-#ifdef __cplusplus
-extern "C"{
-#endif
-*/
+
/***********************************************************************************
**** STRUCTURE ALLOCATIONS ********************************************************
***********************************************************************************/
stat_t cm_deferred_write_callback()
{
if ((cm.cycle_state == CYCLE_OFF) && (cm.deferred_write_flag == true)) {
-#ifdef __AVR
- if (xio_isbusy()) return (STAT_OK); // don't write back if serial RX is not empty
-#endif
- cm.deferred_write_flag = false;
+ if (xio_isbusy()) return (STAT_OK); // don't write back if serial RX is not empty
+ cm.deferred_write_flag = false;
nvObj_t nv;
for (uint8_t i=1; i<=COORDS; i++) {
for (uint8_t j=0; j<AXES; j++) {
{
cm.gm.mist_coolant = (uint8_t)value[0];
-#ifdef __AVR
- if (cm.gm.mist_coolant == true)
+ if (cm.gm.mist_coolant == true)
gpio_set_bit_on(MIST_COOLANT_BIT); // if
gpio_set_bit_off(MIST_COOLANT_BIT); // else
-#endif // __AVR
-
-#ifdef __ARM
- if (cm.gm.mist_coolant == true)
- coolant_enable_pin.set(); // if
- coolant_enable_pin.clear(); // else
-#endif // __ARM
}
stat_t cm_flood_coolant_control(uint8_t flood_coolant)
{
cm.gm.flood_coolant = (uint8_t)value[0];
-#ifdef __AVR
- if (cm.gm.flood_coolant == true) {
+ if (cm.gm.flood_coolant == true) {
gpio_set_bit_on(FLOOD_COOLANT_BIT);
} else {
gpio_set_bit_off(FLOOD_COOLANT_BIT);
float vect[] = { 0,0,0,0,0,0 }; // turn off mist coolant
_exec_mist_coolant_control(vect, vect); // M9 special function
}
-#endif // __AVR
-
-#ifdef __ARM
- if (cm.gm.flood_coolant == true) {
- coolant_enable_pin.set();
- } else {
- coolant_enable_pin.clear();
- float vect[] = { 0,0,0,0,0,0 }; // turn off mist coolant
- _exec_mist_coolant_control(vect, vect); // M9 special function
- }
-#endif // __ARM
}
/*
if (cm_get_runtime_busy() == true)
return (STAT_COMMAND_NOT_ACCEPTED);
-#ifdef __AVR
- xio_reset_usb_rx_buffers(); // flush serial queues
-#endif
- mp_flush_planner(); // flush planner queue
+ xio_reset_usb_rx_buffers(); // flush serial queues
+ mp_flush_planner(); // flush planner queue
qr_request_queue_report(0); // request a queue report, since we've changed the number of buffers available
rx_request_rx_report();
void cm_print_ofs(nvObj_t *nv) { _print_pos(nv, fmt_ofs, MILLIMETERS);}
#endif // __TEXT_MODE
-/*
-#ifdef __cplusplus
-}
-#endif
-*/
#ifndef CANONICAL_MACHINE_H_ONCE
#define CANONICAL_MACHINE_H_ONCE
-/*
-#ifdef __cplusplus
-extern "C"{
-#endif
-*/
+
#include "config.h"
/* Defines, Macros, and Assorted Parameters */
#define cm_print_cpos tx_print_stub
#endif // __TEXT_MODE
-/*
-#ifdef __cplusplus
-}
-#endif
-*/
#endif // End of include guard: CANONICAL_MACHINE_H_ONCE
#include "util.h"
#include "xio.h"
-#ifdef __cplusplus
-extern "C"{
-#endif
-
static void _set_defa(nvObj_t *nv);
/***********************************************************************************
nvObj_t *nv = nv_reset_nv_list();
config_init_assertions();
-#ifdef __ARM
-// ++++ The following code is offered until persistence is implemented.
-// ++++ Then you can use the AVR code (or something like it)
- cfg.comm_mode = JSON_MODE; // initial value until EEPROM is read
- _set_defa(nv);
-#endif
-#ifdef __AVR
- cm_set_units_mode(MILLIMETERS); // must do inits in millimeter mode
+ cm_set_units_mode(MILLIMETERS); // must do inits in millimeter mode
nv->index = 0; // this will read the first record in NVM
read_persistent_value(nv);
}
sr_init_status_report();
}
-#endif
}
/*
*
* On the AVR this will save a little static RAM. The "msg" string will occupy flash
* as an initializer and be instantiated in stack RAM when the function executes.
- * On the ARM (however) this will put the string into flash and skip RAM allocation.
*/
void nv_get_nvObj(nvObj_t *nv)
nv->token,
(char *)nv->stringp);
}
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
#include "config_app.h" // is present at the end of this file
*/
-#ifdef __cplusplus
-extern "C"{
-#endif
-
/**** Config System Overview and Usage ***
*
* --- Config objects and the config list ---
*********************************************************************************************/
#include "config_app.h"
-#ifdef __cplusplus
-}
-#endif
-
#endif // End of include guard: CONFIG_H_ONCE
#include "network.h"
#include "xio.h"
-#ifdef __cplusplus
-extern "C"{
-#endif
-
/*** structures ***/
cfgParameters_t cfg; // application specific configuration parameters
{ "1","1mi",_fip, 0, st_print_mi, get_ui8, st_set_mi, (float *)&st_cfg.mot[MOTOR_1].microsteps, M1_MICROSTEPS },
{ "1","1po",_fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_1].polarity, M1_POLARITY },
{ "1","1pm",_fip, 0, st_print_pm, get_ui8, st_set_pm, (float *)&st_cfg.mot[MOTOR_1].power_mode, M1_POWER_MODE },
-#ifdef __ARM
- { "1","1pl",_fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_1].power_level,M1_POWER_LEVEL },
-#endif
#if (MOTORS >= 2)
{ "2","2ma",_fip, 0, st_print_ma, get_ui8, set_ui8, (float *)&st_cfg.mot[MOTOR_2].motor_map, M2_MOTOR_MAP },
{ "2","2sa",_fip, 3, st_print_sa, get_flt, st_set_sa, (float *)&st_cfg.mot[MOTOR_2].step_angle, M2_STEP_ANGLE },
{ "2","2mi",_fip, 0, st_print_mi, get_ui8, st_set_mi, (float *)&st_cfg.mot[MOTOR_2].microsteps, M2_MICROSTEPS },
{ "2","2po",_fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_2].polarity, M2_POLARITY },
{ "2","2pm",_fip, 0, st_print_pm, get_ui8, st_set_pm, (float *)&st_cfg.mot[MOTOR_2].power_mode, M2_POWER_MODE },
-#ifdef __ARM
- { "2","2pl",_fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_2].power_level,M2_POWER_LEVEL},
-#endif
#endif
#if (MOTORS >= 3)
{ "3","3ma",_fip, 0, st_print_ma, get_ui8, set_ui8, (float *)&st_cfg.mot[MOTOR_3].motor_map, M3_MOTOR_MAP },
{ "3","3mi",_fip, 0, st_print_mi, get_ui8, st_set_mi, (float *)&st_cfg.mot[MOTOR_3].microsteps, M3_MICROSTEPS },
{ "3","3po",_fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_3].polarity, M3_POLARITY },
{ "3","3pm",_fip, 0, st_print_pm, get_ui8, st_set_pm, (float *)&st_cfg.mot[MOTOR_3].power_mode, M3_POWER_MODE },
-#ifdef __ARM
- { "3","3pl",_fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_3].power_level,M3_POWER_LEVEL },
-#endif
#endif
#if (MOTORS >= 4)
{ "4","4ma",_fip, 0, st_print_ma, get_ui8, set_ui8, (float *)&st_cfg.mot[MOTOR_4].motor_map, M4_MOTOR_MAP },
{ "4","4mi",_fip, 0, st_print_mi, get_ui8, st_set_mi, (float *)&st_cfg.mot[MOTOR_4].microsteps, M4_MICROSTEPS },
{ "4","4po",_fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_4].polarity, M4_POLARITY },
{ "4","4pm",_fip, 0, st_print_pm, get_ui8, st_set_pm, (float *)&st_cfg.mot[MOTOR_4].power_mode, M4_POWER_MODE },
-#ifdef __ARM
- { "4","4pl",_fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_4].power_level,M4_POWER_LEVEL },
-#endif
#endif
#if (MOTORS >= 5)
{ "5","5ma",_fip, 0, st_print_ma, get_ui8, set_ui8, (float *)&st_cfg.mot[MOTOR_5].motor_map, M5_MOTOR_MAP },
{ "5","5mi",_fip, 0, st_print_mi, get_ui8, st_set_mi, (float *)&st_cfg.mot[MOTOR_5].microsteps, M5_MICROSTEPS },
{ "5","5po",_fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_5].polarity, M5_POLARITY },
{ "5","5pm",_fip, 0, st_print_pm, get_ui8, st_set_pm, (float *)&st_cfg.mot[MOTOR_5].power_mode, M5_POWER_MODE },
-#ifdef __ARM
- { "5","5pl",_fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_5].power_level,M5_POWER_LEVEL },
-#endif
#endif
#if (MOTORS >= 6)
{ "6","6ma",_fip, 0, st_print_ma, get_ui8, set_ui8, (float *)&st_cfg.mot[MOTOR_6].motor_map, M6_MOTOR_MAP },
{ "6","6mi",_fip, 0, st_print_mi, get_ui8, st_set_mi, (float *)&st_cfg.mot[MOTOR_6].microsteps, M6_MICROSTEPS },
{ "6","6po",_fip, 0, st_print_po, get_ui8, set_01, (float *)&st_cfg.mot[MOTOR_6].polarity, M6_POLARITY },
{ "6","6pm",_fip, 0, st_print_pm, get_ui8, st_set_pm, (float *)&st_cfg.mot[MOTOR_6].power_mode, M6_POWER_MODE },
-#ifdef __ARM
- { "6","6pl",_fip, 3, st_print_pl, get_flt, st_set_pl, (float *)&st_cfg.mot[MOTOR_6].power_level,M6_POWER_LEVEL },
-#endif
#endif
// Axis parameters
{ "x","xam",_fip, 0, cm_print_am, cm_get_am, cm_set_am, (float *)&cm.a[AXIS_X].axis_mode, X_AXIS_MODE },
{ "b","bjm",_fip, 0, cm_print_jm, get_flt, cm_set_xjm,(float *)&cm.a[AXIS_B].jerk_max, B_JERK_MAX },
{ "b","bjd",_fip, 0, cm_print_jd, get_flt, set_flt, (float *)&cm.a[AXIS_B].junction_dev, B_JUNCTION_DEVIATION },
{ "b","bra",_fipc, 3, cm_print_ra, get_flt, set_flt, (float *)&cm.a[AXIS_B].radius, B_RADIUS },
-#ifdef __ARM // B axis extended parameters
- { "b","asn",_fip, 0, cm_print_sn, get_ui8, sw_set_sw, (float *)&sw.s[AXIS_B][SW_MIN].mode, B_SWITCH_MODE_MIN },
- { "b","asx",_fip, 0, cm_print_sx, get_ui8, sw_set_sw, (float *)&sw.s[AXIS_B][SW_MAX].mode, B_SWITCH_MODE_MAX },
- { "b","bsv",_fip, 0, cm_print_sv, get_flt, set_flt, (float *)&cm.a[AXIS_B].search_velocity,B_SEARCH_VELOCITY },
- { "b","blv",_fip, 0, cm_print_lv, get_flt, set_flt, (float *)&cm.a[AXIS_B].latch_velocity, B_LATCH_VELOCITY },
- { "b","blb",_fip, 3, cm_print_lb, get_flt, set_flt, (float *)&cm.a[AXIS_B].latch_backoff, B_LATCH_BACKOFF },
- { "b","bzb",_fip, 3, cm_print_zb, get_flt, set_flt, (float *)&cm.a[AXIS_B].zero_backoff, B_ZERO_BACKOFF },
- { "b","bjh",_fip, 0, cm_print_jh, get_flt, cm_set_xjh,(float *)&cm.a[AXIS_B].jerk_homing, B_JERK_HOMING },
-#endif
{ "c","cam",_fip, 0, cm_print_am, cm_get_am, cm_set_am, (float *)&cm.a[AXIS_C].axis_mode, C_AXIS_MODE },
{ "c","cvm",_fip, 0, cm_print_vm, get_flt, set_flt, (float *)&cm.a[AXIS_C].velocity_max, C_VELOCITY_MAX },
{ "c","cjm",_fip, 0, cm_print_jm, get_flt, cm_set_xjm,(float *)&cm.a[AXIS_C].jerk_max, C_JERK_MAX },
{ "c","cjd",_fip, 0, cm_print_jd, get_flt, set_flt, (float *)&cm.a[AXIS_C].junction_dev, C_JUNCTION_DEVIATION },
{ "c","cra",_fipc, 3, cm_print_ra, get_flt, set_flt, (float *)&cm.a[AXIS_C].radius, C_RADIUS },
-#ifdef __ARM // C axis extended parameters
- { "c","csn",_fip, 0, cm_print_sn, get_ui8, sw_set_sw, (float *)&sw.s[AXIS_C][SW_MIN].mode, C_SWITCH_MODE_MIN },
- { "c","csx",_fip, 0, cm_print_sx, get_ui8, sw_set_sw, (float *)&sw.s[AXIS_C][SW_MAX].mode, C_SWITCH_MODE_MAX },
- { "c","csv",_fip, 0, cm_print_sv, get_flt, set_flt, (float *)&cm.a[AXIS_C].search_velocity,C_SEARCH_VELOCITY },
- { "c","clv",_fip, 0, cm_print_lv, get_flt, set_flt, (float *)&cm.a[AXIS_C].latch_velocity, C_LATCH_VELOCITY },
- { "c","clb",_fip, 3, cm_print_lb, get_flt, set_flt, (float *)&cm.a[AXIS_C].latch_backoff, C_LATCH_BACKOFF },
- { "c","czb",_fip, 3, cm_print_zb, get_flt, set_flt, (float *)&cm.a[AXIS_C].zero_backoff, C_ZERO_BACKOFF },
- { "c","cjh",_fip, 0, cm_print_jh, get_flt, cm_set_xjh,(float *)&cm.a[AXIS_C].jerk_homing, C_JERK_HOMING },
-#endif
// PWM settings
{ "p1","p1frq",_fip, 0, pwm_print_p1frq, get_flt, set_flt,(float *)&pwm.c[PWM_1].frequency, P1_PWM_FREQUENCY },
static stat_t get_rx(nvObj_t *nv)
{
-#ifdef __AVR
- nv->value = (float)xio_get_usb_rx_free();
- nv->valuetype = TYPE_INTEGER;
- return (STAT_OK);
-#endif
-#ifdef __ARM
- nv->value = (float)254; // ARM always says the serial buffer is available (max)
+ nv->value = (float)xio_get_usb_rx_free();
nv->valuetype = TYPE_INTEGER;
return (STAT_OK);
-#endif
}
/* run_sx() - send XOFF, XON --- test only
void cfg_print_rx(nvObj_t *nv) { text_print_ui8(nv, fmt_rx);}
#endif // __TEXT_MODE
-
-#ifdef __cplusplus
-}
-#endif
#ifndef CONFIG_APP_H_ONCE
#define CONFIG_APP_H_ONCE
-#ifdef __cplusplus
-extern "C"{
-#endif
-
/***********************************************************************************
**** APPLICATION_SPECIFIC DEFINITIONS AND SETTINGS ********************************
***********************************************************************************/
#endif // __TEXT_MODE
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-
#endif //End of include guard: CONFIG_APP_H_ONCE
#include "util.h"
#include "xio.h"
-#ifdef __ARM
-#include "Reset.h"
-#endif
-
/***********************************************************************************
**** STRUCTURE ALLOCATIONS *********************************************************
***********************************************************************************/
cs.fw_version = TINYG_FIRMWARE_VERSION;
cs.hw_platform = TINYG_HARDWARE_PLATFORM; // NB: HW version is set from EEPROM
-#ifdef __AVR
- cs.state = CONTROLLER_STARTUP; // ready to run startup lines
+ cs.state = CONTROLLER_STARTUP; // ready to run startup lines
xio_set_stdin(std_in);
xio_set_stdout(std_out);
xio_set_stderr(std_err);
cs.default_src = std_in;
tg_set_primary_source(cs.default_src);
-#endif
-
-#ifdef __ARM
- cs.state = CONTROLLER_NOT_CONNECTED; // find USB next
- IndicatorLed.setFrequency(100000);
-#endif
}
/*
DISPATCH(_sync_to_planner()); // ensure there is at least one free buffer in planning queue
DISPATCH(_sync_to_tx_buffer()); // sync with TX buffer (pseudo-blocking)
-#ifdef __AVR
- DISPATCH(set_baud_callback()); // perform baud rate update (must be after TX sync)
-#endif
- DISPATCH(_command_dispatch()); // read and execute next command
+ DISPATCH(set_baud_callback()); // perform baud rate update (must be after TX sync)
+ DISPATCH(_command_dispatch()); // read and execute next command
DISPATCH(_normal_idler()); // blink LEDs slowly to show everything is OK
}
static stat_t _command_dispatch()
{
-#ifdef __AVR
- stat_t status;
+ stat_t status;
// read input line or return if not a completed line
// xio_gets() is a non-blocking workalike of fgets()
}
return (status); // Note: STAT_EAGAIN, errors, etc. will drop through
}
-#endif // __AVR
-#ifdef __ARM
- // detect USB connection and transition to disconnected state if it disconnected
- if (SerialUSB.isConnected() == false) cs.state = CONTROLLER_NOT_CONNECTED;
-
- // read input line and return if not a completed line
- if (cs.state == CONTROLLER_READY) {
- if (read_line(cs.in_buf, &cs.read_index, sizeof(cs.in_buf)) != STAT_OK) {
- cs.bufp = cs.in_buf;
- return (STAT_OK); // This is an exception: returns OK for anything NOT OK, so the idler always runs
- }
- } else if (cs.state == CONTROLLER_NOT_CONNECTED) {
- if (SerialUSB.isConnected() == false) return (STAT_OK);
- cm_request_queue_flush();
- rpt_print_system_ready_message();
- cs.state = CONTROLLER_STARTUP;
-
- } else if (cs.state == CONTROLLER_STARTUP) { // run startup code
- cs.state = CONTROLLER_READY;
-
- } else {
- return (STAT_OK);
- }
- cs.read_index = 0;
-#endif // __ARM
// set up the buffers
cs.linelen = strlen(cs.in_buf)+1; // linelen only tracks primary input
// dispatch the new text line
switch (toupper(*cs.bufp)) { // first char
- case '!': { cm_request_feedhold(); break; } // include for AVR diagnostics and ARM serial
+ case '!': { cm_request_feedhold(); break; } // include for diagnostics
case '%': { cm_request_queue_flush(); break; }
case '~': { cm_request_cycle_start(); break; }
static stat_t _normal_idler()
{
-#ifdef __ARM
- /*
- * S-curve heartbeat code. Uses forward-differencing math from the stepper code.
- * See plan_line.cpp for explanations.
- * Here, the "velocity" goes from 0.0 to 1.0, then back.
- * t0 = 0, t1 = 0, t2 = 0.5, and we'll complete the S in 100 segments.
- */
-
- // These are statics, and the assignments will only evaluate once.
- static float indicator_led_value = 0.0;
- static float indicator_led_forward_diff_1 = 50.0 * square(1.0/100.0);
- static float indicator_led_forward_diff_2 = indicator_led_forward_diff_1 * 2.0;
-
-
- if (SysTickTimer.getValue() > cs.led_timer) {
- cs.led_timer = SysTickTimer.getValue() + LED_NORMAL_TIMER / 100;
-
- indicator_led_value += indicator_led_forward_diff_1;
- if (indicator_led_value > 100.0)
- indicator_led_value = 100.0;
-
- if ((indicator_led_forward_diff_2 > 0.0 && indicator_led_value >= 50.0) || (indicator_led_forward_diff_2 < 0.0 && indicator_led_value <= 50.0)) {
- indicator_led_forward_diff_2 = -indicator_led_forward_diff_2;
- }
- else if (indicator_led_value <= 0.0) {
- indicator_led_value = 0.0;
-
- // Reset to account for rounding errors
- indicator_led_forward_diff_1 = 50.0 * square(1.0/100.0);
- } else {
- indicator_led_forward_diff_1 += indicator_led_forward_diff_2;
- }
-
- IndicatorLed = indicator_led_value/100.0;
- }
-#endif
-#ifdef __AVR
-/*
- if (SysTickTimer_getValue() > cs.led_timer) {
- cs.led_timer = SysTickTimer_getValue() + LED_NORMAL_TIMER;
-// IndicatorLed_toggle();
- }
-*/
-#endif
- return (STAT_OK);
+ return (STAT_OK);
}
/*
#ifndef CONTROLLER_H_ONCE
#define CONTROLLER_H_ONCE
-#ifdef __cplusplus
-extern "C"{
-#endif
-
#define INPUT_BUFFER_LEN 255 // text buffer size (255 max)
#define SAVED_BUFFER_LEN 100 // saved buffer size (for reporting only)
#define OUTPUT_BUFFER_LEN 512 // text buffer size
void tg_set_primary_source(uint8_t dev);
void tg_set_secondary_source(uint8_t dev);
-#ifdef __cplusplus
-}
-#endif
-
#endif // End of include guard: CONTROLLER_H_ONCE
#include "switch.h"
#include "report.h"
-#ifdef __cplusplus
-extern "C"{
-#endif
-
/**** Homing singleton structure ****/
struct hmHomingSingleton { // persistent homing runtime variables
return (STAT_EAGAIN);
}
-/* UNUSED
-
-static void _trigger_feedhold(switch_t *s)
-{
- cm_request_feedhold();
-}
-
-static void _bind_switch_settings(switch_t *s)
-{
- hm.switch_saved_on_trailing = s->on_trailing;
- s->on_trailing = _trigger_feedhold; // bind feedhold to trailing edge
-}
-
-static void _restore_switch_settings(switch_t *s)
-{
- s->on_trailing = hm.switch_saved_on_trailing;
-}
-*/
static stat_t _homing_axis_start(int8_t axis)
{
// get the first or next axis
static int8_t _get_next_axis(int8_t axis)
{
#if (HOMING_AXES <= 4)
-// uint8_t axis;
-// for(axis = AXIS_X; axis < HOMING_AXES; axis++)
-// if(fp_TRUE(cm.gf.target[axis])) break;
-// if(axis >= HOMING_AXES) return -2;
-// switch(axis) {
-// case -1: if (fp_TRUE(cm.gf.target[AXIS_Z])) return (AXIS_Z);
-// case AXIS_Z: if (fp_TRUE(cm.gf.target[AXIS_X])) return (AXIS_X);
-// case AXIS_X: if (fp_TRUE(cm.gf.target[AXIS_Y])) return (AXIS_Y);
-// case AXIS_Y: if (fp_TRUE(cm.gf.target[AXIS_A])) return (AXIS_A);
-//#if (HOMING_AXES > 4)
-// case AXIS_A: if (fp_TRUE(cm.gf.target[AXIS_B])) return (AXIS_B);
-// case AXIS_B: if (fp_True(cm.gf.target[AXIS_C])) return (AXIS_C);
-//#endif
-// default: return -1;
-// }
- if (axis == -1) { // inelegant brute force solution
+ if (axis == -1) { // inelegant brute force solution
if (fp_TRUE(cm.gf.target[AXIS_Z])) return (AXIS_Z);
if (fp_TRUE(cm.gf.target[AXIS_X])) return (AXIS_X);
if (fp_TRUE(cm.gf.target[AXIS_Y])) return (AXIS_Y);
#endif
}
-
-/*
- * _get_next_axes() - return next axis in sequence based on axis in arg
- *
- * Accepts "axis" arg as the current axis; or -1 to retrieve the first axis
- * Returns next axis based on "axis" argument
- * Returns -1 when all axes have been processed
- * Returns -2 if no axes are specified (Gcode calling error)
- *
- * hm.axis2 is set to the secondary axis if axis is a dual axis
- * hm.axis2 is set to -1 otherwise
- *
- * Isolating this function facilitates implementing more complex and
- * user-specified axis homing orders
- *
- * Note: the logic to test for disabled or inhibited axes will allow the
- * following condition to occur: A single axis is specified but it is
- * disabled or inhibited - homing will say that it was successfully homed.
- */
-
-// _run_homing_dual_axis() - kernal routine for running homing on a dual axis
-//static stat_t _run_homing_dual_axis(int8_t axis) { return (STAT_OK);}
-
-/*
-int8_t _get_next_axes(int8_t axis)
-{
- int8_t next_axis;
- hm.axis2 = -1;
-
- // Scan target vector for case where no valid axes are specified
- for (next_axis = 0; next_axis < AXES; next_axis++) {
- if ((fp_TRUE(cm.gf.target[next_axis])) &&
- (cm.a[next_axis].axis_mode != AXIS_INHIBITED) &&
- (cm.a[next_axis].axis_mode != AXIS_DISABLED)) {
- break;
- }
- }
- if (next_axis == AXES) {
-// fprintf_P(stderr, PSTR("***** Homing failed: none or disabled/inhibited axes specified\n"));
- return (-2); // didn't find any axes to process
- }
-
- // Scan target vector from the current axis to find next axis or the end
- for (next_axis = ++axis; next_axis < AXES; next_axis++) {
- if (fp_TRUE(cm.gf.target[next_axis])) {
- if ((cm.a[next_axis].axis_mode == AXIS_INHIBITED) ||
- (cm.a[next_axis].axis_mode == AXIS_DISABLED)) { // Skip if axis disabled or inhibited
- continue;
- }
- break; // got a good one
- }
- return (-1); // you are done
- }
-
- // Got a valid axis. Find out if it's a dual
- return (STAT_OK);
-}
-*/
-
-#ifdef __cplusplus
-}
-#endif
#include "planner.h"
#include "util.h"
-#ifdef __cplusplus
-extern "C"{
-#endif
-
/**** Jogging singleton structure ****/
struct jmJoggingSingleton { // persistent jogging runtime variables
printf("{\"jog\":0}\n");
return (STAT_OK);
}
-
-/*
-static stat_t _jogging_error_exit(int8_t axis)
-{
- // Generate the warning message. Since the error exit returns via the jogging callback
- // - and not the main controller - it requires its own display processing
-// nv_reset_nv_list();
- _jogging_finalize_exit(axis); // clean up
- return (STAT_JOGGING_CYCLE_FAILED); // jogging state
-}
-*/
-
-#ifdef __cplusplus
-}
-#endif
#include "config.h"
#include "encoder.h"
-#ifdef __cplusplus
-extern "C"{
-#endif
-
/**** Allocate Structures ****/
enEncoders_t en;
-/************************************************************************************
- **** CODE **************************************************************************
- ************************************************************************************/
/*
* encoder_init() - initialize encoders
{
return((float)en.en[motor].encoder_steps);
}
-
-/***********************************************************************************
- * CONFIGURATION AND INTERFACE FUNCTIONS
- * Functions to get and set variables from the cfgArray table
- ***********************************************************************************/
-
-/***********************************************************************************
- * TEXT MODE SUPPORT
- * Functions to print variables from the cfgArray table
- ***********************************************************************************/
-
-#ifdef __TEXT_MODE
-
-#endif // __TEXT_MODE
-
-#ifdef __cplusplus
-}
-#endif
#ifndef ENCODER_H_ONCE
#define ENCODER_H_ONCE
-#ifdef __cplusplus
-extern "C"{
-#endif
-
/**** Configs and Constants ****/
/**** Macros ****/
float en_read_encoder(uint8_t motor);
#endif // End of include guard: ENCODER_H_ONCE
-
-#ifdef __cplusplus
-}
-#endif
#include "util.h"
#include "xio.h" // for char definitions
-#ifdef __cplusplus
-extern "C"{
-#endif
-
struct gcodeParserSingleton { // struct to manage globals
uint8_t modals[MODAL_GROUP_COUNT];// collects modal groups in a block
}; struct gcodeParserSingleton gp;
{
return(gc_gcode_parser(*nv->stringp));
}
-
-/***********************************************************************************
- * TEXT MODE SUPPORT
- * Functions to print variables from the cfgArray table
- ***********************************************************************************/
-
-#ifdef __TEXT_MODE
-
-// no text mode functions here. Move along
-
-#endif // __TEXT_MODE
-
-#ifdef __cplusplus
-}
-#endif
#ifndef GCODE_PARSER_H_ONCE
#define GCODE_PARSER_H_ONCE
-#ifdef __cplusplus
-extern "C"{
-#endif
-
/*
* Global Scope Functions
*/
stat_t gc_get_gc(nvObj_t *nv);
stat_t gc_run_gc(nvObj_t *nv);
-#ifdef __cplusplus
-}
-#endif
-
#endif // End of include guard: GCODE_PARSER_H_ONCE
#include "config.h"
#include "controller.h"
#include "hardware.h"
-//#include "switch.h"
#include "gpio.h"
#include "canonical_machine.h"
#include "xio.h" // signals
void gpio_led_on(uint8_t led)
{
-// if (led == 0) return (gpio_set_bit_on(0x08));
-// if (led == 1) return (gpio_set_bit_on(0x04));
-// if (led == 2) return (gpio_set_bit_on(0x02));
-// if (led == 3) return (gpio_set_bit_on(0x01));
-
- if (led == 0) gpio_set_bit_on(0x08); else
+ if (led == 0) gpio_set_bit_on(0x08); else
if (led == 1) gpio_set_bit_on(0x04); else
if (led == 2) gpio_set_bit_on(0x02); else
if (led == 3) gpio_set_bit_on(0x01);
void gpio_led_off(uint8_t led)
{
-// if (led == 0) return (gpio_set_bit_off(0x08));
-// if (led == 1) return (gpio_set_bit_off(0x04));
-// if (led == 2) return (gpio_set_bit_off(0x02));
-// if (led == 3) return (gpio_set_bit_off(0x01));
-
- if (led == 0) gpio_set_bit_off(0x08); else
+ if (led == 0) gpio_set_bit_off(0x08); else
if (led == 1) gpio_set_bit_off(0x04); else
if (led == 2) gpio_set_bit_off(0x02); else
if (led == 3) gpio_set_bit_off(0x01);
* OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*/
-#ifdef __AVR
#include <avr/wdt.h> // used for software reset
-#endif
#include "tinyg.h" // #1
#include "config.h" // #2
#include "switch.h"
#include "controller.h"
#include "text_parser.h"
-#ifdef __AVR
#include "xmega/xmega_init.h"
#include "xmega/xmega_rtc.h"
-#endif
-
-#ifdef __cplusplus
-extern "C"{
-#endif
/*
* _port_bindings - bind XMEGA ports to hardware - these changed at board revision 7
static void _port_bindings(float hw_version)
{
-#ifdef __AVR
- hw.st_port[0] = &PORT_MOTOR_1;
+ hw.st_port[0] = &PORT_MOTOR_1;
hw.st_port[1] = &PORT_MOTOR_2;
hw.st_port[2] = &PORT_MOTOR_3;
hw.st_port[3] = &PORT_MOTOR_4;
hw.out_port[2] = &PORT_OUT_V6_Z;
hw.out_port[3] = &PORT_OUT_V6_A;
}
-#endif
}
void hardware_init()
{
-#ifdef __AVR
- xmega_init(); // set system clock
+ xmega_init(); // set system clock
_port_bindings(TINYG_HARDWARE_VERSION);
rtc_init(); // real time counter
-#endif
}
/*
* _get_id() - get a human readable signature
*
- * FOR AVR:
* Produce a unique deviceID based on the factory calibration data.
* Format is: 123456-ABC
*
* The number part is a direct readout of the 6 digit lot number
* The alpha is the low 5 bits of wafer number and XY coords in printable ASCII
* Refer to NVM_PROD_SIGNATURES_t in iox192a3.h for details.
- *
- * FOR ARM:
- * Currently not implemented
*/
-/* UNUSED
-static uint8_t _read_calibration_byte(uint8_t index)
-{
- NVM_CMD = NVM_NV_READ_CALIB_ROW_gc; // Load NVM Command register to read the calibration row
- uint8_t result = pgm_read_byte(index);
- NVM_CMD = NVM_NV_NO_OPERATION_gc; // Clean up NVM Command register
- return(result);
-}
-*/
-
enum {
LOTNUM0=8, // Lot Number Byte 0, ASCII
LOTNUM1, // Lot Number Byte 1, ASCII
static void _get_id(char_t *id)
{
-#ifdef __AVR
- char printable[33] = {"ABCDEFGHJKLMNPQRSTUVWXYZ23456789"};
+ char printable[33] = {"ABCDEFGHJKLMNPQRSTUVWXYZ23456789"};
uint8_t i;
NVM_CMD = NVM_CMD_READ_CALIB_ROW_gc; // Load NVM Command register to read the calibration row
id[i] = 0;
NVM_CMD = NVM_CMD_NO_OPERATION_gc; // Clean up NVM Command register
-#endif
}
/*
void hw_hard_reset(void) // software hard reset using the watchdog timer
{
-#ifdef __AVR
- wdt_enable(WDTO_15MS);
+ wdt_enable(WDTO_15MS);
while (true); // loops for about 15ms then resets
-#endif
}
stat_t hw_hard_reset_handler(void)
stat_t hw_bootloader_handler(void)
{
-#ifdef __AVR
- if (cs.bootloader_requested == false)
+ if (cs.bootloader_requested == false)
return (STAT_NOOP);
cli();
CCPWrite(&RST.CTRL, RST_SWRST_bm); // fire a software reset
-#endif
+
return (STAT_EAGAIN); // never gets here but keeps the compiler happy
}
set_flt(nv); // record the hardware version
_port_bindings(nv->value); // reset port bindings
switch_init(); // re-initialize the GPIO ports
-//++++ gpio_init(); // re-initialize the GPIO ports
- return (STAT_OK);
+ return (STAT_OK);
}
/***********************************************************************************
void hw_print_id(nvObj_t *nv) { text_print_str(nv, fmt_id);}
#endif //__TEXT_MODE
-
-#ifdef __cplusplus
-}
-#endif
#include "report.h"
#include "help.h"
-#ifdef __cplusplus
-extern "C"{
-#endif
-
// help helper functions (snicker)
stat_t help_stub(nvObj_t *nv) {return (STAT_OK);}
}
#endif // __HELP_SCREENS
-
-#ifdef __cplusplus
-}
-#endif
#ifndef HELP_H_ONCE
#define HELP_H_ONCE
-#ifdef __cplusplus
-extern "C"{
-#endif
-
#ifdef __HELP_SCREENS
stat_t help_general(nvObj_t *nv);
#endif // __HELP_SCREENS
-#ifdef __cplusplus
-}
-#endif
-
#endif // End of include guard: HELP_H_ONCE
#include "util.h"
#include "xio.h" // for char definitions
-#ifdef __cplusplus
-extern "C"{
-#endif
-
/**** Allocation ****/
jsSingleton_t js;
void js_print_fs(nvObj_t *nv) { text_print_ui8(nv, fmt_fs);}
#endif // __TEXT_MODE
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
#ifndef _JSON_PARSER_H_ONCE
#define _JSON_PARSER_H_ONCE
-#ifdef __cplusplus
-extern "C"{
-#endif
-
/**** Configs, Definitions and Structures ****/
/* JSON array definitions / revisions */
#endif // __TEXT_MODE
-#ifdef __cplusplus
-}
-#endif
-
#endif // End of include guard: JSON_PARSER_H_ONCE
#include "stepper.h"
#include "kinematics.h"
-#ifdef __cplusplus
-extern "C"{
-#endif
-
-//static void _inverse_kinematics(float travel[], float joint[]);
/*
* ik_kinematics() - wrapper routine for inverse kinematics
if (st_cfg.mot[MOTOR_6].motor_map == axis) { steps[MOTOR_6] = joint[axis] * st_cfg.mot[MOTOR_6].steps_per_unit;}
#endif
}
-
-/* The above is a loop unrolled version of this:
- for (uint8_t axis=0; axis<AXES; axis++) {
- for (uint8_t motor=0; motor<MOTORS; motor++) {
- if (st_cfg.mot[motor].motor_map == axis) {
- steps[motor] = joint[axis] * st_cfg.mot[motor].steps_per_unit;
- }
- }
- }
-*/
}
-/*
- * _inverse_kinematics() - inverse kinematics - example is for a cartesian machine
- *
- * You can glue in inverse kinematics here, but be aware of time budget constrants.
- * This function is run during the _exec() portion of the cycle and will therefore
- * be run once per interpolation segment. The total time for the segment load,
- * including the inverse kinematics transformation cannot exceed the segment time,
- * and ideally should be no more than 25-50% of the segment time. Currently segments
- * run avery 5 ms, but this might be lowered. To profile this time look at the
- * time it takes to complete the mp_exec_move() function.
- */
-/*
-static void _inverse_kinematics(float travel[], float joint[])
-{
- for (uint8_t i=0; i<AXES; i++) {
- joint[i] = travel[i];
- }
-}
-*/
-
-#ifdef __cplusplus
-}
-#endif
#ifndef KINEMATICS_H_ONCE
#define KINEMATICS_H_ONCE
-#ifdef __cplusplus
-extern "C"{
-#endif
-
/*
* Global Scope Functions
*/
void ik_kinematics(const float travel[], float steps[]);
-//#ifdef __UNIT_TESTS
-//void ik_unit_tests(void);
-//#endif
-
-#ifdef __cplusplus
-}
-#endif
-
#endif // End of include Guard: KINEMATICS_H_ONCE
#include "pwm.h"
#include "xio.h"
-#ifdef __AVR
#include <avr/interrupt.h>
#include "xmega/xmega_interrupts.h"
-#endif // __AVR
-
-#ifdef __ARM
-#include "MotateTimers.h"
-using Motate::delay;
-
-#ifdef __cplusplus
-extern "C"{
-#endif // __cplusplus
void _init() __attribute__ ((weak));
void _init() {;}
void __libc_init_array(void);
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // __ARM
-
/******************** Application Code ************************/
-
-#ifdef __ARM
-const Motate::USBSettings_t Motate::USBSettings = {
- /*gVendorID = */ 0x1d50,
- /*gProductID = */ 0x606d,
- /*gProductVersion = */ TINYG_FIRMWARE_VERSION,
- /*gAttributes = */ kUSBConfigAttributeSelfPowered,
- /*gPowerConsumption = */ 500
-};
- /*gProductVersion = */ //0.1,
-
-Motate::USBDevice< Motate::USBCDC > usb;
-//Motate::USBDevice< Motate::USBCDC, Motate::USBCDC > usb;
-
-typeof usb._mixin_0_type::Serial &SerialUSB = usb._mixin_0_type::Serial;
-//typeof usb._mixin_1_type::Serial &SerialUSB1 = usb._mixin_1_type::Serial;
-
-MOTATE_SET_USB_VENDOR_STRING( {'S' ,'y', 'n', 't', 'h', 'e', 't', 'o', 's'} )
-MOTATE_SET_USB_PRODUCT_STRING( {'T', 'i', 'n', 'y', 'G', ' ', 'v', '2'} )
-MOTATE_SET_USB_SERIAL_NUMBER_STRING( {'0','0','1'} )
-
-Motate::SPI<kSocket4_SPISlaveSelectPinNumber> spi;
-#endif
-
-/*
- * _system_init()
- */
-
-void _system_init(void)
-{
-#ifdef __ARM
- SystemInit();
-
- // Disable watchdog
- WDT->WDT_MR = WDT_MR_WDDIS;
-
- // Initialize C library
- __libc_init_array();
-
- usb.attach(); // USB setup
- delay(1000);
-#endif
-}
-
-/*
- * _application_init()
- */
-
static void _application_init(void)
{
// There are a lot of dependencies in the order of these inits.
int main(void)
{
- // system initialization
- _system_init();
-
- // TinyG application setup
+ // TinyG application setup
_application_init();
run_canned_startup(); // run any pre-loaded commands
#include "report.h"
#include "canonical_machine.h"
#include "util.h"
-
-#ifdef __AVR
#include "xmega/xmega_eeprom.h"
-#endif
-
-/***********************************************************************************
- **** STRUCTURE ALLOCATIONS ********************************************************
- ***********************************************************************************/
nvmSingleton_t nvm;
-/***********************************************************************************
- **** GENERIC STATIC FUNCTIONS AND VARIABLES ***************************************
- ***********************************************************************************/
-
-
-/***********************************************************************************
- **** CODE *************************************************************************
- ***********************************************************************************/
void persistence_init()
{
-#ifdef __AVR
- nvm.base_addr = NVM_BASE_ADDR;
+ nvm.base_addr = NVM_BASE_ADDR;
nvm.profile_base = 0;
-#endif
- return;
+ return;
}
/************************************************************************************
* It's the responsibility of the caller to make sure the index does not exceed range
*/
-#ifdef __AVR
stat_t read_persistent_value(nvObj_t *nv)
{
nvm.address = nvm.profile_base + (nv->index * NVM_VALUE_LEN);
memcpy(&nv->value, &nvm.byte_array, NVM_VALUE_LEN);
return (STAT_OK);
}
-#endif // __AVR
-
-#ifdef __ARM
-stat_t read_persistent_value(nvObj_t *nv)
-{
- nv->value = 0;
- return (STAT_OK);
-}
-#endif // __ARM
-#ifdef __AVR
stat_t write_persistent_value(nvObj_t *nv)
{
if (cm.cycle_state != CYCLE_OFF)
return(rpt_exception(STAT_FILE_NOT_OPEN)); // can't write when machine is moving
-
-/* not needed
- if (nv->valuetype == TYPE_FLOAT) {
- if (isnan((double)nv->value)) return(rpt_exception(STAT_FLOAT_IS_NAN)); // bad floating point value
- if (isinf((double)nv->value)) return(rpt_exception(STAT_FLOAT_IS_INFINITE));// bad floating point value
- }
-*/
- nvm.tmp_value = nv->value;
+ nvm.tmp_value = nv->value;
ritorno(read_persistent_value(nv));
if ((isnan((double)nv->value)) || (isinf((double)nv->value)) || (fp_NE(nv->value, nvm.tmp_value))) {
memcpy(&nvm.byte_array, &nvm.tmp_value, NVM_VALUE_LEN);
nv->value =nvm.tmp_value; // always restore value
return (STAT_OK);
}
-#endif // __AVR
-
-#ifdef __ARM
-stat_t write_persistent_value(nvObj_t *nv)
-{
- if (cm.cycle_state != CYCLE_OFF)
- return(rpt_exception(STAT_FILE_NOT_OPEN)); // can't write when machine is moving
-
-/* not needed
- if (nv->valuetype == TYPE_FLOAT) {
- if (isnan((double)nv->value)) return(rpt_exception(STAT_FLOAT_IS_NAN)); // bad floating point value
- if (isinf((double)nv->value)) return(rpt_exception(STAT_FLOAT_IS_INFINITE));// bad floating point value
- }
-*/
- return (STAT_OK);
-}
-#endif // __ARM
-
-#ifdef __cplusplus
-}
-#endif
-
return (STAT_MINIMUM_LENGTH_MOVE); // trap zero length arcs that _compute_arc can throw
}
-/* // test arc soft limits
- stat_t status = _test_arc_soft_limits();
- if (status != STAT_OK) {
- cm.gm.motion_mode = MOTION_MODE_CANCEL_MOTION_MODE;
- copy_vector(cm.gm.target, cm.gmx.position); // reset model position
- return (cm_soft_alarm(status));
- }
-*/
- cm_cycle_start(); // if not already started
+ cm_cycle_start(); // if not already started
arc.run_state = MOVE_RUN; // enable arc to be run from the callback
cm_finalize_move();
return (STAT_OK);
arc.arc_time = max(arc.arc_time, fabs(arc.linear_travel/cm.a[arc.linear_axis].feedrate_max));
}
}
-
-/*
- * _test_arc_soft_limits() - return error status if soft limit is exceeded
- *
- * Test if arc extends beyond arc plane boundaries set in soft limits.
- *
- * The arc starting position (P) and target (T) define 2 points that divide the
- * arc plane into 9 rectangles. The center of the arc is (C). P and T define the
- * endpoints of two possible arcs; one that is less than or equal to 180 degrees (acute)
- * and one that is greater than 180 degrees (obtuse), depending on the location of (C).
- *
- * ------------------------------- plane boundaries in X and Y
- * | | | |
- * | 1 | 2 | 3 |
- * | | |
- * --------- P -------------------
- * | | |
- * | 4 | 5 | 6 |
- * | | |
- * ------------------- T ---------
- * | C| | C shows one of many possible center locations
- * | 7 | 8 | 9 |
- * | | | |
- * -------------------------------
- *
- * C will fall along a diagonal bisecting 7, 5 and 3, but there is some tolerance in the
- * circle algorithm that allows C to deviate from the centerline slightly. As the centerline
- * approaches the line connecting S and T the acute arcs will be "above" S and T in sections
- * 5 or 3, and the obtuse arcs will be "below" in sections 5 or 7. But it's simpler, because
- * we know that the arc is > 180 degrees (obtuse) if the angular travel value is > pi.
- *
- * The example below only tests the X axis (0 plane axis), but testing the other axes is similar
- *
- * (1) If Cx <= Px and arc is acute; no test is needed
- *
- * (2) If Cx <= Px and arc is obtuse; test if the radius is greater than
- * the distance from Cx to the negative X boundary
- *
- * (3) If Px < Cx < Tx and arc is acute; test if the radius is greater than
- * the distance from Cx to the positive X boundary
- *
- * (4) If Px < Cx < Tx and arc is obtuse; test if the radius is greater than
- * the distance from Cx to the positive X boundary
- *
- * The arc plane is defined by 0 and 1 depending on G17/G18/G19 plane selected,
- * corresponding to arc planes XY, XZ, YZ, respectively.
- *
- * Must be called with all the following set in the arc struct
- * - arc starting position (arc.position)
- * - arc ending position (arc.gm.target)
- * - arc center (arc.center_0, arc.center_1)
- * - arc.radius (arc.radius)
- * - arc angular travel in radians (arc.angular_travel)
- * - max and min travel in axis 0 and axis 1 (in cm struct)
- */
-/* UNUSED
-static stat_t _test_arc_soft_limit_plane_axis(float center, uint8_t plane_axis)
-{
- if (center <= arc.position[plane_axis]) {
- if (arc.angular_travel < M_PI) { // case (1)
- return (STAT_OK);
- }
- if ((center - arc.radius) < cm.a[plane_axis].travel_min) { // case (2)
- return (STAT_SOFT_LIMIT_EXCEEDED);
- }
- }
- if ((center + arc.radius) > cm.a[plane_axis].travel_max) { // cases (3) and (4)
- return (STAT_SOFT_LIMIT_EXCEEDED);
- }
- return(STAT_OK);
-}
-
-static stat_t _test_arc_soft_limits()
-{
- if (cm.soft_limit_enable == true) {
-
- // Test if target falls outside boundaries. This is a 3 dimensional test
- // so it also checks the linear axis of the arc (helix axis)
- ritorno(cm_test_soft_limits(arc.gm.target));
-
- // test arc extents
- ritorno(_test_arc_soft_limit_plane_axis(arc.center_0, arc.plane_axis_0));
- ritorno(_test_arc_soft_limit_plane_axis(arc.center_1, arc.plane_axis_1));
- }
- return(STAT_OK);
-}
-
-*/
\ No newline at end of file
#include "encoder.h"
#include "report.h"
#include "util.h"
-/*
-#ifdef __cplusplus
-extern "C"{
-#endif
-*/
+
// execute routines (NB: These are all called from the LO interrupt)
static stat_t _exec_aline_head(void);
static stat_t _exec_aline_body(void);
// F = Vi
float h = 1/(mr.segments);
-// float h_3 = h * h * h;
-// float h_4 = h_3 * h;
-// float h_5 = h_4 * h;
float Ah_5 = A * h * h * h * h * h;
float Bh_4 = B * h * h * h * h;
// examine and process mr buffer
mr_available_length = get_axis_vector_length(mr.target, mr.position);
-/* mr_available_length =
- (sqrt(square(mr.endpoint[AXIS_X] - mr.position[AXIS_X]) +
- square(mr.endpoint[AXIS_Y] - mr.position[AXIS_Y]) +
- square(mr.endpoint[AXIS_Z] - mr.position[AXIS_Z]) +
- square(mr.endpoint[AXIS_A] - mr.position[AXIS_A]) +
- square(mr.endpoint[AXIS_B] - mr.position[AXIS_B]) +
- square(mr.endpoint[AXIS_C] - mr.position[AXIS_C])));
-
-*/
-
- // compute next_segment velocity
-// braking_velocity = mr.segment_velocity;
-// if (mr.section != SECTION_BODY) { braking_velocity += mr.forward_diff_1;}
- braking_velocity = _compute_next_segment_velocity();
+ // compute next_segment velocity
+ braking_velocity = _compute_next_segment_velocity();
braking_length = mp_get_target_length(braking_velocity, 0, bp); // bp is OK to use here
// Hack to prevent Case 2 moves for perfect-fit decels. Happens in homing situations
#include "encoder.h"
#include "report.h"
#include "util.h"
-/*
-#ifdef __cplusplus
-extern "C"{
-#endif
-*/
-// Allocate planner structures
+// Allocate planner structures
mpBufferPool_t mb; // move buffer queue
mpMoveMasterSingleton_t mm; // context for line planning
mpMoveRuntimeSingleton_t mr; // context for line runtime
bf->nx = nx; // restore pointers
bf->pv = pv;
}
-
-/*
-// currently this routine is only used by debug routines
-uint8_t mp_get_buffer_index(mpBuf_t *bf)
-{
- mpBuf_t *b = bf; // temp buffer pointer
-
- for (uint8_t i=0; i < PLANNER_BUFFER_POOL_SIZE; i++) {
- if (b->pv > b) {
- return (i);
- }
- b = b->pv;
- }
- return(cm_hard_alarm(PLANNER_BUFFER_POOL_SIZE)); // should never happen
-}
-*/
-
-/****************************
- * END OF PLANNER FUNCTIONS *
- ****************************/
-
-/***********************************************************************************
- * CONFIGURATION AND INTERFACE FUNCTIONS
- * Functions to get and set variables from the cfgArray table
- ***********************************************************************************/
-
-/***********************************************************************************
- * TEXT MODE SUPPORT
- * Functions to print variables from the cfgArray table
- ***********************************************************************************/
-/*
-#ifdef __cplusplus
-}
-#endif
-*/
#define PLANNER_H_ONCE
#include "canonical_machine.h" // used for GCodeState_t
-/*
-#ifdef __cplusplus
-extern "C"{
-#endif
-*/
+
enum moveType { // bf->move_type values
MOVE_TYPE_NULL = 0, // null move - does a no-op
MOVE_TYPE_ALINE, // acceleration planned line
// plan_exec.c functions
stat_t mp_exec_move(void);
stat_t mp_exec_aline(mpBuf_t *bf);
-/*
-#ifdef __cplusplus
-}
-#endif
-*/
+
#endif // End of include Guard: PLANNER_H_ONCE
#include "gpio.h"
#include "pwm.h"
-#ifdef __AVR
#include <avr/interrupt.h>
-#endif
-
-#ifdef __cplusplus
-extern "C"{
-#endif
/***** PWM defines, structures and memory allocation *****/
*/
void pwm_init()
{
-#ifdef __AVR
- gpio_set_bit_off(SPINDLE_PWM);
+ gpio_set_bit_off(SPINDLE_PWM);
// setup PWM channel 1
memset(&pwm.p[PWM_1], 0, sizeof(pwmChannel_t)); // clear parent structure
pwm.p[PWM_2].ctrla = PWM2_CTRLA_CLKSEL;
pwm.p[PWM_2].timer->CTRLB = PWM2_CTRLB;
pwm.p[PWM_2].timer->INTCTRLB = PWM2_INTCTRLB;
-#endif // __AVR
}
/*
* ISRs for PWM timers
*/
-#ifdef __AVR
ISR(PWM1_ISR_vect)
{
return;
{
return;
}
-#endif // __AVR
-/*
-#ifdef __ARM
-MOTATE_TIMER_INTERRUPT
-ISR(PWM1_ISR_vect)
-{
- return;
-}
-ISR(PWM2_ISR_vect)
-{
- return;
-}
-#endif // __ARM
-*/
/*
* pwm_set_freq() - set PWM channel frequency
*
if (freq > PWM_MAX_FREQ) { return (STAT_INPUT_EXCEEDS_MAX_VALUE);}
if (freq < PWM_MIN_FREQ) { return (STAT_INPUT_LESS_THAN_MIN_VALUE);}
-#ifdef __AVR
- // set the period and the prescaler
+ // set the period and the prescaler
float prescale = F_CPU/65536/freq; // optimal non-integer prescaler value
if (prescale <= 1) {
pwm.p[chan].timer->PER = F_CPU/freq;
pwm.p[chan].timer->PER = F_CPU/64/freq;
pwm.p[chan].timer->CTRLA = TC_CLKSEL_DIV64_gc;
}
-#endif // __AVR
-
-#ifdef __ARM
- if (chan == PWM_1) {
- spindle_pwm_pin.setFrequency(freq);
- } else if (chan == PWM_2) {
- secondary_pwm_pin.setFrequency(freq);
- }
-#endif // __ARM
return (STAT_OK);
}
if (duty < 0.0) { return (STAT_INPUT_LESS_THAN_MIN_VALUE);}
if (duty > 1.0) { return (STAT_INPUT_EXCEEDS_MAX_VALUE);}
- #ifdef __AVR
// Ffrq = Fper/(2N(CCA+1))
// Fpwm = Fper/((N(PER+1))
float period_scalar = pwm.p[chan].timer->PER;
pwm.p[chan].timer->CCB = (uint16_t)(period_scalar * duty) + 1;
- #endif // __AVR
-
- #ifdef __ARM
- if (chan == PWM_1) {
- spindle_pwm_pin = duty;
- } else if (chan == PWM_2) {
- secondary_pwm_pin = duty;
- }
- #endif // __ARM
return (STAT_OK);
}
void pwm_print_p1pof(nvObj_t *nv) { text_print_flt(nv, fmt_p1pof);}
#endif //__TEXT_MODE
-
-#ifdef __cplusplus
-}
-#endif
#ifndef PWM_H_ONCE
#define PWM_H_ONCE
-#ifdef __cplusplus
-extern "C"{
-#endif
-
typedef struct pwmConfigChannel {
float frequency; // base frequency for PWM driver, in Hz
float cw_speed_lo; // minimum clockwise spindle speed [0..N]
typedef struct pwmChannel {
uint8_t ctrla; // byte needed to active CTRLA (it's dynamic - rest are static)
-#ifdef __AVR
- TC1_t *timer; // assumes TC1 flavor timers used for PWM channels
-#endif
+ TC1_t *timer; // assumes TC1 flavor timers used for PWM channels
} pwmChannel_t;
typedef struct pwmSingleton {
#endif // __TEXT_MODE
-#ifdef __cplusplus
-}
-#endif
-
#endif // End of include guard: PWM_H_ONCE
#include "util.h"
#include "xio.h"
-#ifdef __cplusplus
-extern "C"{
-#endif
-
/**** Allocation ****/
srSingleton_t sr;
*/
stat_t sr_request_status_report(uint8_t request_type)
{
-#ifdef __ARM
- if (request_type == SR_IMMEDIATE_REQUEST) {
- sr.status_report_systick = SysTickTimer.getValue();
- }
- if ((request_type == SR_TIMED_REQUEST) && (sr.status_report_requested == false)) {
- sr.status_report_systick = SysTickTimer.getValue() + sr.status_report_interval;
- }
-#endif
-#ifdef __AVR
- if (request_type == SR_IMMEDIATE_REQUEST) {
+ if (request_type == SR_IMMEDIATE_REQUEST) {
sr.status_report_systick = SysTickTimer_getValue();
}
if ((request_type == SR_TIMED_REQUEST) && (sr.status_report_requested == false)) {
sr.status_report_systick = SysTickTimer_getValue() + sr.status_report_interval;
}
-#endif
- sr.status_report_requested = true;
+ sr.status_report_requested = true;
return (STAT_OK);
}
if (sr.status_report_requested == false)
return (STAT_NOOP);
-#ifdef __ARM
- if (SysTickTimer.getValue() < sr.status_report_systick)
+ if (SysTickTimer_getValue() < sr.status_report_systick)
return (STAT_NOOP);
-#endif
-#ifdef __AVR
- if (SysTickTimer_getValue() < sr.status_report_systick)
- return (STAT_NOOP);
-#endif
sr.status_report_requested = false; // disable reports until requested again
void qr_print_qv(nvObj_t *nv) { text_print_ui8(nv, fmt_qv);}
#endif // __TEXT_MODE
-
-#ifdef __cplusplus
-}
-#endif
#ifndef REPORT_H_ONCE
#define REPORT_H_ONCE
-#ifdef __cplusplus
-extern "C"{
-#endif
-
/**** Configs, Definitions and Structures ****/
//
// Notes:
stat_t sr_get(nvObj_t *nv);
stat_t sr_set(nvObj_t *nv);
stat_t sr_set_si(nvObj_t *nv);
-//void sr_print_sr(nvObj_t *nv);
void qr_init_queue_report(void);
void qr_request_queue_report(int8_t buffers);
#endif // __TEXT_MODE
-#ifdef __cplusplus
-}
-#endif
-
#endif // End of include guard: REPORT_H_ONCE
// MOTOR_POWERED_ONLY_WHEN_MOVING (3)
#define MOTOR_IDLE_TIMEOUT 2.00 // seconds to maintain motor at full power before idling
-#define MOTOR_POWER_LEVEL 0.25 // default motor power level (0,000 - 1.000, ARM only)
// Communications and reporting settings
#define COMM_MODE JSON_MODE // one of: TEXT_MODE, JSON_MODE
#include "hardware.h"
#include "pwm.h"
-#ifdef __cplusplus
-extern "C"{
-#endif
-
static void _exec_spindle_control(float *value, float *flag);
static void _exec_spindle_speed(float *value, float *flag);
uint8_t spindle_mode = (uint8_t)value[0];
cm_set_spindle_mode(MODEL, spindle_mode);
- #ifdef __AVR
- if (spindle_mode == SPINDLE_CW) {
+ if (spindle_mode == SPINDLE_CW) {
gpio_set_bit_on(SPINDLE_BIT);
gpio_set_bit_off(SPINDLE_DIR);
} else if (spindle_mode == SPINDLE_CCW) {
} else {
gpio_set_bit_off(SPINDLE_BIT); // failsafe: any error causes stop
}
-#endif // __AVR
-#ifdef __ARM
- if (spindle_mode == SPINDLE_CW) {
- spindle_enable_pin.set();
- spindle_dir_pin.clear();
- } else if (spindle_mode == SPINDLE_CCW) {
- spindle_enable_pin.set();
- spindle_dir_pin.set();
- } else {
- spindle_enable_pin.clear(); // failsafe: any error causes stop
- }
-#endif // __ARM
// PWM spindle control
pwm_set_duty(PWM_1, cm_get_spindle_pwm(spindle_mode) );
cm_set_spindle_speed_parameter(MODEL, value[0]);
pwm_set_duty(PWM_1, cm_get_spindle_pwm(cm.gm.spindle_mode) ); // update spindle speed if we're running
}
-
-#ifdef __cplusplus
-}
-#endif
#ifndef SPINDLE_H_ONCE
#define SPINDLE_H_ONCE
-#ifdef __cplusplus
-extern "C"{
-#endif
-
-/*
- * Global Scope Functions
- */
-
void cm_spindle_init();
stat_t cm_set_spindle_speed(float speed); // S parameter
stat_t cm_spindle_control(uint8_t spindle_mode); // M3, M4, M5 integrated spindle control
void cm_exec_spindle_control(uint8_t spindle_mode); // callback for above
-#ifdef __cplusplus
-}
-#endif
-
#endif // End of include guard: SPINDLE_H_ONCE
static void _load_move(void);
static void _request_load_move(void);
-#ifdef __ARM
-static void _set_motor_power_level(const uint8_t motor, const float power_level);
-#endif
// handy macro
#define _f_to_period(f) (uint16_t)((float)F_CPU / (float)f)
-/**** Setup motate ****/
-
-#ifdef __ARM
-using namespace Motate;
-
-OutputPin<kGRBL_CommonEnablePinNumber> common_enable; // shorter form of the above
-OutputPin<kDebug1_PinNumber> dda_debug_pin1;
-OutputPin<kDebug2_PinNumber> dda_debug_pin2;
-OutputPin<kDebug3_PinNumber> dda_debug_pin3;
-
-// Example with prefixed name::
-//Motate::Timer<dda_timer_num> dda_timer(kTimerUpToMatch, FREQUENCY_DDA);// stepper pulse generation
-Timer<dda_timer_num> dda_timer(kTimerUpToMatch, FREQUENCY_DDA); // stepper pulse generation
-Timer<dwell_timer_num> dwell_timer(kTimerUpToMatch, FREQUENCY_DWELL); // dwell timer
-Timer<load_timer_num> load_timer; // triggers load of next stepper segment
-Timer<exec_timer_num> exec_timer; // triggers calculation of next+1 stepper segment
-
-// Motor structures
-template<pin_number step_num, // Setup a stepper template to hold our pins
- pin_number dir_num,
- pin_number enable_num,
- pin_number ms0_num,
- pin_number ms1_num,
- pin_number ms2_num,
- pin_number vref_num>
-
-struct Stepper {
- /* stepper pin assignments */
-
- OutputPin<step_num> step;
- OutputPin<dir_num> dir;
- OutputPin<enable_num> enable;
- OutputPin<ms0_num> ms0;
- OutputPin<ms1_num> ms1;
- OutputPin<ms2_num> ms2;
- PWMOutputPin<vref_num> vref;
-
- /* stepper default values */
-
- // sets default pwm freq for all motor vrefs (comment line also sets HiZ)
- Stepper(const uint32_t frequency = 500000) : vref(frequency) {};
-// Stepper(const uint32_t frequency = 100000) : vref(kDriveLowOnly, frequency) {};
-
- /* functions bound to stepper structures */
-
- void setMicrosteps(const uint8_t microsteps)
- {
- switch (microsteps) {
- case ( 1): { ms2=0; ms1=0; ms0=0; break; }
- case ( 2): { ms2=0; ms1=0; ms0=1; break; }
- case ( 4): { ms2=0; ms1=1; ms0=0; break; }
- case ( 8): { ms2=0; ms1=1; ms0=1; break; }
- case (16): { ms2=1; ms1=0; ms0=0; break; }
- case (32): { ms2=1; ms1=0; ms0=1; break; }
- }
- };
-
- void energize(const uint8_t motor)
- {
- if (st_cfg.mot[motor].power_mode != MOTOR_DISABLED) {
- enable.clear();
- st_run.mot[motor].power_state = MOTOR_POWER_TIMEOUT_START;
- }
- };
-};
-
-Stepper<kSocket1_StepPinNumber,
- kSocket1_DirPinNumber,
- kSocket1_EnablePinNumber,
- kSocket1_Microstep_0PinNumber,
- kSocket1_Microstep_1PinNumber,
- kSocket1_Microstep_2PinNumber,
- kSocket1_VrefPinNumber> motor_1;
-
-Stepper<kSocket2_StepPinNumber,
- kSocket2_DirPinNumber,
- kSocket2_EnablePinNumber,
- kSocket2_Microstep_0PinNumber,
- kSocket2_Microstep_1PinNumber,
- kSocket2_Microstep_2PinNumber,
- kSocket2_VrefPinNumber> motor_2;
-
-Stepper<kSocket3_StepPinNumber,
- kSocket3_DirPinNumber,
- kSocket3_EnablePinNumber,
- kSocket3_Microstep_0PinNumber,
- kSocket3_Microstep_1PinNumber,
- kSocket3_Microstep_2PinNumber,
- kSocket3_VrefPinNumber> motor_3;
-
-Stepper<kSocket4_StepPinNumber,
- kSocket4_DirPinNumber,
- kSocket4_EnablePinNumber,
- kSocket4_Microstep_0PinNumber,
- kSocket4_Microstep_1PinNumber,
- kSocket4_Microstep_2PinNumber,
- kSocket4_VrefPinNumber> motor_4;
-
-Stepper<kSocket5_StepPinNumber,
- kSocket5_DirPinNumber,
- kSocket5_EnablePinNumber,
- kSocket5_Microstep_0PinNumber,
- kSocket5_Microstep_1PinNumber,
- kSocket5_Microstep_2PinNumber,
- kSocket5_VrefPinNumber> motor_5;
-
-Stepper<kSocket6_StepPinNumber,
- kSocket6_DirPinNumber,
- kSocket6_EnablePinNumber,
- kSocket6_Microstep_0PinNumber,
- kSocket6_Microstep_1PinNumber,
- kSocket6_Microstep_2PinNumber,
- kSocket6_VrefPinNumber> motor_6;
-
-#endif // __ARM
-
-/************************************************************************************
- **** CODE **************************************************************************
- ************************************************************************************/
/*
* stepper_init() - initialize stepper motor subsystem
*
memset(&st_run, 0, sizeof(st_run)); // clear all values, pointers and status
stepper_init_assertions();
-#ifdef __AVR
- // Configure virtual ports
+ // Configure virtual ports
PORTCFG.VPCTRLA = PORTCFG_VP0MAP_PORT_MOTOR_1_gc | PORTCFG_VP1MAP_PORT_MOTOR_2_gc;
PORTCFG.VPCTRLB = PORTCFG_VP2MAP_PORT_MOTOR_3_gc | PORTCFG_VP3MAP_PORT_MOTOR_4_gc;
st_pre.buffer_state = PREP_BUFFER_OWNED_BY_EXEC;
st_reset(); // reset steppers to known state
-#endif // __AVR
-
-#ifdef __ARM
- // setup DDA timer (see FOOTNOTE)
- dda_timer.setInterrupts(kInterruptOnOverflow | kInterruptOnMatchA | kInterruptPriorityHighest);
- dda_timer.setDutyCycleA(0.25);
-
- // setup DWELL timer
- dwell_timer.setInterrupts(kInterruptOnOverflow | kInterruptPriorityHighest);
-
- // setup software interrupt load timer
- load_timer.setInterrupts(kInterruptOnSoftwareTrigger | kInterruptPriorityLow);
-
- // setup software interrupt exec timer & initial condition
- exec_timer.setInterrupts(kInterruptOnSoftwareTrigger | kInterruptPriorityLowest);
- st_pre.buffer_state = PREP_BUFFER_OWNED_BY_EXEC;
-
- // setup motor power levels and apply power level to stepper drivers
- for (uint8_t motor=0; motor<MOTORS; motor++) {
- _set_motor_power_level(motor, st_cfg.mot[motor].power_level_scaled);
- st_run.mot[motor].power_level_dynamic = st_cfg.mot[motor].power_level_scaled;
- }
-// motor_1.vref = 0.25; // example of how to set vref duty cycle directly. Freq already set to 500000 Hz.
-#endif // __ARM
}
/*
static void _deenergize_motor(const uint8_t motor)
{
-#ifdef __AVR
- switch (motor) {
+ switch (motor) {
case (MOTOR_1): { PORT_MOTOR_1_VPORT.OUT |= MOTOR_ENABLE_BIT_bm; break; }
case (MOTOR_2): { PORT_MOTOR_2_VPORT.OUT |= MOTOR_ENABLE_BIT_bm; break; }
case (MOTOR_3): { PORT_MOTOR_3_VPORT.OUT |= MOTOR_ENABLE_BIT_bm; break; }
case (MOTOR_4): { PORT_MOTOR_4_VPORT.OUT |= MOTOR_ENABLE_BIT_bm; break; }
}
st_run.mot[motor].power_state = MOTOR_OFF;
-#endif
-#ifdef __ARM
- // Motors that are not defined are not compiled. Saves some ugly #ifdef code
- if (!motor_1.enable.isNull()) if (motor == MOTOR_1) motor_1.enable.set(); // set disables the motor
- if (!motor_2.enable.isNull()) if (motor == MOTOR_2) motor_2.enable.set();
- if (!motor_3.enable.isNull()) if (motor == MOTOR_3) motor_3.enable.set();
- if (!motor_4.enable.isNull()) if (motor == MOTOR_4) motor_4.enable.set();
- if (!motor_5.enable.isNull()) if (motor == MOTOR_5) motor_5.enable.set();
- if (!motor_6.enable.isNull()) if (motor == MOTOR_6) motor_6.enable.set();
- st_run.mot[motor].power_state = MOTOR_OFF;
-#endif
}
static void _energize_motor(const uint8_t motor)
_deenergize_motor(motor);
return;
}
-#ifdef __AVR
+
switch(motor) {
case (MOTOR_1): { PORT_MOTOR_1_VPORT.OUT &= ~MOTOR_ENABLE_BIT_bm; break; }
case (MOTOR_2): { PORT_MOTOR_2_VPORT.OUT &= ~MOTOR_ENABLE_BIT_bm; break; }
case (MOTOR_3): { PORT_MOTOR_3_VPORT.OUT &= ~MOTOR_ENABLE_BIT_bm; break; }
case (MOTOR_4): { PORT_MOTOR_4_VPORT.OUT &= ~MOTOR_ENABLE_BIT_bm; break; }
}
-#endif
-#ifdef __ARM
- // Motors that are not defined are not compiled. Saves some ugly #ifdef code
- // case (MOTOR_1): { motor_1.energize(MOTOR_1); break; }
- if (!motor_1.enable.isNull()) if (motor == MOTOR_1) motor_1.energize(MOTOR_1);
- if (!motor_2.enable.isNull()) if (motor == MOTOR_2) motor_2.energize(MOTOR_2);
- if (!motor_3.enable.isNull()) if (motor == MOTOR_3) motor_3.energize(MOTOR_3);
- if (!motor_4.enable.isNull()) if (motor == MOTOR_4) motor_4.energize(MOTOR_4);
- if (!motor_5.enable.isNull()) if (motor == MOTOR_5) motor_5.energize(MOTOR_5);
- if (!motor_6.enable.isNull()) if (motor == MOTOR_6) motor_6.energize(MOTOR_6);
-#endif
- st_run.mot[motor].power_state = MOTOR_POWER_TIMEOUT_START;
-}
-/*
- * _set_motor_power_level() - applies the power level to the requested motor.
- *
- * The power_level must be a compensated PWM value - presumably one of:
- * st_cfg.mot[motor].power_level_scaled
- * st_run.mot[motor].power_level_dynamic
- */
-#ifdef __ARM
-static void _set_motor_power_level(const uint8_t motor, const float power_level)
-{
- // power_level must be scaled properly for the driver's Vref voltage requirements
- if (!motor_1.enable.isNull()) if (motor == MOTOR_1) motor_1.vref = power_level;
- if (!motor_2.enable.isNull()) if (motor == MOTOR_2) motor_2.vref = power_level;
- if (!motor_3.enable.isNull()) if (motor == MOTOR_3) motor_3.vref = power_level;
- if (!motor_4.enable.isNull()) if (motor == MOTOR_4) motor_4.vref = power_level;
- if (!motor_5.enable.isNull()) if (motor == MOTOR_5) motor_5.vref = power_level;
- if (!motor_6.enable.isNull()) if (motor == MOTOR_6) motor_6.vref = power_level;
+ st_run.mot[motor].power_state = MOTOR_POWER_TIMEOUT_START;
}
-#endif
void st_energize_motors()
{
_energize_motor(motor);
st_run.mot[motor].power_state = MOTOR_POWER_TIMEOUT_START;
}
-#ifdef __ARM
- common_enable.clear(); // enable gShield common enable
-#endif
}
void st_deenergize_motors()
for (uint8_t motor = MOTOR_1; motor < MOTORS; motor++) {
_deenergize_motor(motor);
}
-#ifdef __ARM
- common_enable.set(); // disable gShield common enable
-#endif
}
/*
* ISR - DDA timer interrupt routine - service ticks from DDA timer
*/
-#ifdef __AVR
/*
* Uses direct struct addresses and literal values for hardware devices - it's faster than
* using indexed timer and port accesses. I checked. Even when -0s or -03 is used.
TIMER_DDA.CTRLA = STEP_TIMER_DISABLE; // disable DDA timer
_load_move(); // load the next move
}
-#endif // __AVR
-
-#ifdef __ARM
-/*
- * This interrupt is really 2 interrupts. It fires on timer overflow and also on match.
- * Overflow interrupts are used to set step pins, match interrupts clear step pins.
- * This way the duty cycle of the stepper pulse can be controlled by setting the match value.
- *
- * Note that the motor_N.step.isNull() tests are compile-time tests, not run-time tests.
- * If motor_N is not defined that if{} clause (i.e. that motor) drops out of the complied code.
- */
-namespace Motate { // Must define timer interrupts inside the Motate namespace
-MOTATE_TIMER_INTERRUPT(dda_timer_num)
-{
-// dda_debug_pin1 = 1;
- uint32_t interrupt_cause = dda_timer.getInterruptCause(); // also clears interrupt condition
-
- if (interrupt_cause == kInterruptOnOverflow) {
-
- if (!motor_1.step.isNull() && (st_run.mot[MOTOR_1].substep_accumulator += st_run.mot[MOTOR_1].substep_increment) > 0) {
- motor_1.step.set(); // turn step bit on
- st_run.mot[MOTOR_1].substep_accumulator -= st_run.dda_ticks_X_substeps;
- INCREMENT_ENCODER(MOTOR_1);
- }
- if (!motor_2.step.isNull() && (st_run.mot[MOTOR_2].substep_accumulator += st_run.mot[MOTOR_2].substep_increment) > 0) {
- motor_2.step.set();
- st_run.mot[MOTOR_2].substep_accumulator -= st_run.dda_ticks_X_substeps;
- INCREMENT_ENCODER(MOTOR_2);
- }
- if (!motor_3.step.isNull() && (st_run.mot[MOTOR_3].substep_accumulator += st_run.mot[MOTOR_3].substep_increment) > 0) {
- motor_3.step.set();
- st_run.mot[MOTOR_3].substep_accumulator -= st_run.dda_ticks_X_substeps;
- INCREMENT_ENCODER(MOTOR_3);
- }
- if (!motor_4.step.isNull() && (st_run.mot[MOTOR_4].substep_accumulator += st_run.mot[MOTOR_4].substep_increment) > 0) {
- motor_4.step.set();
- st_run.mot[MOTOR_4].substep_accumulator -= st_run.dda_ticks_X_substeps;
- INCREMENT_ENCODER(MOTOR_4);
- }
- if (!motor_5.step.isNull() && (st_run.mot[MOTOR_5].substep_accumulator += st_run.mot[MOTOR_5].substep_increment) > 0) {
- motor_5.step.set();
- st_run.mot[MOTOR_5].substep_accumulator -= st_run.dda_ticks_X_substeps;
- INCREMENT_ENCODER(MOTOR_5);
- }
- if (!motor_6.step.isNull() && (st_run.mot[MOTOR_6].substep_accumulator += st_run.mot[MOTOR_6].substep_increment) > 0) {
- motor_6.step.set();
- st_run.mot[MOTOR_6].substep_accumulator -= st_run.dda_ticks_X_substeps;
- INCREMENT_ENCODER(MOTOR_6);
- }
-
- } else if (interrupt_cause == kInterruptOnMatchA) {
-// dda_debug_pin2 = 1;
- motor_1.step.clear(); // turn step bits off
- motor_2.step.clear();
- motor_3.step.clear();
- motor_4.step.clear();
- motor_5.step.clear();
- motor_6.step.clear();
-
- if (--st_run.dda_ticks_downcount != 0) return;
-
- // process end of segment
- dda_timer.stop(); // turn it off or it will keep stepping out the last segment
- _load_move(); // load the next move at the current interrupt level
-// dda_debug_pin2 = 0;
- }
-// dda_debug_pin1 = 0;
-} // MOTATE_TIMER_INTERRUPT
-} // namespace Motate
-#endif // __ARM
/***** Dwell Interrupt Service Routine **************************************************
* ISR - DDA timer interrupt routine - service ticks from DDA timer
*/
-#ifdef __AVR
ISR(TIMER_DWELL_ISR_vect) { // DWELL timer interrupt
if (--st_run.dda_ticks_downcount == 0) {
TIMER_DWELL.CTRLA = STEP_TIMER_DISABLE; // disable DWELL timer
_load_move();
}
}
-#endif
-#ifdef __ARM
-namespace Motate { // Must define timer interrupts inside the Motate namespace
-MOTATE_TIMER_INTERRUPT(dwell_timer_num)
-{
- dwell_timer.getInterruptCause(); // read SR to clear interrupt condition
- if (--st_run.dda_ticks_downcount == 0) {
- dwell_timer.stop();
- _load_move();
- }
-}
-} // namespace Motate
-#endif
/****************************************************************************************
* Exec sequencing code - computes and prepares next load segment
* exec_timer interrupt - interrupt handler for calling exec function
*/
-#ifdef __AVR
void st_request_exec_move()
{
if (st_pre.buffer_state == PREP_BUFFER_OWNED_BY_EXEC) {// bother interrupting
}
}
}
-#endif // __AVR
-
-#ifdef __ARM
-void st_request_exec_move()
-{
- if (st_pre.buffer_state == PREP_BUFFER_OWNED_BY_EXEC) {// bother interrupting
- exec_timer.setInterruptPending();
- }
-}
-
-namespace Motate { // Define timer inside Motate namespace
- MOTATE_TIMER_INTERRUPT(exec_timer_num) // exec move SW interrupt
- {
- exec_timer.getInterruptCause(); // clears the interrupt condition
- if (st_pre.buffer_state == PREP_BUFFER_OWNED_BY_EXEC) {
- if (mp_exec_move() != STAT_NOOP) {
- st_pre.buffer_state = PREP_BUFFER_OWNED_BY_LOADER; // flip it back
- _request_load_move();
- }
- }
- }
-} // namespace Motate
-
-#endif // __ARM
/****************************************************************************************
* Loader sequencing code
* request a load (see st_request_load_move())
*/
-#ifdef __AVR
static void _request_load_move()
{
if (st_runtime_isbusy()) {
TIMER_LOAD.CTRLA = LOAD_TIMER_DISABLE; // disable SW interrupt timer
_load_move();
}
-#endif // __AVR
-
-#ifdef __ARM
-static void _request_load_move()
-{
- if (st_runtime_isbusy()) {
- return; // don't request a load if the runtime is busy
- }
- if (st_pre.buffer_state == PREP_BUFFER_OWNED_BY_LOADER) { // bother interrupting
- load_timer.setInterruptPending();
- }
-}
-namespace Motate { // Define timer inside Motate namespace
- MOTATE_TIMER_INTERRUPT(load_timer_num) // load steppers SW interrupt
- {
- load_timer.getInterruptCause(); // read SR to clear interrupt condition
- _load_move();
- }
-} // namespace Motate
-#endif // __ARM
/****************************************************************************************
* _load_move() - Dequeue move and load into stepper struct
* - If axis has 0 steps the direction setting can be omitted
* - If axis has 0 steps the motor must not be enabled to support power mode = 1
*/
-/****** WARNING - THIS CODE IS SPECIFIC TO AVR. SEE G2 FOR ARM CODE ******/
-
static void _load_move()
{
// Be aware that dda_ticks_downcount must equal zero for the loader to run.
return; // exit if the runtime is busy
}
if (st_pre.buffer_state != PREP_BUFFER_OWNED_BY_LOADER) { // if there are no moves to load...
-// for (uint8_t motor = MOTOR_1; motor < MOTORS; motor++) {
-// st_run.mot[motor].power_state = MOTOR_POWER_TIMEOUT_START; // ...start motor power timeouts
-// }
- return;
+ return;
}
// handle aline loads first (most common case)
if (st_pre.move_type == MOVE_TYPE_ALINE) {
static void _set_hw_microsteps(const uint8_t motor, const uint8_t microsteps)
{
-#ifdef __ARM
- switch (motor) {
- if (!motor_1.enable.isNull()) case (MOTOR_1): { motor_1.setMicrosteps(microsteps); break; }
- if (!motor_2.enable.isNull()) case (MOTOR_2): { motor_2.setMicrosteps(microsteps); break; }
- if (!motor_3.enable.isNull()) case (MOTOR_3): { motor_3.setMicrosteps(microsteps); break; }
- if (!motor_4.enable.isNull()) case (MOTOR_4): { motor_4.setMicrosteps(microsteps); break; }
- if (!motor_5.enable.isNull()) case (MOTOR_5): { motor_5.setMicrosteps(microsteps); break; }
- if (!motor_6.enable.isNull()) case (MOTOR_6): { motor_6.setMicrosteps(microsteps); break; }
- }
-#endif //__ARM
-#ifdef __AVR
- if (microsteps == 8) {
+ if (microsteps == 8) {
hw.st_port[motor]->OUTSET = MICROSTEP_BIT_0_bm;
hw.st_port[motor]->OUTSET = MICROSTEP_BIT_1_bm;
} else if (microsteps == 4) {
hw.st_port[motor]->OUTCLR = MICROSTEP_BIT_0_bm;
hw.st_port[motor]->OUTCLR = MICROSTEP_BIT_1_bm;
}
-#endif // __AVR
}
*/
stat_t st_set_pl(nvObj_t *nv) // motor power level
{
-#ifdef __ARM
- if (nv->value < (float)0.0) nv->value = 0.0;
- if (nv->value > (float)1.0) {
- if (nv->value > (float)100) nv->value = 1;
- nv->value /= 100; // accommodate old 0-100 inputs
- }
- set_flt(nv); // set power_setting value in the motor config struct (st)
-
- uint8_t m = _get_motor(nv);
- st_cfg.mot[m].power_level_scaled = (nv->value * POWER_LEVEL_SCALE_FACTOR);
- st_run.mot[m].power_level_dynamic = (st_cfg.mot[m].power_level_scaled);
- _set_motor_power_level(m, st_cfg.mot[m].power_level_scaled);
-#endif
- return(STAT_OK);
+ return(STAT_OK);
}
/*
*
* At 50 KHz constant clock rate we have 20 uSec between pulse timer (DDA) interrupts.
* On the Xmega we consume <10 uSec in the interrupt - a whopping 50% of available cycles
- * going into pulse generation. On the ARM this is less of an issue, and we run a
- * 100 Khz (or higher) pulse rate.
+ * going into pulse generation.
*
* - Pulse timing is also helped by minimizing the time spent loading the next move
* segment. The time budget for the load is less than the time remaining before the
MOTOR_POWER_MODE_MAX_VALUE // for input range checking
};
-// Stepper power management settings (applicable to ARM only)
-#define Vcc 3.3 // volts
-#define MaxVref 2.25 // max vref for driver circuit. Our ckt is 2.25 volts
-#define POWER_LEVEL_SCALE_FACTOR ((MaxVref/Vcc)) // scale power level setting for voltage range
-
// Min/Max timeouts allowed for motor disable. Allow for inertial stop; must be non-zero
#define MOTOR_TIMEOUT_SECONDS_MIN (float)0.1 // seconds !!! SHOULD NEVER BE ZERO !!!
#define MOTOR_TIMEOUT_SECONDS_MAX (float)4294967 // (4294967295/1000) -- for conversion to uint32_t
* 0.90 == a safety factor used to reduce the result from theoretical maximum
*
* The number is about 8.5 million for the Xmega running a 50 KHz DDA with 5 millisecond segments
- * The ARM is about 1/4 that (or less) as the DDA clock rate is 4x higher. Decreasing the nominal
- * segment time increases the number precision.
*/
#define DDA_SUBSTEPS ((MAX_LONG * 0.90) / (FREQUENCY_DDA * (NOM_SEGMENT_TIME * 60)))
int32_t substep_accumulator; // DDA phase angle accumulator
uint8_t power_state; // state machine for managing motor power
uint32_t power_systick; // sys_tick for next motor power state transition
- float power_level_dynamic; // power level for this segment of idle (ARM only)
} stRunMotor_t;
typedef struct stRunSingleton { // Stepper static values and axis parameters
* regardless of board type but are extraneous for v7 boards.
*/
#define PIN_MODE PORT_OPC_PULLUP_gc // pin mode. see iox192a3.h for details
-//#define PIN_MODE PORT_OPC_TOTEM_gc // alternate pin mode for v7 boards
void switch_init(void)
{
for (uint8_t i=0; i<NUM_SWITCH_PAIRS; i++) {
- // old code from when switches fired on one edge or the other:
- // uint8_t int_mode = (sw.switch_type == SW_TYPE_NORMALLY_OPEN) ? PORT_ISC_FALLING_gc : PORT_ISC_RISING_gc;
-
- // setup input bits and interrupts (previously set to inputs by st_init())
+ // setup input bits and interrupts (previously set to inputs by st_init())
if (sw.mode[MIN_SWITCH(i)] != SW_MODE_DISABLED) {
hw.sw_port[i]->DIRCLR = SW_MIN_BIT_bm; // set min input - see 13.14.14
hw.sw_port[i]->PIN6CTRL = (PIN_MODE | PORT_ISC_BOTHEDGES_gc);
if (sw.count[i] == 0) { // trigger point
sw.sw_num_thrown = i; // record number of thrown switch
sw.debounce[i] = SW_LOCKOUT;
-// sw_show_switch(); // only called if __DEBUG enabled
if ((cm.cycle_state == CYCLE_HOMING) || (cm.cycle_state == CYCLE_PROBE)) { // regardless of switch type
cm_request_feedhold();
}
}
-/*
- * _show_switch() - simple display routine
- */
-/*
-void sw_show_switch(void)
-{
- fprintf_P(stderr, PSTR("Limit Switch Thrown Xmin %d Xmax %d Ymin %d Ymax %d \
- Zmin %d Zmax %d Amin %d Amax %d\n"),
- sw.state[SW_MIN_X], sw.state[SW_MAX_X],
- sw.state[SW_MIN_Y], sw.state[SW_MAX_Y],
- sw.state[SW_MIN_Z], sw.state[SW_MAX_Z],
- sw.state[SW_MIN_A], sw.state[SW_MAX_A]);
-}
-*/
/***********************************************************************************
* CONFIGURATION AND INTERFACE FUNCTIONS
static const char fmt_st[] PROGMEM = "[st] switch type%18d [0=NO,1=NC]\n";
void sw_print_st(nvObj_t *nv) { text_print_ui8(nv, fmt_st);}
-//static const char fmt_ss[] PROGMEM = "Switch %s state: %d\n";
-//void sw_print_ss(nvObj_t *nv) { fprintf(stderr, fmt_ss, nv->token, (uint8_t)nv->value);}
-
-/*
-static const char msg_sw0[] PROGMEM = "Disabled";
-static const char msg_sw1[] PROGMEM = "NO homing";
-static const char msg_sw2[] PROGMEM = "NO homing & limit";
-static const char msg_sw3[] PROGMEM = "NC homing";
-static const char msg_sw4[] PROGMEM = "NC homing & limit";
-static const char *const msg_sw[] PROGMEM = { msg_sw0, msg_sw1, msg_sw2, msg_sw3, msg_sw4 };
-*/
-
-
#endif
-
-/*============== G2 switch code - completely different, for now ===================
-
-#include "tinyg2.h"
-#include "switch.h"
-#include "hardware.h"
-#include "canonical_machine.h"
-
-// Allocate switch array structure
-switches_t sw;
-
-static void _no_action(switch_t *s);
-static void _led_on(switch_t *s);
-static void _led_off(switch_t *s);
-static void _trigger_feedhold(switch_t *s);
-static void _trigger_cycle_start(switch_t *s);
-
- *
- * switch_init() - initialize homing/limit switches
- *
- * This function assumes all Motate pins have been set up and that
- * SW_PAIRS and SW_POSITIONS is accurate
- *
- * Note: `type` and `mode` are not initialized as they should be set from configuration
- *
-
-void switch_init(void)
-{
-// sw.type = SW_NORMALLY_OPEN; // set from config
-
- switch_t *s; // shorthand
-
- for (uint8_t axis=0; axis<SW_PAIRS; axis++) {
- for (uint8_t position=0; position<SW_POSITIONS; position++) {
- s = &sw.s[axis][position];
-
- s->type = sw.type; // propagate type from global type
-// s->mode = SW_MODE_DISABLED; // set from config
- s->state = false;
- s->edge = SW_NO_EDGE;
- s->debounce_ticks = SW_LOCKOUT_TICKS;
- s->debounce_timeout = 0;
-
- // functions bound to each switch
- s->when_open = _no_action;
- s->when_closed = _no_action;
- s->on_leading = _trigger_feedhold;
- s->on_trailing = _trigger_cycle_start;
- }
- }
- // functions bound to individual switches
- // <none>
- // sw.s[AXIS_X][SW_MIN].when_open = _led_off;
- // sw.s[AXIS_X][SW_MIN].when_closed = _led_on;
-}
-
-static void _no_action(switch_t *s) { return; }
-static void _led_on(switch_t *s) { IndicatorLed.clear(); }
-static void _led_off(switch_t *s) { IndicatorLed.set(); }
-
- *
- * poll_switches() - run a polling cycle on all switches
- *
-
-stat_t poll_switches()
-{
- read_switch(&sw.s[AXIS_X][SW_MIN], axis_X_min_pin);
- read_switch(&sw.s[AXIS_X][SW_MAX], axis_X_max_pin);
- read_switch(&sw.s[AXIS_Y][SW_MIN], axis_Y_min_pin);
- read_switch(&sw.s[AXIS_Y][SW_MAX], axis_Y_max_pin);
- read_switch(&sw.s[AXIS_Z][SW_MIN], axis_Z_min_pin);
- read_switch(&sw.s[AXIS_Z][SW_MAX], axis_Z_max_pin);
- read_switch(&sw.s[AXIS_A][SW_MIN], axis_A_min_pin);
- read_switch(&sw.s[AXIS_A][SW_MAX], axis_A_max_pin);
- read_switch(&sw.s[AXIS_B][SW_MIN], axis_B_min_pin);
- read_switch(&sw.s[AXIS_B][SW_MAX], axis_B_max_pin);
- read_switch(&sw.s[AXIS_C][SW_MIN], axis_C_min_pin);
- read_switch(&sw.s[AXIS_C][SW_MAX], axis_C_max_pin);
- return (STAT_OK);
-}
-
- *
- * read_switch() - read switch with NO/NC, debouncing and edge detection
- *
- * Returns true if switch state changed - e.g. leading or falling edge detected
- * Assumes pin_value input = 1 means open, 0 is closed. Pin sense is adjusted to mean:
- * 0 = open for both NO and NC switches
- * 1 = closed for both NO and NC switches
- *
-uint8_t read_switch(switch_t *s, uint8_t pin_value)
-{
- // instant return conditions: switch disabled or in a lockout period
- if (s->mode == SW_MODE_DISABLED) {
- return (false);
- }
- if (s->debounce_timeout > GetTickCount()) {
- return (false);
- }
- // return if no change in state
- uint8_t pin_sense_corrected = (pin_value ^ (s->type ^ 1)); // correct for NO or NC mode
- if ( s->state == pin_sense_corrected) {
- s->edge = SW_NO_EDGE;
- if (s->state == SW_OPEN) {
- s->when_open(s);
- } else {
- s->when_closed(s);
- }
- return (false);
- }
- // the switch legitimately changed state - process edges
- if ((s->state = pin_sense_corrected) == SW_OPEN) {
- s->edge = SW_TRAILING;
- s->on_trailing(s);
- } else {
- s->edge = SW_LEADING;
- s->on_leading(s);
- }
- s->debounce_timeout = (GetTickCount() + s->debounce_ticks);
- return (true);
-}
-
-static void _trigger_feedhold(switch_t *s)
-{
- IndicatorLed.toggle();
- cm_request_feedhold();
-
-// if (cm.cycle_state == CYCLE_HOMING) { // regardless of switch type
-// cm.request_feedhold = true;
-// } else if (s->mode & SW_LIMIT_BIT) { // set flag if it's a limit switch
-// cm.limit_tripped_flag = true;
-// }
-
-}
-
-static void _trigger_cycle_start(switch_t *s)
-{
- IndicatorLed.toggle();
- cm_request_cycle_start();
-}
-
- *
- * switch_get_switch_mode() - return switch mode setting
- * switch_get_limit_thrown() - return true if a limit was tripped
- * switch_get_sw_num() - return switch number most recently thrown
- *
-
-uint8_t get_switch_mode(uint8_t sw_num) { return (0);} // ++++
-
-*/
#ifndef test_h
#define test_h
-//#include <stdio.h> // needed for FILE def'n
-
uint8_t run_test(nvObj_t *nv);
void run_canned_startup(void);
uint32_t segments;
float velocity;
float microseconds;
-// float position_x;
-// float target_x;
-// float step_x;
-// float move_time;
-// float accel_time;
};
struct mpSegmentLog sl[SEGMENT_LOGGER_MAX];
uint16_t sl_index;
uint32_t segment_count,
float velocity,
float microseconds
-// float position_x,
-// float target_x,
-// float step_x,
-// float move_time,
-// float accel_time
- );
+ );
#define SEGMENT_LOGGER segment_logger(bf->move_state, \
mr.linenum, mr.segments, mr.segment_count, \
mr.segment_velocity, \
mr.microseconds);
-/*
- mr.microseconds, \
- mr.position[X], \
- mr.target[X], \
- steps[X], \
- mr.segment_move_time, \
- mr.segment_accel_time);
-*/
#else
#define SEGMENT_LOGGER
#endif // __SEGMENT_LOGGER
#include "util.h"
#include "xio.h" // for ASCII char definitions
-#ifdef __cplusplus
-extern "C"{
-#endif
-
txtSingleton_t txt; // declare the singleton for either __TEXT_MODE setting
#ifndef __TEXT_MODE
#endif // __TEXT_MODE
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
#ifndef TEXT_PARSER_H_ONCE
#define TEXT_PARSER_H_ONCE
-#ifdef __cplusplus
-extern "C"{
-#endif
-
enum textVerbosity {
TV_SILENT = 0, // no response is provided
TV_VERBOSE // response is provided. Error responses ech message and failed commands
void text_response_stub(const stat_t status, char_t *buf);
void text_print_list_stub(stat_t status, uint8_t flags);
-#ifdef __cplusplus
-}
-#endif
-
#endif // End of include guard: TEXT_PARSER_H_ONCE
#include <string.h>
#include <math.h>
-//#include "MotatePins.h"
-
/****** REVISIONS ******/
#ifndef TINYG_FIRMWARE_BUILD
//#define __DEBUG_SETTINGS // special settings. See settings.h
//#define __CANNED_STARTUP // run any canned startup moves
-//#ifndef WEAK
-//#define WEAK __attribute__ ((weak))
-//#endif
-
-/************************************************************************************
- ***** PLATFORM COMPATIBILITY *******************************************************
- ************************************************************************************/
-#undef __AVR
-#define __AVR
-//#undef __ARM
-//#define __ARM
-
-/*********************
- * AVR Compatibility *
- *********************/
-#ifdef __AVR
-
#include <avr/pgmspace.h> // defines PROGMEM and PSTR
-typedef char char_t; // ARM/C++ version uses uint8_t as char_t
+typedef char char_t;
// gets rely on nv->index having been set
#define GET_TABLE_WORD(a) pgm_read_word(&cfgArray[nv->index].a) // get word value from cfgArray
// String compatibility
#define strtof strtod // strtof is not in the AVR lib
-#endif // __AVR
-
-/*********************
- * ARM Compatibility *
- *********************/
-#ifdef __ARM
- // Use macros to fake out AVR's PROGMEM and other AVRisms.
-#define PROGMEM // ignore PROGMEM declarations in ARM/GCC++
-#define PSTR (const char *) // AVR macro is: PSTR(s) ((const PROGMEM char *)(s))
-
-typedef char char_t; // In the ARM/GCC++ version char_t is typedef'd to uint8_t
- // because in C++ uint8_t and char are distinct types and
- // we want chars to behave as uint8's
-
- // gets rely on nv->index having been set
-#define GET_TABLE_WORD(a) cfgArray[nv->index].a // get word value from cfgArray
-#define GET_TABLE_BYTE(a) cfgArray[nv->index].a // get byte value from cfgArray
-#define GET_TABLE_FLOAT(a) cfgArray[nv->index].a // get byte value from cfgArray
-#define GET_TOKEN_BYTE(i,a) (char_t)cfgArray[i].a // get token byte value from cfgArray
-
-#define GET_TOKEN_STRING(i,a) cfgArray[(index_t)i].a
-//#define GET_TOKEN_STRING(i,a) (char_t)cfgArray[i].token)// populate the token string given the index
-
-#define GET_TEXT_ITEM(b,a) b[a] // get text from an array of strings in flash
-#define GET_UNITS(a) msg_units[cm_get_units_mode(a)]
-
-// IO settings
-#define DEV_STDIN 0 // STDIO defaults - stdio is not yet used in the ARM version
-#define DEV_STDOUT 0
-#define DEV_STDERR 0
-
-/* String compatibility
- *
- * The ARM stdio functions we are using still use char as input and output. The macros
- * below do the casts for most cases, but not all. Vararg functions like the printf()
- * family need special handling. These like char * as input and require casts as per:
- *
- * printf((const char *)"Good Morning Hoboken!\n");
- *
- * The AVR also has "_P" variants that take PROGMEM strings as args.
- * On the ARM/GCC++ the _P functions are just aliases of the non-P variants.
- */
-#define strncpy(d,s,l) (char_t *)strncpy((char *)d, (char *)s, l)
-#define strpbrk(d,s) (char_t *)strpbrk((char *)d, (char *)s)
-#define strcpy(d,s) (char_t *)strcpy((char *)d, (char *)s)
-#define strcat(d,s) (char_t *)strcat((char *)d, (char *)s)
-#define strstr(d,s) (char_t *)strstr((char *)d, (char *)s)
-#define strchr(d,s) (char_t *)strchr((char *)d, (char)s)
-#define strcmp(d,s) strcmp((char *)d, (char *)s)
-#define strtod(d,p) strtod((char *)d, (char **)p)
-#define strtof(d,p) strtof((char *)d, (char **)p)
-#define strlen(s) strlen((char *)s)
-#define isdigit(c) isdigit((char)c)
-#define isalnum(c) isalnum((char)c)
-#define tolower(c) (char_t)tolower((char)c)
-#define toupper(c) (char_t)toupper((char)c)
-
-#define printf_P printf // these functions want char * as inputs, not char_t *
-#define fprintf_P fprintf // just sayin'
-#define sprintf_P sprintf
-#define strcpy_P strcpy
-
-#endif // __ARM
-
/******************************************************************************
***** TINYG APPLICATION DEFINITIONS ******************************************
******************************************************************************/
#include "tinyg.h"
#include "util.h"
-#ifdef __AVR
#include "xmega/xmega_rtc.h"
-#endif
-
-#ifdef __cplusplus
-extern "C"{
-#endif
/**** Vector utilities ****
* copy_vector() - copy vector of arbitrary length
float vector[AXES]; // statically allocated global for vector utilities
-/*
-void copy_vector(float dst[], const float src[])
-{
- memcpy(dst, src, sizeof(dst));
-}
-*/
uint8_t vector_equal(const float a[], const float b[])
{
* escape_string() - add escapes to a string - currently for quotes only
*/
-/*
-uint8_t * strcpy_U( uint8_t * dst, const uint8_t * src )
-{
- uint16_t index = 0;
- do {
- dst[index] = src[index];
- } while (src[index++] != 0);
- return dst;
-}
-*/
-
uint8_t isnumber(char_t c)
{
if (c == '.') { return (true); }
}
/*
- * pstr2str() - return an AVR style progmem string as a RAM string. No effect on ARMs
+ * pstr2str() - return an AVR style progmem string as a RAM string.
*
- * This function deals with FLASH memory string confusion between the AVR serias and ARMs.
- * AVRs typically have xxxxx_P() functions which take strings from FLASH as args.
- * On ARMs there is no need for this as strings are handled identically in FLASH and RAM.
- *
- * This function copies a string from FLASH to a pre-allocated RAM buffer - see main.c for
- * allocation and max length. On the ARM it's a pass through that just returns the address
- * of the input string
+ * This function copies a string from FLASH to a pre-allocated RAM buffer -
+ * see main.c for allocation and max length.
*/
char_t *pstr2str(const char *pgm_string)
{
-#ifdef __AVR
- strncpy_P(global_string_buf, pgm_string, MESSAGE_LEN);
+ strncpy_P(global_string_buf, pgm_string, MESSAGE_LEN);
return (global_string_buf);
-#endif
-#ifdef __ARM
- return ((char_t *)pgm_string);
-#endif
}
/*
* SysTickTimer_getValue() - this is a hack to get around some compatibility problems
*/
-#ifdef __AVR
uint32_t SysTickTimer_getValue()
{
return (rtc.sys_ticks);
}
-#endif // __AVR
-
-#ifdef __ARM
-uint32_t SysTickTimer_getValue()
-{
- return (SysTickTimer.getValue());
-}
-#endif // __ARM
-
-#ifdef __cplusplus
-}
-#endif
#ifndef UTIL_H_ONCE
#define UTIL_H_ONCE
-#ifdef __ARM
-//#include <stdint.h>
-//#include "sam.h"
-#include "MotateTimers.h"
-using Motate::delay;
-using Motate::SysTickTimer;
-#endif
-
-#ifdef __cplusplus
-extern "C"{
-#endif
-
/****** Global Scope Variables and Functions ******/
//*** vector utilities ***
//*** string utilities ***
-//#ifdef __ARM
-//char_t * strcpy_U( char_t * dst, const char_t * src );
-//#endif
-
uint8_t isnumber(char_t c);
char_t *escape_string(char_t *dst, char_t *src);
char_t *pstr2str(const char *pgm_string);
#define uSec(a) ((float)(a * MICROSECONDS_PER_MINUTE))
#define RADIAN (57.2957795)
-// M_PI is pi as defined in math.h
-// M_SQRT2 is radical2 as defined in math.h
#ifndef M_SQRT3
#define M_SQRT3 (1.73205080756888)
#endif
-#ifdef __cplusplus
-}
-#endif
-
#endif // End of include guard: UTIL_H_ONCE
if (ds[XIO_DEV_SPI1].magic_end != MAGICNUM) return (STAT_XIO_ASSERTION_FAILURE);
if (ds[XIO_DEV_SPI2].magic_start != MAGICNUM) return (STAT_XIO_ASSERTION_FAILURE);
if (ds[XIO_DEV_SPI2].magic_end != MAGICNUM) return (STAT_XIO_ASSERTION_FAILURE);
-// if (ds[XIO_DEV_PGM].magic_start != MAGICNUM) return (STAT_XIO_ASSERTION_FAILURE);
-// if (ds[XIO_DEV_PGM].magic_end != MAGICNUM) return (STAT_XIO_ASSERTION_FAILURE);
- if (stderr != xio.stderr_shadow) return (STAT_XIO_ASSERTION_FAILURE);
+ if (stderr != xio.stderr_shadow) return (STAT_XIO_ASSERTION_FAILURE);
return (STAT_OK);
}
#define CHAR_FEEDHOLD (char)'!'
#define CHAR_CYCLE_START (char)'~'
#define CHAR_QUEUE_FLUSH (char)'%'
-//#define CHAR_BOOTLOADER ESC
/* XIO return codes
* These codes are the "inner nest" for the STAT_ return codes.