Skip to content

Commit 0b43291

Browse files
authored
added conditioning to have rolling tags compilable in older versions (#1071)
1 parent 61617b3 commit 0b43291

File tree

10 files changed

+63
-7
lines changed

10 files changed

+63
-7
lines changed

diff_drive_controller/include/diff_drive_controller/odometry.hpp

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,12 @@
2525
#include <cmath>
2626

2727
#include "rclcpp/time.hpp"
28+
// \note The versions conditioning is added here to support the source-compatibility with Humble
29+
#if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6
2830
#include "rcpputils/rolling_mean_accumulator.hpp"
31+
#else
32+
#include "rcppmath/rolling_mean_accumulator.hpp"
33+
#endif
2934

3035
namespace diff_drive_controller
3136
{
@@ -50,7 +55,12 @@ class Odometry
5055
void setVelocityRollingWindowSize(size_t velocity_rolling_window_size);
5156

5257
private:
58+
// \note The versions conditioning is added here to support the source-compatibility with Humble
59+
#if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6
5360
using RollingMeanAccumulator = rcpputils::RollingMeanAccumulator<double>;
61+
#else
62+
using RollingMeanAccumulator = rcppmath::RollingMeanAccumulator<double>;
63+
#endif
5464

5565
void integrateRungeKutta2(double linear, double angular);
5666
void integrateExact(double linear, double angular);

joint_state_broadcaster/src/joint_state_broadcaster.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,6 @@
2424
#include "hardware_interface/types/hardware_interface_return_values.hpp"
2525
#include "hardware_interface/types/hardware_interface_type_values.hpp"
2626
#include "rclcpp/clock.hpp"
27-
#include "rclcpp/event_handler.hpp"
2827
#include "rclcpp/qos.hpp"
2928
#include "rclcpp/time.hpp"
3029
#include "rclcpp_lifecycle/lifecycle_node.hpp"

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,6 @@
2929
#include "hardware_interface/types/hardware_interface_type_values.hpp"
3030
#include "joint_trajectory_controller/trajectory.hpp"
3131
#include "lifecycle_msgs/msg/state.hpp"
32-
#include "rclcpp/event_handler.hpp"
3332
#include "rclcpp/logging.hpp"
3433
#include "rclcpp/qos.hpp"
3534
#include "rclcpp/time.hpp"

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,6 @@
3232
#include "lifecycle_msgs/msg/state.hpp"
3333
#include "rclcpp/clock.hpp"
3434
#include "rclcpp/duration.hpp"
35-
#include "rclcpp/event_handler.hpp"
3635
#include "rclcpp/executors/multi_threaded_executor.hpp"
3736
#include "rclcpp/executors/single_threaded_executor.hpp"
3837
#include "rclcpp/node.hpp"

pid_controller/src/pid_controller.cpp

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -30,10 +30,24 @@ namespace
3030
{ // utility
3131

3232
// Changed services history QoS to keep all so we don't lose any client service calls
33+
// \note The versions conditioning is added here to support the source-compatibility with Humble
34+
#if RCLCPP_VERSION_MAJOR >= 17
3335
rclcpp::QoS qos_services =
3436
rclcpp::QoS(rclcpp::QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_ALL, 1))
3537
.reliable()
3638
.durability_volatile();
39+
#else
40+
static const rmw_qos_profile_t qos_services = {
41+
RMW_QOS_POLICY_HISTORY_KEEP_ALL,
42+
1, // message queue depth
43+
RMW_QOS_POLICY_RELIABILITY_RELIABLE,
44+
RMW_QOS_POLICY_DURABILITY_VOLATILE,
45+
RMW_QOS_DEADLINE_DEFAULT,
46+
RMW_QOS_LIFESPAN_DEFAULT,
47+
RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT,
48+
RMW_QOS_LIVELINESS_LEASE_DURATION_DEFAULT,
49+
false};
50+
#endif
3751

3852
using ControllerCommandMsg = pid_controller::PidController::ControllerReferenceMsg;
3953

range_sensor_broadcaster/src/range_sensor_broadcaster.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -79,7 +79,10 @@ controller_interface::CallbackReturn RangeSensorBroadcaster::on_configure(
7979
realtime_publisher_->msg_.field_of_view = params_.field_of_view;
8080
realtime_publisher_->msg_.min_range = params_.min_range;
8181
realtime_publisher_->msg_.max_range = params_.max_range;
82+
// \note The versions conditioning is added here to support the source-compatibility with Humble
83+
#if SENSOR_MSGS_VERSION_MAJOR >= 5
8284
realtime_publisher_->msg_.variance = params_.variance;
85+
#endif
8386
realtime_publisher_->unlock();
8487

8588
RCLCPP_DEBUG(get_node()->get_logger(), "configure successful");

range_sensor_broadcaster/test/test_range_sensor_broadcaster.cpp

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -203,7 +203,9 @@ TEST_F(RangeSensorBroadcasterTest, Publish_RangeBroadcaster_Success)
203203
EXPECT_THAT(range_msg.field_of_view, ::testing::FloatEq(field_of_view_));
204204
EXPECT_THAT(range_msg.min_range, ::testing::FloatEq(min_range_));
205205
EXPECT_THAT(range_msg.max_range, ::testing::FloatEq(max_range_));
206+
#if SENSOR_MSGS_VERSION_MAJOR >= 5
206207
EXPECT_THAT(range_msg.variance, ::testing::FloatEq(variance_));
208+
#endif
207209
}
208210

209211
TEST_F(RangeSensorBroadcasterTest, Publish_Bandaries_RangeBroadcaster_Success)
@@ -224,7 +226,9 @@ TEST_F(RangeSensorBroadcasterTest, Publish_Bandaries_RangeBroadcaster_Success)
224226
EXPECT_THAT(range_msg.field_of_view, ::testing::FloatEq(field_of_view_));
225227
EXPECT_THAT(range_msg.min_range, ::testing::FloatEq(min_range_));
226228
EXPECT_THAT(range_msg.max_range, ::testing::FloatEq(max_range_));
229+
#if SENSOR_MSGS_VERSION_MAJOR >= 5
227230
EXPECT_THAT(range_msg.variance, ::testing::FloatEq(variance_));
231+
#endif
228232

229233
sensor_range_ = 4.0;
230234
subscribe_and_get_message(range_msg);
@@ -235,7 +239,9 @@ TEST_F(RangeSensorBroadcasterTest, Publish_Bandaries_RangeBroadcaster_Success)
235239
EXPECT_THAT(range_msg.field_of_view, ::testing::FloatEq(field_of_view_));
236240
EXPECT_THAT(range_msg.min_range, ::testing::FloatEq(min_range_));
237241
EXPECT_THAT(range_msg.max_range, ::testing::FloatEq(max_range_));
242+
#if SENSOR_MSGS_VERSION_MAJOR >= 5
238243
EXPECT_THAT(range_msg.variance, ::testing::FloatEq(variance_));
244+
#endif
239245
}
240246

241247
TEST_F(RangeSensorBroadcasterTest, Publish_OutOfBandaries_RangeBroadcaster_Success)
@@ -257,7 +263,9 @@ TEST_F(RangeSensorBroadcasterTest, Publish_OutOfBandaries_RangeBroadcaster_Succe
257263
EXPECT_THAT(range_msg.field_of_view, ::testing::FloatEq(field_of_view_));
258264
EXPECT_THAT(range_msg.min_range, ::testing::FloatEq(min_range_));
259265
EXPECT_THAT(range_msg.max_range, ::testing::FloatEq(max_range_));
266+
#if SENSOR_MSGS_VERSION_MAJOR >= 5
260267
EXPECT_THAT(range_msg.variance, ::testing::FloatEq(variance_));
268+
#endif
261269

262270
sensor_range_ = 6.0;
263271
subscribe_and_get_message(range_msg);
@@ -269,7 +277,9 @@ TEST_F(RangeSensorBroadcasterTest, Publish_OutOfBandaries_RangeBroadcaster_Succe
269277
EXPECT_THAT(range_msg.field_of_view, ::testing::FloatEq(field_of_view_));
270278
EXPECT_THAT(range_msg.min_range, ::testing::FloatEq(min_range_));
271279
EXPECT_THAT(range_msg.max_range, ::testing::FloatEq(max_range_));
280+
#if SENSOR_MSGS_VERSION_MAJOR >= 5
272281
EXPECT_THAT(range_msg.variance, ::testing::FloatEq(variance_));
282+
#endif
273283
}
274284

275285
int main(int argc, char ** argv)

steering_controllers_library/include/steering_controllers_library/steering_odometry.hpp

Lines changed: 14 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,12 @@
2424
#include "realtime_tools/realtime_buffer.h"
2525
#include "realtime_tools/realtime_publisher.h"
2626

27+
// \note The versions conditioning is added here to support the source-compatibility with Humble
28+
#if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6
2729
#include "rcpputils/rolling_mean_accumulator.hpp"
30+
#else
31+
#include "rcppmath/rolling_mean_accumulator.hpp"
32+
#endif
2833

2934
namespace steering_odometry
3035
{
@@ -229,6 +234,13 @@ class SteeringOdometry
229234
*/
230235
void reset_accumulators();
231236

237+
// \note The versions conditioning is added here to support the source-compatibility with Humble
238+
#if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6
239+
using RollingMeanAccumulator = rcpputils::RollingMeanAccumulator<double>;
240+
#else
241+
using RollingMeanAccumulator = rcppmath::RollingMeanAccumulator<double>;
242+
#endif
243+
232244
/// Current timestamp:
233245
rclcpp::Time timestamp_;
234246

@@ -256,8 +268,8 @@ class SteeringOdometry
256268
double traction_left_wheel_old_pos_;
257269
/// Rolling mean accumulators for the linear and angular velocities:
258270
size_t velocity_rolling_window_size_;
259-
rcpputils::RollingMeanAccumulator<double> linear_acc_;
260-
rcpputils::RollingMeanAccumulator<double> angular_acc_;
271+
RollingMeanAccumulator linear_acc_;
272+
RollingMeanAccumulator angular_acc_;
261273
};
262274
} // namespace steering_odometry
263275

steering_controllers_library/src/steering_odometry.cpp

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

325325
void SteeringOdometry::reset_accumulators()
326326
{
327-
linear_acc_ = rcpputils::RollingMeanAccumulator<double>(velocity_rolling_window_size_);
328-
angular_acc_ = rcpputils::RollingMeanAccumulator<double>(velocity_rolling_window_size_);
327+
linear_acc_ = RollingMeanAccumulator(velocity_rolling_window_size_);
328+
angular_acc_ = RollingMeanAccumulator(velocity_rolling_window_size_);
329329
}
330330

331331
} // namespace steering_odometry

tricycle_controller/include/tricycle_controller/odometry.hpp

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,12 @@
2222
#include <cmath>
2323

2424
#include "rclcpp/time.hpp"
25+
// \note The versions conditioning is added here to support the source-compatibility with Humble
26+
#if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6
2527
#include "rcpputils/rolling_mean_accumulator.hpp"
28+
#else
29+
#include "rcppmath/rolling_mean_accumulator.hpp"
30+
#endif
2631

2732
namespace tricycle_controller
2833
{
@@ -45,7 +50,12 @@ class Odometry
4550
void setVelocityRollingWindowSize(size_t velocity_rolling_window_size);
4651

4752
private:
53+
// \note The versions conditioning is added here to support the source-compatibility with Humble
54+
#if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6
4855
using RollingMeanAccumulator = rcpputils::RollingMeanAccumulator<double>;
56+
#else
57+
using RollingMeanAccumulator = rcppmath::RollingMeanAccumulator<double>;
58+
#endif
4959

5060
void integrateRungeKutta2(double linear, double angular);
5161
void integrateExact(double linear, double angular);

0 commit comments

Comments
 (0)