From 131b9c52bc953acba06ef825d2f44dc06ea70476 Mon Sep 17 00:00:00 2001 From: gwalck Date: Tue, 13 Jun 2023 20:46:31 +0200 Subject: [PATCH] Added -Wconversion flag and fix warnings (#667) (cherry picked from commit 23f0defd94a5a80f07c339b0babc736d2d0dcd25) # Conflicts: # diff_drive_controller/src/diff_drive_controller.cpp # joint_trajectory_controller/src/joint_trajectory_controller.cpp # tricycle_controller/src/tricycle_controller.cpp --- .../src/diff_drive_controller.cpp | 5 +++ .../src/joint_trajectory_controller.cpp | 8 ++++ .../src/tricycle_controller.cpp | 38 +++++++++++++++++++ 3 files changed, 51 insertions(+) diff --git a/diff_drive_controller/src/diff_drive_controller.cpp b/diff_drive_controller/src/diff_drive_controller.cpp index f277fb7aa2..4603910da5 100644 --- a/diff_drive_controller/src/diff_drive_controller.cpp +++ b/diff_drive_controller/src/diff_drive_controller.cpp @@ -167,8 +167,13 @@ controller_interface::return_type DiffDriveController::update( left_feedback_mean += left_feedback; right_feedback_mean += right_feedback; } +<<<<<<< HEAD left_feedback_mean /= static_cast(wheels_per_side_); right_feedback_mean /= static_cast(wheels_per_side_); +======= + left_feedback_mean /= static_cast(params_.wheels_per_side); + right_feedback_mean /= static_cast(params_.wheels_per_side); +>>>>>>> 23f0def (Added -Wconversion flag and fix warnings (#667)) if (params_.position_feedback) { diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 19524664cc..41d1f34a32 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -118,9 +118,17 @@ controller_interface::return_type JointTrajectoryController::update( { return controller_interface::return_type::OK; } +<<<<<<< HEAD auto logger = this->get_node()->get_logger(); // update dynamic parameters if (param_listener_->is_old(params_)) +======= + + auto compute_error_for_joint = [&]( + JointTrajectoryPoint & error, size_t index, + const JointTrajectoryPoint & current, + const JointTrajectoryPoint & desired) +>>>>>>> 23f0def (Added -Wconversion flag and fix warnings (#667)) { params_ = param_listener_->get_params(); default_tolerances_ = get_segment_tolerances(logger, params_); diff --git a/tricycle_controller/src/tricycle_controller.cpp b/tricycle_controller/src/tricycle_controller.cpp index 66c6ed1b0f..761866f4ca 100644 --- a/tricycle_controller/src/tricycle_controller.cpp +++ b/tricycle_controller/src/tricycle_controller.cpp @@ -52,9 +52,47 @@ CallbackReturn TricycleController::on_init() { try { +<<<<<<< HEAD // Create the parameter listener and get the parameters param_listener_ = std::make_shared(get_node()); params_ = param_listener_->get_params(); +======= + // with the lifecycle node being initialized, we can declare parameters + auto_declare("traction_joint_name", std::string()); + auto_declare("steering_joint_name", std::string()); + + auto_declare("wheelbase", wheel_params_.wheelbase); + auto_declare("wheel_radius", wheel_params_.radius); + + auto_declare("odom_frame_id", odom_params_.odom_frame_id); + auto_declare("base_frame_id", odom_params_.base_frame_id); + auto_declare>("pose_covariance_diagonal", std::vector()); + auto_declare>("twist_covariance_diagonal", std::vector()); + auto_declare("open_loop", odom_params_.open_loop); + auto_declare("enable_odom_tf", odom_params_.enable_odom_tf); + auto_declare("odom_only_twist", odom_params_.odom_only_twist); + + auto_declare("cmd_vel_timeout", static_cast(cmd_vel_timeout_.count())); + auto_declare("publish_ackermann_command", publish_ackermann_command_); + auto_declare("velocity_rolling_window_size", 10); + auto_declare("use_stamped_vel", use_stamped_vel_); + + auto_declare("traction.max_velocity", NAN); + auto_declare("traction.min_velocity", NAN); + auto_declare("traction.max_acceleration", NAN); + auto_declare("traction.min_acceleration", NAN); + auto_declare("traction.max_deceleration", NAN); + auto_declare("traction.min_deceleration", NAN); + auto_declare("traction.max_jerk", NAN); + auto_declare("traction.min_jerk", NAN); + + auto_declare("steering.max_position", NAN); + auto_declare("steering.min_position", NAN); + auto_declare("steering.max_velocity", NAN); + auto_declare("steering.min_velocity", NAN); + auto_declare("steering.max_acceleration", NAN); + auto_declare("steering.min_acceleration", NAN); +>>>>>>> 23f0def (Added -Wconversion flag and fix warnings (#667)) } catch (const std::exception & e) {