1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-09-08 21:30:54 +02:00

Fixed a few more 'get' calls.

This commit is contained in:
Stefan de Bruijn
2021-05-20 22:33:23 +02:00
parent 61373732bf
commit de407666c9
10 changed files with 31 additions and 13 deletions

View File

@@ -22,6 +22,7 @@
*/ */
#include "Grbl.h" #include "Grbl.h"
#include "MachineConfig.h"
// Sets up valid jog motion received from g-code parser, checks for soft-limits, and executes the jog. // Sets up valid jog motion received from g-code parser, checks for soft-limits, and executes the jog.
// cancelledInflight will be set to true if was not added to parser due to a cancelJog. // cancelledInflight will be set to true if was not added to parser due to a cancelJog.
@@ -35,7 +36,7 @@ Error jog_execute(plan_line_data_t* pl_data, parser_block_t* gc_block, bool* can
pl_data->line_number = gc_block->values.n; pl_data->line_number = gc_block->values.n;
#endif #endif
if (soft_limits->get()) { if (MachineConfig::instance()->_axes->hasSoftLimits()) {
if (limitsCheckTravel(gc_block->values.xyz)) { if (limitsCheckTravel(gc_block->values.xyz)) {
return Error::TravelExceeded; return Error::TravelExceeded;
} }

View File

@@ -133,6 +133,7 @@ void limits_go_home(uint8_t cycle_mask) {
if (bit_istrue(cycle_mask, bit(idx))) { if (bit_istrue(cycle_mask, bit(idx))) {
n_active_axis++; n_active_axis++;
sys_position[idx] = 0; sys_position[idx] = 0;
// Set target direction based on cycle mask and homing cycle approach state. // Set target direction based on cycle mask and homing cycle approach state.
// NOTE: This happens to compile smaller than any other implementation tried. // NOTE: This happens to compile smaller than any other implementation tried.
auto mask = homing_dir_mask->get(); auto mask = homing_dir_mask->get();
@@ -418,8 +419,10 @@ bool __attribute__((weak)) limitsCheckTravel(float* target) {
auto n_axis = MachineConfig::instance()->_axes->_numberAxis; auto n_axis = MachineConfig::instance()->_axes->_numberAxis;
for (idx = 0; idx < n_axis; idx++) { for (idx = 0; idx < n_axis; idx++) {
float max_mpos, min_mpos; float max_mpos, min_mpos;
auto axisSetting = MachineConfig::instance()->_axes->_axis[idx];
if ((target[idx] < limitsMinPosition(idx) || target[idx] > limitsMaxPosition(idx)) && axis_settings[idx]->max_travel->get() > 0) {
if ((target[idx] < limitsMinPosition(idx) || target[idx] > limitsMaxPosition(idx)) && axisSetting->_maxTravel > 0) {
return true; return true;
} }
} }

View File

@@ -121,6 +121,17 @@ public:
return false; return false;
} }
inline bool hasHardLimits() const {
for (int i = 0; i < _numberAxis; ++i) {
for (int j = 0; j < Axis::MAX_NUMBER_GANGED; ++j) {
if (_axis[i]->_gangs[j]->_endstops != nullptr && _axis[i]->_gangs[j]->_endstops->_hardLimits) {
return true;
}
}
}
return false;
}
// These are used for setup and to talk to the motors as a group. // These are used for setup and to talk to the motors as a group.
void init(); void init();
void read_settings(); // more like 'after read settings, before init'. Oh well... void read_settings(); // more like 'after read settings, before init'. Oh well...
@@ -338,7 +349,7 @@ public:
bool _laserMode = false; bool _laserMode = false;
int _pulseMicroSeconds = 3; int _pulseMicroSeconds = 3;
float _arcTolerance = 0.002; float _arcTolerance = 0.002;
float _junctionDeviation = 0.01; float _junctionDeviation = 0.01;
static MachineConfig*& instance() { static MachineConfig*& instance() {
static MachineConfig* instance = nullptr; static MachineConfig* instance = nullptr;

View File

@@ -364,7 +364,7 @@ namespace Motors {
dxl_count_min = DXL_COUNT_MIN; dxl_count_min = DXL_COUNT_MIN;
dxl_count_max = DXL_COUNT_MAX; dxl_count_max = DXL_COUNT_MAX;
if (bitnum_istrue(dir_invert_mask->get(), axis)) { // normal direction if (_invert_direction) { // normal direction
swap(dxl_count_min, dxl_count_max); swap(dxl_count_min, dxl_count_max);
} }

View File

@@ -96,7 +96,7 @@ namespace Motors {
void init_uart(uint8_t id, uint8_t axis_index, uint8_t dual_axis_index); void init_uart(uint8_t id, uint8_t axis_index, uint8_t dual_axis_index);
static void dxl_finish_message(uint8_t id, char* msg, uint16_t msg_len); static void dxl_finish_message(uint8_t id, char* msg, uint16_t msg_len);
static uint16_t dxl_update_crc(uint16_t crc_accum, char* data_blk_ptr, uint8_t data_blk_size); static uint16_t dxl_update_crc(uint16_t crc_accum, char* data_blk_ptr, uint8_t data_blk_size);
static void dxl_bulk_goal_position(); // set all motorsd init_uart(uint8_t id, uint8_t axis_index, uint8_t dual_axis_index); void dxl_bulk_goal_position(); // set all motorsd init_uart(uint8_t id, uint8_t axis_index, uint8_t dual_axis_index);
float _homing_position; float _homing_position;

View File

@@ -368,7 +368,7 @@ namespace Motors {
if (sys.state == State::Cycle || sys.state == State::Homing || sys.state == State::Jog) { if (sys.state == State::Cycle || sys.state == State::Homing || sys.state == State::Jog) {
for (TrinamicDriver* p = List; p; p = p->link) { for (TrinamicDriver* p = List; p; p = p->link) {
if (p->_stallguardDebugMode) { if (p->_stallguardDebugMode) {
//grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "SG:%d", stallguard_debug_mask->get()); //grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "SG:%d", p->_stallguardDebugMode);
p->debug_message(); p->debug_message();
} }
} }

View File

@@ -165,8 +165,9 @@ float limit_acceleration_by_axis_maximum(float* unit_vec) {
float limit_value = SOME_LARGE_VALUE; float limit_value = SOME_LARGE_VALUE;
auto n_axis = MachineConfig::instance()->_axes->_numberAxis; auto n_axis = MachineConfig::instance()->_axes->_numberAxis;
for (idx = 0; idx < n_axis; idx++) { for (idx = 0; idx < n_axis; idx++) {
auto axisSetting = MachineConfig::instance()->_axes->_axis[idx];
if (unit_vec[idx] != 0) { // Avoid divide by zero. if (unit_vec[idx] != 0) { // Avoid divide by zero.
limit_value = MIN(limit_value, fabs(axis_settings[idx]->acceleration->get() / unit_vec[idx])); limit_value = MIN(limit_value, fabs(axisSetting->_acceleration / unit_vec[idx]));
} }
} }
// The acceleration setting is stored and displayed in units of mm/sec^2, // The acceleration setting is stored and displayed in units of mm/sec^2,
@@ -181,8 +182,9 @@ float limit_rate_by_axis_maximum(float* unit_vec) {
float limit_value = SOME_LARGE_VALUE; float limit_value = SOME_LARGE_VALUE;
auto n_axis = MachineConfig::instance()->_axes->_numberAxis; auto n_axis = MachineConfig::instance()->_axes->_numberAxis;
for (idx = 0; idx < n_axis; idx++) { for (idx = 0; idx < n_axis; idx++) {
auto axisSetting = MachineConfig::instance()->_axes->_axis[idx];
if (unit_vec[idx] != 0) { // Avoid divide by zero. if (unit_vec[idx] != 0) { // Avoid divide by zero.
limit_value = MIN(limit_value, fabs(axis_settings[idx]->max_rate->get() / unit_vec[idx])); limit_value = MIN(limit_value, fabs(axisSetting->_maxRate / unit_vec[idx]));
} }
} }
return limit_value; return limit_value;

View File

@@ -320,14 +320,15 @@ uint8_t plan_buffer_line(float* target, plan_line_data_t* pl_data) {
memcpy(position_steps, pl.position, sizeof(pl.position)); memcpy(position_steps, pl.position, sizeof(pl.position));
} }
auto n_axis = MachineConfig::instance()->_axes->_numberAxis; auto n_axis = MachineConfig::instance()->_axes->_numberAxis;
auto axisSettings = MachineConfig::instance()->_axes->_axis;
for (idx = 0; idx < n_axis; idx++) { for (idx = 0; idx < n_axis; idx++) {
// Calculate target position in absolute steps, number of steps for each axis, and determine max step events. // Calculate target position in absolute steps, number of steps for each axis, and determine max step events.
// Also, compute individual axes distance for move and prep unit vector calculations. // Also, compute individual axes distance for move and prep unit vector calculations.
// NOTE: Computes true distance from converted step values. // NOTE: Computes true distance from converted step values.
target_steps[idx] = lround(target[idx] * axis_settings[idx]->steps_per_mm->get()); target_steps[idx] = lround(target[idx] * axisSettings[idx]->_stepsPerMm);
block->steps[idx] = labs(target_steps[idx] - position_steps[idx]); block->steps[idx] = labs(target_steps[idx] - position_steps[idx]);
block->step_event_count = MAX(block->step_event_count, block->steps[idx]); block->step_event_count = MAX(block->step_event_count, block->steps[idx]);
delta_mm = (target_steps[idx] - position_steps[idx]) / axis_settings[idx]->steps_per_mm->get(); delta_mm = (target_steps[idx] - position_steps[idx]) / axisSettings[idx]->_stepsPerMm;
unit_vec[idx] = delta_mm; // Store unit vector numerator unit_vec[idx] = delta_mm; // Store unit vector numerator
// Set direction bits. Bit enabled always means direction is negative. // Set direction bits. Bit enabled always means direction is negative.
if (delta_mm < 0.0) { if (delta_mm < 0.0) {
@@ -403,7 +404,7 @@ uint8_t plan_buffer_line(float* target, plan_line_data_t* pl_data) {
float sin_theta_d2 = sqrt(0.5 * (1.0 - junction_cos_theta)); // Trig half angle identity. Always positive. float sin_theta_d2 = sqrt(0.5 * (1.0 - junction_cos_theta)); // Trig half angle identity. Always positive.
block->max_junction_speed_sqr = block->max_junction_speed_sqr =
MAX(MINIMUM_JUNCTION_SPEED * MINIMUM_JUNCTION_SPEED, MAX(MINIMUM_JUNCTION_SPEED * MINIMUM_JUNCTION_SPEED,
(junction_acceleration * junction_deviation->get() * sin_theta_d2) / (1.0 - sin_theta_d2)); (junction_acceleration * MachineConfig::instance()->_junctionDeviation * sin_theta_d2) / (1.0 - sin_theta_d2));
} }
} }
} }

View File

@@ -54,7 +54,7 @@ void Probe::set_direction(bool is_away) {
// Returns the probe pin state. Triggered = true. Called by gcode parser and probe state monitor. // Returns the probe pin state. Triggered = true. Called by gcode parser and probe state monitor.
bool Probe::get_state() { bool Probe::get_state() {
return _probePin.undefined() ? false : _probePin.read() ^ probe_invert->get(); return _probePin.undefined() ? false : _probePin.read();
} }
// Monitors probe pin state and records the system position when detected. Called by the // Monitors probe pin state and records the system position when detected. Called by the

View File

@@ -110,7 +110,7 @@ void protocol_main_loop() {
//uint8_t client = CLIENT_SERIAL; // default client //uint8_t client = CLIENT_SERIAL; // default client
// Perform some machine checks to make sure everything is good to go. // Perform some machine checks to make sure everything is good to go.
#ifdef CHECK_LIMITS_AT_INIT #ifdef CHECK_LIMITS_AT_INIT
if (hard_limits->get()) { if (MachineConfig::instance()->_axes->hasHardLimits()) {
if (limits_get_state()) { if (limits_get_state()) {
sys.state = State::Alarm; // Ensure alarm state is active. sys.state = State::Alarm; // Ensure alarm state is active.
report_feedback_message(Message::CheckLimits); report_feedback_message(Message::CheckLimits);