Skip to content

Commit

Permalink
Added -Wconversion flag and fix warnings (#667)
Browse files Browse the repository at this point in the history
(cherry picked from commit 23f0def)
  • Loading branch information
gwalck authored and mergify[bot] committed Oct 26, 2024
1 parent da5c15d commit e20295e
Show file tree
Hide file tree
Showing 23 changed files with 29 additions and 29 deletions.
2 changes: 1 addition & 1 deletion ackermann_steering_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16)
project(ackermann_steering_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic)
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
endif()

# find dependencies
Expand Down
2 changes: 1 addition & 1 deletion admittance_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16)
project(admittance_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic)
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
2 changes: 1 addition & 1 deletion bicycle_steering_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16)
project(bicycle_steering_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic)
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
endif()

# find dependencies
Expand Down
2 changes: 1 addition & 1 deletion diff_drive_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16)
project(diff_drive_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra)
add_compile_options(-Wall -Wextra -Wconversion)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
4 changes: 2 additions & 2 deletions diff_drive_controller/src/diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -167,8 +167,8 @@ controller_interface::return_type DiffDriveController::update(
left_feedback_mean += left_feedback;
right_feedback_mean += right_feedback;
}
left_feedback_mean /= params_.wheels_per_side;
right_feedback_mean /= params_.wheels_per_side;
left_feedback_mean /= static_cast<double>(params_.wheels_per_side);
right_feedback_mean /= static_cast<double>(params_.wheels_per_side);

if (params_.position_feedback)
{
Expand Down
2 changes: 1 addition & 1 deletion effort_controllers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16)
project(effort_controllers LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic)
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
2 changes: 1 addition & 1 deletion force_torque_sensor_broadcaster/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16)
project(force_torque_sensor_broadcaster LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic)
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
2 changes: 1 addition & 1 deletion forward_command_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16)
project(forward_command_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic)
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -222,7 +222,7 @@ TEST_F(ForwardCommandControllerTest, CommandSuccessTest)

// update successful, command received
ASSERT_EQ(
controller_->update(rclcpp::Time(0.1), rclcpp::Duration::from_seconds(0.01)),
controller_->update(rclcpp::Time(100000000), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::OK);

// check joint commands have been modified
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -203,7 +203,7 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, CommandSuccessTest)

// update successful, command received
ASSERT_EQ(
controller_->update(rclcpp::Time(0.1), rclcpp::Duration::from_seconds(0.01)),
controller_->update(rclcpp::Time(100000000), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::OK);

// check command in handle was set
Expand Down Expand Up @@ -298,7 +298,7 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, ActivateDeactivateCommandsRes

// update successful, command received
ASSERT_EQ(
controller_->update(rclcpp::Time(0.1), rclcpp::Duration::from_seconds(0.01)),
controller_->update(rclcpp::Time(100000000), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::OK);

// check command in handle was set
Expand Down
2 changes: 1 addition & 1 deletion gripper_controllers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ if(APPLE OR WIN32)
endif()

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra)
add_compile_options(-Wall -Wextra -Wconversion)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
2 changes: 1 addition & 1 deletion imu_sensor_broadcaster/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16)
project(imu_sensor_broadcaster LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic)
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
2 changes: 1 addition & 1 deletion joint_state_broadcaster/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16)
project(joint_state_broadcaster LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra)
add_compile_options(-Wall -Wextra -Wconversion)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
2 changes: 1 addition & 1 deletion joint_trajectory_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16)
project(joint_trajectory_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra)
add_compile_options(-Wall -Wextra -Wconversion)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -293,7 +293,7 @@ SegmentTolerances get_segment_tolerances(
* REALTIME if true \return True if \p state_error fulfills \p state_tolerance.
*/
inline bool check_state_tolerance_per_joint(
const trajectory_msgs::msg::JointTrajectoryPoint & state_error, int joint_idx,
const trajectory_msgs::msg::JointTrajectoryPoint & state_error, size_t joint_idx,
const StateTolerances & state_tolerance, bool show_errors = false)
{
using std::abs;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,7 @@ controller_interface::return_type JointTrajectoryController::update(
}

auto compute_error_for_joint = [&](
JointTrajectoryPoint & error, int index,
JointTrajectoryPoint & error, size_t index,
const JointTrajectoryPoint & current,
const JointTrajectoryPoint & desired)
{
Expand Down
2 changes: 1 addition & 1 deletion position_controllers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16)
project(position_controllers LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic)
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
2 changes: 1 addition & 1 deletion steering_controllers_library/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16)
project(steering_controllers_library LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic)
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
endif()

# find dependencies
Expand Down
2 changes: 1 addition & 1 deletion tricycle_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16)
project(tricycle_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic)
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
2 changes: 1 addition & 1 deletion tricycle_controller/src/traction_limiter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ double TractionLimiter::limit_acceleration(double & v, double v0, double dt)

double dv_min;
double dv_max;
if (abs(v) >= abs(v0))
if (std::fabs(v) >= std::fabs(v0))
{
dv_min = min_acceleration_ * dt;
dv_max = max_acceleration_ * dt;
Expand Down
10 changes: 5 additions & 5 deletions tricycle_controller/src/tricycle_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ CallbackReturn TricycleController::on_init()
auto_declare<bool>("enable_odom_tf", odom_params_.enable_odom_tf);
auto_declare<bool>("odom_only_twist", odom_params_.odom_only_twist);

auto_declare<int>("cmd_vel_timeout", cmd_vel_timeout_.count());
auto_declare<int>("cmd_vel_timeout", static_cast<int>(cmd_vel_timeout_.count()));
auto_declare<bool>("publish_ackermann_command", publish_ackermann_command_);
auto_declare<int>("velocity_rolling_window_size", 10);
auto_declare<bool>("use_stamped_vel", use_stamped_vel_);
Expand Down Expand Up @@ -234,8 +234,8 @@ controller_interface::return_type TricycleController::update(
AckermannDrive ackermann_command;
// speed in AckermannDrive is defined as desired forward speed (m/s) but it is used here as wheel
// speed (rad/s)
ackermann_command.speed = Ws_write;
ackermann_command.steering_angle = alpha_write;
ackermann_command.speed = static_cast<float>(Ws_write);
ackermann_command.steering_angle = static_cast<float>(alpha_write);
previous_commands_.emplace(ackermann_command);

// Publish ackermann command
Expand All @@ -244,8 +244,8 @@ controller_interface::return_type TricycleController::update(
auto & realtime_ackermann_command = realtime_ackermann_command_publisher_->msg_;
// speed in AckermannDrive is defined desired forward speed (m/s) but we use it here as wheel
// speed (rad/s)
realtime_ackermann_command.speed = Ws_write;
realtime_ackermann_command.steering_angle = alpha_write;
realtime_ackermann_command.speed = static_cast<float>(Ws_write);
realtime_ackermann_command.steering_angle = static_cast<float>(alpha_write);
realtime_ackermann_command_publisher_->unlockAndPublish();
}

Expand Down
2 changes: 1 addition & 1 deletion tricycle_steering_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16)
project(tricycle_steering_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic)
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
endif()

# find dependencies
Expand Down
2 changes: 1 addition & 1 deletion velocity_controllers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16)
project(velocity_controllers LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic)
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down

0 comments on commit e20295e

Please sign in to comment.