Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

cleanup warnings #3028

Merged
merged 2 commits into from
Jun 23, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 3 additions & 4 deletions nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
6 changes: 0 additions & 6 deletions nav2_behaviors/plugins/drive_on_heading.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,14 +13,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <chrono>
#include <ctime>
#include <memory>
#include <utility>

#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)
16 changes: 6 additions & 10 deletions nav2_behaviors/plugins/drive_on_heading.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,13 +41,14 @@ class DriveOnHeading : public TimedBehavior<ActionT>
*/
DriveOnHeading()
: TimedBehavior<ActionT>(),
feedback_(std::make_shared<typename ActionT::Feedback>())
feedback_(std::make_shared<typename ActionT::Feedback>()),
command_x_(0.0),
command_speed_(0.0),
simulate_ahead_time_(0.0)
{
}


~DriveOnHeading()
{}
~DriveOnHeading() = default;

/**
* @brief Initialization to run behavior
Expand Down Expand Up @@ -122,7 +123,6 @@ class DriveOnHeading : public TimedBehavior<ActionT>
return Status::SUCCEEDED;
}

// TODO(mhpanah): cmd_vel value should be passed as a parameter
auto cmd_vel = std::make_unique<geometry_msgs::msg::Twist>();
cmd_vel->linear.y = 0.0;
cmd_vel->angular.z = 0.0;
Expand Down Expand Up @@ -199,18 +199,14 @@ class DriveOnHeading : public TimedBehavior<ActionT>
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_;
double command_speed_;
rclcpp::Duration command_time_allowance_{0, 0};
rclcpp::Time end_time_;
double simulate_ahead_time_;

typename ActionT::Feedback::SharedPtr feedback_;
};

} // namespace nav2_behaviors
Expand Down
20 changes: 9 additions & 11 deletions nav2_behaviors/plugins/spin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,19 +13,13 @@
// limitations under the License.

#include <cmath>
#include <chrono>
#include <ctime>
#include <thread>
#include <algorithm>
#include <memory>
#include <utility>

#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"

Expand All @@ -37,13 +31,17 @@ namespace nav2_behaviors
Spin::Spin()
: TimedBehavior<SpinAction>(),
feedback_(std::make_shared<SpinAction::Feedback>()),
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()
{
Expand Down Expand Up @@ -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<float>(relative_yaw_);
action_server_->publish_feedback(feedback_);

double remaining_yaw = abs(cmd_yaw_) - abs(relative_yaw_);
Expand Down
5 changes: 1 addition & 4 deletions nav2_behaviors/plugins/wait.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,6 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <cmath>
#include <chrono>
#include <memory>

Expand All @@ -27,9 +26,7 @@ Wait::Wait()
{
}

Wait::~Wait()
{
}
Wait::~Wait() = default;

Status Wait::onRun(const std::shared_ptr<const WaitAction::Goal> command)
{
Expand Down
1 change: 0 additions & 1 deletion nav2_behaviors/src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
// See the License for the specific language governing permissions and
// limitations under the License. Reserved.

#include <string>
#include <memory>

#include "nav2_behaviors/behavior_server.hpp"
Expand Down
7 changes: 3 additions & 4 deletions nav2_behaviors/test/test_behaviors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
#include <memory>
#include <chrono>
#include <iostream>
#include <future>
#include <thread>

#include "gtest/gtest.h"
Expand All @@ -42,7 +41,7 @@ class DummyBehavior : public TimedBehavior<BehaviorAction>
: TimedBehavior<BehaviorAction>(),
initialized_(false) {}

~DummyBehavior() {}
~DummyBehavior() = default;

Status onRun(const std::shared_ptr<const BehaviorAction::Goal> goal) override
{
Expand Down Expand Up @@ -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<rclcpp_lifecycle::LifecycleNode>(
Expand Down