Skip to content

Commit

Permalink
Revert "adding base footprint publisher to nav2_util (ros-navigation#…
Browse files Browse the repository at this point in the history
…3860)" (ros-navigation#3994)

This reverts commit cefce2c.
  • Loading branch information
SteveMacenski authored Nov 30, 2023
1 parent c1e4a42 commit ef85df2
Show file tree
Hide file tree
Showing 5 changed files with 0 additions and 237 deletions.
129 changes: 0 additions & 129 deletions nav2_util/include/nav2_util/base_footprint_publisher.hpp

This file was deleted.

5 changes: 0 additions & 5 deletions nav2_util/src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -28,11 +28,6 @@ add_executable(lifecycle_bringup
)
target_link_libraries(lifecycle_bringup ${library_name})

add_executable(base_footprint_publisher
base_footprint_publisher.cpp
)
target_link_libraries(base_footprint_publisher ${library_name})

find_package(Boost REQUIRED COMPONENTS program_options)

install(TARGETS
Expand Down
27 changes: 0 additions & 27 deletions nav2_util/src/base_footprint_publisher.cpp

This file was deleted.

4 changes: 0 additions & 4 deletions nav2_util/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,3 @@ target_link_libraries(test_odometry_utils ${library_name})
ament_add_gtest(test_robot_utils test_robot_utils.cpp)
ament_target_dependencies(test_robot_utils geometry_msgs)
target_link_libraries(test_robot_utils ${library_name})

ament_add_gtest(test_base_footprint_publisher test_base_footprint_publisher.cpp)
ament_target_dependencies(test_base_footprint_publisher geometry_msgs)
target_link_libraries(test_base_footprint_publisher ${library_name})
72 changes: 0 additions & 72 deletions nav2_util/test/test_base_footprint_publisher.cpp

This file was deleted.

0 comments on commit ef85df2

Please sign in to comment.