Skip to content

Commit

Permalink
ArduCopter: Replace fabsF macro with std::abs call to avoid having fl…
Browse files Browse the repository at this point in the history
…oat / double mismatch warnings

AP_Math: Replace fabsF macro with std::abs call in templates to avoid having float / double mismatch warnings
  • Loading branch information
katzfey committed Nov 15, 2024
1 parent a69b777 commit bd75019
Show file tree
Hide file tree
Showing 4 changed files with 6 additions and 6 deletions.
2 changes: 1 addition & 1 deletion ArduCopter/mode_guided.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -733,7 +733,7 @@ void ModeGuided::pos_control_run()

float pos_offset_z_buffer = 0.0; // Vertical buffer size in m
if (guided_pos_terrain_alt) {
pos_offset_z_buffer = MIN(copter.wp_nav->get_terrain_margin() * 100.0, 0.5 * fabsF(guided_pos_target_cm.z));
pos_offset_z_buffer = MIN(copter.wp_nav->get_terrain_margin() * 100.0, 0.5 * std::abs(guided_pos_target_cm.z));
}
pos_control->input_pos_xyz(guided_pos_target_cm, terr_offset, pos_offset_z_buffer);

Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Math/matrix_alg.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,11 +78,11 @@ static void mat_pivot(const T* A, T* pivot, uint16_t n)
uint16_t max_j = i;
for(uint16_t j=i;j<n;j++){
if (std::is_same<T, double>::value) {
if(fabsF(A[j*n + i]) > fabsF(A[max_j*n + i])) {
if(std::abs(A[j*n + i]) > std::abs(A[max_j*n + i])) {
max_j = j;
}
} else {
if(fabsF(A[j*n + i]) > fabsF(A[max_j*n + i])) {
if(std::abs(A[j*n + i]) > std::abs(A[max_j*n + i])) {
max_j = j;
}
}
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Math/quaternion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -694,7 +694,7 @@ void QuaternionT<T>::zero(void)
template <typename T>
bool QuaternionT<T>::is_unit_length(void) const
{
if (fabsF(length_squared() - 1) < 1E-3) {
if (std::abs(length_squared() - 1) < 1E-3) {
return true;
}

Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Math/vector2.h
Original file line number Diff line number Diff line change
Expand Up @@ -251,13 +251,13 @@ struct Vector2
const T intersection_run = point.x-seg_start.x;
// check slopes are identical:
if (::is_zero(expected_run)) {
if (fabsF(intersection_run) > FLT_EPSILON) {
if (std::abs(intersection_run) > FLT_EPSILON) {
return false;
}
} else {
const T expected_slope = (seg_end.y-seg_start.y)/expected_run;
const T intersection_slope = (point.y-seg_start.y)/intersection_run;
if (fabsF(expected_slope - intersection_slope) > FLT_EPSILON) {
if (std::abs(expected_slope - intersection_slope) > FLT_EPSILON) {
return false;
}
}
Expand Down

0 comments on commit bd75019

Please sign in to comment.