Switched from fabs to std::abs which is type-aware and safer going forward.

This commit is contained in:
Rob Giseburt
2017-12-03 16:10:22 -06:00
parent 459f7c5c43
commit b70abe4067
13 changed files with 53 additions and 61 deletions

View File

@@ -99,13 +99,13 @@ stat_t hardware_periodic()
{
#if EXPERIMENTAL_NEOPIXEL_SUPPORT == 1
float x_pos = cm_get_work_position(ACTIVE_MODEL, AXIS_X);
if (fabs(LEDs::old_x_pos - x_pos) > 0.01) {
if (std::abs(LEDs::old_x_pos - x_pos) > 0.01) {
LEDs::old_x_pos = x_pos;
float led_pos = x_pos * ((float)(LEDs::rgbw_leds.count-1) / 40);
for (uint8_t pixel = 0; pixel < LEDs::rgbw_leds.count; pixel++) {
float value = fabs(led_pos - (float)pixel);
float value = std::abs(led_pos - (float)pixel);
if (value < 1.001) {
value = 1.0 - value;
if (LEDs::display_color[pixel].red < value) {

View File

@@ -718,8 +718,8 @@ stat_t cm_test_soft_limits(const float target[])
for (uint8_t axis = AXIS_X; axis < AXES; axis++) {
if (cm.homed[axis] != true) { continue; } // skip axis if not homed
if (fp_EQ(cm.a[axis].travel_min, cm.a[axis].travel_max)) { continue; } // skip axis if identical
if (fabs(cm.a[axis].travel_min) > DISABLE_SOFT_LIMIT) { continue; } // skip min test if disabled
if (fabs(cm.a[axis].travel_max) > DISABLE_SOFT_LIMIT) { continue; } // skip max test if disabled
if (std::abs(cm.a[axis].travel_min) > DISABLE_SOFT_LIMIT) { continue; } // skip min test if disabled
if (std::abs(cm.a[axis].travel_max) > DISABLE_SOFT_LIMIT) { continue; } // skip max test if disabled
if (target[axis] < cm.a[axis].travel_min) {
return (_finalize_soft_limits(STAT_SOFT_LIMIT_EXCEEDED_XMIN + 2*axis));

View File

@@ -235,7 +235,7 @@ static stat_t _homing_axis_start(int8_t axis) {
}
// calculate and test travel distance
float travel_distance = fabs(cm.a[axis].travel_max - cm.a[axis].travel_min) + cm.a[axis].latch_backoff;
float travel_distance = std::abs(cm.a[axis].travel_max - cm.a[axis].travel_min) + cm.a[axis].latch_backoff;
if (fp_ZERO(travel_distance)) {
return (_homing_error_exit(axis, STAT_HOMING_ERROR_TRAVEL_MIN_MAX_IDENTICAL));
}
@@ -245,22 +245,22 @@ static stat_t _homing_axis_start(int8_t axis) {
hm.homing_input = cm.a[axis].homing_input;
gpio_set_homing_mode(hm.homing_input, true);
hm.axis = axis; // persist the axis
hm.search_velocity = fabs(cm.a[axis].search_velocity); // search velocity is always positive
hm.latch_velocity = fabs(cm.a[axis].latch_velocity); // latch velocity is always positive
hm.search_velocity = std::abs(cm.a[axis].search_velocity); // search velocity is always positive
hm.latch_velocity = std::abs(cm.a[axis].latch_velocity); // latch velocity is always positive
bool homing_to_max = cm.a[axis].homing_dir;
// setup parameters for positive or negative travel (homing to the max or min switch)
if (homing_to_max) {
hm.search_travel = travel_distance; // search travels in positive direction
hm.latch_backoff = fabs(cm.a[axis].latch_backoff); // latch travels in positive direction
hm.latch_backoff = std::abs(cm.a[axis].latch_backoff); // latch travels in positive direction
hm.zero_backoff = -max(0.0f, cm.a[axis].zero_backoff); // zero backoff is negative direction (or zero)
// will set the maximum position
// (plus any negative backoff)
hm.setpoint = cm.a[axis].travel_max + (max(0.0f, -cm.a[axis].zero_backoff));
} else {
hm.search_travel = -travel_distance; // search travels in negative direction
hm.latch_backoff = -fabs(cm.a[axis].latch_backoff); // latch travels in negative direction
hm.latch_backoff = -std::abs(cm.a[axis].latch_backoff); // latch travels in negative direction
hm.zero_backoff = max(0.0f, cm.a[axis].zero_backoff); // zero backoff is positive direction (or zero)
// will set the minimum position
// (minus any negative backoff)

View File

@@ -153,7 +153,7 @@ static stat_t _jogging_axis_start(int8_t axis) {
static stat_t _jogging_axis_ramp_jog(int8_t axis) // run the jog ramp
{
float direction = jog.start_pos <= jog.dest_pos ? 1. : -1.;
float delta = fabs(jog.dest_pos - jog.start_pos);
float delta = std::abs(jog.dest_pos - jog.start_pos);
uint8_t last = 0;
float velocity =

View File

@@ -72,7 +72,7 @@ struct HSI_Color_t : NeopixelColorTag {
float h_2 = h * h;
// to_hue needs to be the closest transition
if (fabs(hue - to_hue) > fabs(hue - (360.0 + to_hue))) {
if (std::abs(hue - to_hue) > std::abs(hue - (360.0 + to_hue))) {
to_hue += 360.0;
}

View File

@@ -179,7 +179,7 @@ stat_t cm_arc_feed(const float target[], const bool target_f[], // target en
// test radius arcs for radius tolerance
if (radius_f) {
arc.radius = _to_millimeters(radius); // set radius to internal format (mm)
if (fabs(arc.radius) < MIN_ARC_RADIUS) { // radius value must be > minimum radius
if (std::abs(arc.radius) < MIN_ARC_RADIUS) { // radius value must be > minimum radius
return (STAT_ARC_RADIUS_OUT_OF_TOLERANCE);
}
}
@@ -298,7 +298,7 @@ static stat_t _compute_arc(const bool radius_f)
// Compute end radius from the center of circle (offsets) to target endpoint
float end_0 = arc.gm.target[arc.plane_axis_0] - arc.position[arc.plane_axis_0] - arc.offset[arc.plane_axis_0];
float end_1 = arc.gm.target[arc.plane_axis_1] - arc.position[arc.plane_axis_1] - arc.offset[arc.plane_axis_1];
float err = fabs(hypotf(end_0, end_1) - arc.radius); // end radius - start radius
float err = std::abs(hypotf(end_0, end_1) - arc.radius); // end radius - start radius
if ((err > ARC_RADIUS_ERROR_MAX) ||
((err > ARC_RADIUS_ERROR_MIN) && (err > arc.radius * ARC_RADIUS_TOLERANCE))) {
return (STAT_ARC_HAS_IMPOSSIBLE_CENTER_POINT);
@@ -338,7 +338,7 @@ static stat_t _compute_arc(const bool radius_f)
// Length is the total mm of travel of the helix (or just the planar arc)
arc.linear_travel = arc.gm.target[arc.linear_axis] - arc.position[arc.linear_axis];
arc.planar_travel = arc.angular_travel * arc.radius;
arc.length = hypotf(arc.planar_travel, fabs(arc.linear_travel));
arc.length = hypotf(arc.planar_travel, std::abs(arc.linear_travel));
// Find the minimum number of segments that meet accuracy and time constraints...
// Note: removed segment_length test as segment_time accounts for this (build 083.37)
@@ -497,10 +497,10 @@ static float _estimate_arc_time (float arc_time)
}
// Downgrade the time if there is a rate-limiting axis
arc_time = max(arc_time, (float)fabs(arc.planar_travel/cm.a[arc.plane_axis_0].feedrate_max));
arc_time = max(arc_time, (float)fabs(arc.planar_travel/cm.a[arc.plane_axis_1].feedrate_max));
if (fabs(arc.linear_travel) > 0) {
arc_time = max(arc_time, (float)fabs(arc.linear_travel/cm.a[arc.linear_axis].feedrate_max));
arc_time = max(arc_time, (float)std::abs(arc.planar_travel/cm.a[arc.plane_axis_0].feedrate_max));
arc_time = max(arc_time, (float)std::abs(arc.planar_travel/cm.a[arc.plane_axis_1].feedrate_max));
if (std::abs(arc.linear_travel) > 0) {
arc_time = max(arc_time, (float)std::abs(arc.linear_travel/cm.a[arc.linear_axis].feedrate_max));
}
return (arc_time);
}

View File

@@ -530,10 +530,10 @@ static void _calculate_jerk(mpBuf_t* bf)
float jerk = 0;
for (uint8_t axis = 0; axis < AXES; axis++) {
if (fabs(bf->unit[axis]) > 0) { // if this axis is participating in the move
if (std::abs(bf->unit[axis]) > 0) { // if this axis is participating in the move
float axis_jerk = _get_axis_jerk(bf, axis);
jerk = axis_jerk / fabs(bf->unit[axis]);
jerk = axis_jerk / std::abs(bf->unit[axis]);
if (jerk < bf->jerk) {
bf->jerk = jerk;
// bf->jerk_axis = axis; // +++ diagnostic
@@ -636,9 +636,9 @@ static void _calculate_vmaxes(mpBuf_t* bf, const float axis_length[], const floa
for (uint8_t axis = AXIS_X; axis < AXES; axis++) {
if (bf->axis_flags[axis]) {
if (bf->gm.motion_mode == MOTION_MODE_STRAIGHT_TRAVERSE) {
tmp_time = fabs(axis_length[axis]) / cm.a[axis].velocity_max;
tmp_time = std::abs(axis_length[axis]) / cm.a[axis].velocity_max;
} else { // gm.motion_mode == MOTION_MODE_STRAIGHT_FEED
tmp_time = fabs(axis_length[axis]) / cm.a[axis].feedrate_max;
tmp_time = std::abs(axis_length[axis]) / cm.a[axis].feedrate_max;
}
max_time = max(max_time, tmp_time);
@@ -733,11 +733,11 @@ static void _calculate_junction_vmax(mpBuf_t* bf)
for (uint8_t axis = 0; axis < AXES; axis++) {
if (bf->axis_flags[axis] || bf->nx->axis_flags[axis]) { // (A) skip axes with no movement
float delta = fabs(bf->unit[axis] - bf->nx->unit[axis]); // formula (1)
float delta = std::abs(bf->unit[axis] - bf->nx->unit[axis]); // formula (1)
if (using_junction_unit) { // (B) special case
// use the highest delta of the two
delta = std::max(delta, fabs(bf->junction_unit[axis] - bf->nx->unit[axis])); // formula (1)
delta = std::max(delta, std::abs(bf->junction_unit[axis] - bf->nx->unit[axis])); // formula (1)
// push the junction_unit for this axis into the next block, for future (B) cases
bf->nx->junction_unit[axis] = bf->junction_unit[axis];

View File

@@ -375,7 +375,7 @@ void mp_calculate_ramps(mpBlockRuntimeBuf_t* block, mpBuf_t* bf, const float ent
float mp_get_target_length(const float v_0, const float v_1, const mpBuf_t* bf)
{
const float q_recip_2_sqrt_j = bf->q_recip_2_sqrt_j;
return q_recip_2_sqrt_j * sqrt(fabs(v_1 - v_0)) * (v_1 + v_0);
return q_recip_2_sqrt_j * sqrt(std::abs(v_1 - v_0)) * (v_1 + v_0);
}
/*
@@ -417,7 +417,7 @@ float mp_get_target_velocity(const float v_0, const float L, const mpBuf_t* bf)
// v_1 = 1/3 ((const1a v_0^2)/b + b const2a - v_0)
const float v_1 = const3 * ((const1a * v_0_2) / b + b * const2a - v_0);
return fabs(v_1);
return std::abs(v_1);
}
@@ -447,7 +447,7 @@ float mp_get_decel_velocity(const float v_0, const float L, const mpBuf_t* bf)
const float sqrt_delta_v_0 = sqrt(v_0 - v_1);
const float l_t = q_recip_2_sqrt_j * (sqrt_delta_v_0 * (v_1 + v_0)) - L;
if (fabs(l_t) < 0.00001) {
if (std::abs(l_t) < 0.00001) {
break;
}
// For the first pass, we tested velocity 0.
@@ -548,8 +548,8 @@ static float _get_meet_velocity(const float v_0,
}
// Precompute some common chunks -- note that some attempts may have v_1 < v_0 or v_1 < v_2
const float sqrt_delta_v_0 = sqrt(fabs(v_1 - v_0));
const float sqrt_delta_v_2 = sqrt(fabs(v_1 - v_2)); // 849us
const float sqrt_delta_v_0 = sqrt(std::abs(v_1 - v_0));
const float sqrt_delta_v_2 = sqrt(std::abs(v_1 - v_2)); // 849us
// l_c is our total-length calculation with the current v_1 estimate, minus the expected length.
// This makes l_c == 0 when v_1 is the correct value.

View File

@@ -283,13 +283,13 @@ typedef enum {
//// RG: Simulation shows +-0.001 is about as much as we should allow.
// VELOCITY_EQ(v0,v1) reads: "True if v0 is within 0.0001 of v1"
// VELOCITY_LT(v0,v1) reads: "True if v0 is less than v1 by at least 0.0001"
#define VELOCITY_EQ(v0,v1) ( fabs(v0-v1) < 0.0001 )
#define VELOCITY_EQ(v0,v1) ( std::abs(v0-v1) < 0.0001 )
#define VELOCITY_LT(v0,v1) ( (v1 - v0) > 0.0001 )
#define Vthr2 300.0
#define Veq2_hi 10.0
#define Veq2_lo 1.0
#define VELOCITY_ROUGHLY_EQ(v0,v1) ( (v0 > Vthr2) ? fabs(v0-v1) < Veq2_hi : fabs(v0-v1) < Veq2_lo )
#define VELOCITY_ROUGHLY_EQ(v0,v1) ( (v0 > Vthr2) ? std::abs(v0-v1) < Veq2_hi : std::abs(v0-v1) < Veq2_lo )
//#define ASCII_ART(s) xio_writeline(s)
#define ASCII_ART(s)

View File

@@ -388,7 +388,7 @@ static uint8_t _populate_filtered_status_report()
nv_get_nvObj(nv);
// report values that have changed by more than 0.0001, but always stops and ends
if ((fabs(nv->value - sr.status_report_value[i]) > EPSILON3) ||
if ((std::abs(nv->value - sr.status_report_value[i]) > EPSILON3) ||
((nv->index == sr.stat_index) && fp_EQ(nv->value, COMBINED_PROGRAM_STOP)) ||
((nv->index == sr.stat_index) && fp_EQ(nv->value, COMBINED_PROGRAM_END))) {

View File

@@ -709,15 +709,15 @@ stat_t st_prep_line(float start_velocity, float end_velocity, float travel_steps
// 'Nudge' correction strategy. Inject a single, scaled correction value then hold off
// NOTE: This clause can be commented out to test for numerical accuracy and accumulating errors
if ((--st_pre.mot[motor].correction_holdoff < 0) &&
(fabs(following_error[motor]) > STEP_CORRECTION_THRESHOLD)) {
(std::abs(following_error[motor]) > STEP_CORRECTION_THRESHOLD)) {
st_pre.mot[motor].correction_holdoff = STEP_CORRECTION_HOLDOFF;
correction_steps = following_error[motor] * STEP_CORRECTION_FACTOR;
if (correction_steps > 0) {
correction_steps = std::min(std::min(correction_steps, fabs(travel_steps[motor])), STEP_CORRECTION_MAX);
correction_steps = std::min(std::min(correction_steps, std::abs(travel_steps[motor])), STEP_CORRECTION_MAX);
} else {
correction_steps = std::max(std::max(correction_steps, -fabs(travel_steps[motor])), -STEP_CORRECTION_MAX);
correction_steps = std::max(std::max(correction_steps, -std::abs(travel_steps[motor])), -STEP_CORRECTION_MAX);
}
st_pre.mot[motor].corrected_steps += correction_steps;
travel_steps[motor] -= correction_steps;
@@ -726,7 +726,7 @@ stat_t st_prep_line(float start_velocity, float end_velocity, float travel_steps
// Compute substeb increment. The accumulator must be *exactly* the incoming
// fractional steps times the substep multiplier or positional drift will occur.
// Rounding is performed to eliminate a negative bias in the uint32 conversion
// that results in long-term negative drift. (fabs/round order doesn't matter)
// that results in long-term negative drift. (std::abs/round order doesn't matter)
// t is ticks duration of the move
// T is time duration of the move in minutes
@@ -757,7 +757,7 @@ stat_t st_prep_line(float start_velocity, float end_velocity, float travel_steps
// option 2:
// d = (b (v_1 - v_0))/((t-1) a)
double s_double = fabs(travel_steps[motor] * 2.0);
double s_double = std::abs(travel_steps[motor] * 2.0);
// 1/m_0 = (2 s v_0)/(t (v_0 + v_1))
st_pre.mot[motor].substep_increment = round(((s_double * start_velocity)/(t_v0_v1)) * (double)DDA_SUBSTEPS);

View File

@@ -199,7 +199,7 @@ struct ValueHistory {
float get_std_dev() {
// Important note: this is a POPULATION standard deviation, not a population standard deviation
float variance = (rolling_sum_sq/(float)sampled) - (rolling_mean*rolling_mean);
return sqrt(fabs(variance));
return sqrt(std::abs(variance));
};
float value() {
@@ -209,7 +209,7 @@ struct ValueHistory {
float std_dev = get_std_dev();
for (uint16_t i=0; i<sampled; i++) {
if (fabs(samples[i].value - rolling_mean) < (variance_max * std_dev)) {
if (std::abs(samples[i].value - rolling_mean) < (variance_max * std_dev)) {
temp += samples[i].value;
++samples_kept;
}
@@ -398,7 +398,7 @@ struct Thermistor {
// Call back function from the ADC to tell it that the ADC has a new sample...
void adc_has_new_value() {
raw_adc_value = adc_pin.getRaw();
float v = fabs(adc_pin.getVoltage());
float v = std::abs(adc_pin.getVoltage());
history.add_sample(v);
};
};
@@ -528,7 +528,7 @@ struct PT100 {
// Call back function from the ADC to tell it that the ADC has a new sample...
void adc_has_new_value(bool error = false) {
raw_adc_value = adc_pin.getRaw();
float v = fabs(adc_pin.getVoltage());
float v = std::abs(adc_pin.getVoltage());
// if (v < 0) {
// char buffer[128];
// char *str = buffer;
@@ -684,7 +684,7 @@ struct PID {
// Calculate the e (error)
float e = _set_point - input;
if (fabs(e) < TEMP_SETPOINT_HYSTERESIS) {
if (std::abs(e) < TEMP_SETPOINT_HYSTERESIS) {
if (!_set_point_timeout.isSet()) {
_set_point_timeout.set(TEMP_SETPOINT_HOLD_TIME);
} else if (_set_point_timeout.isPast()) {
@@ -720,11 +720,7 @@ struct PID {
// Now tha we've done all the checks, square the error, maintaining the sign.
// The is because the energy required to heat an object is the number of degrees of change needed squared.
if (e > 0) {
e = e*e;
} else {
e = -(e*e);
}
e = std::abs(e)*e;
// P = Proportional
@@ -760,11 +756,7 @@ struct PID {
float d = _derivative * _d_factor;
_feed_forward = (_set_point-21); // 21 is for a roughly ideal room temperature
if (_feed_forward > 0) {
_feed_forward = _feed_forward*_feed_forward;
} else {
_feed_forward = -(_feed_forward*_feed_forward);
}
_feed_forward = std::abs(_feed_forward)*_feed_forward;
float f = _f_factor * _feed_forward;
@@ -934,7 +926,7 @@ stat_t temperature_callback()
float out1 = pid1.getNewOutput(temp);
fet_pin1.write(out1);
if (fabs(temp - last_reported_temp1) > kTempDiffSRTrigger) {
if (std::abs(temp - last_reported_temp1) > kTempDiffSRTrigger) {
last_reported_temp1 = temp;
sr_requested = true;
}
@@ -946,7 +938,7 @@ stat_t temperature_callback()
float out2 = pid2.getNewOutput(temp);
fet_pin2.write(out2);
if (fabs(temp - last_reported_temp2) > kTempDiffSRTrigger) {
if (std::abs(temp - last_reported_temp2) > kTempDiffSRTrigger) {
last_reported_temp2 = temp;
sr_requested = true;
}
@@ -960,7 +952,7 @@ stat_t temperature_callback()
float out3 = pid3.getNewOutput(temp);
fet_pin3.write(out3);
if (fabs(temp - last_reported_temp3) > kTempDiffSRTrigger) {
if (std::abs(temp - last_reported_temp3) > kTempDiffSRTrigger) {
last_reported_temp3 = temp;
sr_requested = true;
}

View File

@@ -113,7 +113,7 @@ using std::max;
template <typename T>
inline T square(const T x) { return (x)*(x); } /* UNSAFE */
//inline float abs(const float a) { return fabs(a); }
//inline float abs(const float a) { return std::abs(a); }
#ifndef avg
template <typename T>
@@ -129,19 +129,19 @@ inline T avg(const T a,const T b) {return (a+b)/2; }
// These functions all require math.h to be included in each file that uses them
#ifndef fp_EQ
#define fp_EQ(a,b) (fabs(a-b) < EPSILON)
#define fp_EQ(a,b) (std::abs(a-b) < EPSILON)
#endif
#ifndef fp_NE
#define fp_NE(a,b) (fabs(a-b) > EPSILON)
#define fp_NE(a,b) (std::abs(a-b) > EPSILON)
#endif
#ifndef fp_GE
#define fp_GE(a,b) (fabs(a-b) < EPSILON || a-b > EPSILON)
#define fp_GE(a,b) (std::abs(a-b) < EPSILON || a-b > EPSILON)
#endif
#ifndef fp_ZERO
#define fp_ZERO(a) (fabs(a) < EPSILON)
#define fp_ZERO(a) (std::abs(a) < EPSILON)
#endif
#ifndef fp_NOT_ZERO
#define fp_NOT_ZERO(a) (fabs(a) > EPSILON)
#define fp_NOT_ZERO(a) (std::abs(a) > EPSILON)
#endif
#ifndef fp_FALSE
#define fp_FALSE(a) (a < EPSILON)