Skip to content

Commit

Permalink
Rolling mean accumulator (ros-controls#637)
Browse files Browse the repository at this point in the history
* fixing rolling_mean_accumulator issue

* fixed variables' namespace
  • Loading branch information
ARK3r authored and destogl committed May 31, 2023
1 parent 169ff1c commit ff2045d
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include "realtime_tools/realtime_publisher.h"

#include <boost/function.hpp>
#include "rcpputils/rolling_mean_accumulator.hpp"
#include "rcppmath/rolling_mean_accumulator.hpp"

namespace steering_odometry
{
Expand Down Expand Up @@ -253,8 +253,8 @@ class SteeringOdometry
double traction_left_wheel_old_pos_;
/// Rolling mean accumulators for the linear and angular velocities:
size_t velocity_rolling_window_size_;
rcpputils::RollingMeanAccumulator<double> linear_acc_;
rcpputils::RollingMeanAccumulator<double> angular_acc_;
rcppmath::RollingMeanAccumulator<double> linear_acc_;
rcppmath::RollingMeanAccumulator<double> angular_acc_;
};
} // namespace steering_odometry

Expand Down
4 changes: 2 additions & 2 deletions steering_controllers_library/src/steering_odometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -326,8 +326,8 @@ void SteeringOdometry::integrate_exact(double linear, double angular)

void SteeringOdometry::reset_accumulators()
{
linear_acc_ = rcpputils::RollingMeanAccumulator<double>(velocity_rolling_window_size_);
angular_acc_ = rcpputils::RollingMeanAccumulator<double>(velocity_rolling_window_size_);
linear_acc_ = rcppmath::RollingMeanAccumulator<double>(velocity_rolling_window_size_);
angular_acc_ = rcppmath::RollingMeanAccumulator<double>(velocity_rolling_window_size_);
}

} // namespace steering_odometry

0 comments on commit ff2045d

Please sign in to comment.