Skip to content

Commit

Permalink
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Fixed warning messages
Browse files Browse the repository at this point in the history
sanatd33 committed Jan 29, 2024
1 parent 580b39d commit 41df6ad
Showing 5 changed files with 30 additions and 26 deletions.
2 changes: 1 addition & 1 deletion soccer/src/soccer/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -81,7 +81,7 @@ set(ROBOCUP_LIB_SRC
strategy/agent/position/offense.cpp
strategy/agent/position/defense.cpp
strategy/agent/position/waller.cpp
strategy/agent/position/seeking.cpp
strategy/agent/position/seeker.cpp
strategy/agent/position/goal_kicker.cpp
strategy/agent/position/penalty_player.cpp
)
2 changes: 1 addition & 1 deletion soccer/src/soccer/strategy/agent/position/offense.cpp
Original file line number Diff line number Diff line change
@@ -191,7 +191,7 @@ std::optional<RobotIntent> Offense::state_to_task(RobotIntent intent) {
// Only get a new target position if we have reached our target
if (check_is_done() ||
last_world_state_->get_robot(true, robot_id_).velocity.linear().mag() <= 0.01) {
Seeking seeker{robot_id_};
Seeker seeker{robot_id_};
return seeker.get_task(intent, last_world_state_, this->field_dimensions_);
}
}
2 changes: 1 addition & 1 deletion soccer/src/soccer/strategy/agent/position/offense.hpp
Original file line number Diff line number Diff line change
@@ -14,7 +14,7 @@
#include "rj_common/time.hpp"
#include "rj_geometry/geometry_conversions.hpp"
#include "rj_geometry/point.hpp"
#include "seeking.hpp"
#include "seeker.hpp"

