Skip to content

Commit

Permalink
Add few warning flags to error in all ros2_controllers packages and f…
Browse files Browse the repository at this point in the history
…ix tests (#1370)
  • Loading branch information
saikishor authored Nov 18, 2024
1 parent 0590c6a commit 4f447f4
Show file tree
Hide file tree
Showing 32 changed files with 116 additions and 86 deletions.
3 changes: 2 additions & 1 deletion ackermann_steering_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,8 @@ project(ackermann_steering_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
-Werror=return-type -Werror=shadow -Werror=format -Werror=range-loop-construct
-Werror=missing-braces)
endif()

# find dependencies
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -293,9 +293,10 @@ class AckermannSteeringControllerFixture : public ::testing::Test
double front_wheels_radius_ = 0.45;
double rear_wheels_radius_ = 0.45;

std::array<double, 4> joint_state_values_ = {0.5, 0.5, 0.0, 0.0};
std::array<double, 4> joint_command_values_ = {1.1, 3.3, 2.2, 4.4};
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/velocity"};
std::array<double, 4> joint_state_values_ = {{0.5, 0.5, 0.0, 0.0}};
std::array<double, 4> joint_command_values_ = {{1.1, 3.3, 2.2, 4.4}};
std::array<std::string, 2> joint_reference_interfaces_ = {
{"linear/velocity", "angular/velocity"}};
std::string steering_interface_name_ = "position";
// defined in setup
std::string traction_interface_name_ = "";
Expand Down
3 changes: 2 additions & 1 deletion admittance_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,8 @@ project(admittance_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
-Werror=return-type -Werror=shadow -Werror=format -Werror=range-loop-construct
-Werror=missing-braces)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
18 changes: 9 additions & 9 deletions admittance_controller/test/test_admittance_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -371,15 +371,15 @@ class AdmittanceControllerTest : public ::testing::Test
const std::string fixed_world_frame_ = "fixed_world_frame";
const std::string sensor_frame_ = "link_6";

std::array<bool, 6> admittance_selected_axes_ = {true, true, true, true, true, true};
std::array<double, 6> admittance_mass_ = {5.5, 6.6, 7.7, 8.8, 9.9, 10.10};
std::array<double, 6> admittance_damping_ratio_ = {2.828427, 2.828427, 2.828427,
2.828427, 2.828427, 2.828427};
std::array<double, 6> admittance_stiffness_ = {214.1, 214.2, 214.3, 214.4, 214.5, 214.6};

std::array<double, 6> joint_command_values_ = {0.0, 0.0, 0.0, 0.0, 0.0, 0.0};
std::array<double, 6> joint_state_values_ = {1.1, 2.2, 3.3, 4.4, 5.5, 6.6};
std::array<double, 6> fts_state_values_ = {0.0, 0.0, 0.0, 0.0, 0.0, 0.0};
std::array<bool, 6> admittance_selected_axes_ = {{true, true, true, true, true, true}};
std::array<double, 6> admittance_mass_ = {{5.5, 6.6, 7.7, 8.8, 9.9, 10.10}};
std::array<double, 6> admittance_damping_ratio_ = {
{2.828427, 2.828427, 2.828427, 2.828427, 2.828427, 2.828427}};
std::array<double, 6> admittance_stiffness_ = {{214.1, 214.2, 214.3, 214.4, 214.5, 214.6}};

std::array<double, 6> joint_command_values_ = {{0.0, 0.0, 0.0, 0.0, 0.0, 0.0}};
std::array<double, 6> joint_state_values_ = {{1.1, 2.2, 3.3, 4.4, 5.5, 6.6}};
std::array<double, 6> fts_state_values_ = {{0.0, 0.0, 0.0, 0.0, 0.0, 0.0}};
std::vector<std::string> fts_state_names_;

std::vector<hardware_interface::StateInterface> state_itfs_;
Expand Down
3 changes: 2 additions & 1 deletion bicycle_steering_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,8 @@ project(bicycle_steering_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
-Werror=return-type -Werror=shadow -Werror=format -Werror=range-loop-construct
-Werror=missing-braces)
endif()

# find dependencies
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -247,22 +247,24 @@ class BicycleSteeringControllerFixture : public ::testing::Test
bool open_loop_ = false;
unsigned int velocity_rolling_window_size_ = 10;
bool position_feedback_ = false;
std::vector<std::string> rear_wheels_names_ = {"rear_wheel_joint"};
std::vector<std::string> front_wheels_names_ = {"steering_axis_joint"};
std::vector<std::string> joint_names_ = {rear_wheels_names_[0], front_wheels_names_[0]};
std::vector<std::string> rear_wheels_names_ = {{"rear_wheel_joint"}};
std::vector<std::string> front_wheels_names_ = {{"steering_axis_joint"}};
std::vector<std::string> joint_names_ = {{rear_wheels_names_[0], front_wheels_names_[0]}};

std::vector<std::string> rear_wheels_preceeding_names_ = {"pid_controller/rear_wheel_joint"};
std::vector<std::string> front_wheels_preceeding_names_ = {"pid_controller/steering_axis_joint"};
std::vector<std::string> rear_wheels_preceeding_names_ = {{"pid_controller/rear_wheel_joint"}};
std::vector<std::string> front_wheels_preceeding_names_ = {
{"pid_controller/steering_axis_joint"}};
std::vector<std::string> preceeding_joint_names_ = {
rear_wheels_preceeding_names_[0], front_wheels_preceeding_names_[0]};

double wheelbase_ = 3.24644;
double front_wheels_radius_ = 0.45;
double rear_wheels_radius_ = 0.45;

std::array<double, 2> joint_state_values_ = {3.3, 0.5};
std::array<double, 2> joint_command_values_ = {1.1, 2.2};
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/velocity"};
std::array<double, 2> joint_state_values_ = {{3.3, 0.5}};
std::array<double, 2> joint_command_values_ = {{1.1, 2.2}};
std::array<std::string, 2> joint_reference_interfaces_ = {
{"linear/velocity", "angular/velocity"}};
std::string steering_interface_name_ = "position";

// defined in setup
Expand Down
4 changes: 3 additions & 1 deletion diff_drive_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,9 @@ 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 -Werror=conversion -Werror=unused-but-set-variable -Werror=return-type -Werror=shadow -Werror=format)
add_compile_options(-Wall -Wextra -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format -Werror=range-loop-construct
-Werror=missing-braces)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
3 changes: 2 additions & 1 deletion effort_controllers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,8 @@ project(effort_controllers LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
-Werror=return-type -Werror=shadow -Werror=format -Werror=range-loop-construct
-Werror=missing-braces)
endif()

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

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
-Werror=return-type -Werror=shadow -Werror=format -Werror=range-loop-construct
-Werror=missing-braces)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -282,8 +282,8 @@ TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_Publish_Success_with_Offsets
{
SetUpFTSBroadcaster();

std::array<double, 3> force_offsets = {10.0, 30.0, -50.0};
std::array<double, 3> torque_offsets = {1.0, -1.2, -5.2};
std::array<double, 3> force_offsets = {{10.0, 30.0, -50.0}};
std::array<double, 3> torque_offsets = {{1.0, -1.2, -5.2}};
// set the params 'sensor_name' and 'frame_id'
fts_broadcaster_->get_node()->set_parameter({"sensor_name", sensor_name_});
fts_broadcaster_->get_node()->set_parameter({"frame_id", frame_id_});
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ class ForceTorqueSensorBroadcasterTest : public ::testing::Test
protected:
const std::string sensor_name_ = "fts_sensor";
const std::string frame_id_ = "fts_sensor_frame";
std::array<double, 6> sensor_values_ = {1.1, 2.2, 3.3, 4.4, 5.5, 6.6};
std::array<double, 6> sensor_values_ = {{1.1, 2.2, 3.3, 4.4, 5.5, 6.6}};

hardware_interface::StateInterface fts_force_x_{sensor_name_, "force.x", &sensor_values_[0]};
hardware_interface::StateInterface fts_force_y_{sensor_name_, "force.y", &sensor_values_[1]};
Expand Down
3 changes: 2 additions & 1 deletion forward_command_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,8 @@ project(forward_command_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
-Werror=return-type -Werror=shadow -Werror=format -Werror=range-loop-construct
-Werror=missing-braces)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
4 changes: 3 additions & 1 deletion gripper_controllers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,9 @@ if(APPLE OR WIN32)
endif()

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Werror=conversion -Werror=unused-but-set-variable -Werror=return-type -Werror=shadow -Werror=format)
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format -Werror=range-loop-construct
-Werror=missing-braces)
endif()

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

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
-Werror=return-type -Werror=shadow -Werror=format -Werror=range-loop-construct
-Werror=missing-braces)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ class IMUSensorBroadcasterTest : public ::testing::Test
protected:
const std::string sensor_name_ = "imu_sensor";
const std::string frame_id_ = "imu_sensor_frame";
std::array<double, 10> sensor_values_ = {1.1, 2.2, 3.3, 4.4, 5.5, 6.6, 7.7, 8.8, 9.9, 10.10};
std::array<double, 10> sensor_values_ = {{1.1, 2.2, 3.3, 4.4, 5.5, 6.6, 7.7, 8.8, 9.9, 10.10}};
hardware_interface::StateInterface imu_orientation_x_{
sensor_name_, "orientation.x", &sensor_values_[0]};
hardware_interface::StateInterface imu_orientation_y_{
Expand Down
3 changes: 2 additions & 1 deletion joint_state_broadcaster/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,8 @@ project(joint_state_broadcaster LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
-Werror=return-type -Werror=shadow -Werror=format -Werror=range-loop-construct
-Werror=missing-braces)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
4 changes: 3 additions & 1 deletion joint_trajectory_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,9 @@ 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 -Werror=conversion -Werror=unused-but-set-variable -Werror=return-type -Werror=shadow -Werror=format)
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format -Werror=range-loop-construct
-Werror=missing-braces)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
3 changes: 2 additions & 1 deletion parallel_gripper_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,8 @@ project(parallel_gripper_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
-Werror=return-type -Werror=shadow -Werror=format -Werror=range-loop-construct
-Werror=missing-braces)
endif()

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

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Werror=conversion -Werror=unused-but-set-variable -Werror=return-type -Werror=shadow -Werror=format)
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format -Werror=range-loop-construct
-Werror=missing-braces)
endif()

