/* spindle_control.c - spindle control methods Part of Grbl PEN_SERVO update by Bart Dring 8/2017 Copyright (c) 2012-2017 Sungeun K. Jeon for Gnea Research LLC Copyright (c) 2009-2011 Simen Svale Skogsrud Grbl is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. Grbl is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License along with Grbl. If not, see . */ #include "grbl.h" /* Pen Servo: For a pen bot I want to use the spindle PWM to control a servo When the spindle is on, the servo moves the pen down When it is off the pen moves up The spindle output is using a PWM, but we need to adjust that We only need a rough Use 1024 prescaler to get. ... 16,000,000 Mhz / 1024 = 15625 Hz It is an 8 bit timer so 15625 / 256 = 61 Hz. This is pretty close the the 50Hz recommended for servos Each tick = 0.000064sec One end of servo is 0.001 sec (0.001 / 0.000064 = 15.6 ticks) The other end is 0.002 sec (0.002 / 0.000064 = 31 ticks) */ #define PEN_SERVO // these are full travel values. If you want to move less than full travel adjust these values // If your servo is going the wrong way, swap them. #define PEN_SERVO_DOWN 32 #define PEN_SERVO_UP 64 #ifdef VARIABLE_SPINDLE static float pwm_gradient; // Precalulated value to speed up rpm to PWM conversions. #endif void spindle_init() { #ifdef VARIABLE_SPINDLE SPINDLE_PWM_DDR |= (1<= settings.rpm_max) || (rpm >= RPM_MAX)) { rpm = RPM_MAX; pwm_value = SPINDLE_PWM_MAX_VALUE; } else if (rpm <= RPM_MIN){ if (rpm == 0.0) { // S0 disables spindle pwm_value = SPINDLE_PWM_OFF_VALUE; } else { rpm = RPM_MIN; pwm_value = SPINDLE_PWM_MIN_VALUE; } } else { // Compute intermediate PWM value with linear spindle speed model via piecewise linear fit model. #if (N_PIECES > 3) if (rpm > RPM_POINT34) { pwm_value = floor(RPM_LINE_A4*rpm - RPM_LINE_B4); } else #endif #if (N_PIECES > 2) if (rpm > RPM_POINT23) { pwm_value = floor(RPM_LINE_A3*rpm - RPM_LINE_B3); } else #endif #if (N_PIECES > 1) if (rpm > RPM_POINT12){ pwm_value = floor(RPM_LINE_A2*rpm - RPM_LINE_B2); } else #endif { pwm_value = floor(RPM_LINE_A1*rpm - RPM_LINE_B1); } } sys.spindle_speed = rpm; return(pwm_value); } #else // Called by spindle_set_state() and step segment generator. Keep routine small and efficient. uint8_t spindle_compute_pwm_value(float rpm) // 328p PWM register is 8-bit. { uint8_t pwm_value; rpm *= (0.010*sys.spindle_speed_ovr); // Scale by spindle speed override value. // Calculate PWM register value based on rpm max/min settings and programmed rpm. if ((settings.rpm_min >= settings.rpm_max) || (rpm >= settings.rpm_max)) { // No PWM range possible. Set simple on/off spindle control pin state. sys.spindle_speed = settings.rpm_max; pwm_value = SPINDLE_PWM_MAX_VALUE; } else if (rpm <= settings.rpm_min) { if (rpm == 0.0) { // S0 disables spindle sys.spindle_speed = 0.0; pwm_value = SPINDLE_PWM_OFF_VALUE; } else { // Set minimum PWM output sys.spindle_speed = settings.rpm_min; pwm_value = SPINDLE_PWM_MIN_VALUE; } } else { // Compute intermediate PWM value with linear spindle speed model. // NOTE: A nonlinear model could be installed here, if required, but keep it VERY light-weight. sys.spindle_speed = rpm; pwm_value = floor((rpm-settings.rpm_min)*pwm_gradient) + SPINDLE_PWM_MIN_VALUE; } return(pwm_value); } #endif #endif // Immediately sets spindle running state with direction and spindle rpm via PWM, if enabled. // Called by g-code parser spindle_sync(), parking retract and restore, g-code program end, // sleep, and spindle stop override. #ifdef VARIABLE_SPINDLE void spindle_set_state(uint8_t state, float rpm) #else void _spindle_set_state(uint8_t state) #endif { if (sys.abort) { return; } // Block during abort. if (state == SPINDLE_DISABLE) { // Halt or set spindle direction and rpm. #ifdef VARIABLE_SPINDLE sys.spindle_speed = 0.0; #endif spindle_stop(); } else { #ifndef USE_SPINDLE_DIR_AS_ENABLE_PIN if (state == SPINDLE_ENABLE_CW) { SPINDLE_DIRECTION_PORT &= ~(1<