Sergey Pastor / grbl1
Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers limits.c Source File

limits.c

00001 /*
00002   limits.c - code pertaining to limit-switches and performing the homing cycle
00003   Part of Grbl
00004 
00005   Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
00006   Copyright (c) 2009-2011 Simen Svale Skogsrud
00007 
00008   Grbl is free software: you can redistribute it and/or modify
00009   it under the terms of the GNU General Public License as published by
00010   the Free Software Foundation, either version 3 of the License, or
00011   (at your option) any later version.
00012 
00013   Grbl is distributed in the hope that it will be useful,
00014   but WITHOUT ANY WARRANTY; without even the implied warranty of
00015   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00016   GNU General Public License for more details.
00017 
00018   You should have received a copy of the GNU General Public License
00019   along with Grbl.  If not, see <http://www.gnu.org/licenses/>.
00020 */
00021 
00022 #include "grbl.h"
00023 
00024 
00025 // Homing axis search distance multiplier. Computed by this value times the cycle travel.
00026 #ifndef HOMING_AXIS_SEARCH_SCALAR
00027   #define HOMING_AXIS_SEARCH_SCALAR  1.5f // Must be > 1 to ensure limit switch will be engaged.
00028 #endif
00029 #ifndef HOMING_AXIS_LOCATE_SCALAR
00030   #define HOMING_AXIS_LOCATE_SCALAR  5.0f // Must be > 1 to ensure limit switch is cleared.
00031 #endif
00032 
00033 void limits_init()
00034 {
00035 #ifdef AVRTARGET
00036   LIMIT_DDR &= ~(LIMIT_MASK); // Set as input pins
00037 
00038   #ifdef DISABLE_LIMIT_PIN_PULL_UP
00039     LIMIT_PORT &= ~(LIMIT_MASK); // Normal low operation. Requires external pull-down.
00040   #else
00041     LIMIT_PORT |= (LIMIT_MASK);  // Enable internal pull-up resistors. Normal high operation.
00042   #endif
00043 
00044   if (bit_istrue(settings.flags,BITFLAG_HARD_LIMIT_ENABLE)) {
00045     LIMIT_PCMSK |= LIMIT_MASK; // Enable specific pins of the Pin Change Interrupt
00046     PCICR |= (1 << LIMIT_INT); // Enable Pin Change Interrupt
00047   } else {
00048     limits_disable();
00049   }
00050 
00051   #ifdef ENABLE_SOFTWARE_DEBOUNCE
00052     MCUSR &= ~(1<<WDRF);
00053     WDTCSR |= (1<<WDCE) | (1<<WDE);
00054     WDTCSR = (1<<WDP0); // Set time-out at ~32msec.
00055   #endif
00056 #endif
00057 #ifdef STM32F103C8
00058     GPIO_InitTypeDef GPIO_InitStructure;
00059     RCC_APB2PeriphClockCmd(RCC_LIMIT_PORT | RCC_APB2Periph_AFIO, ENABLE);
00060     GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
00061     GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
00062     GPIO_InitStructure.GPIO_Pin = LIMIT_MASK;
00063     GPIO_Init(LIMIT_PORT, &GPIO_InitStructure);
00064 
00065     if (bit_istrue(settings.flags, BITFLAG_HARD_LIMIT_ENABLE))
00066     {
00067         GPIO_EXTILineConfig(GPIO_LIMIT_PORT, X_LIMIT_BIT);
00068         GPIO_EXTILineConfig(GPIO_LIMIT_PORT, Y_LIMIT_BIT);
00069         GPIO_EXTILineConfig(GPIO_LIMIT_PORT, Z_LIMIT_BIT);
00070 
00071         EXTI_InitTypeDef EXTI_InitStructure;
00072         EXTI_InitStructure.EXTI_Line = LIMIT_MASK;    //
00073         EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt; //Interrupt mode, optional values for the interrupt EXTI_Mode_Interrupt and event EXTI_Mode_Event.
00074         EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling; //Trigger mode, can be a falling edge trigger EXTI_Trigger_Falling, the rising edge triggered EXTI_Trigger_Rising, or any level (rising edge and falling edge trigger EXTI_Trigger_Rising_Falling)
00075         EXTI_InitStructure.EXTI_LineCmd = ENABLE;
00076         EXTI_Init(&EXTI_InitStructure);
00077 
00078         NVIC_InitTypeDef NVIC_InitStructure;
00079         NVIC_InitStructure.NVIC_IRQChannel = EXTI15_10_IRQn; //Enable keypad external interrupt channel
00080         NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0x02; //Priority 2,
00081         NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0x02; //Sub priority 2
00082         NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; //Enable external interrupt channel
00083         NVIC_Init(&NVIC_InitStructure);
00084     }
00085     else
00086     {
00087         limits_disable();
00088     }
00089 #endif
00090 }
00091 
00092 
00093 // Disables hard limits.
00094 void limits_disable()
00095 {
00096 #ifdef AVRTARGET
00097   LIMIT_PCMSK &= ~LIMIT_MASK;  // Disable specific pins of the Pin Change Interrupt
00098   PCICR &= ~(1 << LIMIT_INT);  // Disable Pin Change Interrupt
00099 #endif
00100 #ifdef STM32F103C8
00101   NVIC_DisableIRQ(EXTI15_10_IRQn);
00102 #endif
00103 }
00104 
00105 
00106 // Returns limit state as a bit-wise uint8 variable. Each bit indicates an axis limit, where
00107 // triggered is 1 and not triggered is 0. Invert mask is applied. Axes are defined by their
00108 // number in bit position, i.e. Z_AXIS is (1<<2) or bit 2, and Y_AXIS is (1<<1) or bit 1.
00109 uint8_t limits_get_state()
00110 {
00111   uint8_t limit_state = 0;
00112 #if defined(AVRTARGET) || defined(STM32F103C8)
00113 #if defined(AVRTARGET)
00114   uint8_t pin = (LIMIT_PIN & LIMIT_MASK);
00115 #endif
00116 #if defined(STM32F103C8)
00117   uint16_t pin = GPIO_ReadInputData(LIMIT_PIN);
00118 #endif
00119   #ifdef INVERT_LIMIT_PIN_MASK
00120     pin ^= INVERT_LIMIT_PIN_MASK;
00121   #endif
00122   if (bit_isfalse(settings.flags,BITFLAG_INVERT_LIMIT_PINS)) { pin ^= LIMIT_MASK; }
00123   if (pin) {
00124     uint8_t idx;
00125     for (idx=0; idx<N_AXIS; idx++) {
00126       if (pin & limit_pin_mask[idx]) { limit_state |= (1 << idx); }
00127     }
00128   }
00129 #endif
00130   return(limit_state);
00131 }
00132 
00133 
00134 // This is the Limit Pin Change Interrupt, which handles the hard limit feature. A bouncing
00135 // limit switch can cause a lot of problems, like false readings and multiple interrupt calls.
00136 // If a switch is triggered at all, something bad has happened and treat it as such, regardless
00137 // if a limit switch is being disengaged. It's impossible to reliably tell the state of a
00138 // bouncing pin because the Arduino microcontroller does not retain any state information when
00139 // detecting a pin change. If we poll the pins in the ISR, you can miss the correct reading if the 
00140 // switch is bouncing.
00141 // NOTE: Do not attach an e-stop to the limit pins, because this interrupt is disabled during
00142 // homing cycles and will not respond correctly. Upon user request or need, there may be a
00143 // special pinout for an e-stop, but it is generally recommended to just directly connect
00144 // your e-stop switch to the Arduino reset pin, since it is the most correct way to do this.
00145 #ifndef ENABLE_SOFTWARE_DEBOUNCE
00146 #if defined(AVRTARGET) || defined (STM32F103C8)
00147 #if defined(AVRTARGET) 
00148 ISR(LIMIT_INT_vect) // DEFAULT: Limit pin change interrupt process.
00149 #else
00150 void EXTI15_10_IRQHandler(void)
00151 #endif
00152 {
00153 #if defined (STM32F103C8)
00154     if (EXTI_GetITStatus(1 << X_LIMIT_BIT) != RESET)
00155     {
00156         EXTI_ClearITPendingBit(1 << X_LIMIT_BIT);
00157     }
00158     if (EXTI_GetITStatus(1 << Y_LIMIT_BIT) != RESET)
00159     {
00160         EXTI_ClearITPendingBit(1 << Y_LIMIT_BIT);
00161     }
00162     if (EXTI_GetITStatus(1 << Z_LIMIT_BIT) != RESET)
00163     {
00164         EXTI_ClearITPendingBit(1 << Z_LIMIT_BIT);
00165     }
00166     NVIC_ClearPendingIRQ(EXTI15_10_IRQn);
00167 #endif
00168   // Ignore limit switches if already in an alarm state or in-process of executing an alarm.
00169   // When in the alarm state, Grbl should have been reset or will force a reset, so any pending
00170   // moves in the planner and serial buffers are all cleared and newly sent blocks will be
00171   // locked out until a homing cycle or a kill lock command. Allows the user to disable the hard
00172   // limit setting if their limits are constantly triggering after a reset and move their axes.
00173   if (sys.state != STATE_ALARM) {
00174     if (!(sys_rt_exec_alarm)) {
00175 #ifdef HARD_LIMIT_FORCE_STATE_CHECK
00176       // Check limit pin state.
00177       if (limits_get_state()) {
00178         mc_reset(); // Initiate system kill.
00179         system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
00180       }
00181 #else
00182       mc_reset(); // Initiate system kill.
00183       system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
00184 #endif
00185     }
00186   }
00187 }
00188 #endif
00189 #else // OPTIONAL: Software debounce limit pin routine.
00190 #if defined(AVRTARGET)
00191 // Upon limit pin change, enable watchdog timer to create a short delay. 
00192 ISR(LIMIT_INT_vect) { if (!(WDTCSR & (1 << WDIE))) { WDTCSR |= (1 << WDIE); } }
00193 ISR(WDT_vect) // Watchdog timer ISR
00194 {
00195   WDTCSR &= ~(1 << WDIE); // Disable watchdog timer. 
00196   if (sys.state != STATE_ALARM) {  // Ignore if already in alarm state. 
00197     if (!(sys_rt_exec_alarm)) {
00198       // Check limit pin state. 
00199       if (limits_get_state()) {
00200         mc_reset(); // Initiate system kill.
00201         system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
00202       }
00203     }
00204   }
00205 }
00206 #else
00207 #error ENABLE_SOFTWARE_DEBOUNCE is not supported yet
00208 #endif
00209 #endif
00210 
00211 // Homes the specified cycle axes, sets the machine position, and performs a pull-off motion after
00212 // completing. Homing is a special motion case, which involves rapid uncontrolled stops to locate
00213 // the trigger point of the limit switches. The rapid stops are handled by a system level axis lock
00214 // mask, which prevents the stepper algorithm from executing step pulses. Homing motions typically
00215 // circumvent the processes for executing motions in normal operation.
00216 // NOTE: Only the abort realtime command can interrupt this process.
00217 // TODO: Move limit pin-specific calls to a general function for portability.
00218 void limits_go_home(uint8_t cycle_mask)
00219 {
00220   if (sys.abort) { return; } // Block if system reset has been issued.
00221 
00222   // Initialize plan data struct for homing motion. Spindle and coolant are disabled.
00223   plan_line_data_t plan_data;
00224   plan_line_data_t *pl_data = &plan_data;
00225   memset(pl_data,0,sizeof(plan_line_data_t));
00226   pl_data->condition = (PL_COND_FLAG_SYSTEM_MOTION|PL_COND_FLAG_NO_FEED_OVERRIDE);
00227   #ifdef USE_LINE_NUMBERS
00228     pl_data->line_number = HOMING_CYCLE_LINE_NUMBER;
00229   #endif
00230 
00231   // Initialize variables used for homing computations.
00232   uint8_t n_cycle = (2*N_HOMING_LOCATE_CYCLE+1);
00233   uint8_t step_pin[N_AXIS];
00234   float target[N_AXIS];
00235   float max_travel = 0.0f;
00236   uint8_t idx;
00237   for (idx=0; idx<N_AXIS; idx++) {
00238     // Initialize step pin masks
00239     step_pin[idx] = step_pin_mask[idx];
00240     #ifdef COREXY
00241       if ((idx==A_MOTOR)||(idx==B_MOTOR)) { step_pin[idx] = (step_pin_mask[X_AXIS]| step_pin_mask[Y_AXIS]); }
00242     #endif
00243 
00244     if (bit_istrue(cycle_mask,bit(idx))) {
00245       // Set target based on max_travel setting. Ensure homing switches engaged with search scalar.
00246       // NOTE: settings.max_travel[] is stored as a negative value.
00247       max_travel = max(max_travel,(-HOMING_AXIS_SEARCH_SCALAR)*settings.max_travel[idx]);
00248     }
00249   }
00250 
00251   // Set search mode with approach at seek rate to quickly engage the specified cycle_mask limit switches.
00252   bool approach = true;
00253   float homing_rate = settings.homing_seek_rate;
00254 
00255   uint8_t limit_state, axislock, n_active_axis;
00256   do {
00257 
00258     system_convert_array_steps_to_mpos(target,sys_position);
00259 
00260     // Initialize and declare variables needed for homing routine.
00261     axislock = 0;
00262     n_active_axis = 0;
00263     for (idx=0; idx<N_AXIS; idx++) {
00264       // Set target location for active axes and setup computation for homing rate.
00265       if (bit_istrue(cycle_mask,bit(idx))) {
00266         n_active_axis++;
00267         #ifdef COREXY
00268           if (idx == X_AXIS) {
00269             int32_t axis_position = system_convert_corexy_to_y_axis_steps(sys_position);
00270             sys_position[A_MOTOR] = axis_position;
00271             sys_position[B_MOTOR] = -axis_position;
00272           } else if (idx == Y_AXIS) {
00273             int32_t axis_position = system_convert_corexy_to_x_axis_steps(sys_position);
00274             sys_position[A_MOTOR] = sys_position[B_MOTOR] = axis_position;
00275           } else {
00276             sys_position[Z_AXIS] = 0;
00277           }
00278         #else
00279           sys_position[idx] = 0;
00280         #endif
00281         // Set target direction based on cycle mask and homing cycle approach state.
00282         // NOTE: This happens to compile smaller than any other implementation tried.
00283         if (bit_istrue(settings.homing_dir_mask,bit(idx))) {
00284           if (approach) { target[idx] = -max_travel; }
00285           else { target[idx] = max_travel; }
00286         } else {
00287           if (approach) { target[idx] = max_travel; }
00288           else { target[idx] = -max_travel; }
00289         }
00290         // Apply axislock to the step port pins active in this cycle.
00291         axislock |= step_pin[idx];
00292       }
00293 
00294     }
00295     homing_rate *= sqrtf(n_active_axis); // [sqrt(N_AXIS)] Adjust so individual axes all move at homing rate.
00296     sys.homing_axis_lock = axislock;
00297 
00298     // Perform homing cycle. Planner buffer should be empty, as required to initiate the homing cycle.
00299     pl_data->feed_rate = homing_rate; // Set current homing rate.
00300     plan_buffer_line(target, pl_data); // Bypass mc_line(). Directly plan homing motion.
00301 
00302     sys.step_control = STEP_CONTROL_EXECUTE_SYS_MOTION; // Set to execute homing motion and clear existing flags.
00303     st_prep_buffer(); // Prep and fill segment buffer from newly planned block.
00304     st_wake_up(); // Initiate motion
00305     do {
00306       if (approach) {
00307         // Check limit state. Lock out cycle axes when they change.
00308         limit_state = limits_get_state();
00309         for (idx=0; idx<N_AXIS; idx++) {
00310           if (axislock & step_pin[idx]) {
00311             if (limit_state & (1 << idx)) {
00312               #ifdef COREXY
00313                 if (idx==Z_AXIS) { axislock &= ~(step_pin[Z_AXIS]); }
00314                 else { axislock &= ~(step_pin[A_MOTOR]|step_pin[B_MOTOR]); }
00315               #else
00316                 axislock &= ~(step_pin[idx]);
00317               #endif
00318             }
00319           }
00320         }
00321         sys.homing_axis_lock = axislock;
00322       }
00323 
00324       st_prep_buffer(); // Check and prep segment buffer. NOTE: Should take no longer than 200us.
00325 
00326       // Exit routines: No time to run protocol_execute_realtime() in this loop.
00327       if (sys_rt_exec_state & (EXEC_SAFETY_DOOR | EXEC_RESET | EXEC_CYCLE_STOP)) {
00328         uint8_t rt_exec = sys_rt_exec_state;
00329         // Homing failure condition: Reset issued during cycle.
00330         if (rt_exec & EXEC_RESET) { system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_RESET); }
00331         // Homing failure condition: Safety door was opened.
00332         if (rt_exec & EXEC_SAFETY_DOOR) { system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_DOOR); }
00333         // Homing failure condition: Limit switch still engaged after pull-off motion
00334         if (!approach && (limits_get_state() & cycle_mask)) { system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_PULLOFF); }
00335         // Homing failure condition: Limit switch not found during approach.
00336         if (approach && (rt_exec & EXEC_CYCLE_STOP)) { system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_APPROACH); }
00337         if (sys_rt_exec_alarm) {
00338           mc_reset(); // Stop motors, if they are running.
00339           protocol_execute_realtime();
00340           return;
00341         } else {
00342           // Pull-off motion complete. Disable CYCLE_STOP from executing.
00343           system_clear_exec_state_flag(EXEC_CYCLE_STOP);
00344           break;
00345         }
00346       }
00347 
00348     } while (STEP_MASK & axislock);
00349 
00350     st_reset(); // Immediately force kill steppers and reset step segment buffer.
00351     delay_ms(settings.homing_debounce_delay); // Delay to allow transient dynamics to dissipate.
00352 
00353     // Reverse direction and reset homing rate for locate cycle(s).
00354     approach = !approach;
00355 
00356     // After first cycle, homing enters locating phase. Shorten search to pull-off distance.
00357     if (approach) {
00358       max_travel = settings.homing_pulloff*HOMING_AXIS_LOCATE_SCALAR;
00359       homing_rate = settings.homing_feed_rate;
00360     } else {
00361       max_travel = settings.homing_pulloff;
00362       homing_rate = settings.homing_seek_rate;
00363     }
00364 
00365   } while (n_cycle-- > 0);
00366 
00367   // The active cycle axes should now be homed and machine limits have been located. By
00368   // default, Grbl defines machine space as all negative, as do most CNCs. Since limit switches
00369   // can be on either side of an axes, check and set axes machine zero appropriately. Also,
00370   // set up pull-off maneuver from axes limit switches that have been homed. This provides
00371   // some initial clearance off the switches and should also help prevent them from falsely
00372   // triggering when hard limits are enabled or when more than one axes shares a limit pin.
00373   int32_t set_axis_position;
00374   // Set machine positions for homed limit switches. Don't update non-homed axes.
00375   for (idx=0; idx<N_AXIS; idx++) {
00376     // NOTE: settings.max_travel[] is stored as a negative value.
00377     if (cycle_mask & bit(idx)) {
00378       #ifdef HOMING_FORCE_SET_ORIGIN
00379         set_axis_position = 0;
00380       #else
00381         if ( bit_istrue(settings.homing_dir_mask,bit(idx)) ) {
00382           set_axis_position = lroundf((settings.max_travel[idx]+settings.homing_pulloff)*settings.steps_per_mm[idx]);
00383         } else {
00384           set_axis_position = lroundf(-settings.homing_pulloff*settings.steps_per_mm[idx]);
00385         }
00386       #endif
00387 
00388       #ifdef COREXY
00389         if (idx==X_AXIS) {
00390           int32_t off_axis_position = system_convert_corexy_to_y_axis_steps(sys_position);
00391           sys_position[A_MOTOR] = set_axis_position + off_axis_position;
00392           sys_position[B_MOTOR] = set_axis_position - off_axis_position;
00393         } else if (idx==Y_AXIS) {
00394           int32_t off_axis_position = system_convert_corexy_to_x_axis_steps(sys_position);
00395           sys_position[A_MOTOR] = off_axis_position + set_axis_position;
00396           sys_position[B_MOTOR] = off_axis_position - set_axis_position;
00397         } else {
00398           sys_position[idx] = set_axis_position;
00399         }
00400       #else
00401         sys_position[idx] = set_axis_position;
00402       #endif
00403 
00404     }
00405   }
00406   sys.step_control = STEP_CONTROL_NORMAL_OP; // Return step control to normal operation.
00407 }
00408 
00409 
00410 // Performs a soft limit check. Called from mc_line() only. Assumes the machine has been homed,
00411 // the workspace volume is in all negative space, and the system is in normal operation.
00412 // NOTE: Used by jogging to limit travel within soft-limit volume.
00413 void limits_soft_check(float *target)
00414 {
00415   if (system_check_travel_limits(target)) {
00416     sys.soft_limit = true;
00417     // Force feed hold if cycle is active. All buffered blocks are guaranteed to be within
00418     // workspace volume so just come to a controlled stop so position is not lost. When complete
00419     // enter alarm mode.
00420     if (sys.state == STATE_CYCLE) {
00421       system_set_exec_state_flag(EXEC_FEED_HOLD);
00422       do {
00423         protocol_execute_realtime();
00424         if (sys.abort) { return; }
00425       } while ( sys.state != STATE_IDLE );
00426     }
00427     mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown.
00428     system_set_exec_alarm(EXEC_ALARM_SOFT_LIMIT); // Indicate soft limit critical event
00429     protocol_execute_realtime(); // Execute to enter critical event loop and system abort
00430     return;
00431   }
00432 }