From 3705a884c3d2654a0158d658386c227b98e140f4 Mon Sep 17 00:00:00 2001 From: Joshua Wallace <47819219+jwallace42@users.noreply.github.com> Date: Thu, 23 Jun 2022 16:41:59 -0400 Subject: [PATCH] cleanup warnings (#3028) * cleanup warnings * removed referenc --- .../include/nav2_behaviors/timed_behavior.hpp | 7 +++---- nav2_behaviors/plugins/drive_on_heading.cpp | 6 ------ nav2_behaviors/plugins/drive_on_heading.hpp | 16 ++++++--------- nav2_behaviors/plugins/spin.cpp | 20 +++++++++---------- nav2_behaviors/plugins/wait.cpp | 5 +---- nav2_behaviors/src/main.cpp | 1 - nav2_behaviors/test/test_behaviors.cpp | 7 +++---- 7 files changed, 22 insertions(+), 40 deletions(-) diff --git a/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp b/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp index 0c41b13f495..06528be8872 100644 --- a/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp +++ b/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp @@ -63,13 +63,12 @@ class TimedBehavior : public nav2_core::Behavior TimedBehavior() : action_server_(nullptr), cycle_frequency_(10.0), - enabled_(false) + enabled_(false), + transform_tolerance_(0.0) { } - virtual ~TimedBehavior() - { - } + virtual ~TimedBehavior() = default; // Derived classes can override this method to catch the command and perform some checks // before getting into the main loop. The method will only be called diff --git a/nav2_behaviors/plugins/drive_on_heading.cpp b/nav2_behaviors/plugins/drive_on_heading.cpp index dae6ed83a11..53525b3bb6e 100644 --- a/nav2_behaviors/plugins/drive_on_heading.cpp +++ b/nav2_behaviors/plugins/drive_on_heading.cpp @@ -13,14 +13,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include -#include #include -#include - #include "drive_on_heading.hpp" -#include "nav2_util/node_utils.hpp" -#include "nav2_msgs/action/back_up.hpp" #include "pluginlib/class_list_macros.hpp" PLUGINLIB_EXPORT_CLASS(nav2_behaviors::DriveOnHeading<>, nav2_core::Behavior) diff --git a/nav2_behaviors/plugins/drive_on_heading.hpp b/nav2_behaviors/plugins/drive_on_heading.hpp index 65ab8f11579..79c8d81c719 100644 --- a/nav2_behaviors/plugins/drive_on_heading.hpp +++ b/nav2_behaviors/plugins/drive_on_heading.hpp @@ -41,13 +41,14 @@ class DriveOnHeading : public TimedBehavior */ DriveOnHeading() : TimedBehavior(), - feedback_(std::make_shared()) + feedback_(std::make_shared()), + command_x_(0.0), + command_speed_(0.0), + simulate_ahead_time_(0.0) { } - - ~DriveOnHeading() - {} + ~DriveOnHeading() = default; /** * @brief Initialization to run behavior @@ -122,7 +123,6 @@ class DriveOnHeading : public TimedBehavior return Status::SUCCEEDED; } - // TODO(mhpanah): cmd_vel value should be passed as a parameter auto cmd_vel = std::make_unique(); cmd_vel->linear.y = 0.0; cmd_vel->angular.z = 0.0; @@ -199,9 +199,7 @@ class DriveOnHeading : public TimedBehavior node->get_parameter("simulate_ahead_time", simulate_ahead_time_); } - double min_linear_vel_; - double max_linear_vel_; - double linear_acc_lim_; + typename ActionT::Feedback::SharedPtr feedback_; geometry_msgs::msg::PoseStamped initial_pose_; double command_x_; @@ -209,8 +207,6 @@ class DriveOnHeading : public TimedBehavior rclcpp::Duration command_time_allowance_{0, 0}; rclcpp::Time end_time_; double simulate_ahead_time_; - - typename ActionT::Feedback::SharedPtr feedback_; }; } // namespace nav2_behaviors diff --git a/nav2_behaviors/plugins/spin.cpp b/nav2_behaviors/plugins/spin.cpp index 641f59064e0..a76fe38f525 100644 --- a/nav2_behaviors/plugins/spin.cpp +++ b/nav2_behaviors/plugins/spin.cpp @@ -13,19 +13,13 @@ // limitations under the License. #include -#include -#include #include #include #include #include #include "spin.hpp" -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wpedantic" #include "tf2/utils.h" -#pragma GCC diagnostic pop -#include "tf2/LinearMath/Quaternion.h" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "nav2_util/node_utils.hpp" @@ -37,13 +31,17 @@ namespace nav2_behaviors Spin::Spin() : TimedBehavior(), feedback_(std::make_shared()), - prev_yaw_(0.0) + min_rotational_vel_(0.0), + max_rotational_vel_(0.0), + rotational_acc_lim_(0.0), + cmd_yaw_(0.0), + prev_yaw_(0.0), + relative_yaw_(0.0), + simulate_ahead_time_(0.0) { } -Spin::~Spin() -{ -} +Spin::~Spin() = default; void Spin::onConfigure() { @@ -128,7 +126,7 @@ Status Spin::onCycleUpdate() relative_yaw_ += delta_yaw; prev_yaw_ = current_yaw; - feedback_->angular_distance_traveled = relative_yaw_; + feedback_->angular_distance_traveled = static_cast(relative_yaw_); action_server_->publish_feedback(feedback_); double remaining_yaw = abs(cmd_yaw_) - abs(relative_yaw_); diff --git a/nav2_behaviors/plugins/wait.cpp b/nav2_behaviors/plugins/wait.cpp index 7ca00e2abc4..236f7122018 100644 --- a/nav2_behaviors/plugins/wait.cpp +++ b/nav2_behaviors/plugins/wait.cpp @@ -12,7 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include #include #include @@ -27,9 +26,7 @@ Wait::Wait() { } -Wait::~Wait() -{ -} +Wait::~Wait() = default; Status Wait::onRun(const std::shared_ptr command) { diff --git a/nav2_behaviors/src/main.cpp b/nav2_behaviors/src/main.cpp index 0b06ea9f173..4af82831f32 100644 --- a/nav2_behaviors/src/main.cpp +++ b/nav2_behaviors/src/main.cpp @@ -13,7 +13,6 @@ // See the License for the specific language governing permissions and // limitations under the License. Reserved. -#include #include #include "nav2_behaviors/behavior_server.hpp" diff --git a/nav2_behaviors/test/test_behaviors.cpp b/nav2_behaviors/test/test_behaviors.cpp index de1253cdc95..4cd7527fbcf 100644 --- a/nav2_behaviors/test/test_behaviors.cpp +++ b/nav2_behaviors/test/test_behaviors.cpp @@ -16,7 +16,6 @@ #include #include #include -#include #include #include "gtest/gtest.h" @@ -42,7 +41,7 @@ class DummyBehavior : public TimedBehavior : TimedBehavior(), initialized_(false) {} - ~DummyBehavior() {} + ~DummyBehavior() = default; Status onRun(const std::shared_ptr goal) override { @@ -96,9 +95,9 @@ class BehaviorTest : public ::testing::Test { protected: BehaviorTest() {SetUp();} - ~BehaviorTest() {} + ~BehaviorTest() = default; - void SetUp() + void SetUp() override { node_lifecycle_ = std::make_shared(