Commit a2f53e69 authored by MagoKimbra's avatar MagoKimbra

Merge remote-tracking branch 'refs/remotes/origin/dev'

parents 33759619 e5d046c6
This diff is collapsed.
......@@ -61,12 +61,10 @@
#include "module/language/language.h"
#include "module/printcounter/printcounter.h"
#include "module/MK_Main.h"
#include "module/motion/planner.h"
#include "module/planner/planner.h"
#include "module/endstop/endstops.h"
#include "module/motion/stepper_indirection.h"
#include "module/motion/stepper.h"
#include "module/motion/endstops.h"
#include "module/motion/vector_3.h"
#include "module/motion/qr_solve.h"
#include "module/motion/cartesian_correction.h"
#include "module/temperature/temperature.h"
#include "module/sensor/flowmeter.h"
......
......@@ -12,11 +12,11 @@
*
* This program 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
* 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 this program. If not, see <http://www.gnu.org/licenses/>.
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
......@@ -32,11 +32,11 @@
*
* This program 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
* 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 this program. If not, see <http://www.gnu.org/licenses/>.
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*
* Description: *** HAL for Arduino ***
......
......@@ -12,11 +12,11 @@
*
* This program 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
* 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 this program. If not, see <http://www.gnu.org/licenses/>.
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
......
This diff is collapsed.
......@@ -79,8 +79,12 @@ void prepare_move();
void kill(const char *);
void Stop();
#if !MECH(DELTA) && !MECH(SCARA)
void set_current_position_from_planner();
#endif
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
void filrunout();
void handle_filament_runout();
#endif
/**
......
......@@ -444,6 +444,9 @@
#define MIN_PROBE_Y (max(Y_MIN_POS, Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
#define MAX_PROBE_Y (min(Y_MAX_POS, Y_MAX_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
#define HAS_Z_ENDSTOP_SERVO (ENABLED(Z_ENDSTOP_SERVO_NR) && Z_ENDSTOP_SERVO_NR >= 0)
#define SERVO_LEVELING (ENABLED(AUTO_BED_LEVELING_FEATURE) && HAS_Z_ENDSTOP_SERVO)
// Make sure probing points are reachable
#if LEFT_PROBE_BED_POSITION < MIN_PROBE_X
#undef LEFT_PROBE_BED_POSITION
......
......@@ -25,7 +25,7 @@
*/
#include "../../base.h"
#include "endstops.h"
//#include "endstops.h"
// TEST_ENDSTOP: test the old and the current status of an endstop
#define TEST_ENDSTOP(ENDSTOP) (TEST(current_endstop_bits & old_endstop_bits, ENDSTOP))
......@@ -189,6 +189,9 @@ void Endstops::report_state() {
card.sdprinting = false;
card.closeFile();
quickStop();
#if NOMECH(DELTA) && NOMECH(SCARA)
set_current_position_from_planner();
#endif
disable_all_heaters(); // switch off all heaters.
disable_all_coolers();
}
......
/**
* MK & MK4due 3D Printer Firmware
*
......@@ -24,6 +23,7 @@
/**
* laser.cpp - Laser control library for Arduino using 16 bit timers- Version 1
* Copyright (c) 2013 Timothy Schmidt. All right reserved.
* Copyright (c) 2016 Franco (nextime) Lanza
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
......@@ -32,7 +32,7 @@
*
* This library 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
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
......@@ -58,16 +58,16 @@
void timer3_init(int pin) {
#if ENABLED(LASER_PULSE_METHOD)
TCCR3A = 0; // clear control register A
TCCR3B = pulsebit(WGM33); // set mode as phase and frequency correct pwm, stop the timer
TCCR3B = pulsebit(WGM33); // set mode as phase and frequency correct pwm, stop the timer
ICR3 = F_CPU / LASER_PWM / 2; // the counter runs backwards after TOP
ICR3 = F_CPU / LASER_PWM / 2; // the counter runs backwards after TOP
TCCR3B &= ~(bit(CS30) | bit(CS31) | bit(CS32)); // Stop timer
TCCR3A |= pulsebit(COM3A1); // Connect pin5 to timer register
DDRE |= pulsebit(PORTE3); // Actually output on pin 5
TCCR3A |= pulsebit(COM3A1); // Connect pin5 to timer register
DDRE |= pulsebit(PORTE3); // Actually output on pin 5
OCR3A = 0; // Zero duty cycle = OFF
TCCR3B |= pulsebit(CS30); // No prescaler, start timer
OCR3A = 0; // Zero duty cycle = OFF
TCCR3B |= pulsebit(CS30); // No prescaler, start timer
// Use timer4 to end laser pulse
/*
......@@ -162,20 +162,20 @@
void timer4_init(int pin) {
pinMode(pin, OUTPUT);
analogWrite(pin, 1); // let Arduino setup do it's thing to the PWM pin
TCCR4B = 0x00; // stop Timer4 clock for register updates
TCCR4A = 0x82; // Clear OC4A on match, fast PWM mode, lower WGM4x=14
ICR4 = labs(F_CPU / LASER_PWM); // clock cycles per PWM pulse
OCR4A = labs(F_CPU / LASER_PWM) - 1; // ICR4 - 1 force immediate compare on next tick
TCCR4B = 0x18 | 0x01; // upper WGM4x = 14, clock sel = prescaler, start running
noInterrupts();
TCCR4B &= 0xf8; // stop timer, OC4A may be active now
TCNT4 = labs(F_CPU / LASER_PWM); // force immediate compare on next tick
ICR4 = labs(F_CPU / LASER_PWM); // set new PWM period
TCCR4B |= 0x01; // start the timer with proper prescaler value
interrupts();
analogWrite(pin, 1); // let Arduino setup do it's thing to the PWM pin
TCCR4B = 0x00; // stop Timer4 clock for register updates
TCCR4A = 0x82; // Clear OC4A on match, fast PWM mode, lower WGM4x=14
ICR4 = labs(F_CPU / LASER_PWM); // clock cycles per PWM pulse
OCR4A = labs(F_CPU / LASER_PWM) - 1; // ICR4 - 1 force immediate compare on next tick
TCCR4B = 0x18 | 0x01; // upper WGM4x = 14, clock sel = prescaler, start running
noInterrupts();
TCCR4B &= 0xf8; // stop timer, OC4A may be active now
TCNT4 = labs(F_CPU / LASER_PWM); // force immediate compare on next tick
ICR4 = labs(F_CPU / LASER_PWM); // set new PWM period
TCCR4B |= 0x01; // start the timer with proper prescaler value
interrupts();
}
#endif // LASER_PULSE_METHOD
......@@ -305,7 +305,7 @@
#if ENABLED(LASER_PERIPHERALS)
bool laser_peripherals_ok() { return !digitalRead(LASER_PERIPHERALS_STATUS_PIN); }
void laser_peripherals_on() {
digitalWrite(LASER_PERIPHERALS_PIN, LOW);
if (laser.diagnostics)
......@@ -335,7 +335,6 @@
}
}
}
#endif // LASER_PERIPHERALS
#endif // LASERBEAM
......@@ -23,6 +23,7 @@
/**
* laser.cpp - Laser control library for Arduino using 16 bit timers- Version 1
* Copyright (c) 2013 Timothy Schmidt. All right reserved.
* Copyright (c) 2016 Franco (nextime) Lanza
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
......@@ -31,7 +32,7 @@
*
* This library 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
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
......
This diff is collapsed.
......@@ -29,7 +29,7 @@
mesh_bed_leveling::mesh_bed_leveling() { reset(); }
void mesh_bed_leveling::reset() {
active = 0;
status = MBL_STATUS_NONE;
z_offset = 0;
for (int8_t y = MESH_NUM_Y_POINTS; y--;)
for (int8_t x = MESH_NUM_X_POINTS; x--;)
......
......@@ -22,12 +22,14 @@
#if ENABLED(MESH_BED_LEVELING)
enum MBLStatus { MBL_STATUS_NONE = 0, MBL_STATUS_HAS_MESH_BIT = 0, MBL_STATUS_ACTIVE_BIT = 1 };
#define MESH_X_DIST ((MESH_MAX_X - (MESH_MIN_X))/(MESH_NUM_X_POINTS - 1))
#define MESH_Y_DIST ((MESH_MAX_Y - (MESH_MIN_Y))/(MESH_NUM_Y_POINTS - 1))
class mesh_bed_leveling {
public:
bool active;
uint8_t status; // Has Mesh and Is Active bits
float z_offset;
float z_values[MESH_NUM_Y_POINTS][MESH_NUM_X_POINTS];
......@@ -39,6 +41,11 @@
static FORCE_INLINE float get_probe_y(int8_t i) { return MESH_MIN_Y + (MESH_Y_DIST) * i; }
void set_z(const int8_t px, const int8_t py, const float z) { z_values[py][px] = z; }
bool active() { return TEST(status, MBL_STATUS_ACTIVE_BIT); }
void set_active(bool onOff) { if (onOff) SBI(status, MBL_STATUS_ACTIVE_BIT); else CBI(status, MBL_STATUS_ACTIVE_BIT); }
bool has_mesh() { return TEST(status, MBL_STATUS_HAS_MESH_BIT); }
void set_has_mesh(bool onOff) { if (onOff) SBI(status, MBL_STATUS_HAS_MESH_BIT); else CBI(status, MBL_STATUS_HAS_MESH_BIT); }
inline void zigzag(int8_t index, int8_t &px, int8_t &py) {
px = index % (MESH_NUM_X_POINTS);
py = index / (MESH_NUM_X_POINTS);
......
......@@ -12,11 +12,11 @@
*
* This program 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
* 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 this program. If not, see <http://www.gnu.org/licenses/>.
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
......@@ -33,11 +33,11 @@
*
* This program 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
* 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 this program. If not, see <http://www.gnu.org/licenses/>.
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "../../base.h"
......
......@@ -12,11 +12,11 @@
*
* This program 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
* 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 this program. If not, see <http://www.gnu.org/licenses/>.
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
......@@ -33,11 +33,11 @@
*
* This program 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
* 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 this program. If not, see <http://www.gnu.org/licenses/>.
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef MFRC522_H
......
......@@ -12,17 +12,17 @@
*
* This program 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
* 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 this program. If not, see <http://www.gnu.org/licenses/>.
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/**
* cartesian_correction.cpp
* A class that manages hysteresis by inserting extra plan_buffer_line when necessary
* A class that manages hysteresis by inserting extra planner.buffer_line when necessary
* A class that manages ZWobble
*
* Copyright (c) 2012 Neil James Martin
......@@ -86,7 +86,7 @@
//===========================================================================
void Hysteresis::calcSteps() {
for (uint8_t i = 0; i < NUM_AXIS; i++)
m_hysteresis_steps[i] = (long)(m_hysteresis_mm[i] * axis_steps_per_unit[i]);
m_hysteresis_steps[i] = (long)(m_hysteresis_mm[i] * planner.axis_steps_per_unit[i]);
}
//===========================================================================
......@@ -135,9 +135,9 @@
}
//===========================================================================
// insert a plan_buffer_line if required to handle any hysteresis
// insert a planner.buffer_line if required to handle any hysteresis
void Hysteresis::InsertCorrection(const float x, const float y, const float z, const float e) {
long destination[NUM_AXIS] = {x * axis_steps_per_unit[X_AXIS], y * axis_steps_per_unit[Y_AXIS], z * axis_steps_per_unit[Z_AXIS], e * axis_steps_per_unit[E_AXIS + active_extruder]};
long destination[NUM_AXIS] = {x * planner.axis_steps_per_unit[X_AXIS], y * planner.axis_steps_per_unit[Y_AXIS], z * planner.axis_steps_per_unit[Z_AXIS], e * planner.axis_steps_per_unit[E_AXIS + active_extruder]};
uint8_t direction_bits = calc_direction_bits(position, destination);
uint8_t move_bits = calc_move_bits(position, destination);
......@@ -459,12 +459,12 @@
}
//===========================================================================
// insert a plan_buffer_line if required to handle any hysteresis
// insert a planner.buffer_line if required to handle any hysteresis
void ZWobble::InsertCorrection(const float targetZ) {
if (!m_consistent) return; // don't go through consistency checks all the time; just check one bool
float originZ = (float)position[Z_AXIS] / axis_steps_per_unit[Z_AXIS];
float originZ = (float)position[Z_AXIS] / planner.axis_steps_per_unit[Z_AXIS];
if (originZ < ZWOBBLE_MIN_Z || targetZ < ZWOBBLE_MIN_Z) return;
......@@ -492,7 +492,7 @@
ECHO_MV(" Target Rod: ", targetZRod);
// difference in steps between the correct movement (originZRod->targetZRod) and the planned movement
long stepDiff = lround((targetZRod - originZRod) * axis_steps_per_unit[Z_AXIS]) - (lround(targetZ * axis_steps_per_unit[Z_AXIS]) - position[Z_AXIS]);
long stepDiff = lround((targetZRod - originZRod) * planner.axis_steps_per_unit[Z_AXIS]) - (lround(targetZ * planner.axis_steps_per_unit[Z_AXIS]) - position[Z_AXIS]);
if (DEBUGGING(DEBUG))
ECHO_EMV(" stepDiff: ", stepDiff);
......
......@@ -12,17 +12,17 @@
*
* This program 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
* 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 this program. If not, see <http://www.gnu.org/licenses/>.
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/**
* cartesian_correction.h
* A class that manages hysteresis by inserting extra plan_buffer_line when necessary
* A class that manages hysteresis by inserting extra planner.buffer_line when necessary
* A class that manages ZWobble
*
* Copyright (c) 2012 Neil James Martin
......
This diff is collapsed.
......@@ -417,7 +417,7 @@ ISR(TIMER1_COMPA_vect) {
if (cleaning_buffer_counter) {
current_block = NULL;
plan_discard_current_block();
planner.discard_current_block();
#if ENABLED(SD_FINISHED_RELEASECOMMAND)
if ((cleaning_buffer_counter == 1) && (SD_FINISHED_STEPPERRELEASE)) enqueue_and_echo_commands_P(PSTR(SD_FINISHED_RELEASECOMMAND));
#endif
......@@ -438,7 +438,7 @@ ISR(TIMER1_COMPA_vect) {
// If there is no current block, attempt to pop one from the buffer
if (!current_block) {
// Anything in the buffer?
current_block = plan_get_current_block();
current_block = planner.get_current_block();
if (current_block) {
current_block->busy = true;
trapezoid_generator_reset();
......@@ -651,12 +651,6 @@ ISR(TIMER1_COMPA_vect) {
#endif
#endif // LASERBEAM
// safe check for erroneous calculated events count
if(current_block->step_event_count >= MAX_EVENTS_COUNT) {
kill_current_block();
break;
}
step_events_completed++;
if (step_events_completed >= current_block->step_event_count) break;
}
......@@ -710,7 +704,6 @@ ISR(TIMER1_COMPA_vect) {
if (step_rate <= acc_step_rate) {
step_rate = acc_step_rate - step_rate; // Decelerate from acceleration end point.
// lower limit
NOLESS(step_rate, current_block->final_rate);
}
else {
......@@ -763,7 +756,7 @@ ISR(TIMER1_COMPA_vect) {
// If current block is finished, reset pointer
if (step_events_completed >= current_block->step_event_count) {
current_block = NULL;
plan_discard_current_block();
planner.discard_current_block();
#if ENABLED(LASERBEAM) && ENABLED(LASER_PULSE_METHOD)
if (current_block->laser_mode == CONTINUOUS && current_block->laser_status == LASER_ON)
laser_extinguish();
......@@ -1043,7 +1036,7 @@ void st_init() {
/**
* Block until all buffered steps are executed
*/
void st_synchronize() { while (blocks_queued()) idle(); }
void st_synchronize() { while (planner.blocks_queued()) idle(); }
/**
* Set the stepper positions directly in steps
......@@ -1119,7 +1112,7 @@ float st_get_axis_position_mm(AxisEnum axis) {
axis_pos = st_get_position(axis);
#endif
return axis_pos / axis_steps_per_unit[axis];
return axis_pos / planner.axis_steps_per_unit[axis];
}
void enable_all_steppers() {
......@@ -1150,7 +1143,7 @@ void finishAndDisableSteppers() {
void quickStop() {
cleaning_buffer_counter = 5000;
DISABLE_STEPPER_DRIVER_INTERRUPT();
while (blocks_queued()) plan_discard_current_block();
while (planner.blocks_queued()) planner.discard_current_block();
current_block = NULL;
ENABLE_STEPPER_DRIVER_INTERRUPT();
}
......@@ -1217,7 +1210,7 @@ void kill_current_block() {
}
float triggered_position_mm(AxisEnum axis) {
return endstops_trigsteps[axis] / axis_steps_per_unit[axis];
return endstops_trigsteps[axis] / planner.axis_steps_per_unit[axis];
}
bool motor_direction(AxisEnum axis) { return TEST(last_direction_bits, axis); }
......@@ -1456,7 +1449,7 @@ void microstep_readings() {
}
#if ENABLED(Z_DUAL_ENDSTOPS)
void In_Homing_Process(bool state) { performing_homing = state; }
void Lock_z_motor(bool state) { locked_z_motor = state; }
void Lock_z2_motor(bool state) { locked_z2_motor = state; }
void set_homing_flag(bool state) { performing_homing = state; }
void set_z_lock(bool state) { locked_z_motor = state; }
void set_z2_lock(bool state) { locked_z2_motor = state; }
#endif
......@@ -22,10 +22,26 @@
/**
* stepper.h - stepper motor driver: executes motion plans of planner.c using the stepper motors
* Part of Grbl
*
* 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 <http://www.gnu.org/licenses/>.
*/
#ifndef STEPPER_H
#define STEPPER_H
#define STEPPER_H
/**
* Axis indices as enumerated constants
......@@ -107,9 +123,9 @@
void kill_current_block();
#if ENABLED(Z_DUAL_ENDSTOPS)
void In_Homing_Process(bool state);
void Lock_z_motor(bool state);
void Lock_z2_motor(bool state);
void set_homing_flag(bool state);
void set_z_lock(bool state);
void set_z2_lock(bool state);
#endif
#if ENABLED(BABYSTEPPING)
......
This diff is collapsed.
/**
* MK & MK4due 3D Printer Firmware
*
* Based on Marlin, Sprinter and grbl
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
* Copyright (C) 2013 - 2016 Alberto Cotronei @MagoKimbra
*
* This program 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.
*
* This program 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 this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/**
* vector_3.cpp - Vector library for bed leveling
* Copyright (c) 2012 Lars Brubaker. All right reserved.
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 2.1 of the License, or (at your option) any later version.
*
* This library 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
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include "../../base.h"
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#include <math.h>
#include "vector_3.h"
vector_3::vector_3() : x(0), y(0), z(0) { }
vector_3::vector_3(float x_, float y_, float z_) : x(x_), y(y_), z(z_) { }
vector_3 vector_3::cross(vector_3 left, vector_3 right) {
return vector_3(left.y * right.z - left.z * right.y,
left.z * right.x - left.x * right.z,
left.x * right.y - left.y * right.x);
}
vector_3 vector_3::operator+(vector_3 v) { return vector_3((x + v.x), (y + v.y), (z + v.z)); }
vector_3 vector_3::operator-(vector_3 v) { return vector_3((x - v.x), (y - v.y), (z - v.z)); }
vector_3 vector_3::get_normal() {
vector_3 normalized = vector_3(x, y, z);
normalized.normalize();
return normalized;
}
float vector_3::get_length() { return sqrt((x * x) + (y * y) + (z * z)); }
void vector_3::normalize() {
float length = get_length();
x /= length;
y /= length;
z /= length;
}
void vector_3::apply_rotation(matrix_3x3 matrix) {
float resultX = x * matrix.matrix[0][0] + y * matrix.matrix[1][0] + z * matrix.matrix[2][0];
float resultY = x * matrix.matrix[0][1] + y * matrix.matrix[1][1] + z * matrix.matrix[2][1];
float resultZ = x * matrix.matrix[0][2] + y * matrix.matrix[1][2] + z * matrix.matrix[2][2];
x = resultX;
y = resultY;
z = resultZ;
}
void vector_3::debug(const char title[]) {
ECHO_ST(DB, title);
ECHO_MV(" x: ", x, 6);
ECHO_MV(" y: ", y, 6);
ECHO_EMV(" z: ", z, 6);
}
void apply_rotation_xyz(matrix_3x3 matrix, float& x, float& y, float& z) {
vector_3 vector = vector_3(x, y, z);
vector.apply_rotation(matrix);
x = vector.x;
y = vector.y;
z = vector.z;
}
matrix_3x3 matrix_3x3::create_from_rows(vector_3 row_0, vector_3 row_1, vector_3 row_2) {
//row_0.debug("row_0");
//row_1.debug("row_1");
//row_2.debug("row_2");
matrix_3x3 new_matrix;
new_matrix.matrix[0][0] = row_0.x; new_matrix.matrix[0][1] = row_0.y; new_matrix.matrix[0][2] = row_0.z;
new_matrix.matrix[1][0] = row_1.x; new_matrix.matrix[1][1] = row_1.y; new_matrix.matrix[1][2] = row_1.z;
new_matrix.matrix[2][0] = row_2.x; new_matrix.matrix[2][1] = row_2.y; new_matrix.matrix[2][2] = row_2.z;
//new_matrix.debug("new_matrix");
return new_matrix;
}
void matrix_3x3::set_to_identity() {
matrix[0][0] = 1; matrix[0][1] = 0; matrix[0][2] = 0;
matrix[1][0] = 0; matrix[1][1] = 1; matrix[1][2] = 0;
matrix[2][0] = 0; matrix[2][1] = 0; matrix[2][2] = 1;
}
matrix_3x3 matrix_3x3::create_look_at(vector_3 target) {
vector_3 z_row = target.get_normal();
vector_3 x_row = vector_3(1, 0, -target.x / target.z).get_normal();
vector_3 y_row = vector_3::cross(z_row, x_row).get_normal();
// x_row.debug("x_row");
// y_row.debug("y_row");
// z_row.debug("z_row");
// create the matrix already correctly transposed
matrix_3x3 rot = matrix_3x3::create_from_rows(x_row, y_row, z_row);
// rot.debug("rot");
return rot;
}
matrix_3x3 matrix_3x3::transpose(matrix_3x3 original) {
matrix_3x3 new_matrix;
new_matrix.matrix[0][0] = original.matrix[0][0]; new_matrix.matrix[0][1] = original.matrix[1][0]; new_matrix.matrix[0][2] = original.matrix[2][0];
new_matrix.matrix[1][0] = original.matrix[0][1]; new_matrix.matrix[1][1] = original.matrix[1][1]; new_matrix.matrix[1][2] = original.matrix[2][1];
new_matrix.matrix[2][0] = original.matrix[0][2]; new_matrix.matrix[2][1] = original.matrix[1][2]; new_matrix.matrix[2][2] = original.matrix[2][2];
return new_matrix;
}
void matrix_3x3::debug(const char title[]) {
ECHO_LT(DB, title);
for (uint8_t i = 0; i < 3; i++) {
ECHO_S(DB);
for (uint8_t j = 0; j < 3; j++) {
if (matrix[i][j] >= 0.0) ECHO_C('+');
ECHO_V(matrix[i][j], 6);
ECHO_C(' ');
}
ECHO_E;
}
}
#endif // AUTO_BED_LEVELING_FEATURE
This diff is collapsed.
......@@ -12,31 +12,39 @@
*
* This program 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
* 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 this program. If not, see <http://www.gnu.org/licenses/>.
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#include "../../base.h"
#ifndef QR_SOLVE_H
#define QR_SOLVE_H
#if ENABLED(AUTO_BED_LEVELING_GRID)
void daxpy(int n, double da, double dx[], int incx, double dy[], int incy);
double ddot(int n, double dx[], int incx, double dy[], int incy);
double dnrm2(int n, double x[], int incx);
void dqrank(double a[], int lda, int m, int n, double tol, int* kr,
int jpvt[], double qraux[]);
void dqrdc(double a[], int lda, int n, int p, double qraux[], int jpvt[],
double work[], int job);
int dqrls(double a[], int lda, int m, int n, double tol, int* kr, double b[],
double x[], double rsd[], int jpvt[], double qraux[], int itask);
void dqrlss(double a[], int lda, int m, int n, int kr, double b[], double x[],
double rsd[], int jpvt[], double qraux[]);
int dqrsl(double a[], int lda, int n, int k, double qraux[], double y[],
double qy[], double qty[], double b[], double rsd[], double ab[], int job);
void dscal(int n, double sa, double x[], int incx);
void dswap(int n, double x[], int incx, double y[], int incy);
void qr_solve(double x[], int m, int n, double a[], double b[]);
void daxpy(int n, double da, double dx[], int incx, double dy[], int incy);
double ddot(int n, double dx[], int incx, double dy[], int incy);
double dnrm2(int n, double x[], int incx);
void dqrank(double a[], int lda, int m, int n, double tol, int* kr,
int jpvt[], double qraux[]);
void dqrdc(double a[], int lda, int n, int p, double qraux[], int jpvt[],
double work[], int job);
int dqrls(double a[], int lda, int m, int n, double tol, int* kr, double b[],
double x[], double rsd[], int jpvt[], double qraux[], int itask);
void dqrlss(double a[], int lda, int m, int n, int kr, double b[], double x[],
double rsd[], int jpvt[], double qraux[]);
int dqrsl(double a[], int lda, int n, int k, double qraux[], double y[],
double qy[], double qty[], double b[], double rsd[], double ab[], int job);
void dscal(int n, double sa, double x[], int incx);
void dswap(int n, double x[], int incx, double y[], int incy);
void qr_solve(double x[], int m, int n, double a[], double b[]);
#endif // ENABLED(AUTO_BED_LEVELING_GRID)
#endif // QR_SOLVE_H
#endif
/**
* MK & MK4due 3D Printer Firmware
*
* Based on Marlin, Sprinter and grbl
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
* Copyright (C) 2013 - 2016 Alberto Cotronei @MagoKimbra
*
* This program 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.
*
* This program 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 this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/**
* vector_3.cpp - Vector library for bed leveling
* Copyright (c) 2012 Lars Brubaker. All right reserved.
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 2.1 of the License, or (at your option) any later version.
*
* This library 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
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include "../../base.h"
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#include <math.h>
#include "vector_3.h"
vector_3::vector_3() : x(0), y(0), z(0) { }
vector_3::vector_3(float x_, float y_, float z_) : x(x_), y(y_), z(z_) { }
vector_3 vector_3::cross(vector_3 left, vector_3 right) {
return vector_3(left.y * right.z - left.z * right.y,
left.z * right.x - left.x * right.z,
left.x * right.y - left.y * right.x);
}
vector_3 vector_3::operator+(vector_3 v) { return vector_3((x + v.x), (y + v.y), (z + v.z)); }
vector_3 vector_3::operator-(vector_3 v) { return vector_3((x - v.x), (y - v.y), (z - v.z)); }
vector_3 vector_3::get_normal() {
vector_3 normalized = vector_3(x, y, z);
normalized.normalize();
return normalized;
}
float vector_3::get_length() { return sqrt((x * x) + (y * y) + (z * z)); }
void vector_3::normalize() {
float length = get_length();
x /= length;
y /= length;
z /= length;
}
void vector_3::apply_rotation(matrix_3x3 matrix) {
float resultX = x * matrix.matrix[3 * 0 + 0] + y * matrix.matrix[3 * 1 + 0] + z * matrix.matrix[3 * 2 + 0];
float resultY = x * matrix.matrix[3 * 0 + 1] + y * matrix.matrix[3 * 1 + 1] + z * matrix.matrix[3 * 2 + 1];
float resultZ = x * matrix.matrix[3 * 0 + 2] + y * matrix.matrix[3 * 1 + 2] + z * matrix.matrix[3 * 2 + 2];
x = resultX;
y = resultY;
z = resultZ;
}
void vector_3::debug(const char title[]) {
ECHO_ST(DB, title);
ECHO_MV(" x: ", x, 6);
ECHO_MV(" y: ", y, 6);
ECHO_EMV(" z: ", z, 6);
}
void apply_rotation_xyz(matrix_3x3 matrix, float& x, float& y, float& z) {
vector_3 vector = vector_3(x, y, z);
vector.apply_rotation(matrix);
x = vector.x;
y = vector.y;
z = vector.z;
}
matrix_3x3 matrix_3x3::create_from_rows(vector_3 row_0, vector_3 row_1, vector_3 row_2) {
//row_0.debug("row_0");
//row_1.debug("row_1");
//row_2.debug("row_2");
matrix_3x3 new_matrix;
new_matrix.matrix[0] = row_0.x; new_matrix.matrix[1] = row_0.y; new_matrix.matrix[2] = row_0.z;
new_matrix.matrix[3] = row_1.x; new_matrix.matrix[4] = row_1.y; new_matrix.matrix[5] = row_1.z;
new_matrix.matrix[6] = row_2.x; new_matrix.matrix[7] = row_2.y; new_matrix.matrix[8] = row_2.z;
//new_matrix.debug("new_matrix");
return new_matrix;
}
void matrix_3x3::set_to_identity() {
matrix[0] = 1; matrix[1] = 0; matrix[2] = 0;
matrix[3] = 0; matrix[4] = 1; matrix[5] = 0;
matrix[6] = 0; matrix[7] = 0; matrix[8] = 1;
}
matrix_3x3 matrix_3x3::create_look_at(vector_3 target) {
vector_3 z_row = target.get_normal();
vector_3 x_row = vector_3(1, 0, -target.x / target.z).get_normal();
vector_3 y_row = vector_3::cross(z_row, x_row).get_normal();
// x_row.debug("x_row");
// y_row.debug("y_row");
// z_row.debug("z_row");
// create the matrix already correctly transposed
matrix_3x3 rot = matrix_3x3::create_from_rows(x_row, y_row, z_row);
// rot.debug("rot");
return rot;
}
matrix_3x3 matrix_3x3::transpose(matrix_3x3 original) {
matrix_3x3 new_matrix;
new_matrix.matrix[0] = original.matrix[0]; new_matrix.matrix[1] = original.matrix[3]; new_matrix.matrix[2] = original.matrix[6];
new_matrix.matrix[3] = original.matrix[1]; new_matrix.matrix[4] = original.matrix[4]; new_matrix.matrix[5] = original.matrix[7];
new_matrix.matrix[6] = original.matrix[2]; new_matrix.matrix[7] = original.matrix[5]; new_matrix.matrix[8] = original.matrix[8];
return new_matrix;
}
void matrix_3x3::debug(const char title[]) {
ECHO_LT(DB, title);
int count = 0;
for (int i = 0; i < 3; i++) {
for (int j = 0; j < 3; j++) {
if (matrix[count] >= 0.0) ECHO_C('+');
ECHO_V(matrix[count], 6);
ECHO_C(' ');
count++;
}
ECHO_E;
}
}
#endif // AUTO_BED_LEVELING_FEATURE
......@@ -12,11 +12,11 @@
*
* This program 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
* 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 this program. If not, see <http://www.gnu.org/licenses/>.
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
......@@ -33,11 +33,11 @@
*
* This Library 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
* 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 the Arduino SdFat Library. If not, see
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
......
......@@ -12,11 +12,11 @@
*
* This program 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
* 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 this program. If not, see <http://www.gnu.org/licenses/>.
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
......
......@@ -12,11 +12,11 @@
*
* This program 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
* 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 this program. If not, see <http://www.gnu.org/licenses/>.
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
......
......@@ -12,11 +12,11 @@
*
* This program 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
* 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 this program. If not, see <http://www.gnu.org/licenses/>.
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
......
......@@ -39,7 +39,7 @@
*/
/**
* Defines for 16 bit timers used with Servo library
* Defines for 16 bit timers used with Servo library
*
* If _useTimerX is defined then TimerX is a 16 bit timer on the current board
* timer16_Sequence_t enumerates the sequence that the timers should be allocated
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment