From 089a803fe0fedb96049cc2d22f4f265b28e20819 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Wed, 5 Jun 2024 19:28:24 +0000 Subject: [PATCH] Apply consistent variable naming Co-authored-by: Quique Llorente --- .../src/ackermann_steering_controller.cpp | 14 +++++++------- .../src/bicycle_steering_controller.cpp | 8 ++++---- .../src/tricycle_steering_controller.cpp | 10 ++++++---- 3 files changed, 17 insertions(+), 15 deletions(-) diff --git a/ackermann_steering_controller/src/ackermann_steering_controller.cpp b/ackermann_steering_controller/src/ackermann_steering_controller.cpp index 00a8c45442..d9d95bf8b5 100644 --- a/ackermann_steering_controller/src/ackermann_steering_controller.cpp +++ b/ackermann_steering_controller/src/ackermann_steering_controller.cpp @@ -66,25 +66,25 @@ bool AckermannSteeringController::update_odometry(const rclcpp::Duration & perio state_interfaces_[STATE_TRACTION_RIGHT_WHEEL].get_value(); const double traction_left_wheel_value = state_interfaces_[STATE_TRACTION_LEFT_WHEEL].get_value(); - const double right_steer_position = state_interfaces_[STATE_STEER_RIGHT_WHEEL].get_value(); - const double left_steer_position = state_interfaces_[STATE_STEER_LEFT_WHEEL].get_value(); + const double steering_right_position = state_interfaces_[STATE_STEER_RIGHT_WHEEL].get_value(); + const double steering_left_position = state_interfaces_[STATE_STEER_LEFT_WHEEL].get_value(); if ( std::isfinite(traction_right_wheel_value) && std::isfinite(traction_left_wheel_value) && - std::isfinite(right_steer_position) && std::isfinite(left_steer_position)) + std::isfinite(steering_right_position) && std::isfinite(steering_left_position)) { if (params_.position_feedback) { // Estimate linear and angular velocity using joint information odometry_.update_from_position( - traction_right_wheel_value, traction_left_wheel_value, right_steer_position, - left_steer_position, period.seconds()); + traction_right_wheel_value, traction_left_wheel_value, steering_right_position, + steering_left_position, period.seconds()); } else { // Estimate linear and angular velocity using joint information odometry_.update_from_velocity( - traction_right_wheel_value, traction_left_wheel_value, right_steer_position, - left_steer_position, period.seconds()); + traction_right_wheel_value, traction_left_wheel_value, steering_right_position, + steering_left_position, period.seconds()); } } } diff --git a/bicycle_steering_controller/src/bicycle_steering_controller.cpp b/bicycle_steering_controller/src/bicycle_steering_controller.cpp index 14d503fcda..95eaf1965c 100644 --- a/bicycle_steering_controller/src/bicycle_steering_controller.cpp +++ b/bicycle_steering_controller/src/bicycle_steering_controller.cpp @@ -61,18 +61,18 @@ bool BicycleSteeringController::update_odometry(const rclcpp::Duration & period) else { const double traction_wheel_value = state_interfaces_[STATE_TRACTION_WHEEL].get_value(); - const double steer_position = state_interfaces_[STATE_STEER_AXIS].get_value(); - if (std::isfinite(traction_wheel_value) && std::isfinite(steer_position)) + const double steering_position = state_interfaces_[STATE_STEER_AXIS].get_value(); + if (std::isfinite(traction_wheel_value) && std::isfinite(steering_position)) { if (params_.position_feedback) { // Estimate linear and angular velocity using joint information - odometry_.update_from_position(traction_wheel_value, steer_position, period.seconds()); + odometry_.update_from_position(traction_wheel_value, steering_position, period.seconds()); } else { // Estimate linear and angular velocity using joint information - odometry_.update_from_velocity(traction_wheel_value, steer_position, period.seconds()); + odometry_.update_from_velocity(traction_wheel_value, steering_position, period.seconds()); } } } diff --git a/tricycle_steering_controller/src/tricycle_steering_controller.cpp b/tricycle_steering_controller/src/tricycle_steering_controller.cpp index fa7aad9410..03be6b88f0 100644 --- a/tricycle_steering_controller/src/tricycle_steering_controller.cpp +++ b/tricycle_steering_controller/src/tricycle_steering_controller.cpp @@ -64,22 +64,24 @@ bool TricycleSteeringController::update_odometry(const rclcpp::Duration & period state_interfaces_[STATE_TRACTION_RIGHT_WHEEL].get_value(); const double traction_left_wheel_value = state_interfaces_[STATE_TRACTION_LEFT_WHEEL].get_value(); - const double steer_position = state_interfaces_[STATE_STEER_AXIS].get_value(); + const double steering_position = state_interfaces_[STATE_STEER_AXIS].get_value(); if ( std::isfinite(traction_right_wheel_value) && std::isfinite(traction_left_wheel_value) && - std::isfinite(steer_position)) + std::isfinite(steering_position)) { if (params_.position_feedback) { // Estimate linear and angular velocity using joint information odometry_.update_from_position( - traction_right_wheel_value, traction_left_wheel_value, steer_position, period.seconds()); + traction_right_wheel_value, traction_left_wheel_value, steering_position, + period.seconds()); } else { // Estimate linear and angular velocity using joint information odometry_.update_from_velocity( - traction_right_wheel_value, traction_left_wheel_value, steer_position, period.seconds()); + traction_right_wheel_value, traction_left_wheel_value, steering_position, + period.seconds()); } } }