Skip to content

Commit

Permalink
Remove urdf model from controller
Browse files Browse the repository at this point in the history
  • Loading branch information
Wiktor-99 committed Nov 5, 2024
1 parent 9929eb1 commit 13ba72b
Show file tree
Hide file tree
Showing 2 changed files with 0 additions and 4 deletions.
2 changes: 0 additions & 2 deletions gpio_controllers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@ find_package(rclcpp_lifecycle REQUIRED)
find_package(realtime_tools REQUIRED)
find_package(std_msgs REQUIRED)
find_package(generate_parameter_library REQUIRED)
find_package(urdf REQUIRED)


generate_parameter_library(gpio_command_controller_parameters
Expand All @@ -42,7 +41,6 @@ ament_target_dependencies(gpio_controllers PUBLIC
rcutils
realtime_tools
std_msgs
urdf
)
# Causes the visibility macros to use dllexport rather than dllimport,
# which is appropriate when building the dll but not consuming it.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@
#include "rclcpp_lifecycle/state.hpp"
#include "realtime_tools/realtime_buffer.h"
#include "realtime_tools/realtime_publisher.h"
#include "urdf/model.hpp"

namespace gpio_controllers
{
Expand Down Expand Up @@ -108,7 +107,6 @@ class GpioCommandController : public controller_interface::ControllerInterface

std::shared_ptr<gpio_command_controller_parameters::ParamListener> param_listener_{};
gpio_command_controller_parameters::Params params_;
urdf::Model model_;
};

} // namespace gpio_controllers
Expand Down

0 comments on commit 13ba72b

Please sign in to comment.