diff --git a/.github/workflows/build_g2.yml b/.github/workflows/build_g2.yml index 71cad09d7..5d81a3b40 100644 --- a/.github/workflows/build_g2.yml +++ b/.github/workflows/build_g2.yml @@ -1,4 +1,4 @@ -name: C/C++ CI +name: Build G2 on: push: @@ -10,19 +10,21 @@ on: # branches: jobs: - checkout: - name: checkout the repo with submodules + Build: + name: Checkout and Build runs-on: ubuntu-latest steps: - - uses: actions/checkout@v1 + + - uses: actions/checkout@v3 with: submodules: recursive + - name: Cache Tools id: cache-tools - uses: actions/cache@v1 + uses: actions/cache@v3 with: path: ./Motate/Tools/linux - key: ${{ runner.os }}-tools-02 # Change the number to invalidate the tools caches + key: ${{ runner.os }}-tools-03 # Change the number to invalidate the tools caches - name: prepare working-directory: ${{ github.workspace }}/g2core/ diff --git a/.vscode/launch.json b/.vscode/launch.json index 1ac79250d..188bab16b 100644 --- a/.vscode/launch.json +++ b/.vscode/launch.json @@ -29,9 +29,9 @@ "request": "launch", "servertype": "jlink", "cwd": "${workspaceRoot}/g2core/", - "executable": "./bin/r7-gquintic-d/g2core.elf", - "device": "ATSAMS70N19", - "svdFile": "${workspaceRoot}/Motate/MotateProject/motate/cmsis/TARGET_Atmel/sams70/ATSAMS70N19.svd", + "executable": "./bin/r7-gquintic-g/g2core.elf", + "device": "ATSAMS70N20", + "svdFile": "${workspaceRoot}/Motate/MotateProject/motate/cmsis/TARGET_Atmel/sams70/ATSAMS70N20B.svd", "interface": "swd", "showDevDebugOutput": "none", "osx": { diff --git a/Docker/Dockerfile b/Docker/Dockerfile new file mode 100644 index 000000000..8f7802c7f --- /dev/null +++ b/Docker/Dockerfile @@ -0,0 +1,44 @@ +# Use a Debian-based image as a parent image +FROM debian:buster-slim + +# Install build-essential, git, and uucp +RUN apt-get update && DEBIAN_FRONTEND=noninteractive apt-get install -y build-essential git wget xz-utils uucp bossa-cli + +# Set the working directory to /app +WORKDIR /app + +# Clone the g2 GitHub repo +RUN git clone https://github.com/synthetos/g2.git && \ + cd g2 && \ + git submodule init && \ + git submodule update + +RUN mkdir -p /app/g2/Motate/Tools/linux && \ + wget -P /app/g2/Motate/Tools/linux https://github.com/synthetos/gcc-arm-none-eabi-archive/releases/download/12.2.Rel1/arm-gnu-toolchain-12.2.rel1-linux-x86_64-arm-none-eabi.tar.xz + + + +#Extract the toolchain archive to the directory + +RUN cd /app/g2/Motate/Tools/linux && \ + tar xf arm-gnu-toolchain-12.2.rel1-linux-x86_64-arm-none-eabi.tar.xz && \ + rm -f "arm-gnu-toolchain-12.2.rel1-linux-x86_64-arm-none-eabi.tar.xz" + +RUN apt-get install dos2unix + +# Set the TERM environment variable +ENV TERM=xterm + +# Set the working directory to the cloned repo directory +WORKDIR /app/g2/g2core + +# Create a volume for storing build output +VOLUME /app/g2/g2core/bin + +COPY entrypoint.sh /app/entrypoint.sh +RUN dos2unix /app/entrypoint.sh +ENTRYPOINT ["/app/entrypoint.sh"] + + +# Define the default command to run the build +#CMD ["BOARD=gShield", "SETTINGS=default_settings.h"] \ No newline at end of file diff --git a/Docker/entrypoint.sh b/Docker/entrypoint.sh new file mode 100644 index 000000000..2fce5e25d --- /dev/null +++ b/Docker/entrypoint.sh @@ -0,0 +1,28 @@ +#!/bin/bash + +set -e + + +if [ "$1" == "--build" ]; then + BOARD="$2" + SETTINGS="$3" + if [ -z "$2" ] || [ -z "$3" ]; then + echo "Usage: $0 --build BOARD SETTING" + exit 1 + fi + + if [ ! -f "/app/g2/g2core/settings/$SETTINGS" ]; then + echo "Error: Settings file not found: /g2/g2core/settings/$SETTINGS" + exit 1 + fi + + + + + echo "Building g2core for board $BOARD with setting $SETTINGS" + echo "Build started in 5 seconds..." + sleep 5 + cd /app/g2/g2core + make BOARD="$BOARD" SETTINGS_FILE="$SETTINGS" +fi + diff --git a/Motate b/Motate index ce6585499..7d156279d 160000 --- a/Motate +++ b/Motate @@ -1 +1 @@ -Subproject commit ce6585499db1d282c1b93296c9c3c7b0603dc63d +Subproject commit 7d156279d9b079b91405e0b6d479dd3fa51a2640 diff --git a/g2core.xcworkspace/contents.xcworkspacedata b/g2core.xcworkspace/contents.xcworkspacedata deleted file mode 100644 index 3021249bf..000000000 --- a/g2core.xcworkspace/contents.xcworkspacedata +++ /dev/null @@ -1,10 +0,0 @@ - - - - - - - diff --git a/g2core/boards.mk b/g2core/boards.mk index b545fb72f..573caa868 100644 --- a/g2core/boards.mk +++ b/g2core/boards.mk @@ -65,6 +65,13 @@ ifeq ("$(CONFIG)","MiniMillrevD") SETTINGS_FILE="settings_minimill.h" endif +ifeq ("$(CONFIG)","EnderLaser") + ifeq ("$(BOARD)","NONE") + BOARD=gquintic-g + endif + SETTINGS_FILE="settings_ender_laser.h" +endif + ifeq ("$(CONFIG)","MiniMill") ifeq ("$(BOARD)","NONE") BOARD=gquintic-g diff --git a/g2core/cycle_homing.cpp b/g2core/cycle_homing.cpp index 2873aa48d..8016989cf 100644 --- a/g2core/cycle_homing.cpp +++ b/g2core/cycle_homing.cpp @@ -50,6 +50,8 @@ struct hmHomingSingleton { // persistent homing runtime variables stat_t (*func)(int8_t axis); // binding for callback function state machine bool axis_flags[AXES]; // local storage for axis flags + uint8_t axis_moves_needed; + uint8_t axis_move; // per-axis parameters float direction; // set to 1 for positive (max), -1 for negative (to min); @@ -199,6 +201,8 @@ stat_t cm_homing_cycle_start(const float axes[], const bool flags[]) { hm.axis = -1; // set to retrieve initial axis hm.func = _homing_axis_start; // bind initial processing function + hm.axis_moves_needed = 0; + hm.axis_move = 0; cm->machine_state = MACHINE_CYCLE; cm->cycle_type = CYCLE_HOMING; cm->homing_state = HOMING_NOT_HOMED; @@ -303,7 +307,7 @@ static stat_t _homing_axis_start(int8_t axis) { hm.homing_input = cm->a[axis].homing_input; din_handlers[INPUT_ACTION_INTERNAL].registerHandler(&_homing_handler); - hm.axis = axis; // persist the axis + hm.axis = axis; // persist the axis hm.search_velocity = std::abs(cm->a[axis].search_velocity); // search velocity is always positive hm.latch_velocity = std::abs(cm->a[axis].latch_velocity); // latch velocity is always positive @@ -311,18 +315,18 @@ static stat_t _homing_axis_start(int8_t axis) { // setup parameters for positive or negative travel (homing to the max or min switch) if (homing_to_max) { - hm.search_travel = travel_distance; // search travels in positive direction - hm.latch_backoff = std::abs(cm->a[axis].latch_backoff); // latch travels in positive direction - hm.zero_backoff = -std::max(0.0f, cm->a[axis].zero_backoff);// zero backoff is negative direction (or zero) - // will set the maximum position - // (plus any negative backoff) + hm.search_travel = travel_distance; // search travels in positive direction + hm.latch_backoff = std::abs(cm->a[axis].latch_backoff); // latch travels in positive direction + hm.zero_backoff = -std::max(0.0f, cm->a[axis].zero_backoff); // zero backoff is negative direction (or zero) + // will set the maximum position + // (plus any negative backoff) hm.setpoint = cm->a[axis].travel_max + (std::max(0.0f, -cm->a[axis].zero_backoff)); } else { - hm.search_travel = -travel_distance; // search travels in negative direction - hm.latch_backoff = -std::abs(cm->a[axis].latch_backoff); // latch travels in negative direction + hm.search_travel = -travel_distance; // search travels in negative direction + hm.latch_backoff = -std::abs(cm->a[axis].latch_backoff); // latch travels in negative direction hm.zero_backoff = std::max(0.0f, cm->a[axis].zero_backoff); // zero backoff is positive direction (or zero) - // will set the minimum position - // (minus any negative backoff) + // will set the minimum position + // (minus any negative backoff) hm.setpoint = cm->a[axis].travel_min + (std::max(0.0f, -cm->a[axis].zero_backoff)); } @@ -492,142 +496,163 @@ static stat_t _homing_finalize_exit(int8_t axis) // third part of return to hom */ static int8_t _get_next_axis(int8_t axis) { + if (hm.axis_moves_needed > hm.axis_move) { + kn->axis_set_homing_move(axis, hm.axis_move); + hm.axis_move++; + return axis; + } + + auto ret_axis = -1; // done #if (HOMING_AXES <= 4) if (axis == -1) { // inelegant brute force solution if (hm.axis_flags[AXIS_Z]) { - return (AXIS_Z); - } + ret_axis = AXIS_Z; + } else if (hm.axis_flags[AXIS_X]) { - return (AXIS_X); - } + ret_axis = AXIS_X; + } else if (hm.axis_flags[AXIS_Y]) { - return (AXIS_Y); - } + ret_axis = AXIS_Y; + } else if (hm.axis_flags[AXIS_A]) { - return (AXIS_A); - } + ret_axis = AXIS_A; + } else if (hm.axis_flags[AXIS_B]) { - return (AXIS_B); - } + ret_axis = AXIS_B; + } else if (hm.axis_flags[AXIS_C]) { - return (AXIS_C); + ret_axis = AXIS_C; + } else { + ret_axis = -2; // error } - return (-2); // error } else if (axis == AXIS_Z) { if (hm.axis_flags[AXIS_X]) { - return (AXIS_X); - } + ret_axis = AXIS_X; + } else if (hm.axis_flags[AXIS_Y]) { - return (AXIS_Y); - } + ret_axis = AXIS_Y; + } else if (hm.axis_flags[AXIS_A]) { - return (AXIS_A); - } + ret_axis = AXIS_A; + } else if (hm.axis_flags[AXIS_B]) { - return (AXIS_B); - } + ret_axis = AXIS_B; + } else if (hm.axis_flags[AXIS_C]) { - return (AXIS_C); + ret_axis = AXIS_C; } } else if (axis == AXIS_X) { if (hm.axis_flags[AXIS_Y]) { - return (AXIS_Y); - } + ret_axis = AXIS_Y; + } else if (hm.axis_flags[AXIS_A]) { - return (AXIS_A); - } + ret_axis = AXIS_A; + } else if (hm.axis_flags[AXIS_B]) { - return (AXIS_B); - } + ret_axis = AXIS_B; + } else if (hm.axis_flags[AXIS_C]) { - return (AXIS_C); + ret_axis = AXIS_C; } } else if (axis == AXIS_Y) { if (hm.axis_flags[AXIS_A]) { - return (AXIS_A); - } + ret_axis = AXIS_A; + } else if (hm.axis_flags[AXIS_B]) { - return (AXIS_B); - } + ret_axis = AXIS_B; + } else if (hm.axis_flags[AXIS_C]) { - return (AXIS_C); + ret_axis = AXIS_C; } } - return (-1); // done #else if (axis == -1) { if (hm.axis_flags[AXIS_Z]) { - return (AXIS_Z); - } + ret_axis = AXIS_Z; + } else if (hm.axis_flags[AXIS_X]) { - return (AXIS_X); - } + ret_axis = AXIS_X; + } else if (hm.axis_flags[AXIS_Y]) { - return (AXIS_Y); - } + ret_axis = AXIS_Y; + } else if (hm.axis_flags[AXIS_A]) { - return (AXIS_A); - } + ret_axis = AXIS_A; + } else if (hm.axis_flags[AXIS_B]) { - return (AXIS_B); - } + ret_axis = AXIS_B; + } else if (hm.axis_flags[AXIS_C]) { - return (AXIS_C); + ret_axis = AXIS_C; } - return (-2); // error + // ret_axis = -2; // error } else if (axis == AXIS_Z) { if (hm.axis_flags[AXIS_X]) { - return (AXIS_X); - } + ret_axis = AXIS_X; + } else if (hm.axis_flags[AXIS_Y]) { - return (AXIS_Y); - } + ret_axis = AXIS_Y; + } else if (hm.axis_flags[AXIS_A]) { - return (AXIS_A); - } + ret_axis = AXIS_A; + } else if (hm.axis_flags[AXIS_B]) { - return (AXIS_B); - } + ret_axis = AXIS_B; + } else if (hm.axis_flags[AXIS_C]) { - return (AXIS_C); + ret_axis = AXIS_C; } } else if (axis == AXIS_X) { if (hm.axis_flags[AXIS_Y]) { - return (AXIS_Y); - } + ret_axis = AXIS_Y; + } else if (hm.axis_flags[AXIS_A]) { - return (AXIS_A); - } + ret_axis = AXIS_A; + } else if (hm.axis_flags[AXIS_B]) { - return (AXIS_B); - } + ret_axis = AXIS_B; + } else if (hm.axis_flags[AXIS_C]) { - return (AXIS_C); + ret_axis = AXIS_C; } } else if (axis == AXIS_Y) { if (hm.axis_flags[AXIS_A]) { - return (AXIS_A); - } + ret_axis = AXIS_A; + } else if (hm.axis_flags[AXIS_B]) { - return (AXIS_B); - } + ret_axis = AXIS_B; + } else if (hm.axis_flags[AXIS_C]) { - return (AXIS_C); + ret_axis = AXIS_C; } } else if (axis == AXIS_A) { if (hm.axis_flags[AXIS_B]) { - return (AXIS_B); - } + ret_axis = AXIS_B; + } else if (hm.axis_flags[AXIS_C]) { - return (AXIS_C); + ret_axis = AXIS_C; } } else if (axis == AXIS_B) { if (hm.axis_flags[AXIS_C]) { - return (AXIS_C); + ret_axis = AXIS_C; } + } else { + ret_axis = -1; // done } - return (-1); // done #endif // (HOMING_AXES <= 4) + + if (ret_axis > 0) { + hm.axis_moves_needed = kn->axis_homing_moves(ret_axis); + hm.axis_move = 0; + kn->axis_set_homing_move(ret_axis, hm.axis_move); + hm.axis_move++; + } else { + hm.axis_moves_needed = 0; + hm.axis_move = 0; + kn->set_homing_done(); + } + + return ret_axis; } diff --git a/g2core/gpio.h b/g2core/gpio.h index 3bf7a87bd..5151506d4 100644 --- a/g2core/gpio.h +++ b/g2core/gpio.h @@ -116,7 +116,7 @@ extern gpioDigitalInputReader* const in_r[16]; * Example gpioDigitalInputHandler object creation: gpioDigitalInputHandler limitHandler { - [&](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { + [](const bool state, const inputEdgeFlag edge, const uint8_t triggering_pin_number) { if (edge != INPUT_EDGE_LEADING) { return; } limit_requested = true; // record that a limit was requested for later processing return false; // allow others to see this notice diff --git a/g2core/kinematics.h b/g2core/kinematics.h index 1a88fdec5..4d12f081c 100644 --- a/g2core/kinematics.h +++ b/g2core/kinematics.h @@ -75,6 +75,18 @@ struct KinematicsBase { // sync any external sensors with the current step position virtual void sync_encoders(const float step_position[motors], const float position[axes]); + + // homing support - since kinematics is between the stepper and the gcode, we put this here + + // how many moves will this axis need to home? normal is 1, but if it has two motors on it it may need 3 (see cartesian override) + virtual uint8_t axis_homing_moves(uint8_t axis) { return 1; } + + // set which of the axis moves will be homed next - may freeze motors or change the kinematics output somehow + // if move > axis_homing_moves(axis) then it clears homing for that axis + virtual void axis_set_homing_move(uint8_t axis, uint8_t move) { /* nothing to do */ } + + // called to give the opportunity to clean up after any homing setups + virtual void set_homing_done() { /* nothing to do here */ } }; extern KinematicsBase *kn; diff --git a/g2core/kinematics_cartesian.h b/g2core/kinematics_cartesian.h index 3707f6f11..15ee85316 100644 --- a/g2core/kinematics_cartesian.h +++ b/g2core/kinematics_cartesian.h @@ -62,13 +62,15 @@ struct CartesianKinematics : KinematicsBase { float motor_offset[motors]; bool needs_sync_encoders = true; // if true, we need to update the steps_offset int8_t motor_map[motors]; // for each motor, which joint it maps from - + bool hold_motor[motors]; // true if the motor is to be held when the axis moves - for homing only ATM float joint_position[joints]; + float last_known_steps[motors]; void configure(const float new_steps_per_unit[motors], const int8_t new_motor_map[motors]) override { for (uint8_t motor = 0; motor < motors; motor++) { motor_map[motor] = new_motor_map[motor]; + hold_motor[motor] = false; int8_t joint = motor_map[motor]; if (joint == -1) { motor_offset[motor] = 0; @@ -91,7 +93,13 @@ struct CartesianKinematics : KinematicsBase { continue; } - steps[motor] = (target[joint] * steps_per_unit[motor]) + motor_offset[motor]; + if (hold_motor[motor]) { + steps[motor] = last_known_steps[motor]; + motor_offset[motor] = steps[motor] - (target[joint] * steps_per_unit[motor]); + } else { + steps[motor] = (target[joint] * steps_per_unit[motor]) + motor_offset[motor]; + last_known_steps[motor] = steps[motor]; + } } for (uint8_t joint = 0; joint < joints; joint++) { @@ -148,7 +156,41 @@ struct CartesianKinematics : KinematicsBase { motor_offset[motor] = step_position[motor] - (position[joint] * steps_per_unit[motor]); } } -}; + + virtual uint8_t axis_homing_moves(uint8_t axis) { + uint8_t motors_used = 0; + for (uint8_t motor = 0; motor < motors; motor++) { + int8_t joint = motor_map[motor]; + if (joint == axis) { motors_used++; } + } + // if we have two or more motors, we need an additional (first) move for all motors together + if (motors_used > 1) { + motors_used++; + } + return motors_used; + } + + void axis_set_homing_move(uint8_t axis, uint8_t move) override { + uint8_t motors_seen = 0; + for (uint8_t motor = 0; motor < motors; motor++) { + int8_t joint = motor_map[motor]; + + // move == 0 means move all motors + // move == 1 mean hold all but the first motor + // move == 2 mean hold all but the second motor + if (joint == axis) { + motors_seen++; + hold_motor[motor] = (move != 0) && (motors_seen != move); + } + } + } + + void set_homing_done() override { + for (uint8_t motor = 0; motor < motors; motor++) { + hold_motor[motor] = false; + } + } +}; // CartesianKinematics // Support for CoreXY Kinematics - http://corexy.com/ @@ -212,6 +254,6 @@ struct CoreXYKinematics final : CartesianKinematics { position[0] = 0.5 * (deltaA + deltaB); position[1] = 0.5 * (deltaA - deltaB); } -}; +}; // CoreXYKinematics #endif // End of include Guard: KINEMATICS_CARTESIAN_H_ONCE diff --git a/g2core/settings/settings_ender_laser.h b/g2core/settings/settings_ender_laser.h new file mode 100644 index 000000000..d3ffe3f82 --- /dev/null +++ b/g2core/settings/settings_ender_laser.h @@ -0,0 +1,340 @@ +/* + * settings_minimill.h - OpenBuilds MiniMill support + * This file is part of the g2core project + * + * This file ("the software") is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License, version 2 as published by the + * Free Software Foundation. You should have received a copy of the GNU General Public + * License, version 2 along with the software. If not, see . + * + * As a special exception, you may use this file as part of a software library without + * restriction. Specifically, if other files instantiate templates or use macros or + * inline functions from this file, or you compile this file and link it with other + * files to produce an executable, this file does not by itself cause the resulting + * executable to be covered by the GNU General Public License. This exception does not + * however invalidate any other reasons why the executable file might be covered by the + * GNU General Public License. + * + * THE SOFTWARE IS DISTRIBUTED IN THE HOPE THAT IT WILL BE USEFUL, BUT WITHOUT ANY + * WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT + * SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF + * OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + */ + +/***********************************************************************/ +/**** Otherlab OtherMill profile ***************************************/ +/***********************************************************************/ + +// ***> NOTE: The init message must be a single line with no CRs or LFs +#define INIT_MESSAGE "Initializing configs to Ender Laser settings" + +//**** GLOBAL / GENERAL SETTINGS ****************************************************** + +#define JUNCTION_INTEGRATION_TIME 0.15 // cornering - between 0.10 and 2.00 (higher is faster) +#define CHORDAL_TOLERANCE 0.01 // chordal accuracy for arc drawing (in mm) + +#define HAS_LASER 1 // We have a laser, but no shark (yet) +#define HAS_PRESSURE 0 + +#define SOFT_LIMIT_ENABLE 0 // 0=off, 1=on +#define HARD_LIMIT_ENABLE 1 // 0=off, 1=on +#define SAFETY_INTERLOCK_ENABLE 1 // 0=off, 1=on + +#define SPINDLE_ENABLE_POLARITY 0 // 0=active low, 1=active high +#define SPINDLE_DIR_POLARITY 0 // 0=clockwise is low, 1=clockwise is high +#define SPINDLE_PAUSE_ON_HOLD true +#define SPINDLE_SPINUP_DELAY 1.5 // after unpausing and turning the spindle on, dwell for 1.5s + +#if HAS_LASER +// #define LASER_FIRE_PIN_NUMBER Motate::kOutput3_PinNumber // note this is a MOTATE pin number, NOT a GPIO pin number +#define LASER_FIRE_PIN_NUMBER Motate::kOutput7_PinNumber // note this is a MOTATE pin number, NOT a GPIO pin number +#define LASER_ENABLE_OUTPUT_NUMBER 4 +#define LASER_TOOL 5 // default tool is 5 - note that TOOLS may be limited to 5! +#define LASER_MIN_S 0.0001 // {th2mns:0.0001} +#define LASER_MAX_S 255.0 // {th2mxs:255.0} +#define LASER_MIN_PPM 100 // {th2mnp:100} +#define LASER_MAX_PPM 2500 // {th2mxp:2500} + +#define LASER_PULSE_DURATION 150 // in microseconds {th2pd:150} + + +/* +M100 ({th2pd:150}) ; laser on period +M100 ({th2mnp:100}) ; laser min pulses per mm +M100 ({th2mxp:1500}) ; laser max pulses per mm +*/ + +#define KINEMATICS KINE_OTHER // Due to it having the laser +#define BASE_KINEMATICS CartesianKinematics +// Another option is CoreXY: +// #define BASE_KINEMATICS CoreXYKinematics + +// Ensure that we set these - these should match the LASER_FIRE_PIN_NUMBER !!! +#define DO7_ENABLED IO_ENABLED +#define DO7_POLARITY IO_ACTIVE_HIGH +#define DO7_EXTERNAL_NUMBER 7 + +#else + +// #define KINEMATICS KINE_CARTESIAN +#define KINEMATICS KINE_PRESSURE + +#endif // HAS_LASER + +// Only used in Bantam mode +#define ESC_BOOT_TIME 5000 // how long the ESC takes to boot, in milliseconds +#define ESC_LOCKOUT_TIME 900 // how long the interlock needs to be engaged before killing power... actually 1s, but be conservative + +#define COOLANT_MIST_POLARITY 1 // 0=active low, 1=active high +#define COOLANT_FLOOD_POLARITY 1 // 0=active low, 1=active high +#define COOLANT_PAUSE_ON_HOLD true + +#define MIST_ENABLE_OUTPUT_NUMBER 0 +#define FLOOD_ENABLE_OUTPUT_NUMBER 0 + +#define SPINDLE_ENABLE_OUTPUT_NUMBER 4 +#define SPINDLE_DIRECTION_OUTPUT_NUMBER 5 +#define SPINDLE_PWM_NUMBER 6 + +#define FEEDHOLD_Z_LIFT 3 // mm to lift Z on feedhold +#define PROBE_REPORT_ENABLE true + +#define SPINDLE_SPEED_CHANGE_PER_MS 7 // external non-speed-controlled spindle, but we can use this as a built-in delay + +/* +// Switch definitions for interlock & E-stop +#define ENABLE_INTERLOCK_AND_ESTOP +#define INTERLOCK_SWITCH_AXIS AXIS_Y +#define INTERLOCK_SWITCH_POSITION SW_MAX +#define ESTOP_SWITCH_AXIS AXIS_X +#define ESTOP_SWITCH_POSITION SW_MAX +#define PAUSE_DWELL_TIME 1.5 //after unpausing and turning the spindle on, dwell for 1.5s +*/ + +// Communications and reporting settings + +#define USB_SERIAL_PORTS_EXPOSED 1 // Valid options are 1 or 2, only! + +#define COMM_MODE JSON_MODE // one of: TEXT_MODE, JSON_MODE +#define XIO_ENABLE_FLOW_CONTROL FLOW_CONTROL_RTS // FLOW_CONTROL_OFF, FLOW_CONTROL_RTS + +#define TEXT_VERBOSITY TV_VERBOSE // one of: TV_SILENT, TV_VERBOSE +#define JSON_VERBOSITY JV_MESSAGES // one of: JV_SILENT, JV_FOOTER, JV_CONFIGS, JV_MESSAGES, JV_LINENUM, JV_VERBOSE +#define QUEUE_REPORT_VERBOSITY QR_OFF // one of: QR_OFF, QR_SINGLE, QR_TRIPLE + +#define STATUS_REPORT_VERBOSITY SR_FILTERED // one of: SR_OFF, SR_FILTERED, SR_VERBOSE +#define STATUS_REPORT_MIN_MS 100 // milliseconds - enforces a viable minimum +#define STATUS_REPORT_INTERVAL_MS 100 // milliseconds - set $SV=0 to disable +//#define STATUS_REPORT_DEFAULTS "knfc", "stat", "knft", "knht", "prs1", "flow1slm", "flow1vol", "flow1prs", "feed", "knev", "kniv", "kndv", "knec", "knuoc", "knumc", "knpos1" +#define STATUS_REPORT_DEFAULTS "mpox", "mpoy", "mpoz", \ + "ofsx", "ofsy", "ofsz", \ + "g55x", "g55y", "g55z", \ + "unit", "stat", "coor", "momo", "dist", \ + "home", "mots", "plan", "line", "path", \ + "frmo", "prbe", "safe", "estp", "spc", \ + "hold", "macs", "cycs", "sps", "vel" + +// Gcode startup defaults +#define GCODE_DEFAULT_UNITS MILLIMETERS // MILLIMETERS or INCHES +#define GCODE_DEFAULT_PLANE CANON_PLANE_XY // CANON_PLANE_XY, CANON_PLANE_XZ, or CANON_PLANE_YZ +#define GCODE_DEFAULT_COORD_SYSTEM G55 // G54, G55, G56, G57, G58 or G59 +#define GCODE_DEFAULT_PATH_CONTROL PATH_CONTINUOUS +#define GCODE_DEFAULT_DISTANCE_MODE ABSOLUTE_DISTANCE_MODE + +// *** motor settings ************************************************************************************ + +// NOTE: Motor numbers are reversed from TinyGv8 in order to maintain compatibility with wiring harnesses + +#define MOTOR_POWER_LEVEL_XY 0.6 // default motor power level 0.00 - 1.00 +#define MOTOR_POWER_LEVEL_XY_IDLE 0.15 +#define MOTOR_POWER_LEVEL_Z 0.375 +#define MOTOR_POWER_LEVEL_Z_IDLE 0.15 +#define MOTOR_POWER_LEVEL_DISABLED 0.05 + +#define MOTOR_POWER_MODE MOTOR_POWER_REDUCED_WHEN_IDLE +#define MOTOR_POWER_TIMEOUT 2.00 // motor power timeout in seconds + +#define M1_MOTOR_MAP AXIS_X_EXTERNAL // 1ma +#define M1_STEP_ANGLE 1.8 // 1sa +#define M1_TRAVEL_PER_REV 8 // 1tr +#define M1_MICROSTEPS 32 // 1mi 1,2,4,8,16,32 +#define M1_POLARITY 0 // 1po 0=normal, 1=reversed +#define M1_POWER_MODE MOTOR_POWER_MODE // 1pm See enum cmMotorPowerMode in stepper.h +#define M1_POWER_LEVEL MOTOR_POWER_LEVEL_XY // 0.00=off, 1.00=max +#define M1_POWER_LEVEL_IDLE MOTOR_POWER_LEVEL_XY_IDLE + +#define M2_MOTOR_MAP AXIS_Y_EXTERNAL +#define M2_STEP_ANGLE 1.8 +#define M2_TRAVEL_PER_REV 8 +#define M2_MICROSTEPS 32 +#define M2_POLARITY 1 +#define M2_POWER_MODE MOTOR_POWER_MODE +#define M2_POWER_LEVEL MOTOR_POWER_LEVEL_XY +#define M2_POWER_LEVEL_IDLE MOTOR_POWER_LEVEL_XY_IDLE + +#define M3_MOTOR_MAP AXIS_Z_EXTERNAL +#define M3_STEP_ANGLE 1.8 +#define M3_TRAVEL_PER_REV 8 +#define M3_MICROSTEPS 32 +#define M3_POLARITY 0 +#define M3_POWER_MODE MOTOR_POWER_MODE +#define M3_POWER_LEVEL MOTOR_POWER_LEVEL_Z +#define M3_POWER_LEVEL_IDLE MOTOR_POWER_LEVEL_Z_IDLE + +#define M4_MOTOR_MAP AXIS_A_EXTERNAL +#define M4_STEP_ANGLE 1.8 +#define M4_TRAVEL_PER_REV 360 // degrees moved per motor rev +#define M4_MICROSTEPS 32 +#define M4_POLARITY 1 +#define M4_POWER_MODE MOTOR_DISABLED +#define M4_POWER_LEVEL MOTOR_POWER_LEVEL_DISABLED +#define M4_POWER_LEVEL_IDLE MOTOR_POWER_LEVEL_DISABLED + +#define M5_MOTOR_MAP AXIS_B_EXTERNAL +#define M5_STEP_ANGLE 1.8 +#define M5_TRAVEL_PER_REV 360 // degrees moved per motor rev +#define M5_MICROSTEPS 32 +#define M5_POLARITY 0 +#define M5_POWER_MODE MOTOR_DISABLED +#define M5_POWER_LEVEL MOTOR_POWER_LEVEL_DISABLED +#define M5_POWER_LEVEL_IDLE MOTOR_POWER_LEVEL_DISABLED + +#define M6_MOTOR_MAP AXIS_C_EXTERNAL +#define M6_STEP_ANGLE 1.8 +#define M6_TRAVEL_PER_REV 360 // degrees moved per motor rev +#define M6_MICROSTEPS 32 +#define M6_POLARITY 0 +#define M6_POWER_MODE MOTOR_DISABLED +#define M6_POWER_LEVEL MOTOR_POWER_LEVEL_DISABLED +#define M6_POWER_LEVEL_IDLE MOTOR_POWER_LEVEL_DISABLED + +// *** axis settings ********************************************************************************** + +#define JERK_MAX 80000 // 500 million mm/(min^3) +#define JERK_HIGH_SPEED 80000 // 1000 million mm/(min^3) // Jerk during homing needs to stop *fast* +#define VELOCITY_MAX 9000 +#define LATCH_VELOCITY 5000 // reeeeally slow for accuracy + +#define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values +#define X_VELOCITY_MAX VELOCITY_MAX // xvm G0 max velocity in mm/min +#define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min +#define X_TRAVEL_MIN -5 // xtn minimum travel for soft limits +#define X_TRAVEL_MAX 110 // xtr travel between switches or crashes +#define X_JERK_MAX JERK_MAX // xjm +#define X_JERK_HIGH_SPEED JERK_HIGH_SPEED // xjh +#define X_HOMING_INPUT 1 // xhi input used for homing or 0 to disable +#define X_HOMING_DIRECTION 0 // xhd 0=search moves negative, 1= search moves positive +#define X_SEARCH_VELOCITY 1000 // xsv +#define X_LATCH_VELOCITY LATCH_VELOCITY // xlv mm/min +#define X_LATCH_BACKOFF 10 // xlb mm +#define X_ZERO_BACKOFF 1 // xzb mm + +#define Y_AXIS_MODE AXIS_STANDARD +#define Y_VELOCITY_MAX VELOCITY_MAX +#define Y_FEEDRATE_MAX Y_VELOCITY_MAX +#define Y_TRAVEL_MIN 0 +#define Y_TRAVEL_MAX 195 +#define Y_JERK_MAX JERK_MAX +#define Y_JERK_HIGH_SPEED JERK_HIGH_SPEED +#define Y_HOMING_INPUT 2 +#define Y_HOMING_DIRECTION 1 +#define Y_SEARCH_VELOCITY 1000 +#define Y_LATCH_VELOCITY LATCH_VELOCITY +#define Y_LATCH_BACKOFF 4 +#define Y_ZERO_BACKOFF 1 + +#define Z_AXIS_MODE AXIS_STANDARD +#define Z_VELOCITY_MAX 7000 +#define Z_FEEDRATE_MAX Z_VELOCITY_MAX +#define Z_TRAVEL_MIN 0 +#define Z_TRAVEL_MAX 87 +#define Z_JERK_MAX 1000 +#define Z_JERK_HIGH_SPEED Z_JERK_MAX +#define Z_HOMING_INPUT 3 +#define Z_HOMING_DIRECTION 1 +#define Z_SEARCH_VELOCITY 500 +#define Z_LATCH_VELOCITY LATCH_VELOCITY +#define Z_LATCH_BACKOFF 4 +#define Z_ZERO_BACKOFF 1 + +//*** Input / output settings *** +/* + See gpio.h GPIO defines for options + + Homing and probing settings are independent of ACTION and FUNCTION settings + but rely on proper switch MODE setting (i.e. NC or NO) + + IO_MODE_DISABLED + IO_ACTIVE_LOW aka NORMALLY_OPEN + IO_ACTIVE_HIGH aka NORMALLY_CLOSED + + INPUT_ACTION_NONE + INPUT_ACTION_STOP + INPUT_ACTION_FAST_STOP + INPUT_ACTION_HALT + INPUT_ACTION_RESET + + INPUT_FUNCTION_NONE + INPUT_FUNCTION_LIMIT + INPUT_FUNCTION_INTERLOCK + INPUT_FUNCTION_SHUTDOWN + INPUT_FUNCTION_PANIC +*/ + +// Xmin on v9 board // X homing - see X axis setup +#define DI1_POLARITY IO_ACTIVE_LOW // Normally Open +#define DI1_ACTION INPUT_ACTION_NONE + +// Xmax // External ESTOP +#define DI2_POLARITY IO_ACTIVE_LOW +#define DI2_ACTION INPUT_ACTION_SHUTDOWN + +// Ymin // Y homing - see Y axis setup +#define DI3_POLARITY IO_ACTIVE_LOW +#define DI3_ACTION INPUT_ACTION_NONE + +// Ymax // Safety interlock +#define DI4_POLARITY IO_ACTIVE_LOW +#define DI4_ACTION INPUT_ACTION_INTERLOCK + +// Zmin // Z probe +#define DI5_POLARITY IO_ACTIVE_LOW // Normally Open +#define DI5_ACTION INPUT_ACTION_NONE +#define PROBING_INPUT 6 + +// Zmax // Z homing - see Z axis for setup +#define DI6_POLARITY IO_ACTIVE_LOW +#define DI6_ACTION INPUT_ACTION_NONE + +// Amin // Unused +#define DI7_ENABLED IO_DISABLED +#define DI7_ACTION INPUT_ACTION_NONE + +// Amax // Unused +#define DI8_ENABLED IO_DISABLED +#define DI8_ACTION INPUT_ACTION_NONE + +// Safety line w/HW timer // Unused +#define DI9_ENABLED IO_DISABLED +#define DI9_ACTION INPUT_ACTION_NONE + + +// *** PWM SPINDLE CONTROL *** + +#define P1_PWM_FREQUENCY 100 // in Hz +#define P1_CW_SPEED_LO 10500 // in RPM (arbitrary units) +#define P1_CW_SPEED_HI 16400 +#define P1_CW_PHASE_LO 0.13 // phase [0..1] +#define P1_CW_PHASE_HI 0.17 +#define P1_CCW_SPEED_LO 0 +#define P1_CCW_SPEED_HI 0 +#define P1_CCW_PHASE_LO 0.1 +#define P1_CCW_PHASE_HI 0.1 +#define P1_PWM_PHASE_OFF 0.1 + +// {"tt5":{"x":0,"y":-2,"z":38.1,"a":0,"b":0,"c":0}} +#define TT5_X_OFFSET 0 +#define TT5_Y_OFFSET -2 +#define TT5_Z_OFFSET 38.1 diff --git a/g2core/settings/settings_smw3d_r7.h b/g2core/settings/settings_smw3d_r7.h index 820a20c4b..dfd6c2ec2 100644 --- a/g2core/settings/settings_smw3d_r7.h +++ b/g2core/settings/settings_smw3d_r7.h @@ -36,140 +36,143 @@ // Machine configuration settings -#define JUNCTION_INTEGRATION_TIME 0.75 // cornering - between 0.10 and 2.00 (higher is faster) -#define CHORDAL_TOLERANCE 0.01 // chordal tolerance for arcs (in mm) +#define JUNCTION_INTEGRATION_TIME 0.75 // cornering - between 0.10 and 2.00 (higher is faster) +#define CHORDAL_TOLERANCE 0.01 // chordal tolerance for arcs (in mm) -#define SOFT_LIMIT_ENABLE 0 // 0=off, 1=on -#define HARD_LIMIT_ENABLE 0 // 0=off, 1=on -#define SAFETY_INTERLOCK_ENABLE 1 // 0=off, 1=on +#define SOFT_LIMIT_ENABLE 0 // 0=off, 1=on +#define HARD_LIMIT_ENABLE 0 // 0=off, 1=on +#define SAFETY_INTERLOCK_ENABLE 1 // 0=off, 1=on -#define SPINDLE_ENABLE_OUTPUT_NUMBER 4 -#define SPINDLE_ENABLE_POLARITY 1 // 0=active low, 1=active high +#define SPINDLE_ENABLE_OUTPUT_NUMBER 4 +#define SPINDLE_ENABLE_POLARITY 0 // 1=active low, 0=active high #define SPINDLE_DIRECTION_OUTPUT_NUMBER 5 -#define SPINDLE_DIR_POLARITY 0 // 0=clockwise is low, 1=clockwise is high -#define SPINDLE_PAUSE_ON_HOLD true -#define SPINDLE_SPINUP_DELAY 1.0 -#define SPINDLE_PWM_NUMBER 6 -#define SECONDARY_PWM_OUTPUT_NUMBER 0 // disabled -#define SPINDLE_SPEED_CHANGE_PER_MS 4 // 20k RPM in 5 seconds - -#define COOLANT_MIST_POLARITY 1 // 0=active low, 1=active high -#define COOLANT_FLOOD_POLARITY 1 // 0=active low, 1=active high -#define COOLANT_PAUSE_ON_HOLD false -#define FLOOD_ENABLE_OUTPUT_NUMBER 0 // disabled -#define MIST_ENABLE_OUTPUT_NUMBER 0 // disabled +#define SPINDLE_DIR_POLARITY 0 // 0=clockwise is low, 1=clockwise is high +#define SPINDLE_PAUSE_ON_HOLD true +#define SPINDLE_SPINUP_DELAY 1.0 +#define SPINDLE_PWM_NUMBER 6 +#define SECONDARY_PWM_OUTPUT_NUMBER 0 // disabled + +#define COOLANT_MIST_POLARITY 0 // 1=active low, 0=active high +#define COOLANT_FLOOD_POLARITY 0 // 1=active low, 0=active high +#define COOLANT_PAUSE_ON_HOLD false +#define FLOOD_ENABLE_OUTPUT_NUMBER 9 // disabled +#define MIST_ENABLE_OUTPUT_NUMBER 7 // disabled + +#define FEEDHOLD_Z_LIFT -1 // mm to lift Z on feedhold, or -1 to go to Z-max // Communications and reporting settings -#define USB_SERIAL_PORTS_EXPOSED 1 // 1=single endpoint usb, 2=dual endpoint usb -#define COMM_MODE JSON_MODE // one of: TEXT_MODE, JSON_MODE -#define XIO_ENABLE_FLOW_CONTROL FLOW_CONTROL_RTS // FLOW_CONTROL_OFF, FLOW_CONTROL_RTS +#define USB_SERIAL_PORTS_EXPOSED 1 // 1=single endpoint usb, 2=dual endpoint usb +#define COMM_MODE JSON_MODE // one of: TEXT_MODE, JSON_MODE +#define XIO_ENABLE_FLOW_CONTROL FLOW_CONTROL_RTS // FLOW_CONTROL_OFF, FLOW_CONTROL_RTS -#define TEXT_VERBOSITY TV_VERBOSE // one of: TV_SILENT, TV_VERBOSE -#define JSON_VERBOSITY JV_MESSAGES // one of: JV_SILENT, JV_FOOTER, JV_CONFIGS, JV_MESSAGES, JV_LINENUM, JV_VERBOSE -#define QUEUE_REPORT_VERBOSITY QR_OFF // one of: QR_OFF, QR_SINGLE, QR_TRIPLE +#define TEXT_VERBOSITY TV_VERBOSE // one of: TV_SILENT, TV_VERBOSE +#define JSON_VERBOSITY JV_MESSAGES // one of: JV_SILENT, JV_FOOTER, JV_CONFIGS, JV_MESSAGES, JV_LINENUM, JV_VERBOSE +#define QUEUE_REPORT_VERBOSITY QR_OFF // one of: QR_OFF, QR_SINGLE, QR_TRIPLE -#define STATUS_REPORT_VERBOSITY SR_FILTERED // one of: SR_OFF, SR_FILTERED, SR_VERBOSE +#define STATUS_REPORT_VERBOSITY SR_FILTERED // one of: SR_OFF, SR_FILTERED, SR_VERBOSE -#define STATUS_REPORT_MIN_MS 100 // milliseconds - enforces a viable minimum -#define STATUS_REPORT_INTERVAL_MS 250 // milliseconds - set $SV=0 to disable +#define STATUS_REPORT_MIN_MS 100 // milliseconds - enforces a viable minimum +#define STATUS_REPORT_INTERVAL_MS 250 // milliseconds - set $SV=0 to disable -//#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","posa","feed","vel","unit","coor","dist","admo","frmo","momo","stat" -#define STATUS_REPORT_DEFAULTS "line","posx","posy","posz","feed","vel","momo","stat" +// #define STATUS_REPORT_DEFAULTS +// "line","posx","posy","posz","posa","feed","vel","unit","coor","dist","admo","frmo","momo","stat" +#define STATUS_REPORT_DEFAULTS "line", "posx", "posy", "posz", "feed", "vel", "momo", "stat" // Alternate SRs that report in drawable units -//#define STATUS_REPORT_DEFAULTS "line","vel","mpox","mpoy","mpoz","mpoa","coor","ofsa","ofsx","ofsy","ofsz","dist","unit","stat","homz","homy","homx","momo" -//#define STATUS_REPORT_DEFAULTS "_ts1","_cs1","_es1","_xs1","_fe1","line","posx","posy","posz","vel","stat" +// #define STATUS_REPORT_DEFAULTS +// "line","vel","mpox","mpoy","mpoz","mpoa","coor","ofsa","ofsx","ofsy","ofsz","dist","unit","stat","homz","homy","homx","momo" +// #define STATUS_REPORT_DEFAULTS "_ts1","_cs1","_es1","_xs1","_fe1","line","posx","posy","posz","vel","stat" // Gcode startup defaults -#define GCODE_DEFAULT_UNITS MILLIMETERS // MILLIMETERS or INCHES -#define GCODE_DEFAULT_PLANE CANON_PLANE_XY // CANON_PLANE_XY, CANON_PLANE_XZ, or CANON_PLANE_YZ -#define GCODE_DEFAULT_COORD_SYSTEM G54 // G54, G55, G56, G57, G58 or G59 -#define GCODE_DEFAULT_PATH_CONTROL PATH_CONTINUOUS +#define GCODE_DEFAULT_UNITS MILLIMETERS // MILLIMETERS or INCHES +#define GCODE_DEFAULT_PLANE CANON_PLANE_XY // CANON_PLANE_XY, CANON_PLANE_XZ, or CANON_PLANE_YZ +#define GCODE_DEFAULT_COORD_SYSTEM G54 // G54, G55, G56, G57, G58 or G59 +#define GCODE_DEFAULT_PATH_CONTROL PATH_CONTINUOUS #define GCODE_DEFAULT_DISTANCE_MODE ABSOLUTE_DISTANCE_MODE // *** motor settings ************************************************************************************ -#define MOTOR_POWER_MODE MOTOR_POWERED_IN_CYCLE // default motor power mode (see cmMotorPowerMode in stepper.h) -#define MOTOR_POWER_TIMEOUT 2.00 // motor power timeout in seconds - -#define M1_MOTOR_MAP AXIS_X // 1ma -#define M1_STEP_ANGLE 1.8 // 1sa -#define M1_TRAVEL_PER_REV 8.0934060625 // 1tr -#define M1_MICROSTEPS 64 // 1mi 1,2,4,8,16,32 -#define M1_POLARITY 1 // 1po 0=normal, 1=reversed -#define M1_POWER_MODE MOTOR_ALWAYS_POWERED // 1pm TRUE=low power idle enabled -#define M1_POWER_LEVEL 0.500 - -#define M2_MOTOR_MAP AXIS_Y -#define M2_STEP_ANGLE 1.8 -#define M2_TRAVEL_PER_REV 8.0934060625 -#define M2_MICROSTEPS 64 -#define M2_POLARITY 0 -#define M2_POWER_MODE MOTOR_ALWAYS_POWERED -#define M2_POWER_LEVEL 0.500 - -#define M3_MOTOR_MAP AXIS_Y -#define M3_STEP_ANGLE 1.8 -#define M3_TRAVEL_PER_REV 8.0934060625 -#define M3_MICROSTEPS 64 -#define M3_POLARITY 0 -#define M3_POWER_MODE MOTOR_ALWAYS_POWERED -#define M3_POWER_LEVEL 0.500 - -#define M4_MOTOR_MAP AXIS_Z -#define M4_STEP_ANGLE 1.8 -#define M4_TRAVEL_PER_REV 8.0934060625 -#define M4_MICROSTEPS 64 -#define M4_POLARITY 1 -#define M4_POWER_MODE MOTOR_ALWAYS_POWERED -#define M4_POWER_LEVEL 0.750 +#define MOTOR_POWER_MODE MOTOR_POWERED_IN_CYCLE // default motor power mode (see cmMotorPowerMode in stepper.h) +#define MOTOR_POWER_TIMEOUT 2.00 // motor power timeout in seconds + +#define M1_MOTOR_MAP AXIS_X // 1ma +#define M1_STEP_ANGLE 1.8 // 1sa +#define M1_TRAVEL_PER_REV 8.0934060625 // 1tr +#define M1_MICROSTEPS 64 // 1mi 1,2,4,8,16,32 +#define M1_POLARITY 1 // 1po 0=normal, 1=reversed +#define M1_POWER_MODE MOTOR_ALWAYS_POWERED // 1pm TRUE=low power idle enabled +#define M1_POWER_LEVEL 0.500 + +#define M2_MOTOR_MAP AXIS_Y +#define M2_STEP_ANGLE 1.8 +#define M2_TRAVEL_PER_REV 8.0934060625 +#define M2_MICROSTEPS 64 +#define M2_POLARITY 0 +#define M2_POWER_MODE MOTOR_ALWAYS_POWERED +#define M2_POWER_LEVEL 0.500 + +#define M3_MOTOR_MAP AXIS_Y +#define M3_STEP_ANGLE 1.8 +#define M3_TRAVEL_PER_REV 8.0934060625 +#define M3_MICROSTEPS 64 +#define M3_POLARITY 0 +#define M3_POWER_MODE MOTOR_ALWAYS_POWERED +#define M3_POWER_LEVEL 0.500 + +#define M4_MOTOR_MAP AXIS_Z +#define M4_STEP_ANGLE 1.8 +#define M4_TRAVEL_PER_REV 8.0934060625 +#define M4_MICROSTEPS 64 +#define M4_POLARITY 1 +#define M4_POWER_MODE MOTOR_ALWAYS_POWERED +#define M4_POWER_LEVEL 0.750 // *** axis settings ********************************************************************************** -#define JERK_MAX 5000 - -#define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values -#define X_VELOCITY_MAX 5000 // xvm G0 max velocity in mm/min -#define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min -#define X_TRAVEL_MIN 0 // xtn minimum travel for soft limits -#define X_TRAVEL_MAX 824 // xtm travel between switches or crashes -#define X_JERK_MAX 3500 // xjm jerk * 1,000,000 -#define X_JERK_HIGH_SPEED 20000 // xjh -#define X_HOMING_INPUT 1 // xhi input used for homing or 0 to disable -#define X_HOMING_DIRECTION 1 // xhd 0=search moves negative, 1= search moves positive -#define X_SEARCH_VELOCITY 2000 // xsv minus means move to minimum switch -#define X_LATCH_VELOCITY 100 // xlv mm/min -#define X_LATCH_BACKOFF 4 // xlb mm -#define X_ZERO_BACKOFF 2 // xzb mm - -#define Y_AXIS_MODE AXIS_STANDARD -#define Y_VELOCITY_MAX 5000 -#define Y_FEEDRATE_MAX Y_VELOCITY_MAX -#define Y_TRAVEL_MIN 0 -#define Y_TRAVEL_MAX 781 -#define Y_JERK_MAX 3500 -#define Y_JERK_HIGH_SPEED 20000 -#define Y_HOMING_INPUT 2 -#define Y_HOMING_DIRECTION 1 -#define Y_SEARCH_VELOCITY 2000 -#define Y_LATCH_VELOCITY 100 -#define Y_LATCH_BACKOFF 4 -#define Y_ZERO_BACKOFF 2 - -#define Z_AXIS_MODE AXIS_STANDARD -#define Z_VELOCITY_MAX 1200 -#define Z_FEEDRATE_MAX Z_VELOCITY_MAX -#define Z_TRAVEL_MAX 75 -#define Z_TRAVEL_MIN -15 -#define Z_JERK_MAX 500 -#define Z_JERK_HIGH_SPEED 1000 -#define Z_HOMING_INPUT 3 -#define Z_HOMING_DIRECTION 1 -#define Z_SEARCH_VELOCITY (Z_VELOCITY_MAX * 0.66666) -#define Z_LATCH_VELOCITY 25 -#define Z_LATCH_BACKOFF 4 -#define Z_ZERO_BACKOFF 2 +#define JERK_MAX 5000 + +#define X_AXIS_MODE AXIS_STANDARD // xam see canonical_machine.h cmAxisMode for valid values +#define X_VELOCITY_MAX 2000 // xvm G0 max velocity in mm/min +#define X_FEEDRATE_MAX X_VELOCITY_MAX // xfr G1 max feed rate in mm/min +#define X_TRAVEL_MIN 0 // xtn minimum travel for soft limits +#define X_TRAVEL_MAX 824 // xtm travel between switches or crashes +#define X_JERK_MAX 3500 // xjm jerk * 1,000,000 +#define X_JERK_HIGH_SPEED 20000 // xjh +#define X_HOMING_INPUT 1 // xhi input used for homing or 0 to disable +#define X_HOMING_DIRECTION 1 // xhd 0=search moves negative, 1= search moves positive +#define X_SEARCH_VELOCITY 1000 // xsv minus means move to minimum switch +#define X_LATCH_VELOCITY 100 // xlv mm/min +#define X_LATCH_BACKOFF 4 // xlb mm +#define X_ZERO_BACKOFF 2 // xzb mm + +#define Y_AXIS_MODE AXIS_STANDARD +#define Y_VELOCITY_MAX 4000 +#define Y_FEEDRATE_MAX Y_VELOCITY_MAX +#define Y_TRAVEL_MIN 0 +#define Y_TRAVEL_MAX 781 +#define Y_JERK_MAX 3500 +#define Y_JERK_HIGH_SPEED 20000 +#define Y_HOMING_INPUT 2 +#define Y_HOMING_DIRECTION 1 +#define Y_SEARCH_VELOCITY 1000 +#define Y_LATCH_VELOCITY 100 +#define Y_LATCH_BACKOFF 4 +#define Y_ZERO_BACKOFF 2 + +#define Z_AXIS_MODE AXIS_STANDARD +#define Z_VELOCITY_MAX 1200 +#define Z_FEEDRATE_MAX Z_VELOCITY_MAX +#define Z_TRAVEL_MAX 75 +#define Z_TRAVEL_MIN -15 +#define Z_JERK_MAX 500 +#define Z_JERK_HIGH_SPEED 1000 +#define Z_HOMING_INPUT 3 +#define Z_HOMING_DIRECTION 1 +#define Z_SEARCH_VELOCITY (Z_VELOCITY_MAX * 0.66666) +#define Z_LATCH_VELOCITY 25 +#define Z_LATCH_BACKOFF 4 +#define Z_ZERO_BACKOFF 2 //*** Input / output settings *** /* @@ -193,38 +196,37 @@ #define PROBING_INPUT 5 -#define DI1_POLARITY IO_ACTIVE_HIGH +#define DI1_POLARITY IO_ACTIVE_HIGH // #define DI1_ACTION INPUT_ACTION_LIMIT -#define DI1_ACTION INPUT_ACTION_NONE +#define DI1_ACTION INPUT_ACTION_NONE -#define DI2_POLARITY IO_ACTIVE_HIGH +#define DI2_POLARITY IO_ACTIVE_HIGH // #define DI2_ACTION INPUT_ACTION_LIMIT -#define DI2_ACTION INPUT_ACTION_NONE - -#define DI3_POLARITY IO_ACTIVE_HIGH -//#define DI3_ACTION INPUT_ACTION_LIMIT -#define DI3_ACTION INPUT_ACTION_NONE +#define DI2_ACTION INPUT_ACTION_NONE -#define DI4_POLARITY IO_ACTIVE_HIGH -//#define DI4_ACTION INPUT_ACTION_LIMIT -#define DI4_ACTION INPUT_ACTION_NONE +#define DI3_POLARITY IO_ACTIVE_HIGH +// #define DI3_ACTION INPUT_ACTION_LIMIT +#define DI3_ACTION INPUT_ACTION_NONE -#define DI5_POLARITY IO_ACTIVE_HIGH // Z probe -#define DI5_ACTION INPUT_ACTION_NONE +#define DI4_POLARITY IO_ACTIVE_HIGH +// #define DI4_ACTION INPUT_ACTION_LIMIT +#define DI4_ACTION INPUT_ACTION_NONE -#define DI6_POLARITY IO_ACTIVE_HIGH -//#define DI6_ACTION INPUT_ACTION_LIMIT -#define DI6_ACTION INPUT_ACTION_NONE +#define DI5_POLARITY IO_ACTIVE_LOW // Z probe +#define DI5_ACTION INPUT_ACTION_NONE -#define DI7_ENABLED IO_DISABLED -#define DI7_ACTION INPUT_ACTION_NONE +#define DI6_POLARITY IO_ACTIVE_HIGH +// #define DI6_ACTION INPUT_ACTION_LIMIT +#define DI6_ACTION INPUT_ACTION_NONE -#define DI8_ENABLED IO_DISABLED -#define DI8_ACTION INPUT_ACTION_NONE +#define DI7_ENABLED IO_DISABLED +#define DI7_ACTION INPUT_ACTION_NONE -#define DI9_ENABLED IO_DISABLED -#define DI9_ACTION INPUT_ACTION_NONE +#define DI8_ENABLED IO_DISABLED +#define DI8_ACTION INPUT_ACTION_NONE +#define DI9_ENABLED IO_DISABLED +#define DI9_ACTION INPUT_ACTION_NONE // *** PWM SPINDLE CONTROL *** @@ -256,7 +258,7 @@ */ #define P1_PWM_FREQUENCY 100000 // in Hz -#define P1_CW_SPEED_LO 1 // in RPM (arbitrary units) +#define P1_CW_SPEED_LO 1 // in RPM (arbitrary units) #define P1_CW_SPEED_HI 24000 #define P1_CW_PHASE_LO 0.05 // phase [0..1] #define P1_CW_PHASE_HI 1.0 diff --git a/g2core/stepper.cpp b/g2core/stepper.cpp index 021cdc805..0e2b1d27d 100644 --- a/g2core/stepper.cpp +++ b/g2core/stepper.cpp @@ -98,7 +98,7 @@ The full implementation that uses it is small and may help: It's just like a function, and is used as a function pointer. But the closure part means that whatever variables that were in scope where the -[&](parameters){code} is will be captured by the compiler as references in the generated +[](parameters){code} is will be captured by the compiler as references in the generated function and used wherever the function gets called. In this particular use, there isn't anything that wouldn't be available anywhere in that file, but they're not being called from that file. They're being called by the systick interrupt which is over in SamTmers.cpp diff --git a/g2core/utils/g2flash.py b/g2core/utils/g2flash.py new file mode 100644 index 000000000..7a3e5cb0d --- /dev/null +++ b/g2core/utils/g2flash.py @@ -0,0 +1,131 @@ +#!/usr/bin/env python3 + +import os +import sys +import argparse +import serial.tools.list_ports +import subprocess +import shutil + + +def flash_board(serial_port, g2core_bin_path): + # Set the baud rate on the selected serial port + + + # Flash the board using bossac + cmd = f"bossac --port={serial_port} -u=true -e -w -v -i -b -R {g2core_bin_path}" + proc = subprocess.Popen(cmd, shell=True, stdout=subprocess.PIPE, stderr=subprocess.STDOUT) + + # Print the output of the command to the console + while True: + line = proc.stdout.readline() + if not line: + break + print(line.decode("utf-8").rstrip()) + + # Wait for the command to complete + proc.wait() + if proc.returncode != 0: + print_message("red", f"Error flashing g2core board. bossac command exited with status {proc.returncode}") + else: + print_message("green", "g2core board successfully flashed!") + +# Define function to print colored text +def print_message(color, message): + if len(color) == 0: + print(message) + elif color == "red": + print("\033[0;31m" + message + "\033[0m") + elif color == "green": + print("\033[0;32m" + message + "\033[0m") + +# Define function to prompt user to select a serial port +def select_serial_port(): + # List available serial ports + serial_ports = [port.device for port in serial.tools.list_ports.comports()] + + if not serial_ports: + print_message("red", "No serial ports found. Make sure your device is connected and try again.") + sys.exit(1) + + while True: + print_message("", "Select the serial port to use:") + for i, port in enumerate(serial_ports): + print(f"{i+1}. {port}") + port_number = input("Enter the number of the serial port to use: ") + + # Check that the user entered a valid number + if not port_number.isdigit() or not 1 <= int(port_number) <= len(serial_ports): + print_message("red", f"Invalid port number: {port_number}") + else: + return serial_ports[int(port_number)-1] + + + +def check_dependencies(): + # Check for pyserial module + try: + import serial + except ImportError: + print("pyserial module is not installed.") + return False + + # Check for bossac command + if shutil.which("bossac") is None: + print("bossac command not found. Please make sure it is installed and in your PATH.") + return False + + return True + +def enter_bootloader(serial_port): + # Set the baud rate on the selected serial port + # This is not needed on ArduinoDUE boards + # You do however need to be in the programming port for flashing to work + try: + with serial.Serial(port=serial_port, baudrate=1200) as ser: + ser.setDTR() + with serial.Serial(port=serial_port, baudrate=9600, timeout=1) as ser: + ser.flushInput() + except serial.serialutil.SerialException as e: + print(f"Error setting baud rate on port {serial_port}: {str(e)}") + sys.exit(1) + + + +# Define main function +def main(): + # Parse command line arguments + parser = argparse.ArgumentParser(description='Flash a g2core board.') + parser.add_argument('--port', type=str, help='The serial port to use') + parser.add_argument('bin', type=str, help='The path to the g2core binary file to flash') + args = parser.parse_args() + + if not check_dependencies(): + sys.exit() + + # Select a serial port if the --port argument is not given + if not args.port: + args.port = select_serial_port() + + args.bin = " ../bin/EnderLaser-gquintic-g/g2core.bin " + + # Detect operating system and display appropriate installation message for pyserial + if sys.platform.startswith("linux"): + print('asdf') + + if "microsoft" in os.uname().release.lower(): + print('asdf') + # WSL 2 + enter_bootloader(args.port) + flash_board(args.port, args.bin) + print('asdf') + + elif sys.platform.startswith("darwin"): + pass + + else: + print_message("red", "Unsupported operating system. Cannot install pyserial module.") + sys.exit(1) + +if __name__ == "__main__": + main() \ No newline at end of file