diff --git a/diff_drive_controller/include/diff_drive_controller/odometry.hpp b/diff_drive_controller/include/diff_drive_controller/odometry.hpp index 83ab270f72..edca431d3d 100644 --- a/diff_drive_controller/include/diff_drive_controller/odometry.hpp +++ b/diff_drive_controller/include/diff_drive_controller/odometry.hpp @@ -25,7 +25,12 @@ #include #include "rclcpp/time.hpp" +// \note The versions conditioning is added here to support the source-compatibility with Humble +#if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6 #include "rcpputils/rolling_mean_accumulator.hpp" +#else +#include "rcppmath/rolling_mean_accumulator.hpp" +#endif namespace diff_drive_controller { @@ -50,7 +55,12 @@ class Odometry void setVelocityRollingWindowSize(size_t velocity_rolling_window_size); private: +// \note The versions conditioning is added here to support the source-compatibility with Humble +#if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6 using RollingMeanAccumulator = rcpputils::RollingMeanAccumulator; +#else + using RollingMeanAccumulator = rcppmath::RollingMeanAccumulator; +#endif void integrateRungeKutta2(double linear, double angular); void integrateExact(double linear, double angular); diff --git a/steering_controllers_library/include/steering_controllers_library/steering_odometry.hpp b/steering_controllers_library/include/steering_controllers_library/steering_odometry.hpp index 95bcef7e63..e4a22f6d3b 100644 --- a/steering_controllers_library/include/steering_controllers_library/steering_odometry.hpp +++ b/steering_controllers_library/include/steering_controllers_library/steering_odometry.hpp @@ -24,7 +24,12 @@ #include "realtime_tools/realtime_buffer.h" #include "realtime_tools/realtime_publisher.h" +// \note The versions conditioning is added here to support the source-compatibility with Humble +#if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6 #include "rcpputils/rolling_mean_accumulator.hpp" +#else +#include "rcppmath/rolling_mean_accumulator.hpp" +#endif namespace steering_odometry { @@ -229,6 +234,13 @@ class SteeringOdometry */ void reset_accumulators(); +// \note The versions conditioning is added here to support the source-compatibility with Humble +#if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6 + using RollingMeanAccumulator = rcpputils::RollingMeanAccumulator; +#else + using RollingMeanAccumulator = rcppmath::RollingMeanAccumulator; +#endif + /// Current timestamp: rclcpp::Time timestamp_; @@ -256,8 +268,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 linear_acc_; - rcpputils::RollingMeanAccumulator angular_acc_; + RollingMeanAccumulator linear_acc_; + RollingMeanAccumulator angular_acc_; }; } // namespace steering_odometry diff --git a/steering_controllers_library/src/steering_odometry.cpp b/steering_controllers_library/src/steering_odometry.cpp index e2ced036ff..aadd047f2e 100644 --- a/steering_controllers_library/src/steering_odometry.cpp +++ b/steering_controllers_library/src/steering_odometry.cpp @@ -324,8 +324,8 @@ void SteeringOdometry::integrate_exact(double linear, double angular) void SteeringOdometry::reset_accumulators() { - linear_acc_ = rcpputils::RollingMeanAccumulator(velocity_rolling_window_size_); - angular_acc_ = rcpputils::RollingMeanAccumulator(velocity_rolling_window_size_); + linear_acc_ = RollingMeanAccumulator(velocity_rolling_window_size_); + angular_acc_ = RollingMeanAccumulator(velocity_rolling_window_size_); } } // namespace steering_odometry diff --git a/tricycle_controller/include/tricycle_controller/odometry.hpp b/tricycle_controller/include/tricycle_controller/odometry.hpp index 62eb51d6cc..13d65a980a 100644 --- a/tricycle_controller/include/tricycle_controller/odometry.hpp +++ b/tricycle_controller/include/tricycle_controller/odometry.hpp @@ -22,7 +22,12 @@ #include #include "rclcpp/time.hpp" +// \note The versions conditioning is added here to support the source-compatibility with Humble +#if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6 #include "rcpputils/rolling_mean_accumulator.hpp" +#else +#include "rcppmath/rolling_mean_accumulator.hpp" +#endif namespace tricycle_controller { @@ -45,7 +50,12 @@ class Odometry void setVelocityRollingWindowSize(size_t velocity_rolling_window_size); private: +// \note The versions conditioning is added here to support the source-compatibility with Humble +#if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6 using RollingMeanAccumulator = rcpputils::RollingMeanAccumulator; +#else + using RollingMeanAccumulator = rcppmath::RollingMeanAccumulator; +#endif void integrateRungeKutta2(double linear, double angular); void integrateExact(double linear, double angular);