Skip to content

Commit 427e86b

Browse files
Karsten1987bmagyar
andauthored
use rolling mean from rcppmath (#211)
* use rolling mean from rcppmath Signed-off-by: Karsten Knese <[email protected]> * remove test build * add explicit dependency on rcpputils Co-authored-by: Bence Magyar <[email protected]>
1 parent b74460e commit 427e86b

File tree

5 files changed

+5
-135
lines changed

5 files changed

+5
-135
lines changed

diff_drive_controller/CMakeLists.txt

Lines changed: 2 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@ find_package(nav_msgs REQUIRED)
1818
find_package(pluginlib REQUIRED)
1919
find_package(rclcpp REQUIRED)
2020
find_package(rclcpp_lifecycle REQUIRED)
21+
find_package(rcpputils REQUIRED)
2122
find_package(realtime_tools REQUIRED)
2223
find_package(tf2 REQUIRED)
2324
find_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-
10296
endif()
10397

10498
ament_export_dependencies(

diff_drive_controller/include/diff_drive_controller/odometry.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,8 +24,8 @@
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

3030
namespace diff_drive_controller
3131
{
@@ -50,7 +50,7 @@ class Odometry
5050
void setVelocityRollingWindowSize(size_t velocity_rolling_window_size);
5151

5252
private:
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);

diff_drive_controller/include/diff_drive_controller/rolling_mean_accumulator.hpp

Lines changed: 0 additions & 67 deletions
This file was deleted.

diff_drive_controller/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
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>

diff_drive_controller/test/test_accumulator.cpp

Lines changed: 0 additions & 58 deletions
This file was deleted.

0 commit comments

Comments
 (0)