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

Fixed compiler warnings #2313

Open
wants to merge 9 commits into
base: ros2
Choose a base branch
from
Open
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
1 change: 1 addition & 0 deletions framework
Submodule framework added at a6c523
12 changes: 7 additions & 5 deletions rj_utils/src/logging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,22 +30,24 @@ 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;
default:
break;
}
}

Expand Down
2 changes: 1 addition & 1 deletion rj_vision_receiver/src/vision_receiver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ void VisionReceiver::publish_thread() {
}
}

void VisionReceiver::set_port(const std::string& interface, int port) {
void VisionReceiver::set_port( [[maybe_unused]] const std::string& interface, int port) {
// If the socket is already open, close it to cancel any pending
// operations before we reopen it on a new port.
if (socket_.is_open()) {
Expand Down
1 change: 1 addition & 0 deletions robocup-software
Submodule robocup-software added at 178878
2 changes: 1 addition & 1 deletion soccer/src/rj_vision_filter/ball/ball_bounce.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -176,7 +176,7 @@ bool BallBounce::calc_ball_bounce(const KalmanBall& ball,
intersect_pt_reflection_vector.normalized();

// Scale magnitude of velocity by a percentage
double dampen_lin_coeff = PARAM_robot_body_lin_dampen;
[[maybe_unused]] double dampen_lin_coeff = PARAM_robot_body_lin_dampen;
double dampen_angle_coeff = PARAM_robot_body_angle_dampen;

if (did_hit_mouth) {
Expand Down
2 changes: 1 addition & 1 deletion soccer/src/rj_vision_filter/camera/camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -163,7 +163,7 @@ void Camera::update_balls_mhkf(RJ::Time calc_time, const std::vector<CameraBall>
const CameraBall& camera_ball = ball_list.at(i);
bool was_used = used_camera_ball.at(i);

if (!was_used && kalman_ball_list_.size() < PARAM_max_num_kalman_balls) {
if (!was_used && (int64_t) kalman_ball_list_.size() < PARAM_max_num_kalman_balls) {
kalman_ball_list_.emplace_back(camera_id_, calc_time, camera_ball, previous_world_ball);
}
}
Expand Down
12 changes: 6 additions & 6 deletions soccer/src/soccer/control/trapezoidal_motion_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -169,12 +169,12 @@ TEST(TrapezoidalMotion2, more_tests) {
}

TEST(TrapezoidalMotion3, more_tests) {
double pos_out = 1.11101;
double path_length = 1.11101;
double max_speed = 2.2;
double max_acc = 1;
double start_speed = 0.901393;
double final_speed = 0;
[[maybe_unused]] double pos_out = 1.11101;
[[maybe_unused]] double path_length = 1.11101;
[[maybe_unused]] double max_speed = 2.2;
[[maybe_unused]] double max_acc = 1;
[[maybe_unused]] double start_speed = 0.901393;
[[maybe_unused]] double final_speed = 0;

double result = Trapezoidal::get_time(2.03294, 2.03294, 2.2, 1, 0.176091, 0);
EXPECT_FALSE(std::isnan(result));
Expand Down
2 changes: 1 addition & 1 deletion soccer/src/soccer/log_viewer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
#include <vector>

class LogViewer : public QMainWindow {
Q_OBJECT;
Q_OBJECT

public:
LogViewer(QWidget* parent = nullptr);
Expand Down
2 changes: 1 addition & 1 deletion soccer/src/soccer/optimization/nelder_mead_2d_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ static float eval_function1(rj_geometry::Point p) {
return -1 * sqrt(p.x() * p.x() + p.y() * p.y());
}

static float eval_function2(rj_geometry::Point p) { return 1; }
static float eval_function2([[maybe_unused]] rj_geometry::Point p) { return 1; }

TEST(NelderMead2D, execute) {
std::function<float(rj_geometry::Point)> f = &eval_function1;
Expand Down
4 changes: 2 additions & 2 deletions soccer/src/soccer/planning/planner/collect_path_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ Trajectory CollectPathPlanner::plan(const PlanRequest& plan_request) {

const RJ::Time cur_time = plan_request.start.stamp;

const MotionCommand& command = plan_request.motion_command;
[[maybe_unused]] const MotionCommand& command = plan_request.motion_command;

// Start state for specified robot
RobotInstant start_instant = plan_request.start;
Expand All @@ -33,7 +33,7 @@ Trajectory CollectPathPlanner::plan(const PlanRequest& plan_request) {
// All the max velocity / acceleration constraints for translation /
// rotation
RobotConstraints robot_constraints = plan_request.constraints;
MotionConstraints& motion_constraints = robot_constraints.mot;
[[maybe_unused]] MotionConstraints& motion_constraints = robot_constraints.mot;

// The small beginning part of the previous path
Trajectory partial_path;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ Trajectory EscapeObstaclesPathPlanner::plan(const PlanRequest& plan_request) {
Point unblocked =
find_non_blocked_goal(start_instant.position(), previous_target_, obstacles, 300);

std::optional<Point> opt_prev_pt;
[[maybe_unused]] std::optional<Point> opt_prev_pt;

LinearMotionInstant goal{unblocked, Point()};
auto result = CreatePath::simple(start_instant.linear_motion(), goal, motion_constraints,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ Trajectory PathTargetPathPlanner::plan(const PlanRequest& request) {
}

LinearMotionInstant target_instant = command.target;
Point goal_point = target_instant.position;
[[maybe_unused]] Point goal_point = target_instant.position;

// Cache the start and goal instants for is_done()
cached_target_instant_ = target_instant;
Expand Down
4 changes: 2 additions & 2 deletions soccer/src/soccer/planning/planner/pivot_path_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,10 +34,10 @@ Trajectory PivotPathPlanner::plan(const PlanRequest& request) {
auto pivot_target = command.target.position;

// TODO(Kyle): These need real constants
const bool pivot_target_unchanged =
[[maybe_unused]] const bool pivot_target_unchanged =
cached_pivot_target_.has_value() &&
cached_pivot_target_.value().dist_to(pivot_target) < kRobotMouthWidth / 2;
bool pivot_point_unchanged =
[[maybe_unused]] bool pivot_point_unchanged =
cached_pivot_point_.has_value() &&
cached_pivot_point_.value().dist_to(pivot_point) < kRobotMouthWidth / 2;

Expand Down
4 changes: 2 additions & 2 deletions soccer/src/soccer/planning/planner/plan_request.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,8 @@ rj_geometry::Circle make_robot_obstacle(const RobotState& robot) {
}

void fill_obstacles(const PlanRequest& in, rj_geometry::ShapeSet* out_static,
std::vector<DynamicObstacle>* out_dynamic, bool avoid_ball,
Trajectory* out_ball_trajectory) {
[[maybe_unused]] std::vector<DynamicObstacle>* out_dynamic, bool avoid_ball,
[[maybe_unused]] Trajectory* out_ball_trajectory) {
out_static->clear();
out_static->add(in.field_obstacles);
out_static->add(in.virtual_obstacles);
Expand Down
1 change: 0 additions & 1 deletion soccer/src/soccer/planning/planner/plan_request.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,6 @@ struct PlanRequest {

// Whether the robot has a ball
bool ball_sense = false;
/**
/**
* How far away to stay from the ball, if the MotionCommand chooses to avoid the ball.
*/
Expand Down
4 changes: 2 additions & 2 deletions soccer/src/soccer/planning/planner/rotate_path_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,8 @@ bool RotatePathPlanner::is_done() const {

Trajectory RotatePathPlanner::pivot(const PlanRequest& request) {
const RobotInstant& start_instant = request.start;
const auto& linear_constraints = request.constraints.mot;
const auto& rotation_constraints = request.constraints.rot;
[[maybe_unused]] const auto& linear_constraints = request.constraints.mot;
[[maybe_unused]] const auto& rotation_constraints = request.constraints.rot;

rj_geometry::ShapeSet static_obstacles;
std::vector<DynamicObstacle> dynamic_obstacles;
Expand Down
2 changes: 1 addition & 1 deletion soccer/src/soccer/planning/planner/settle_path_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ Trajectory SettlePathPlanner::plan(const PlanRequest& plan_request) {

BallState ball = plan_request.world_state->ball;

const RJ::Time cur_time = plan_request.start.stamp;
[[maybe_unused]] const RJ::Time cur_time = plan_request.start.stamp;

const MotionCommand& command = plan_request.motion_command;

Expand Down
4 changes: 2 additions & 2 deletions soccer/src/soccer/planning/planner_for_robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,8 +86,8 @@ void PlannerForRobot::execute_intent(const RobotIntent& intent) {
}

void PlannerForRobot::plan_hypothetical_robot_path(
const std::shared_ptr<rj_msgs::srv::PlanHypotheticalPath::Request>& request,
std::shared_ptr<rj_msgs::srv::PlanHypotheticalPath::Response>& response) {
[[maybe_unused]] const std::shared_ptr<rj_msgs::srv::PlanHypotheticalPath::Request>& request,
[[maybe_unused]] std::shared_ptr<rj_msgs::srv::PlanHypotheticalPath::Response>& response) {
/* const auto intent = rj_convert::convert_from_ros(request->intent); */
/* auto plan_request = make_request(intent); */
/* auto trajectory = safe_plan_for_robot(plan_request); */
Expand Down
4 changes: 2 additions & 2 deletions soccer/src/soccer/planning/primitives/path_smoothing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ static void fit_cubic_bezier(Point vi, Point vf, const std::vector<Point>& point

int num_curves = static_cast<int>(points.size()) - 1;

if (ks.size() != num_curves) {
if (static_cast<int>(ks.size()) != num_curves) {
throw std::invalid_argument("Expected ks.size() == points.size() - 1");
}

Expand Down Expand Up @@ -187,7 +187,7 @@ void BezierPath::evaluate(double s, rj_geometry::Point* position, rj_geometry::P

// This will only happen when s = 1 - in that case, we actually want to use
// the last segment.
if (index == num_curves) {
if (index == (int) num_curves) {
index--;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,10 +42,10 @@ class RoboCupStateSpace : public RRT::StateSpace<rj_geometry::Point> {
return source + dir * step_size;
}

rj_geometry::Point intermediateState(const rj_geometry::Point& source,
const rj_geometry::Point& target,
double min_step_size,
double max_step_size) const override {
rj_geometry::Point intermediateState([[maybe_unused]] const rj_geometry::Point& source,
[[maybe_unused]] const rj_geometry::Point& target,
[[maybe_unused]] double min_step_size,
[[maybe_unused]] double max_step_size) const override {
throw std::runtime_error("Adaptive stepsize control not implemented");
}

Expand Down
6 changes: 4 additions & 2 deletions soccer/src/soccer/planning/primitives/rrt_util.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ void draw_bi_rrt(const RRT::BiRRT<Point>& bi_rrt, DebugDrawer* debug_drawer, uns
}

vector<Point> run_rrt_helper(Point start, Point goal, const ShapeSet& obstacles,
const vector<Point>& waypoints, bool straight_line) {
const vector<Point>& waypoints, [[maybe_unused]] bool straight_line) {
auto state_space =
std::make_shared<RoboCupStateSpace>(FieldDimensions::current_dimensions, obstacles);
RRT::BiRRT<Point> bi_rrt(state_space, Point::hash, 2);
Expand All @@ -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
2 changes: 1 addition & 1 deletion soccer/src/soccer/planning/tests/trajectory_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -185,7 +185,7 @@ TEST(Trajectory, SubTrajectory) {
{
RJ::Time t0{4s};
RJ::Time t1{6s};
RobotInstant bc = traj.evaluate(t0).value();
[[maybe_unused]] RobotInstant bc = traj.evaluate(t0).value();

Trajectory sub = traj.sub_trajectory(t0, t1);
EXPECT_TRUE(Trajectory::nearly_equal(sub, Trajectory{{c}}));
Expand Down
4 changes: 2 additions & 2 deletions soccer/src/soccer/radio/sim_radio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,7 @@ SimRadio::SimRadio(bool blue_team)

void SimRadio::send_control_message(uint8_t robot_id, const rj_msgs::msg::MotionSetpoint& motion,
const rj_msgs::msg::ManipulatorSetpoint& manipulator,
strategy::Positions role) {
[[maybe_unused]] strategy::Positions role) {
RobotControl sim_packet;

// Send a sim packet with a single robot. The simulator can handle many robots, but our commands
Expand Down Expand Up @@ -157,7 +157,7 @@ void SimRadio::start_receive() {
});
}

void SimRadio::receive_packet(const boost::system::error_code& error, std::size_t num_bytes) {
void SimRadio::receive_packet([[maybe_unused]] const boost::system::error_code& error, [[maybe_unused]] std::size_t num_bytes) {
std::string data(buffer_.begin(), buffer_.end());
handle_receive(data);
start_receive();
Expand Down
2 changes: 1 addition & 1 deletion soccer/src/soccer/ros2_temp/autonomy_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ AutonomyInterface::AutonomyInterface(Context* context, rclcpp::Executor* executo

executor->add_node(node_);
status_subs_.reserve(kNumShells);
for (int i = 0; i < kNumShells; i++) {
for (int i = 0; i < (int) kNumShells; i++) {
status_subs_.emplace_back(node_->create_subscription<rj_msgs::msg::RobotStatus>(
radio::topics::robot_status_topic(i), rclcpp::QoS(1),
[this, i](rj_msgs::msg::RobotStatus::SharedPtr status) { // NOLINT
Expand Down
2 changes: 1 addition & 1 deletion soccer/src/soccer/ros2_temp/debug_draw_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ void DebugDrawInterface::run() {
color_to_qt(segment.color),
QString::fromStdString(layer));
}
for (const auto& pose : debug_draw->poses) {
for ([[maybe_unused]] const auto& pose : debug_draw->poses) {
// TODO(#1584): Handle poses
}
for (const auto& path : debug_draw->paths) {
Expand Down
2 changes: 1 addition & 1 deletion soccer/src/soccer/strategy/agent/agent_action_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -253,7 +253,7 @@ void AgentActionClient::get_communication() {
return;
}

for (int i = 0; i < optional_communication_request.size(); i++) {
for (int i = 0; i < (int) optional_communication_request.size(); i++) {
auto communication_request = optional_communication_request.front();
optional_communication_request.pop_front();

Expand Down
2 changes: 1 addition & 1 deletion soccer/src/soccer/strategy/agent/position/goalie.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ class Goalie : public Position {
const rj_geometry::Point clear_point_{0.0, 4.5};

// temp
int send_idle_ct_ = 0;
[[maybe_unused]] int send_idle_ct_ = 0;

// see Position superclass
std::optional<RobotIntent> derived_get_task(RobotIntent intent) override;
Expand Down
2 changes: 1 addition & 1 deletion soccer/src/soccer/strategy/agent/position/marker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ void Marker::choose_target(const WorldState* ws) {
// If we ever use multiple Markers, they should choose different
// robots to track from each other. Logic for this operation must be
// added because multiple markers currently mark the same robot.
for (int i = 0; i < kNumShells; i++) {
for (int i = 0; i < (int) kNumShells; i++) {
if (std::fabs(ws->get_robot(false, i).pose.position().x()) < marker_follow_cutoff &&
ws->get_robot(false, i).pose.position().y() < y_bound &&
(ws->ball.position - ws->get_robot(false, i).pose.position()).mag() > .25) {
Expand Down
2 changes: 1 addition & 1 deletion soccer/src/soccer/strategy/agent/position/position.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ Position::Position(int r_id, std::string position_name)

std::optional<RobotIntent> Position::get_task(WorldState& world_state,
FieldDimensions& field_dimensions,
PlayState& play_state) {
[[maybe_unused]] PlayState& play_state) {
// Point class variables to parameter references
// TODO (Prabhanjan): Don't copy references into local vars
field_dimensions_ = field_dimensions;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -197,7 +197,7 @@ void RobotFactoryPosition::start_kicker_picker() {
bool RobotFactoryPosition::have_all_kicker_responses() {
int num_alive = std::count(alive_robots_.begin(), alive_robots_.end(), true);

return kicker_distances_.size() == num_alive - 1; // Don't expect the goalie to respond
return (int) kicker_distances_.size() == num_alive - 1; // Don't expect the goalie to respond
}

bool RobotFactoryPosition::am_closest_kicker() {
Expand Down
2 changes: 1 addition & 1 deletion soccer/src/soccer/strategy/agent/position/waller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ std::optional<RobotIntent> Waller::get_task(RobotIntent intent, const WorldState
}

if ((target_point.x() < robot_pos.x() && waller_pos_ != 1) ||
(target_point.x() > robot_pos.x() && waller_pos_ != num_wallers)) {
(target_point.x() > robot_pos.x() && waller_pos_ != (int) num_wallers)) {
auto parent_point = world_state->get_robot(true, parent_id).pose.position();
angle = (parent_point - goal_pos).angle();
delta_angle = wall_spacing / min_wall_rad;
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
Loading
Loading