Skip to content

Commit

Permalink
fixed more compiler warnings
Browse files Browse the repository at this point in the history
  • Loading branch information
jonagil1661 committed Dec 4, 2024
1 parent d69ce62 commit 6573f9f
Show file tree
Hide file tree
Showing 3 changed files with 27 additions and 8 deletions.
10 changes: 5 additions & 5 deletions rj_utils/src/logging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,19 +30,19 @@ void Ros2Sink<Mutex>::sink_it_(const spdlog::details::log_msg& msg) {
switch (msg.level) {
case spdlog::level::trace:
case spdlog::level::debug:
RCLCPP_DEBUG(logger, string.c_str()); // NOLINT
RCLCPP_DEBUG(logger, "%s", string.c_str()); // NOLINT
break;
case spdlog::level::info:
RCLCPP_INFO(logger, string.c_str()); // NOLINT
RCLCPP_INFO(logger, "%s", string.c_str()); // NOLINT
break;
case spdlog::level::warn:
RCLCPP_WARN(logger, string.c_str()); // NOLINT
RCLCPP_WARN(logger, "%s", string.c_str()); // NOLINT
break;
case spdlog::level::err:
RCLCPP_ERROR(logger, string.c_str()); // NOLINT
RCLCPP_ERROR(logger, "%s", string.c_str()); // NOLINT
break;
case spdlog::level::critical:
RCLCPP_FATAL(logger, string.c_str()); // NOLINT
RCLCPP_FATAL(logger, "%s", string.c_str()); // NOLINT
break;
case spdlog::level::off:
break;
Expand Down
4 changes: 3 additions & 1 deletion soccer/src/soccer/planning/primitives/rrt_util.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,9 @@ vector<Point> run_rrt_helper(Point start, Point goal, const ShapeSet& obstacles,
}
vector<Point> points = bi_rrt.getPath();
RRT::SmoothPath(points, *state_space);
return std::move(points);
// return std::move(points);
// allows copy elision by removing std::move()
return points;
}

vector<Point> generate_rrt(Point start, Point goal, const ShapeSet& obstacles,
Expand Down
21 changes: 19 additions & 2 deletions soccer/src/soccer/strategy/agent/position/zoner.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,25 @@ class Zoner : public Position {
~Zoner() override = default;
Zoner(const Position& other);
Zoner(Zoner&& other) = default;
Zoner& operator=(const Zoner& other) = default;
Zoner& operator=(Zoner&& other) = default;
// Zoner& operator=(const Zoner& other) = default;
Zoner& operator=(const Zoner& other) {
// copies base class's members except for const
// values to fix implicit deletion compiler warning
if (this != &other) {
current_state_ = other.current_state_;
}
return *this;
}
// Zoner& operator=(Zoner&& other) = default;
Zoner& operator=(Zoner&& other) {
// copies base class's members except for const
// values to fix implicit deletion compiler warning
if (this != &other) {
current_state_ = other.current_state_;
}
return *this;
}


private:
std::optional<RobotIntent> derived_get_task(RobotIntent intent) override;
Expand Down

0 comments on commit 6573f9f

Please sign in to comment.