Skip to content

Commit ff2045d

Browse files
ARK3rdestogl
authored andcommitted
Rolling mean accumulator (ros-controls#637)
* fixing rolling_mean_accumulator issue * fixed variables' namespace
1 parent 169ff1c commit ff2045d

File tree

2 files changed

+5
-5
lines changed

2 files changed

+5
-5
lines changed

steering_controllers_library/include/steering_controllers_library/steering_odometry.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@
2525
#include "realtime_tools/realtime_publisher.h"
2626

2727
#include <boost/function.hpp>
28-
#include "rcpputils/rolling_mean_accumulator.hpp"
28+
#include "rcppmath/rolling_mean_accumulator.hpp"
2929

3030
namespace steering_odometry
3131
{
@@ -253,8 +253,8 @@ class SteeringOdometry
253253
double traction_left_wheel_old_pos_;
254254
/// Rolling mean accumulators for the linear and angular velocities:
255255
size_t velocity_rolling_window_size_;
256-
rcpputils::RollingMeanAccumulator<double> linear_acc_;
257-
rcpputils::RollingMeanAccumulator<double> angular_acc_;
256+
rcppmath::RollingMeanAccumulator<double> linear_acc_;
257+
rcppmath::RollingMeanAccumulator<double> angular_acc_;
258258
};
259259
} // namespace steering_odometry
260260

steering_controllers_library/src/steering_odometry.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -326,8 +326,8 @@ void SteeringOdometry::integrate_exact(double linear, double angular)
326326

327327
void SteeringOdometry::reset_accumulators()
328328
{
329-
linear_acc_ = rcpputils::RollingMeanAccumulator<double>(velocity_rolling_window_size_);
330-
angular_acc_ = rcpputils::RollingMeanAccumulator<double>(velocity_rolling_window_size_);
329+
linear_acc_ = rcppmath::RollingMeanAccumulator<double>(velocity_rolling_window_size_);
330+
angular_acc_ = rcppmath::RollingMeanAccumulator<double>(velocity_rolling_window_size_);
331331
}
332332

333333
} // namespace steering_odometry

0 commit comments

Comments
 (0)