File tree Expand file tree Collapse file tree 5 files changed +5
-135
lines changed
include/diff_drive_controller Expand file tree Collapse file tree 5 files changed +5
-135
lines changed Original file line number Diff line number Diff line change @@ -18,6 +18,7 @@ find_package(nav_msgs REQUIRED)
1818find_package (pluginlib REQUIRED)
1919find_package (rclcpp REQUIRED)
2020find_package (rclcpp_lifecycle REQUIRED)
21+ find_package (rcpputils REQUIRED)
2122find_package (realtime_tools REQUIRED)
2223find_package (tf2 REQUIRED)
2324find_package (tf2_msgs REQUIRED)
@@ -38,6 +39,7 @@ ament_target_dependencies(diff_drive_controller
3839 pluginlib
3940 rclcpp
4041 rclcpp_lifecycle
42+ rcpputils
4143 realtime_tools
4244 tf2
4345 tf2_msgs
@@ -91,14 +93,6 @@ if(BUILD_TESTING)
9193 ros2_control_test_assets
9294 )
9395
94- ament_add_gmock(
95- test_accumulator
96- test /test_accumulator.cpp
97- )
98-
99- target_include_directories (test_accumulator PRIVATE include )
100- ament_target_dependencies(test_accumulator)
101-
10296endif ()
10397
10498ament_export_dependencies(
Original file line number Diff line number Diff line change 2424
2525#include < cmath>
2626
27- #include " diff_drive_controller/rolling_mean_accumulator.hpp"
2827#include " rclcpp/time.hpp"
28+ #include " rcppmath/rolling_mean_accumulator.hpp"
2929
3030namespace diff_drive_controller
3131{
@@ -50,7 +50,7 @@ class Odometry
5050 void setVelocityRollingWindowSize (size_t velocity_rolling_window_size);
5151
5252private:
53- using RollingMeanAccumulator = diff_drive_controller ::RollingMeanAccumulator<double >;
53+ using RollingMeanAccumulator = rcppmath ::RollingMeanAccumulator<double >;
5454
5555 void integrateRungeKutta2 (double linear, double angular);
5656 void integrateExact (double linear, double angular);
Load Diff This file was deleted.
Original file line number Diff line number Diff line change 1616 <depend >nav_msgs</depend >
1717 <depend >rclcpp</depend >
1818 <depend >rclcpp_lifecycle</depend >
19+ <depend >rcpputils</depend >
1920 <depend >realtime_tools</depend >
2021 <depend >tf2</depend >
2122 <depend >tf2_msgs</depend >
Load Diff This file was deleted.
You can’t perform that action at this time.
0 commit comments