namespace strategy {

Original file line number Diff line number Diff line change
@@ -1,38 +1,38 @@
#include "seeking.hpp"
#include "seeker.hpp"

namespace strategy {

Seeking::Seeking(int robot_id) { robot_id_ = robot_id; }
Seeker::Seeker(int robot_id) { robot_id_ = robot_id; }

std::optional<RobotIntent> Seeking::get_task(RobotIntent intent, const WorldState* last_world_state,
std::optional<RobotIntent> Seeker::get_task(RobotIntent intent, const WorldState* last_world_state,
FieldDimensions field_dimensions) {
// Determine target position for seeking
rj_geometry::Point current_loc = last_world_state->get_robot(true, robot_id_).pose.position();

target_pt = get_open_point(last_world_state, current_loc, field_dimensions);
target_pt_ = get_open_point(last_world_state, current_loc, field_dimensions);

planning::PathTargetFaceOption face_option = planning::FaceBall{};
bool ignore_ball = false;
planning::LinearMotionInstant goal{target_pt, rj_geometry::Point{0.0, 0.0}};
planning::LinearMotionInstant goal{target_pt_, rj_geometry::Point{0.0, 0.0}};
intent.motion_command = planning::MotionCommand{"path_target", goal, face_option, ignore_ball};

return intent;
}

rj_geometry::Point Seeking::get_open_point(const WorldState* world_state,
rj_geometry::Point Seeker::get_open_point(const WorldState* world_state,
rj_geometry::Point current_loc,
FieldDimensions field_dimensions) {
return Seeking::calculate_open_point(3.0, .2, current_loc, world_state, field_dimensions);
const FieldDimensions& field_dimensions) const {
return Seeker::calculate_open_point(3.0, .2, current_loc, world_state, field_dimensions);
}

rj_geometry::Point Seeking::calculate_open_point(double current_prec, double min_prec,
rj_geometry::Point Seeker::calculate_open_point(double current_prec, double min_prec,
rj_geometry::Point current_point,
const WorldState* world_state,
FieldDimensions field_dimensions) {
const FieldDimensions& field_dimensions) const {
while (current_prec > min_prec) {
rj_geometry::Point ball_pos = world_state->ball.position;
rj_geometry::Point min = current_point;
double min_val = eval_point(ball_pos, current_point, world_state);
double min_val = Seeker::eval_point(ball_pos, current_point, world_state);
double curr_val{};
// Points in a current_prec radius of the current point, at 45 degree intervals
std::vector<rj_geometry::Point> check_points{
@@ -55,7 +55,7 @@ rj_geometry::Point Seeking::calculate_open_point(double current_prec, double min

// Finds the best point out of the ones checked
for (auto point : check_points) {
curr_val = eval_point(ball_pos, point, world_state);
curr_val = Seeker::eval_point(ball_pos, point, world_state);
if (curr_val < min_val) {
min_val = curr_val;
min = point;
@@ -67,7 +67,7 @@ rj_geometry::Point Seeking::calculate_open_point(double current_prec, double min
return current_point;
}

rj_geometry::Point Seeking::correct_point(rj_geometry::Point p, FieldDimensions field_dimensions) {
rj_geometry::Point Seeker::correct_point(rj_geometry::Point p, const FieldDimensions& field_dimensions) const {
double BORDER_BUFFER = .2;
double x = p.x();
double y = p.y();
@@ -128,7 +128,7 @@ rj_geometry::Point Seeking::correct_point(rj_geometry::Point p, FieldDimensions
return rj_geometry::Point(x, y);
}

double Seeking::eval_point(rj_geometry::Point ball_pos, rj_geometry::Point current_point,
double Seeker::eval_point(rj_geometry::Point ball_pos, rj_geometry::Point current_point,
const WorldState* world_state) {
// Determines 'how good' a point is
// A higher value is a worse point
Original file line number Diff line number Diff line change
@@ -20,13 +20,17 @@
namespace strategy {

/*
* The Seeking role provides the implementation for a offensive robot that
* The Seeker role provides the implementation for a offensive robot that
* is trying to get open, so that they can receive a pass
*/
class Seeking : public RoleInterface {
class Seeker : public RoleInterface {
public:
Seeking(int robot_id);
~Seeking() = default;
Seeker(int robot_id);
~Seeker() = default;
Seeker(const Seeker& other) = default;
Seeker(Seeker&& other) = default;
Seeker& operator=(const Seeker& other) = default;
Seeker& operator=(Seeker&& other) = default;

/**
* @brief Returns a seeker behavior which aims to get open
@@ -44,7 +48,7 @@ class Seeking : public RoleInterface {
// The seeker's id
int robot_id_;
// The taret point to move to
rj_geometry::Point target_pt{0.0, 0.0};
rj_geometry::Point target_pt_{0.0, 0.0};

/**
* @brief Returns the point which is most 'open'
@@ -57,7 +61,7 @@ class Seeking : public RoleInterface {
*/
rj_geometry::Point get_open_point(const WorldState* world_state,
rj_geometry::Point current_position,
FieldDimensions field_dimensions);
const FieldDimensions& field_dimensions) const;

/**
* @brief Calculates which point is the best by iteratively searching around the robot
@@ -73,7 +77,7 @@ class Seeking : public RoleInterface {
rj_geometry::Point calculate_open_point(double current_prec, double min_prec,
rj_geometry::Point current_point,
const WorldState* world_state,
FieldDimensions field_dimensions);
const FieldDimensions& field_dimensions) const;

/**
* @brief Corrects the point to be within the field
@@ -83,7 +87,7 @@ class Seeking : public RoleInterface {
*
* @return rj_geometry::Point The corrected point
*/
rj_geometry::Point correct_point(rj_geometry::Point point, FieldDimensions field_dimensions);
rj_geometry::Point correct_point(rj_geometry::Point point, const FieldDimensions& field_dimensions) const;

/**
* @brief Calculates how 'good' a target point is
@@ -94,7 +98,7 @@ class Seeking : public RoleInterface {
*
* @return double The evaluation of that target point
*/
double eval_point(rj_geometry::Point ball_pos, rj_geometry::Point current_point,
static double eval_point(rj_geometry::Point ball_pos, rj_geometry::Point current_point,
const WorldState* world_state);
};

0 comments on commit 41df6ad

Please sign in to comment.