Skip to content

Commit

Permalink
Use std::hypot over std::sqrt and std::pow
Browse files Browse the repository at this point in the history
  • Loading branch information
matthew-reynolds committed Apr 5, 2020
1 parent 756b4b7 commit db0d371
Showing 1 changed file with 2 additions and 3 deletions.
5 changes: 2 additions & 3 deletions src/urdf_geometry_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -154,9 +154,8 @@ namespace urdf_geometry_parser{
if(!getTransformVector(second_joint_name, base_link_, second_transform))
return false;

// Calculate the Euclidean distance using the Pythagorean formula
distance = std::sqrt(std::pow(first_transform.x - second_transform.x, 2)
+ std::pow(first_transform.y - second_transform.y, 2));
// Calculate the Euclidean distance
distance = std::hypot(first_transform.x - second_transform.x, first_transform.y - second_transform.y);
return true;
}

Expand Down

0 comments on commit db0d371

Please sign in to comment.