Skip to content

Commit

Permalink
added version conditioning for rcpputils library
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Mar 3, 2024
1 parent 2fc80f6 commit 60d908e
Show file tree
Hide file tree
Showing 4 changed files with 36 additions and 4 deletions.
10 changes: 10 additions & 0 deletions diff_drive_controller/include/diff_drive_controller/odometry.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,12 @@
#include <cmath>

#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
{
Expand All @@ -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<double>;
#else
using RollingMeanAccumulator = rcppmath::RollingMeanAccumulator<double>;
#endif

void integrateRungeKutta2(double linear, double angular);
void integrateExact(double linear, double angular);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand Down Expand Up @@ -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<double>;
#else
using RollingMeanAccumulator = rcppmath::RollingMeanAccumulator<double>;
#endif

/// Current timestamp:
rclcpp::Time timestamp_;

Expand Down Expand Up @@ -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<double> linear_acc_;
rcpputils::RollingMeanAccumulator<double> angular_acc_;
RollingMeanAccumulator linear_acc_;
RollingMeanAccumulator 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 @@ -324,8 +324,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_ = RollingMeanAccumulator(velocity_rolling_window_size_);
angular_acc_ = RollingMeanAccumulator(velocity_rolling_window_size_);
}

} // namespace steering_odometry
10 changes: 10 additions & 0 deletions tricycle_controller/include/tricycle_controller/odometry.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,12 @@
#include <cmath>

#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
{
Expand All @@ -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<double>;
#else
using RollingMeanAccumulator = rcppmath::RollingMeanAccumulator<double>;
#endif

void integrateRungeKutta2(double linear, double angular);
void integrateExact(double linear, double angular);
Expand Down

0 comments on commit 60d908e

Please sign in to comment.