Skip to content

Commit

Permalink
Apply suggestions from code review
Browse files Browse the repository at this point in the history
  • Loading branch information
destogl authored Apr 13, 2023
1 parent ceb3beb commit f939193
Show file tree
Hide file tree
Showing 4 changed files with 1 addition and 4 deletions.
1 change: 0 additions & 1 deletion controller_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
)

find_package(ament_cmake REQUIRED)
find_package(backward_ros REQUIRED)
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
find_package(${Dependency} REQUIRED)
endforeach()
Expand Down
1 change: 0 additions & 1 deletion controller_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<build_depend>backward_ros</build_depend>
<build_depend>hardware_interface</build_depend>
<build_depend>rclcpp_lifecycle</build_depend>
<build_depend>sensor_msgs</build_depend>
Expand Down
1 change: 0 additions & 1 deletion hardware_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
)

find_package(ament_cmake REQUIRED)
find_package(backward_ros REQUIRED)
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
find_package(${Dependency} REQUIRED)
endforeach()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

namespace hardware_interface
{
/// Constant defining position interface
/// Constant defining position interface name
constexpr char HW_IF_POSITION[] = "position";
/// Constant defining velocity interface
constexpr char HW_IF_VELOCITY[] = "velocity";
Expand Down

0 comments on commit f939193

Please sign in to comment.