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

Fixed a bunch of signed/unsigned comparisons and implicit type conversions.

This commit is contained in:
Stefan de Bruijn
2021-07-03 22:29:35 +02:00
parent 6b7f9116b0
commit 9a9f9db18c
14 changed files with 57 additions and 60 deletions

View File

@@ -45,7 +45,6 @@ void CoolantControl::init() {
// Returns current coolant output state. Overrides may alter it from programmed state.
CoolantState CoolantControl::get_state() {
CoolantState cl_state = {};
bool pinState;
if (_flood.defined()) {
auto pinState = _flood.read();

View File

@@ -211,8 +211,8 @@ Error gc_execute_line(char* line, uint8_t client) {
// a good enough compromise and catch most all non-integer errors. To make it compliant,
// we would simply need to change the mantissa to int16, but this add compiled flash space.
// Maybe update this later.
int_value = trunc(value);
mantissa = round(100 * (value - int_value)); // Compute mantissa for Gxx.x commands.
int_value = int8_t(trunc(value));
mantissa = int16_t(round(100 * (value - int_value))); // Compute mantissa for Gxx.x commands.
// NOTE: Rounding must be used to catch small floating point errors.
// Check if the g-code word is supported or errors due to modal group violations or has
// been repeated in the g-code block. If ok, update the command or record its value.
@@ -642,7 +642,7 @@ Error gc_execute_line(char* line, uint8_t client) {
break;
case 'N':
axis_word_bit = GCodeWord::N;
gc_block.values.n = trunc(value);
gc_block.values.n = int32_t(trunc(value));
break;
case 'P':
axis_word_bit = GCodeWord::P;
@@ -942,7 +942,7 @@ Error gc_execute_line(char* line, uint8_t client) {
}
}
// Select the coordinate system based on the P word
pValue = trunc(gc_block.values.p); // Convert p value to integer
pValue = int8_t(trunc(gc_block.values.p)); // Convert p value to integer
if (pValue > 0) {
// P1 means G54, P2 means G55, etc.
coord_select = static_cast<CoordIndex>(pValue - 1 + int(CoordIndex::G54));
@@ -1174,7 +1174,7 @@ Error gc_execute_line(char* line, uint8_t client) {
*/
// First, use h_x2_div_d to compute 4*h^2 to check if it is negative or r is smaller
// than d. If so, the sqrt of a negative number is complex and error out.
float h_x2_div_d = 4.0 * gc_block.values.r * gc_block.values.r - x * x - y * y;
float h_x2_div_d = 4.0f * gc_block.values.r * gc_block.values.r - x * x - y * y;
if (h_x2_div_d < 0) {
FAIL(Error::GcodeArcRadiusError); // [Arc radius error]
}
@@ -1208,8 +1208,8 @@ Error gc_execute_line(char* line, uint8_t client) {
gc_block.values.r = -gc_block.values.r; // Finished with r. Set to positive for mc_arc
}
// Complete the operation by calculating the actual center of the arc
gc_block.values.ijk[axis_0] = 0.5 * (x - (y * h_x2_div_d));
gc_block.values.ijk[axis_1] = 0.5 * (y + (x * h_x2_div_d));
gc_block.values.ijk[axis_0] = 0.5f * (x - (y * h_x2_div_d));
gc_block.values.ijk[axis_1] = 0.5f * (y + (x * h_x2_div_d));
} else { // Arc Center Format Offset Mode
if (!(ijk_words & (bit(axis_0) | bit(axis_1)))) {
FAIL(Error::GcodeNoOffsetsInPlane); // [No offsets in plane]
@@ -1436,7 +1436,7 @@ Error gc_execute_line(char* line, uint8_t client) {
}
if ((gc_block.modal.io_control == IoControl::SetAnalogSync) || (gc_block.modal.io_control == IoControl::SetAnalogImmediate)) {
if (gc_block.values.e < MaxUserDigitalPin) {
gc_block.values.q = constrain(gc_block.values.q, 0.0, 100.0); // force into valid range
gc_block.values.q = constrain(gc_block.values.q, 0.0f, 100.0f); // force into valid range
if (gc_block.modal.io_control == IoControl::SetAnalogSync) {
protocol_buffer_synchronize();
}

View File

@@ -155,8 +155,7 @@ static void limits_go_home(uint8_t cycle_mask, uint32_t n_locate_cycles) {
// subsequent fine-positioning steps
bool seek = true;
uint8_t n_active_axis;
AxisMask limit_state, axislock;
AxisMask axislock;
float homing_rate = 0.0;
do {
float* target = system_get_mpos();
@@ -222,7 +221,7 @@ static void limits_go_home(uint8_t cycle_mask, uint32_t n_locate_cycles) {
target[axis] *= limitingRate * scaler;
}
}
homing_rate = sqrt(homing_rate); // Magnitude of homing rate vector
homing_rate = float(sqrt(homing_rate)); // Magnitude of homing rate vector
sys.homing_axis_lock = axislock;
@@ -285,7 +284,7 @@ static void limits_go_home(uint8_t cycle_mask, uint32_t n_locate_cycles) {
// set up pull-off maneuver from axes limit switches that have been homed. This provides
// some initial clearance off the switches and should also help prevent them from falsely
// triggering when hard limits are enabled or when more than one axes shares a limit pin.
int32_t set_axis_position;
// Set machine positions for homed limit switches. Don't update non-homed axes.
for (int axis = 0; axis < n_axis; axis++) {
Machine::Axis* axisConf = config->_axes->_axis[axis];
@@ -295,9 +294,9 @@ static void limits_go_home(uint8_t cycle_mask, uint32_t n_locate_cycles) {
auto pulloff = homing->_pulloff;
auto steps = axisConf->_stepsPerMm;
if (homing->_positiveDirection) {
sys_position[axis] = (mpos + pulloff) * steps;
sys_position[axis] = int32_t((mpos + pulloff) * steps);
} else {
sys_position[axis] = (mpos - pulloff) * steps;
sys_position[axis] = int32_t((mpos - pulloff) * steps);
}
}
}
@@ -591,7 +590,6 @@ bool WEAK_LINK limitsCheckTravel(float* target) {
auto axes = config->_axes;
auto n_axis = axes->_numberAxis;
for (int axis = 0; axis < n_axis; axis++) {
float max_mpos, min_mpos;
auto axisSetting = axes->_axis[axis];
if ((target[axis] < limitsMinPosition(axis) || target[axis] > limitsMaxPosition(axis)) && axisSetting->_maxTravel > 0) {
return true;

View File

@@ -182,7 +182,7 @@ namespace Machine {
// log_debug("Configuration file has " << int(filesize) << " bytes");
buffer = new char[filesize + 1];
long pos = 0;
size_t pos = 0;
while (pos < filesize) {
auto read = file.read((uint8_t*)(buffer + pos), filesize - pos);
if (read == 0) {

View File

@@ -166,14 +166,14 @@ void mc_arc(float* target,
}
// CCW angle between position and target from circle center. Only one atan2() trig computation required.
float angular_travel = atan2(r_axis0 * rt_axis1 - r_axis1 * rt_axis0, r_axis0 * rt_axis0 + r_axis1 * rt_axis1);
float angular_travel = float(atan2(r_axis0 * rt_axis1 - r_axis1 * rt_axis0, r_axis0 * rt_axis0 + r_axis1 * rt_axis1));
if (is_clockwise_arc) { // Correct atan2 output per direction
if (angular_travel >= -ARC_ANGULAR_TRAVEL_EPSILON) {
angular_travel -= 2 * M_PI;
angular_travel -= 2 * float(M_PI);
}
} else {
if (angular_travel <= ARC_ANGULAR_TRAVEL_EPSILON) {
angular_travel += 2 * M_PI;
angular_travel += 2 * float(M_PI);
}
}
@@ -183,7 +183,8 @@ void mc_arc(float* target,
// (2x) arc_tolerance. For 99% of users, this is just fine. If a different arc segment fit
// is desired, i.e. least-squares, midpoint on arc, just change the mm_per_arc_segment calculation.
// For the intended uses of Grbl, this value shouldn't exceed 2000 for the strictest of cases.
uint16_t segments = floor(fabs(0.5 * angular_travel * radius) / sqrt(mconfig->_arcTolerance * (2 * radius - mconfig->_arcTolerance)));
uint16_t segments =
uint16_t(floor(fabs(0.5 * angular_travel * radius) / sqrt(mconfig->_arcTolerance * (2 * radius - mconfig->_arcTolerance))));
if (segments) {
// Multiply inverse feed_rate to compensate for the fact that this movement is approximated
// by a number of discrete segments. The inverse feed_rate should be correct for the sum of
@@ -220,8 +221,8 @@ void mc_arc(float* target,
This is important when there are successive arc motions.
*/
// Computes: cos_T = 1 - theta_per_segment^2/2, sin_T = theta_per_segment - theta_per_segment^3/6) in ~52usec
float cos_T = 2.0 - theta_per_segment * theta_per_segment;
float sin_T = theta_per_segment * 0.16666667 * (cos_T + 4.0);
float cos_T = 2.0f - theta_per_segment * theta_per_segment;
float sin_T = theta_per_segment * 0.16666667f * (cos_T + 4.0f);
cos_T *= 0.5;
float sin_Ti;
float cos_Ti;
@@ -239,8 +240,8 @@ void mc_arc(float* target,
} else {
// Arc correction to radius vector. Computed only every N_ARC_CORRECTION increments. ~375 usec
// Compute exact location by applying transformation matrix from initial radius vector(=-offset).
cos_Ti = cos(i * theta_per_segment);
sin_Ti = sin(i * theta_per_segment);
cos_Ti = float(cos(i * theta_per_segment));
sin_Ti = float(sin(i * theta_per_segment));
r_axis0 = -offset[axis_0] * cos_Ti + offset[axis_1] * sin_Ti;
r_axis1 = -offset[axis_0] * sin_Ti - offset[axis_1] * cos_Ti;
count = 0;

View File

@@ -121,8 +121,8 @@ namespace Motors {
}
void Dynamixel2::read_settings() {
_dxl_count_min = _countMin;
_dxl_count_max = _countMax;
_dxl_count_min = float(_countMin);
_dxl_count_max = float(_countMax);
if (_invert_direction) { // normal direction
swap(_dxl_count_min, _dxl_count_min);
@@ -169,7 +169,7 @@ namespace Motors {
}
auto axis = config->_axes->_axis[_axis_index];
sys_position[_axis_index] = axis->_homing->_mpos * axis->_stepsPerMm; // convert to steps
sys_position[_axis_index] = int32_t(axis->_homing->_mpos * axis->_stepsPerMm); // convert to steps
set_disable(false);
set_location(); // force the PWM to update now
@@ -188,7 +188,7 @@ namespace Motors {
}
uint32_t Dynamixel2::dxl_read_position() {
uint8_t data_len = 4;
uint16_t data_len = 4;
dxl_read(DXL_PRESENT_POSITION, data_len);
@@ -309,7 +309,6 @@ namespace Motors {
*/
void Dynamixel2::dxl_bulk_goal_position() {
char tx_message[100]; // outgoing to dynamixel
float position_min, position_max;
float dxl_count_min, dxl_count_max;
uint16_t msg_index = DXL_MSG_INSTR; // index of the byte in the message we are currently filling
@@ -331,8 +330,8 @@ namespace Motors {
if (current_id != 0) {
count++; // keep track of the count for the message length
dxl_count_min = _countMin;
dxl_count_max = _countMax;
dxl_count_min = float(_countMin);
dxl_count_max = float(_countMax);
if (_invert_direction) { // normal direction
swap(dxl_count_min, dxl_count_max);
@@ -366,9 +365,9 @@ namespace Motors {
//uint16_t msg_len;
uint16_t crc = 0;
// header
msg[DXL_MSG_HDR1] = 0xFF;
msg[DXL_MSG_HDR2] = 0xFF;
msg[DXL_MSG_HDR3] = 0xFD;
msg[DXL_MSG_HDR1] = char(0xFF);
msg[DXL_MSG_HDR2] = char(0xFF);
msg[DXL_MSG_HDR3] = char(0xFD);
//
// reserved
msg[DXL_MSG_RSRV] = 0x00;

View File

@@ -80,11 +80,11 @@ namespace Motors {
static const int DXL_BROADCAST_ID = 0xFE;
// protocol 2 instruction numbers
static const int DXL_INSTR_PING = 0x01;
static const int PING_RSP_LEN = 14;
static const int DXL_READ = 0x02;
static const int DXL_WRITE = 0x03;
static const int DXL_SYNC_WRITE = 0x83;
static const int DXL_INSTR_PING = 0x01;
static const int PING_RSP_LEN = 14;
static const char DXL_READ = char(0x02);
static const char DXL_WRITE = char(0x03);
static const char DXL_SYNC_WRITE = char(0x83);
// protocol 2 register locations
static const int DXL_OPERATING_MODE = 11;

View File

@@ -86,7 +86,7 @@ namespace Motors {
// Homing justs sets the new system position and the servo will move there
bool RcServo::set_homing_mode(bool isHoming) {
auto axis = config->_axes->_axis[_axis_index];
sys_position[_axis_index] = axis->_homing->_mpos * axis->_stepsPerMm; // convert to steps
sys_position[_axis_index] = int32_t(axis->_homing->_mpos * axis->_stepsPerMm); // convert to steps
set_location(); // force the PWM to update now
vTaskDelay(750); // give time to move
@@ -120,8 +120,8 @@ namespace Motors {
void RcServo::read_settings() {
if (_invert_direction) {
// swap the pwm values
_pwm_pulse_min = SERVO_MAX_PULSE * (1.0 + (1.0 - _cal_min));
_pwm_pulse_max = SERVO_MIN_PULSE * (1.0 + (1.0 - _cal_max));
_pwm_pulse_min = SERVO_MAX_PULSE * (1.0f + (1.0f - _cal_min));
_pwm_pulse_max = SERVO_MIN_PULSE * (1.0f + (1.0f - _cal_max));
} else {
_pwm_pulse_min = SERVO_MIN_PULSE * _cal_min;

View File

@@ -91,11 +91,11 @@ uint8_t read_float(const char* line, uint8_t* char_counter, float* float_ptr) {
// expected range of E0 to E-4.
if (fval != 0) {
while (exp <= -2) {
fval *= 0.01;
fval *= 0.01f;
exp += 2;
}
if (exp < 0) {
fval *= 0.1;
fval *= 0.1f;
} else if (exp > 0) {
do {
fval *= 10.0;
@@ -143,7 +143,7 @@ bool delay_msec(int32_t milliseconds, DwellMode mode) {
// Simple hypotenuse computation function.
float hypot_f(float x, float y) {
return sqrt(x * x + y * y);
return float(sqrt(x * x + y * y));
}
float convert_delta_vector_to_unit_vector(float* vector) {
@@ -155,8 +155,8 @@ float convert_delta_vector_to_unit_vector(float* vector) {
magnitude += vector[idx] * vector[idx];
}
}
magnitude = sqrt(magnitude);
float inv_magnitude = 1.0 / magnitude;
magnitude = float(sqrt(magnitude));
float inv_magnitude = 1.0f / magnitude;
for (idx = 0; idx < n_axis; idx++) {
vector[idx] *= inv_magnitude;
}

View File

@@ -30,7 +30,7 @@ enum class DwellMode : uint8_t {
SysSuspend = 1, //G92.1 (Do not alter value)
};
const double SOME_LARGE_VALUE = 1.0E+38;
const float SOME_LARGE_VALUE = 1.0E+38f;
// Axis array index values. Must start with 0 and be continuous.
// Note: You set the number of axes used by changing MAX_N_AXIS.
@@ -60,7 +60,7 @@ static inline int toMotor2(int axis) {
}
// Conversions
const double MM_PER_INCH = (25.40);
const float MM_PER_INCH = (25.40f);
const double INCH_PER_MM = (0.0393701);
// Useful macros

View File

@@ -41,8 +41,8 @@ namespace Pins {
// I/O:
void DebugPinDetail::write(int high) {
if (high != _isHigh) {
_isHigh = high;
if (high != int(_isHigh)) {
_isHigh = bool(high);
if (shouldEvent()) {
WriteSerial("Write %s < %d", toString().c_str(), high);
}
@@ -116,7 +116,7 @@ namespace Pins {
// This method basically ensures we don't flood users:
auto time = millis();
if (_lastEvent + 1000 < time) {
if (uint32_t(_lastEvent + 1000) < time) {
_lastEvent = time;
_eventCount = 1;
return true;

View File

@@ -128,7 +128,7 @@ namespace Pins {
_claimed[index] = true;
// readWriteMask is xor'ed with the value to invert it if active low
_readWriteMask = _attributes.has(PinAttributes::ActiveLow);
_readWriteMask = int(_attributes.has(PinAttributes::ActiveLow));
}
PinAttributes GPIOPinDetail::getAttr() const { return _attributes; }
@@ -181,7 +181,7 @@ namespace Pins {
// If the pin is ActiveLow, we should take that into account here:
if (value.has(PinAttributes::Output)) {
__digitalWrite(_index, value.has(PinAttributes::InitialOn) ^ _readWriteMask);
__digitalWrite(_index, int(value.has(PinAttributes::InitialOn)) ^ _readWriteMask);
}
__pinMode(_index, pinModeValue);

View File

@@ -252,10 +252,10 @@ uint8_t plan_check_full_buffer() {
float plan_compute_profile_nominal_speed(plan_block_t* block) {
float nominal_speed = block->programmed_rate;
if (block->motion.rapidMotion) {
nominal_speed *= (0.01 * sys.r_override);
nominal_speed *= (0.01f * sys.r_override);
} else {
if (!(block->motion.noFeedOverride)) {
nominal_speed *= (0.01 * sys.f_override);
nominal_speed *= (0.01f * sys.f_override);
}
if (nominal_speed > block->rapid_rate) {
nominal_speed = block->rapid_rate;
@@ -400,10 +400,10 @@ bool plan_buffer_line(float* target, plan_line_data_t* pl_data) {
} else {
convert_delta_vector_to_unit_vector(junction_unit_vec);
float junction_acceleration = limit_acceleration_by_axis_maximum(junction_unit_vec);
float sin_theta_d2 = sqrt(0.5 * (1.0 - junction_cos_theta)); // Trig half angle identity. Always positive.
float sin_theta_d2 = float(sqrt(0.5f * (1.0f - junction_cos_theta))); // Trig half angle identity. Always positive.
block->max_junction_speed_sqr =
MAX(MINIMUM_JUNCTION_SPEED * MINIMUM_JUNCTION_SPEED,
(junction_acceleration * config->_junctionDeviation * sin_theta_d2) / (1.0 - sin_theta_d2));
(junction_acceleration * config->_junctionDeviation * sin_theta_d2) / (1.0f - sin_theta_d2));
}
}
}

View File

@@ -222,7 +222,7 @@ void protocol_main_loop() {
}
// check to see if we should disable the stepper drivers ... esp32 work around for disable in main loop.
if (stepper_idle && config->_idleTime != 255) {
if (esp_timer_get_time() > stepper_idle_counter) {
if (uint64_t(esp_timer_get_time()) > stepper_idle_counter) {
config->_axes->set_disable(true);
}
}