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 11 commits into
base: ros2
Choose a base branch
from
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
@@ -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) {
2 changes: 1 addition & 1 deletion soccer/src/rj_vision_filter/camera/camera.cpp
Original file line number Diff line number Diff line change
@@ -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);
}
}
2 changes: 1 addition & 1 deletion soccer/src/soccer/log_viewer.hpp
Original file line number Diff line number Diff line change
@@ -8,7 +8,7 @@
#include <vector>

class LogViewer : public QMainWindow {
Q_OBJECT;
Q_OBJECT

public:
LogViewer(QWidget* parent = nullptr);
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
@@ -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;
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
@@ -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;
@@ -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;
Original file line number Diff line number Diff line change
@@ -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,
Original file line number Diff line number Diff line change
@@ -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;
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
@@ -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;

2 changes: 1 addition & 1 deletion soccer/src/soccer/planning/planner/rotate_path_planner.cpp
Original file line number Diff line number Diff line change
@@ -33,7 +33,7 @@ bool RotatePathPlanner::is_done() const {
Trajectory RotatePathPlanner::pivot(const PlanRequest& request) {
const RobotInstant& start_instant = request.start;
[[maybe_unused]] const auto& linear_constraints = request.constraints.mot;
[[maybe_unused]]const auto& rotation_constraints = request.constraints.rot;
[[maybe_unused]] const auto& rotation_constraints = request.constraints.rot;

rj_geometry::ShapeSet static_obstacles;
std::vector<DynamicObstacle> dynamic_obstacles;
2 changes: 1 addition & 1 deletion soccer/src/soccer/planning/primitives/path_smoothing.cpp
Original file line number Diff line number Diff line change
@@ -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");
}

4 changes: 2 additions & 2 deletions soccer/src/soccer/radio/sim_radio.cpp
Original file line number Diff line number Diff line change
@@ -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
@@ -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();
2 changes: 1 addition & 1 deletion soccer/src/soccer/ros2_temp/autonomy_interface.cpp
Original file line number Diff line number Diff line change
@@ -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
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
@@ -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) {
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
@@ -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();

2 changes: 1 addition & 1 deletion soccer/src/soccer/strategy/agent/position/goalie.hpp
Original file line number Diff line number Diff line change
@@ -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;
2 changes: 1 addition & 1 deletion soccer/src/soccer/strategy/agent/position/marker.cpp
Original file line number Diff line number Diff line change
@@ -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) {
2 changes: 1 addition & 1 deletion soccer/src/soccer/strategy/agent/position/position.cpp
Original file line number Diff line number Diff line change
@@ -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;
Original file line number Diff line number Diff line change
@@ -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() {
2 changes: 1 addition & 1 deletion soccer/src/soccer/strategy/agent/position/waller.cpp
Original file line number Diff line number Diff line change
@@ -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_ != static_cast<int>(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;
14 changes: 7 additions & 7 deletions soccer/src/soccer/ui/main_window.cpp
Original file line number Diff line number Diff line change
@@ -341,7 +341,7 @@ void MainWindow::updateViews() {
QString("Log: %1 kiB").arg(QString::number((context_->logs.size_bytes + 512) / 1024)));
}

auto value = _ui.logHistoryLocation->value();
[[maybe_unused]] auto value = _ui.logHistoryLocation->value();

std::shared_ptr<LogFrame> live_frame;
RJ::Time start_time;
@@ -521,7 +521,7 @@ void MainWindow::updateViews() {
auto maybe_robot =
[&]() -> std::optional<std::reference_wrapper<const Packet::LogFrame_Robot>> {
for (int i = 0; i < currentFrame->self_size(); i++) {
if (currentFrame->self(i).shell() == shell) {
if ((currentFrame->self(i).shell() == (int) shell)) {
return currentFrame->self(i);
}
}
@@ -878,7 +878,7 @@ void MainWindow::on_actionNyanStyle_triggered() {

// Manual control commands

void MainWindow::on_actionDampedRotation_toggled(bool value) {
void MainWindow::on_actionDampedRotation_toggled([[maybe_unused]] bool value) {
#if MANUAL
cout << "DampedRotation is ";
if (value)
@@ -891,7 +891,7 @@ void MainWindow::on_actionDampedRotation_toggled(bool value) {
#endif
}

void MainWindow::on_actionDampedTranslation_toggled(bool value) {
void MainWindow::on_actionDampedTranslation_toggled([[maybe_unused]] bool value) {
#if MANUAL
cout << "DampedTranslation is ";
if (value)
@@ -1015,19 +1015,19 @@ void MainWindow::on_actionTeamYellow_triggered() {
update_cache(_game_settings.request_blue_team, false, &_game_settings_valid);
}

void MainWindow::on_manualID_currentIndexChanged(int value) {
void MainWindow::on_manualID_currentIndexChanged([[maybe_unused]] int value) {
#if MANUAL
context_->game_settings.joystick_config.manualID = value - 1;
#endif
}

void MainWindow::on_actionUse_Field_Oriented_Controls_toggled(bool value) {
void MainWindow::on_actionUse_Field_Oriented_Controls_toggled([[maybe_unused]] bool value) {
#if MANUAL
context_->game_settings.joystick_config.useFieldOrientedDrive = value;
#endif
}

void MainWindow::on_actionUse_Multiple_Joysticks_toggled(bool value) {
void MainWindow::on_actionUse_Multiple_Joysticks_toggled([[maybe_unused]] bool value) {
// TODO(Kyle): Reimplement multiple manual
}

6 changes: 3 additions & 3 deletions soccer/testing/rj_vision_filter/kalman_robot_test.cpp
Original file line number Diff line number Diff line change
@@ -20,7 +20,7 @@ TEST(KalmanRobot, invalid_world_robot) {

rj_geometry::Point rp = kb.get_pos();
rj_geometry::Point rv = kb.get_vel();
double th = kb.get_theta();
[[maybe_unused]] double th = kb.get_theta();
double om = kb.get_omega();

EXPECT_EQ(rp.x(), pose.position().x());
@@ -95,9 +95,9 @@ TEST(KalmanRobot, predict) {
kb.predict(t);

rj_geometry::Point rp2 = kb.get_pos();
rj_geometry::Point rv2 = kb.get_vel();
[[maybe_unused]] rj_geometry::Point rv2 = kb.get_vel();
double th2 = kb.get_theta();
double om2 = kb.get_omega();
[[maybe_unused]] double om2 = kb.get_omega();

EXPECT_NEAR(rp2.x(), rp.x() + rv.y() * 0.01, 0.01);
EXPECT_NEAR(rp2.y(), rp.y() + rv.y() * 0.01, 0.01);