X-Git-Url: https://git.hcoop.net/clinton/Smoothieware.git/blobdiff_plain/e714bd3287d325017d823051a715f0f8c72a9c81..918cc8d76e4749eb38d48d3dd43fe10fef2e53a1:/src/modules/tools/zprobe/ZProbe.cpp diff --git a/src/modules/tools/zprobe/ZProbe.cpp b/src/modules/tools/zprobe/ZProbe.cpp index 4d7e0c13..c7842f47 100644 --- a/src/modules/tools/zprobe/ZProbe.cpp +++ b/src/modules/tools/zprobe/ZProbe.cpp @@ -26,6 +26,7 @@ #include "PublicData.h" #include "LevelingStrategy.h" #include "StepTicker.h" +#include "utils.h" // strategies we know about #include "DeltaCalibrationStrategy.h" @@ -40,9 +41,11 @@ #define return_feedrate_checksum CHECKSUM("return_feedrate") #define probe_height_checksum CHECKSUM("probe_height") #define gamma_max_checksum CHECKSUM("gamma_max") +#define reverse_z_direction_checksum CHECKSUM("reverse_z") // from endstop section #define delta_homing_checksum CHECKSUM("delta_homing") +#define rdelta_homing_checksum CHECKSUM("rdelta_homing") #define X_AXIS 0 #define Y_AXIS 1 @@ -62,7 +65,6 @@ void ZProbe::on_module_loaded() delete this; return; } - this->running = false; // load settings this->on_config_reload(this); @@ -70,6 +72,10 @@ void ZProbe::on_module_loaded() register_for_event(ON_GCODE_RECEIVED); THEKERNEL->step_ticker->register_acceleration_tick_handler([this](){acceleration_tick(); }); + + // we read the probe in this timer, currently only for G38 probes. + probing= false; + THEKERNEL->slow_ticker->attach(1000, this, &ZProbe::read_probe); } void ZProbe::on_config_reload(void *argument) @@ -113,6 +119,7 @@ void ZProbe::on_config_reload(void *argument) // need to know if we need to use delta kinematics for homing this->is_delta = THEKERNEL->config->value(delta_homing_checksum)->by_default(false)->as_bool(); + this->is_rdelta = THEKERNEL->config->value(rdelta_homing_checksum)->by_default(false)->as_bool(); // default for backwards compatibility add DeltaCalibrationStrategy if a delta // will be deprecated @@ -128,6 +135,7 @@ void ZProbe::on_config_reload(void *argument) this->fast_feedrate = THEKERNEL->config->value(zprobe_checksum, fast_feedrate_checksum)->by_default(100)->as_number(); // feedrate in mm/sec this->return_feedrate = THEKERNEL->config->value(zprobe_checksum, return_feedrate_checksum)->by_default(0)->as_number(); // feedrate in mm/sec this->max_z = THEKERNEL->config->value(gamma_max_checksum)->by_default(500)->as_number(); // maximum zprobe distance + this->reverse_z = THEKERNEL->config->value(reverse_z_direction_checksum)->by_default(false)->as_bool(); // Z probe moves in reverse direction (upside down rdelta) } bool ZProbe::wait_for_probe(int& steps) @@ -140,12 +148,14 @@ bool ZProbe::wait_for_probe(int& steps) return false; } + bool delta= is_delta || is_rdelta; + // if no stepper is moving, moves are finished and there was no touch - if( !STEPPER[Z_AXIS]->is_moving() && (!is_delta || (!STEPPER[Y_AXIS]->is_moving() && !STEPPER[Z_AXIS]->is_moving())) ) { + if( !STEPPER[Z_AXIS]->is_moving() && (!delta || (!STEPPER[Y_AXIS]->is_moving() && !STEPPER[Z_AXIS]->is_moving())) ) { return false; } - // if the touchprobe is active... + // if the probe is active... if( this->pin.get() ) { //...increase debounce counter... if( debounce < debounce_count) { @@ -157,7 +167,7 @@ bool ZProbe::wait_for_probe(int& steps) steps= STEPPER[Z_AXIS]->get_stepped(); STEPPER[Z_AXIS]->move(0, 0); } - if(is_delta) { + if(delta) { for( int i = X_AXIS; i <= Y_AXIS; i++ ) { if ( STEPPER[i]->is_moving() ) { STEPPER[i]->move(0, 0); @@ -175,7 +185,7 @@ bool ZProbe::wait_for_probe(int& steps) // single probe with custom feedrate // returns boolean value indicating if probe was triggered -bool ZProbe::run_probe_feed(int& steps, float feedrate, float max_dist) +bool ZProbe::run_probe(int& steps, float feedrate, float max_dist, bool reverse) { // not a block move so disable the last tick setting for ( int c = X_AXIS; c <= Z_AXIS; c++ ) { @@ -188,11 +198,13 @@ bool ZProbe::run_probe_feed(int& steps, float feedrate, float max_dist) float maxz= max_dist < 0 ? this->max_z*2 : max_dist; // move Z down - STEPPER[Z_AXIS]->move(true, maxz * Z_STEPS_PER_MM, 0); // always probes down, no more than 2*maxz - if(this->is_delta) { + bool dir= !reverse_z; + if(reverse) dir= !dir; // specified to move in opposite Z direction + STEPPER[Z_AXIS]->move(dir, maxz * Z_STEPS_PER_MM, 0); // probe in specified direction, no more than maxz + if(this->is_delta || this->is_rdelta) { // for delta need to move all three actuators - STEPPER[X_AXIS]->move(true, maxz * STEPS_PER_MM(X_AXIS), 0); - STEPPER[Y_AXIS]->move(true, maxz * STEPS_PER_MM(Y_AXIS), 0); + STEPPER[X_AXIS]->move(dir, maxz * STEPS_PER_MM(X_AXIS), 0); + STEPPER[Y_AXIS]->move(dir, maxz * STEPS_PER_MM(Y_AXIS), 0); } // start acceleration processing @@ -206,16 +218,7 @@ bool ZProbe::run_probe_feed(int& steps, float feedrate, float max_dist) return r; } -// single probe with either fast or slow feedrate -// returns boolean value indicating if probe was triggered -bool ZProbe::run_probe(int& steps, bool fast) -{ - float feedrate = (fast ? this->fast_feedrate : this->slow_feedrate); - return run_probe_feed(steps, feedrate); - -} - -bool ZProbe::return_probe(int steps) +bool ZProbe::return_probe(int steps, bool reverse) { // move probe back to where it was @@ -229,16 +232,18 @@ bool ZProbe::return_probe(int steps) this->current_feedrate = fr * Z_STEPS_PER_MM; // feedrate in steps/sec bool dir= steps < 0; + if(reverse) dir= !dir; steps= abs(steps); + bool delta= (this->is_delta || this->is_rdelta); STEPPER[Z_AXIS]->move(dir, steps, 0); - if(this->is_delta) { + if(delta) { STEPPER[X_AXIS]->move(dir, steps, 0); STEPPER[Y_AXIS]->move(dir, steps, 0); } this->running = true; - while(STEPPER[Z_AXIS]->is_moving() || (is_delta && (STEPPER[X_AXIS]->is_moving() || STEPPER[Y_AXIS]->is_moving())) ) { + while(STEPPER[Z_AXIS]->is_moving() || (delta && (STEPPER[X_AXIS]->is_moving() || STEPPER[Y_AXIS]->is_moving())) ) { // wait for it to complete THEKERNEL->call_event(ON_IDLE); if(THEKERNEL->is_halted()){ @@ -298,23 +303,38 @@ void ZProbe::on_gcode_received(void *argument) int steps; bool probe_result; - if(gcode->has_letter('F')) { - probe_result = run_probe_feed(steps, gcode->get_value('F') / 60); - } else { - probe_result = run_probe(steps); - } + bool reverse= (gcode->has_letter('R') && gcode->get_value('R') != 0); // specify to probe in reverse direction + float rate= gcode->has_letter('F') ? gcode->get_value('F') / 60 : this->slow_feedrate; + probe_result = run_probe(steps, rate, -1, reverse); if(probe_result) { + // the result is in actuator coordinates and raw steps gcode->stream->printf("Z:%1.4f C:%d\n", zsteps_to_mm(steps), steps); + + // set the last probe position to the current actuator units + THEKERNEL->robot->set_last_probe_position(std::make_tuple( + THEKERNEL->robot->actuators[X_AXIS]->get_current_position(), + THEKERNEL->robot->actuators[Y_AXIS]->get_current_position(), + THEKERNEL->robot->actuators[Z_AXIS]->get_current_position(), + 1)); + // move back to where it started, unless a Z is specified - if(gcode->has_letter('Z')) { + if(gcode->has_letter('Z') && !is_rdelta) { // set Z to the specified value, and leave probe where it is THEKERNEL->robot->reset_axis_position(gcode->get_value('Z'), Z_AXIS); + } else { - return_probe(steps); + // return to pre probe position + return_probe(steps, reverse); } + } else { gcode->stream->printf("ZProbe not triggered\n"); + THEKERNEL->robot->set_last_probe_position(std::make_tuple( + THEKERNEL->robot->actuators[X_AXIS]->get_current_position(), + THEKERNEL->robot->actuators[Y_AXIS]->get_current_position(), + THEKERNEL->robot->actuators[Z_AXIS]->get_current_position(), + 0)); } } else { @@ -346,7 +366,7 @@ void ZProbe::on_gcode_received(void *argument) } else if(gcode->has_g && gcode->g == 38 ) { // G38.2 Straight Probe with error, G38.3 straight probe without error // linuxcnc/grbl style probe http://www.linuxcnc.org/docs/2.5/html/gcode/gcode.html#sec:G38-probe if(gcode->subcode != 2 && gcode->subcode != 3) { - gcode->stream->printf("error: Only G38.2 and G38.3 are supported\n"); + gcode->stream->printf("error:Only G38.2 and G38.3 are supported\n"); return; } @@ -355,6 +375,7 @@ void ZProbe::on_gcode_received(void *argument) gcode->stream->printf("error:ZProbe not connected.\n"); return; } + if(this->pin.get()) { gcode->stream->printf("error:ZProbe triggered before move, aborting command.\n"); return; @@ -363,53 +384,29 @@ void ZProbe::on_gcode_received(void *argument) // first wait for an empty queue i.e. no moves left THEKERNEL->conveyor->wait_for_empty_queue(); + // turn off any compensation transform + auto savect= THEKERNEL->robot->compensationTransform; + THEKERNEL->robot->compensationTransform= nullptr; + if(gcode->has_letter('X')) { // probe in the X axis - gcode->stream->printf("error:Not currently supported.\n"); + probe_XYZ(gcode, X_AXIS); }else if(gcode->has_letter('Y')) { // probe in the Y axis - gcode->stream->printf("error:Not currently supported.\n"); + probe_XYZ(gcode, Y_AXIS); }else if(gcode->has_letter('Z')) { - // we need to know where we started the probe from - float current_machine_pos[3]; - THEKERNEL->robot->get_axis_position(current_machine_pos); - - // probe down in the Z axis no more than the Z value in mm - float rate = (gcode->has_letter('F')) ? gcode->get_value('F') / 60 : this->slow_feedrate; - int steps; - bool probe_result = run_probe_feed(steps, rate, gcode->get_value('Z')); - - if(probe_result) { - float z= current_machine_pos[Z_AXIS] - zsteps_to_mm(steps); - if(THEKERNEL->is_grbl_mode()) { - gcode->stream->printf("[PRB:%1.3f,%1.3f,%1.3f:1]\n", current_machine_pos[X_AXIS], current_machine_pos[Y_AXIS], z); - - }else{ - gcode->stream->printf("INFO: delta Z %1.4f (Steps %d)\n", steps / Z_STEPS_PER_MM, steps); - } - - // set position to where it stopped - THEKERNEL->robot->reset_axis_position(z, Z_AXIS); - - } else { - if(THEKERNEL->is_grbl_mode()) { - if(gcode->subcode == 2) { - gcode->stream->printf("ALARM: Probe fail\n"); - THEKERNEL->call_event(ON_HALT, nullptr); - } - gcode->stream->printf("[PRB:%1.3f,%1.3f,%1.3f:0]\n", current_machine_pos[X_AXIS], current_machine_pos[Y_AXIS], current_machine_pos[Z_AXIS]); - - }else{ - gcode->stream->printf("error:ZProbe not triggered\n"); - } - } + // probe in the Z axis + probe_XYZ(gcode, Z_AXIS); }else{ gcode->stream->printf("error:at least one of X Y or Z must be specified\n"); - } + + // restore compensationTransform + THEKERNEL->robot->compensationTransform= savect; + return; } else if(gcode->has_m) { @@ -447,13 +444,80 @@ void ZProbe::on_gcode_received(void *argument) } } +uint32_t ZProbe::read_probe(uint32_t dummy) +{ + if(!probing || probe_detected) return 0; + + // TODO add debounce/noise filter + if(this->pin.get()) { + probe_detected= true; + // now tell all the stepper_motors to stop + for(auto &a : THEKERNEL->robot->actuators) a->force_finish_move(); + } + return 0; +} + +// special way to probe in the X or Y or Z direction using planned moves, should work with any kinematics +void ZProbe::probe_XYZ(Gcode *gcode, int axis) +{ + // enable the probe checking in the timer + probing= true; + probe_detected= false; + THEKERNEL->robot->disable_segmentation= true; // we must disable segmentation as this won't work with it enabled (beware on deltas probing in X or Y) + + // get probe feedrate if specified + float rate = (gcode->has_letter('F')) ? gcode->get_value('F')*60 : this->slow_feedrate; + + // do a regular move which will stop as soon as the probe is triggered, or the distance is reached + switch(axis) { + case X_AXIS: coordinated_move(gcode->get_value('X'), 0, 0, rate, true); break; + case Y_AXIS: coordinated_move(0, gcode->get_value('Y'), 0, rate, true); break; + case Z_AXIS: coordinated_move(0, 0, gcode->get_value('Z'), rate, true); break; + } + + // coordinated_move returns when the move is finished + + // disable probe checking + probing= false; + THEKERNEL->robot->disable_segmentation= false; + + float pos[3]; + { + // get the current position + ActuatorCoordinates current_position{ + THEKERNEL->robot->actuators[X_AXIS]->get_current_position(), + THEKERNEL->robot->actuators[Y_AXIS]->get_current_position(), + THEKERNEL->robot->actuators[Z_AXIS]->get_current_position() + }; + + // get machine position from the actuator position using FK + THEKERNEL->robot->arm_solution->actuator_to_cartesian(current_position, pos); + } + + uint8_t probeok= this->probe_detected ? 1 : 0; + + // print results using the GRBL format + gcode->stream->printf("[PRB:%1.3f,%1.3f,%1.3f:%d]\n", pos[X_AXIS], pos[Y_AXIS], pos[Z_AXIS], probeok); + THEKERNEL->robot->set_last_probe_position(std::make_tuple(pos[X_AXIS], pos[Y_AXIS], pos[Z_AXIS], probeok)); + + if(!probeok && gcode->subcode == 2) { + // issue error if probe was not triggered and subcode == 2 + gcode->stream->printf("ALARM:Probe fail\n"); + THEKERNEL->call_event(ON_HALT, nullptr); + + }else if(probeok){ + // if the probe stopped the move we need to correct the last_milestone as it did not reach where it thought + THEKERNEL->robot->reset_position_from_current_actuator_position(); + } +} + // Called periodically to change the speed to match acceleration void ZProbe::acceleration_tick(void) { if(!this->running) return; // nothing to do if(STEPPER[Z_AXIS]->is_moving()) accelerate(Z_AXIS); - if(is_delta) { + if(is_delta || is_rdelta) { // deltas needs to move all actuators for ( int c = X_AXIS; c <= Y_AXIS; c++ ) { if( !STEPPER[c]->is_moving() ) continue;