From 2d9aaba799201c50f4e23e0f658c3e1c7670a1b7 Mon Sep 17 00:00:00 2001 From: Joshua Wallace Date: Mon, 20 Jun 2022 18:31:01 -0400 Subject: [PATCH 1/2] cleanup warnings --- .../include/nav2_behaviors/timed_behavior.hpp | 9 ++++---- nav2_behaviors/plugins/back_up.cpp | 2 +- nav2_behaviors/plugins/back_up.hpp | 2 +- nav2_behaviors/plugins/drive_on_heading.cpp | 6 ----- nav2_behaviors/plugins/drive_on_heading.hpp | 18 ++++++--------- nav2_behaviors/plugins/spin.cpp | 22 +++++++++---------- nav2_behaviors/plugins/spin.hpp | 2 +- nav2_behaviors/plugins/wait.cpp | 7 ++---- nav2_behaviors/plugins/wait.hpp | 2 +- nav2_behaviors/src/main.cpp | 1 - nav2_behaviors/test/test_behaviors.cpp | 9 ++++---- 11 files changed, 31 insertions(+), 49 deletions(-) diff --git a/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp b/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp index 0c41b13f495..386a8e8e364 100644 --- a/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp +++ b/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp @@ -63,18 +63,17 @@ 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 // once and should return SUCCEEDED otherwise behavior will return FAILED. - virtual Status onRun(const std::shared_ptr command) = 0; + virtual Status onRun(const std::shared_ptr &command) = 0; // This is the method derived classes should mainly implement diff --git a/nav2_behaviors/plugins/back_up.cpp b/nav2_behaviors/plugins/back_up.cpp index 90a69a686ed..c0c68172c33 100644 --- a/nav2_behaviors/plugins/back_up.cpp +++ b/nav2_behaviors/plugins/back_up.cpp @@ -17,7 +17,7 @@ namespace nav2_behaviors { -Status BackUp::onRun(const std::shared_ptr command) +Status BackUp::onRun(const std::shared_ptr &command) { if (command->target.y != 0.0 || command->target.z != 0.0) { RCLCPP_INFO( diff --git a/nav2_behaviors/plugins/back_up.hpp b/nav2_behaviors/plugins/back_up.hpp index f892c5b0e2d..d81250e5121 100644 --- a/nav2_behaviors/plugins/back_up.hpp +++ b/nav2_behaviors/plugins/back_up.hpp @@ -28,7 +28,7 @@ namespace nav2_behaviors class BackUp : public DriveOnHeading { public: - Status onRun(const std::shared_ptr command) override; + Status onRun(const std::shared_ptr &command) override; }; } 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..810be77144a 100644 --- a/nav2_behaviors/plugins/drive_on_heading.hpp +++ b/nav2_behaviors/plugins/drive_on_heading.hpp @@ -41,20 +41,21 @@ 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 * @param command Goal to execute * @return Status of behavior */ - Status onRun(const std::shared_ptr command) override + Status onRun(const std::shared_ptr &command) override { if (command->target.y != 0.0 || command->target.z != 0.0) { RCLCPP_INFO( @@ -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..055298d174b 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() { @@ -73,7 +71,7 @@ void Spin::onConfigure() node->get_parameter("rotational_acc_lim", rotational_acc_lim_); } -Status Spin::onRun(const std::shared_ptr command) +Status Spin::onRun(const std::shared_ptr &command) { geometry_msgs::msg::PoseStamped current_pose; if (!nav2_util::getCurrentPose( @@ -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/spin.hpp b/nav2_behaviors/plugins/spin.hpp index 7174c91f467..9fa733ae899 100644 --- a/nav2_behaviors/plugins/spin.hpp +++ b/nav2_behaviors/plugins/spin.hpp @@ -45,7 +45,7 @@ class Spin : public TimedBehavior * @param command Goal to execute * @return Status of behavior */ - Status onRun(const std::shared_ptr command) override; + Status onRun(const std::shared_ptr &command) override; /** * @brief Configuration of behavior action diff --git a/nav2_behaviors/plugins/wait.cpp b/nav2_behaviors/plugins/wait.cpp index 7ca00e2abc4..861d490ecd7 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,11 +26,9 @@ Wait::Wait() { } -Wait::~Wait() -{ -} +Wait::~Wait() = default; -Status Wait::onRun(const std::shared_ptr command) +Status Wait::onRun(const std::shared_ptr &command) { wait_end_ = std::chrono::steady_clock::now() + rclcpp::Duration(command->time).to_chrono(); diff --git a/nav2_behaviors/plugins/wait.hpp b/nav2_behaviors/plugins/wait.hpp index 38e85fd14aa..f27e15b8f63 100644 --- a/nav2_behaviors/plugins/wait.hpp +++ b/nav2_behaviors/plugins/wait.hpp @@ -44,7 +44,7 @@ class Wait : public TimedBehavior * @param command Goal to execute * @return Status of behavior */ - Status onRun(const std::shared_ptr command) override; + Status onRun(const std::shared_ptr &command) override; /** * @brief Loop function to run behavior 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..31f6581dc03 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,9 +41,9 @@ class DummyBehavior : public TimedBehavior : TimedBehavior(), initialized_(false) {} - ~DummyBehavior() {} + ~DummyBehavior() = default; - Status onRun(const std::shared_ptr goal) override + Status onRun(const std::shared_ptr &goal) override { // A normal behavior would catch the command and initialize initialized_ = false; @@ -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( From 821751d8f548bcc61c0738d71d64f359d5416c61 Mon Sep 17 00:00:00 2001 From: Joshua Wallace Date: Tue, 21 Jun 2022 18:10:02 -0400 Subject: [PATCH 2/2] removed referenc --- nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp | 2 +- nav2_behaviors/plugins/back_up.cpp | 2 +- nav2_behaviors/plugins/back_up.hpp | 2 +- nav2_behaviors/plugins/drive_on_heading.hpp | 2 +- nav2_behaviors/plugins/spin.cpp | 2 +- nav2_behaviors/plugins/spin.hpp | 2 +- nav2_behaviors/plugins/wait.cpp | 2 +- nav2_behaviors/plugins/wait.hpp | 2 +- nav2_behaviors/test/test_behaviors.cpp | 2 +- 9 files changed, 9 insertions(+), 9 deletions(-) diff --git a/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp b/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp index 386a8e8e364..06528be8872 100644 --- a/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp +++ b/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp @@ -73,7 +73,7 @@ class TimedBehavior : public nav2_core::Behavior // 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 // once and should return SUCCEEDED otherwise behavior will return FAILED. - virtual Status onRun(const std::shared_ptr &command) = 0; + virtual Status onRun(const std::shared_ptr command) = 0; // This is the method derived classes should mainly implement diff --git a/nav2_behaviors/plugins/back_up.cpp b/nav2_behaviors/plugins/back_up.cpp index c0c68172c33..90a69a686ed 100644 --- a/nav2_behaviors/plugins/back_up.cpp +++ b/nav2_behaviors/plugins/back_up.cpp @@ -17,7 +17,7 @@ namespace nav2_behaviors { -Status BackUp::onRun(const std::shared_ptr &command) +Status BackUp::onRun(const std::shared_ptr command) { if (command->target.y != 0.0 || command->target.z != 0.0) { RCLCPP_INFO( diff --git a/nav2_behaviors/plugins/back_up.hpp b/nav2_behaviors/plugins/back_up.hpp index d81250e5121..f892c5b0e2d 100644 --- a/nav2_behaviors/plugins/back_up.hpp +++ b/nav2_behaviors/plugins/back_up.hpp @@ -28,7 +28,7 @@ namespace nav2_behaviors class BackUp : public DriveOnHeading { public: - Status onRun(const std::shared_ptr &command) override; + Status onRun(const std::shared_ptr command) override; }; } diff --git a/nav2_behaviors/plugins/drive_on_heading.hpp b/nav2_behaviors/plugins/drive_on_heading.hpp index 810be77144a..79c8d81c719 100644 --- a/nav2_behaviors/plugins/drive_on_heading.hpp +++ b/nav2_behaviors/plugins/drive_on_heading.hpp @@ -55,7 +55,7 @@ class DriveOnHeading : public TimedBehavior * @param command Goal to execute * @return Status of behavior */ - Status onRun(const std::shared_ptr &command) override + Status onRun(const std::shared_ptr command) override { if (command->target.y != 0.0 || command->target.z != 0.0) { RCLCPP_INFO( diff --git a/nav2_behaviors/plugins/spin.cpp b/nav2_behaviors/plugins/spin.cpp index 055298d174b..a76fe38f525 100644 --- a/nav2_behaviors/plugins/spin.cpp +++ b/nav2_behaviors/plugins/spin.cpp @@ -71,7 +71,7 @@ void Spin::onConfigure() node->get_parameter("rotational_acc_lim", rotational_acc_lim_); } -Status Spin::onRun(const std::shared_ptr &command) +Status Spin::onRun(const std::shared_ptr command) { geometry_msgs::msg::PoseStamped current_pose; if (!nav2_util::getCurrentPose( diff --git a/nav2_behaviors/plugins/spin.hpp b/nav2_behaviors/plugins/spin.hpp index 9fa733ae899..7174c91f467 100644 --- a/nav2_behaviors/plugins/spin.hpp +++ b/nav2_behaviors/plugins/spin.hpp @@ -45,7 +45,7 @@ class Spin : public TimedBehavior * @param command Goal to execute * @return Status of behavior */ - Status onRun(const std::shared_ptr &command) override; + Status onRun(const std::shared_ptr command) override; /** * @brief Configuration of behavior action diff --git a/nav2_behaviors/plugins/wait.cpp b/nav2_behaviors/plugins/wait.cpp index 861d490ecd7..236f7122018 100644 --- a/nav2_behaviors/plugins/wait.cpp +++ b/nav2_behaviors/plugins/wait.cpp @@ -28,7 +28,7 @@ Wait::Wait() Wait::~Wait() = default; -Status Wait::onRun(const std::shared_ptr &command) +Status Wait::onRun(const std::shared_ptr command) { wait_end_ = std::chrono::steady_clock::now() + rclcpp::Duration(command->time).to_chrono(); diff --git a/nav2_behaviors/plugins/wait.hpp b/nav2_behaviors/plugins/wait.hpp index f27e15b8f63..38e85fd14aa 100644 --- a/nav2_behaviors/plugins/wait.hpp +++ b/nav2_behaviors/plugins/wait.hpp @@ -44,7 +44,7 @@ class Wait : public TimedBehavior * @param command Goal to execute * @return Status of behavior */ - Status onRun(const std::shared_ptr &command) override; + Status onRun(const std::shared_ptr command) override; /** * @brief Loop function to run behavior diff --git a/nav2_behaviors/test/test_behaviors.cpp b/nav2_behaviors/test/test_behaviors.cpp index 31f6581dc03..4cd7527fbcf 100644 --- a/nav2_behaviors/test/test_behaviors.cpp +++ b/nav2_behaviors/test/test_behaviors.cpp @@ -43,7 +43,7 @@ class DummyBehavior : public TimedBehavior ~DummyBehavior() = default; - Status onRun(const std::shared_ptr &goal) override + Status onRun(const std::shared_ptr goal) override { // A normal behavior would catch the command and initialize initialized_ = false;