Skip to content

Commit

Permalink
Devt (#882)
Browse files Browse the repository at this point in the history
* Oled2 (#834)

* WIP

* WIP

* Update platformio.ini

* WIP

* Cleanup

* Update platformio.ini

* Turn off soft limits with max travel (#836)

#831

* Yalang YL620 VFD (#838)

* New SpindleType YL620

Files for new SpindleType Yalang 620. So far the contents are a duplicate of H2ASpindle.h and H2ASpindle.cpp

* Added register documentation and implemented read and write data packets

* Some fixes, mostly regarding RX packet length

* OLED and Other Updates (#844)

* publish

* Updates - CoreXY and OLED

- Moved position calculation out of report_realtime_status(...) so other functions can access it.
- Added a function to check if a limit switch is defined
- CoreXY fixed bug in forward kinematics when midtbot is used.
- Modified OLED display.

* Cleanup for PR

* Delete midtbot_x2.h

* Incorporated PR 846

- Some OLED cleanup
- verified correct forward kinematics on MidTbot

* Pio down rev (#850)

* Update platformio.ini

* Update Grbl.h

* Use local UART driver not HardwareSerial (#857)

* Use local UART driver not HardwareSerial

The HardwareSerial driver is broken in Arduino framework versions
1.0.5 and 1.0.6 .  espressif/arduino-esp32#5005
Instead of waiting for a fix, I wrote a very simple UART driver that
does exactly what we need with no unnecessary bells and whistles to
cause problems.

* Added missing files, changed method signatures

The methods implemented by the UART class now
have the same signatures as the HardwareSerial
class, so it will be easy to switch back if we
need to.

* Incorporated suggestions from Stefan

* Fixed TX_IDLE_NUM bug reported by mstrens

* Quick test for Bf: problem

This is not the final solution.

* Fixed stupid typo in last commit

* Another test - check for client_buffer space

* Use the esp-idf uart driver

You can revert to the direct driver for testing by
defining DIRECT_UART

* Uart class now supports VFD and TMC

* data bits, stop bits, parity as enum classes

The constants for data bits, stop bits, and parity
were changed to enum classes so the compiler can
check for argument order mismatches.

* Set half duplex after uart init

* Init TMC UART only once

* rx/tx pin order mixup, missing _uart_started

* Test: use Arduino Serial

This reverts to the Arduino serial driver for
UI communication, leaving the VFS comms on the
Uart class on top of the esp_idf UART driver.

You can switch back and forth with the
   define REVERT_TO_SERIAL
line in Serial.cpp

* REVERT_TO_ARDUINO_SERIAL off by default

* Added debug messages

* Update Grbl.h

* Update platformio.ini

Co-authored-by: bdring <barton.dring@gmail.com>

* Fixed spindle sync for all VFD spindles (#868)

* Implemented H2A spindle sync fix. Untested.

* Changed the spindle sync fix to be in the VFD code.

* Update Grbl.h

Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com>
Co-authored-by: bdring <barton.dring@gmail.com>

* New jog fix (#872)

* Applied 741 to new Devt

* Make kinematics routines weak

to eliminate ifdefs

* Fixed warning

* Update build date

Co-authored-by: bdring <barton.dring@gmail.com>

* Big kinematics cleanup (#875)

* Applied 741 to new Devt

* Make kinematics routines weak

to eliminate ifdefs

* Fixed warning

* Big kinematics cleanup

* Cleanup

* no isCancelled arg for jog_execute; return it instead

* WIP

* Made OLED compliant with new kinematics

* Added system_get_mpos

* system_get_mpos() returns float*

* WIP

* Cleanup after testing

- Had MPos and WPos text on OLED backwards.
- Added my cartesian test def
- Will remove test defs before merging to devt.

* Cleanup of remaining user optional code.

* Fixed delta kinematics loop ending early.

* Account for jog cancel in saved motor positions

* Update Grbl.h

Co-authored-by: bdring <barton.dring@gmail.com>

Co-authored-by: Mitch Bradley <wmb@firmworks.com>
Co-authored-by: marcosprojects <marco1601@web.de>
Co-authored-by: Stefan de Bruijn <atlaste@users.noreply.github.com>
Co-authored-by: Stefan de Bruijn <stefan@nubilosoft.com>
  • Loading branch information
5 people committed Apr 25, 2021
1 parent 48e204e commit f3ca8b2
Show file tree
Hide file tree
Showing 36 changed files with 604 additions and 421 deletions.
106 changes: 41 additions & 65 deletions Grbl_Esp32/Custom/CoreXY.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,6 @@ const float geometry_factor = 1.0;
const float geometry_factor = 2.0;
#endif

static float last_motors[MAX_N_AXIS] = { 0.0 }; // A place to save the previous motor angles for distance/feed rate calcs
static float last_cartesian[MAX_N_AXIS] = {};

// prototypes for helper functions
Expand All @@ -59,6 +58,19 @@ void machine_init() {
#endif
}

// Converts Cartesian to motors with no motion control
static void cartesian_to_motors(float* position) {
float motors[MAX_N_AXIS];

motors[X_AXIS] = geometry_factor * position[X_AXIS] + position[Y_AXIS];
motors[Y_AXIS] = geometry_factor * position[X_AXIS] - position[Y_AXIS];

position[X_AXIS] = motors[X_AXIS];
position[Y_AXIS] = motors[Y_AXIS];

// Z and higher just pass through unchanged
}

// Cycle mask is 0 unless the user sends a single axis command like $HZ
// This will always return true to prevent the normal Grbl homing cycle
bool user_defined_homing(uint8_t cycle_mask) {
Expand Down Expand Up @@ -131,11 +143,11 @@ bool user_defined_homing(uint8_t cycle_mask) {
}

for (int axis = Z_AXIS; axis < n_axis; axis++) {
target[axis] = system_convert_axis_steps_to_mpos(sys_position, axis);
target[axis] = sys_position[axis] / axis_settings[axis]->steps_per_mm->get();
}

// convert back to motor steps
inverse_kinematics(target);
cartesian_to_motors(target);

pl_data->feed_rate = homing_rate; // feed or seek rates
plan_buffer_line(target, pl_data); // Bypass mc_line(). Directly plan homing motion.
Expand Down Expand Up @@ -222,11 +234,11 @@ bool user_defined_homing(uint8_t cycle_mask) {
last_cartesian[Y_AXIS] = target[Y_AXIS];

for (int axis = Z_AXIS; axis < n_axis; axis++) {
last_cartesian[axis] = system_convert_axis_steps_to_mpos(sys_position, axis);
last_cartesian[axis] = sys_position[axis] / axis_settings[axis]->steps_per_mm->get();
}

// convert to motors
inverse_kinematics(target);
cartesian_to_motors(target);
// convert to steps
for (axis = X_AXIS; axis <= Y_AXIS; axis++) {
sys_position[axis] = target[axis] * axis_settings[axis]->steps_per_mm->get();
Expand All @@ -242,86 +254,52 @@ bool user_defined_homing(uint8_t cycle_mask) {
return true;
}

// This function is used by Grbl convert Cartesian to motors
// this does not do any motion control
void inverse_kinematics(float* position) {
float motors[MAX_N_AXIS];

motors[X_AXIS] = geometry_factor * position[X_AXIS] + position[Y_AXIS];
motors[Y_AXIS] = geometry_factor * position[X_AXIS] - position[Y_AXIS];

position[X_AXIS] = motors[X_AXIS];
position[Y_AXIS] = motors[Y_AXIS];
static void transform_cartesian_to_motors(float* motors, float* cartesian) {
motors[X_AXIS] = geometry_factor * cartesian[X_AXIS] + cartesian[Y_AXIS];
motors[Y_AXIS] = geometry_factor * cartesian[X_AXIS] - cartesian[Y_AXIS];

// Z and higher just pass through unchanged
auto n_axis = number_axis->get();
for (uint8_t axis = Z_AXIS; axis <= n_axis; axis++) {
motors[axis] = cartesian[axis];
}
}

// Inverse Kinematics calculates motor positions from real world cartesian positions
// position is the current position
// position is the old machine position, target the new machine position
// Breaking into segments is not needed with CoreXY, because it is a linear system.
void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position) //The target and position are provided in MPos
{
bool cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position) {
float dx, dy, dz; // distances in each cartesian axis
float motors[MAX_N_AXIS];

float feed_rate = pl_data->feed_rate; // save original feed rate

// calculate cartesian move distance for each axis
dx = target[X_AXIS] - position[X_AXIS];
dy = target[Y_AXIS] - position[Y_AXIS];
dz = target[Z_AXIS] - position[Z_AXIS];
float dist = sqrt((dx * dx) + (dy * dy) + (dz * dz));

motors[X_AXIS] = geometry_factor * target[X_AXIS] + target[Y_AXIS];
motors[Y_AXIS] = geometry_factor * target[X_AXIS] - target[Y_AXIS];

auto n_axis = number_axis->get();
for (uint8_t axis = Z_AXIS; axis <= n_axis; axis++) {
motors[axis] = target[axis];
}

float motor_distance = three_axis_dist(motors, last_motors);
float motors[n_axis];
transform_cartesian_to_motors(motors, target);

if (!pl_data->motion.rapidMotion) {
pl_data->feed_rate *= (motor_distance / dist);
float last_motors[n_axis];
transform_cartesian_to_motors(last_motors, position);
pl_data->feed_rate *= (three_axis_dist(motors, last_motors) / dist);
}

memcpy(last_motors, motors, sizeof(motors));

mc_line(motors, pl_data);
return mc_line(motors, pl_data);
}

// motors -> cartesian
void forward_kinematics(float* position) {
float calc_fwd[MAX_N_AXIS];
float wco[MAX_N_AXIS];
float print_position[N_AXIS];
int32_t current_position[N_AXIS]; // Copy current state of the system position variable

memcpy(current_position, sys_position, sizeof(sys_position));
system_convert_array_steps_to_mpos(print_position, current_position);

// determine the Work Coordinate Offsets for each axis
auto n_axis = number_axis->get();
for (int axis = 0; axis < n_axis; axis++) {
// Apply work coordinate offsets and tool length offset to current position.
wco[axis] = gc_state.coord_system[axis] + gc_state.coord_offset[axis];
if (axis == TOOL_LENGTH_OFFSET_AXIS) {
wco[axis] += gc_state.tool_length_offset;
}
}

void motors_to_cartesian(float* cartesian, float* motors, int n_axis) {
// apply the forward kinemetics to the machine coordinates
// https://corexy.com/theory.html
//calc_fwd[X_AXIS] = 0.5 / geometry_factor * (position[X_AXIS] + position[Y_AXIS]);
calc_fwd[X_AXIS] = ((0.5 * (print_position[X_AXIS] + print_position[Y_AXIS]) / geometry_factor) - wco[X_AXIS]);
calc_fwd[Y_AXIS] = ((0.5 * (print_position[X_AXIS] - print_position[Y_AXIS])) - wco[Y_AXIS]);
cartesian[X_AXIS] = 0.5 * (motors[X_AXIS] + motors[Y_AXIS]) / geometry_factor;
cartesian[Y_AXIS] = 0.5 * (motors[X_AXIS] - motors[Y_AXIS]);

for (int axis = 0; axis < n_axis; axis++) {
if (axis > Y_AXIS) { // for axes above Y there is no kinematics
calc_fwd[axis] = print_position[axis] - wco[axis];
}
position[axis] = calc_fwd[axis]; // this is the value returned to reporting
for (int axis = Z_AXIS; axis < n_axis; axis++) {
cartesian[axis] = motors[axis];
}
}

Expand All @@ -331,14 +309,12 @@ bool kinematics_pre_homing(uint8_t cycle_mask) {

void kinematics_post_homing() {
auto n_axis = number_axis->get();
for (uint8_t axis = X_AXIS; axis <= n_axis; axis++) {
gc_state.position[axis] = last_cartesian[axis];
}
memcpy(gc_state.position, last_cartesian, n_axis * sizeof(last_cartesian[0]));
}

// this is used used by Grbl soft limits to see if the range of the machine is exceeded.
uint8_t kinematic_limits_check(float* target) {
return true;
// this is used used by Limits.cpp to see if the range of the machine is exceeded.
bool limitsCheckTravel(float* target) {
return false;
}

void user_m30() {}
Expand Down
5 changes: 1 addition & 4 deletions Grbl_Esp32/Custom/atari_1020.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,15 +75,12 @@ void machine_init() {
// this task tracks the Z position and sets the solenoid
void solenoidSyncTask(void* pvParameters) {
int32_t current_position[N_AXIS]; // copy of current location
float m_pos[N_AXIS]; // machine position in mm
TickType_t xLastWakeTime;
const TickType_t xSolenoidFrequency = SOLENOID_TASK_FREQ; // in ticks (typically ms)
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
while (true) {
// don't ever return from this or the task dies
memcpy(current_position, sys_position, sizeof(sys_position)); // get current position in step
system_convert_array_steps_to_mpos(m_pos, current_position); // convert to millimeters
calc_solenoid(m_pos[Z_AXIS]); // calculate kinematics and move the servos
calc_solenoid(system_get_mpos()[Z_AXIS]); // calculate kinematics and move the servos
vTaskDelayUntil(&xLastWakeTime, xSolenoidFrequency);
}
}
Expand Down
73 changes: 27 additions & 46 deletions Grbl_Esp32/Custom/custom_code_template.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,37 +24,39 @@
=======================================================================
This is a template for user-defined C++ code functions. Grbl can be
configured to call some optional functions, enabled by #define statements
in the machine definition .h file. Implement the functions thus enabled
herein. The possible functions are listed and described below.
configured to call some optional functions. These functions have weak definitions
in the main code. If you create your own version they will be used instead
To use this file, copy it to a name of your own choosing, and also copy
Machines/template.h to a similar name.
Put all of your functions in a .cpp file in the "Custom" folder.
Add this to your machine definition file
#define CUSTOM_CODE_FILENAME "../Custom/YourFile.cpp"
Example:
Machines/my_machine.h
Custom/my_machine.cpp
Be careful to return the correct values
Edit machine.h to include your Machines/my_machine.h file
===============================================================================
Edit Machines/my_machine.h according to the instructions therein.
Below are all the current weak function
Fill in the function definitions below for the functions that you have
enabled with USE_ defines in Machines/my_machine.h
*/

===============================================================================
/*
This function is used as a one time setup for your machine.
*/
void machine_init() {}

/*
This is used to initialize a display.
*/
void display_init() {}

#ifdef USE_MACHINE_INIT
/*
machine_init() is called when Grbl_ESP32 first starts. You can use it to do any
special things your machine needs at startup.
limitsCheckTravel() is called to check soft limits
It returns true if the motion is outside the limit values
*/
void machine_init() {}
#endif
bool limitsCheckTravel() {
return false;
}

#ifdef USE_CUSTOM_HOMING
/*
user_defined_homing(uint8_t cycle_mask) is called at the begining of the normal Grbl_ESP32 homing
sequence. If user_defined_homing(uint8_t cycle_mask) returns false, the rest of normal Grbl_ESP32
Expand All @@ -66,17 +68,14 @@ bool user_defined_homing(uint8_t cycle_mask) {
// True = done with homing, false = continue with normal Grbl_ESP32 homing
return true;
}
#endif

#ifdef USE_KINEMATICS
/*
Inverse Kinematics converts X,Y,Z cartesian coordinate to the steps
on your "joint" motors. It requires the following three functions:
*/

/*
inverse_kinematics() looks at incoming move commands and modifies
them before Grbl_ESP32 puts them in the motion planner.
cartesian_to_motors() converts from cartesian coordinates to motor space.
Grbl_ESP32 processes arcs by converting them into tiny little line segments.
Kinematics in Grbl_ESP32 works the same way. Search for this function across
Expand All @@ -86,9 +85,9 @@ bool user_defined_homing(uint8_t cycle_mask) {
pl_data = planner data (see the definition of this type to see what it is)
position = an N_AXIS array of where the machine is starting from for this move
*/
void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* position) {
bool cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position) {
// this simply moves to the target. Replace with your kinematics.
mc_line(target, pl_data);
return mc_line(target, pl_data);
}

/*
Expand All @@ -97,60 +96,42 @@ void inverse_kinematics(float* target, plan_line_data_t* pl_data, float* positio
cycle_mask is a bit mask of the axes being homed this time.
*/
bool kinematics_pre_homing(uint8_t cycle_mask))
{
bool kinematics_pre_homing(uint8_t cycle_mask) {
return false; // finish normal homing cycle
}

/*
kinematics_post_homing() is called at the end of normal homing
*/
void kinematics_post_homing() {}
#endif

#ifdef USE_FWD_KINEMATICS
/*
The status command uses forward_kinematics() to convert
The status command uses motors_to_cartesian() to convert
your motor positions to cartesian X,Y,Z... coordinates.
Convert the N_AXIS array of motor positions to cartesian in your code.
*/
void forward_kinematics(float* position) {
void motors_to_cartesian(float* cartesian, float* motors, int n_axis) {
// position[X_AXIS] =
// position[Y_AXIS] =
}
#endif

#ifdef USE_TOOL_CHANGE
/*
user_tool_change() is called when tool change gcode is received,
to perform appropriate actions for your machine.
*/
void user_tool_change(uint8_t new_tool) {}
#endif

#if defined(MACRO_BUTTON_0_PIN) || defined(MACRO_BUTTON_1_PIN) || defined(MACRO_BUTTON_2_PIN)
/*
options. user_defined_macro() is called with the button number to
perform whatever actions you choose.
*/
void user_defined_macro(uint8_t index) {}
#endif

#ifdef USE_M30
/*
user_m30() is called when an M30 gcode signals the end of a gcode file.
*/
void user_m30() {}
#endif

#ifdef USE_MACHINE_TRINAMIC_INIT
/*
machine_triaminic_setup() replaces the normal setup of trinamic
drivers with your own code. For example, you could setup StallGuard
*/
void machine_trinamic_setup() {}
#endif

// If you add any additional functions specific to your machine that
// require calls from common code, guard their calls in the common code with
Expand Down
2 changes: 0 additions & 2 deletions Grbl_Esp32/Custom/mpcnc_laser_module.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/

#ifdef USE_MACHINE_INIT
/*
machine_init() is called when Grbl_ESP32 first starts. You can use it to do any
special things your machine needs at startup.
Expand All @@ -32,4 +31,3 @@ void machine_init() {
pinMode(LVL_SHIFT_ENABLE, OUTPUT);
digitalWrite(LVL_SHIFT_ENABLE, HIGH);
}
#endif
9 changes: 6 additions & 3 deletions Grbl_Esp32/Custom/oled_basic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,6 @@ void draw_checkbox(int16_t x, int16_t y, int16_t width, int16_t height, bool che

void displayDRO() {
uint8_t oled_y_pos;
float print_position[MAX_N_AXIS];
//float wco[MAX_N_AXIS];

display.setTextAlignment(TEXT_ALIGN_LEFT);
Expand All @@ -135,10 +134,14 @@ void displayDRO() {
ControlPins ctrl_pin_state = system_control_get_state();
bool prb_pin_state = probe_get_state();

display.setTextAlignment(TEXT_ALIGN_RIGHT);

float* print_position = system_get_mpos();
if (bit_istrue(status_mask->get(), RtStatus::Position)) {
calc_mpos(print_position);
display.drawString(60, 14, "M Pos");
} else {
calc_wpos(print_position);
display.drawString(60, 14, "W Pos");
mpos_to_wpos(print_position);
}

for (uint8_t axis = X_AXIS; axis < n_axis; axis++) {
Expand Down
Loading

0 comments on commit f3ca8b2

Please sign in to comment.