if(WIN32)
Expand Down
3 changes: 2 additions & 1 deletion pose_broadcaster/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,8 @@ project(pose_broadcaster

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
-Werror=return-type -Werror=shadow -Werror=format -Werror=range-loop-construct
-Werror=missing-braces)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
2 changes: 1 addition & 1 deletion pose_broadcaster/test/test_pose_broadcaster.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ class PoseBroadcasterTest : public ::testing::Test
const std::string frame_id_ = "pose_base_frame";
const std::string tf_child_frame_id_ = "pose_frame";

std::array<double, 7> pose_values_ = {1.1, 2.2, 3.3, 4.4, 5.5, 6.6, 7.7};
std::array<double, 7> pose_values_ = {{1.1, 2.2, 3.3, 4.4, 5.5, 6.6, 7.7}};

hardware_interface::StateInterface pose_position_x_{pose_name_, "position.x", &pose_values_[0]};
hardware_interface::StateInterface pose_position_y_{pose_name_, "position.x", &pose_values_[1]};
Expand Down
3 changes: 2 additions & 1 deletion position_controllers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,8 @@ project(position_controllers LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
-Werror=return-type -Werror=shadow -Werror=format -Werror=range-loop-construct
-Werror=missing-braces)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
4 changes: 3 additions & 1 deletion range_sensor_broadcaster/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,9 @@ if(NOT CMAKE_CXX_STANDARD)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic -Werror=unused-but-set-variable -Werror=return-type -Werror=shadow -Werror=format)
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format -Werror=range-loop-construct
-Werror=missing-braces)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
8 changes: 4 additions & 4 deletions range_sensor_broadcaster/src/range_sensor_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,10 +75,10 @@ controller_interface::CallbackReturn RangeSensorBroadcaster::on_configure(

realtime_publisher_->lock();
realtime_publisher_->msg_.header.frame_id = params_.frame_id;
realtime_publisher_->msg_.radiation_type = params_.radiation_type;
realtime_publisher_->msg_.field_of_view = params_.field_of_view;
realtime_publisher_->msg_.min_range = params_.min_range;
realtime_publisher_->msg_.max_range = params_.max_range;
realtime_publisher_->msg_.radiation_type = static_cast<uint8_t>(params_.radiation_type);
realtime_publisher_->msg_.field_of_view = static_cast<float>(params_.field_of_view);
realtime_publisher_->msg_.min_range = static_cast<float>(params_.min_range);
realtime_publisher_->msg_.max_range = static_cast<float>(params_.max_range);
// \note The versions conditioning is added here to support the source-compatibility with Humble
#if SENSOR_MSGS_VERSION_MAJOR >= 5
realtime_publisher_->msg_.variance = params_.variance;
Expand Down
Loading

0 comments on commit 4f447f4

Please sign in to comment.