Skip to content

Commit

Permalink
Remove tf2 dependency
Browse files Browse the repository at this point in the history
  • Loading branch information
matthew-reynolds authored and bmagyar committed Apr 5, 2020
1 parent 3e5bb4e commit f27a378
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 9 deletions.
1 change: 0 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@ project(urdf_geometry_parser)
# Load catkin and all dependencies required for this package
find_package(catkin REQUIRED COMPONENTS
roscpp
tf2
urdf
)

Expand Down
2 changes: 0 additions & 2 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,6 @@
<depend>roscpp</depend>
<depend>urdf</depend>

<build_depend>tf2</build_depend>

<test_depend>rostest</test_depend>
<test_depend>xacro</test_depend>
</package>
10 changes: 4 additions & 6 deletions src/urdf_geometry_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@

#include <urdf_geometry_parser/urdf_geometry_parser.h>

#include <tf2/LinearMath/Vector3.h>
#include <cmath>

namespace urdf_geometry_parser{

Expand Down Expand Up @@ -154,11 +154,9 @@ namespace urdf_geometry_parser{
if(!getTransformVector(second_joint_name, base_link_, second_transform))
return false;

tf2::Vector3 v1(first_transform.x, first_transform.y, 0.0),
v2(second_transform.x, second_transform.y, 0.0);
distance = v1.distance(v2);
ROS_DEBUG_STREAM("first_transform : "<<first_transform.x<<","<<first_transform.y);
ROS_DEBUG_STREAM("distance "<<distance);
// 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));
return true;
}

Expand Down

0 comments on commit f27a378

Please sign in to comment.