Skip to content

Commit

Permalink
Satisfy clang more
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Dec 4, 2024
1 parent 25ec991 commit 35abc6c
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 3 deletions.
2 changes: 1 addition & 1 deletion diff_drive_controller/src/diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -292,7 +292,7 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
const double right_wheel_radius = params_.right_wheel_radius_multiplier * params_.wheel_radius;

odometry_.setWheelParams(wheel_separation, left_wheel_radius, right_wheel_radius);
odometry_.setVelocityRollingWindowSize(params_.velocity_rolling_window_size);
odometry_.setVelocityRollingWindowSize(static_cast<size_t>(params_.velocity_rolling_window_size));

cmd_vel_timeout_ = std::chrono::milliseconds{static_cast<int>(params_.cmd_vel_timeout * 1000.0)};
publish_limited_velocity_ = params_.publish_limited_velocity;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,8 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure(
const rclcpp_lifecycle::State & /*previous_state*/)
{
params_ = param_listener_->get_params();
odometry_.set_velocity_rolling_window_size(params_.velocity_rolling_window_size);
odometry_.set_velocity_rolling_window_size(
static_cast<size_t>(params_.velocity_rolling_window_size));

configure_odometry();

Expand Down
2 changes: 1 addition & 1 deletion tricycle_controller/src/tricycle_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -236,7 +236,7 @@ CallbackReturn TricycleController::on_configure(const rclcpp_lifecycle::State &
}

odometry_.setWheelParams(params_.wheelbase, params_.wheel_radius);
odometry_.setVelocityRollingWindowSize(params_.velocity_rolling_window_size);
odometry_.setVelocityRollingWindowSize(static_cast<size_t>(params_.velocity_rolling_window_size));

cmd_vel_timeout_ = std::chrono::milliseconds{params_.cmd_vel_timeout};
params_.publish_ackermann_command =
Expand Down

0 comments on commit 35abc6c

Please sign in to comment.