Skip to content

Commit

Permalink
cleaning up code from previous commit
Browse files Browse the repository at this point in the history
  • Loading branch information
jvogt23 committed Jan 29, 2024
1 parent 7629be6 commit 1e8cacf
Show file tree
Hide file tree
Showing 5 changed files with 25 additions and 13 deletions.
15 changes: 7 additions & 8 deletions soccer/src/soccer/strategy/agent/position/defense.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,6 @@ Defense::Defense(int r_id) :
marker_{static_cast<uint8_t>(r_id)}
{
position_name_ = "Defense";
// if (robot_id_ == 2) {
// current_state_ = ENTERING_MARKING;
// }
}

std::optional<RobotIntent> Defense::derived_get_task(RobotIntent intent) {
Expand Down Expand Up @@ -42,10 +39,11 @@ Defense::State Defense::update_state() {
walling_robots_ = {(u_int8_t)robot_id_};
break;
case WALLING:
//Should remove the robot with the highest ID from a wall
//If a wall is already full,
//Remove the robot with the highest ID from a wall
//and make them a marker instead.
if (this->robot_id_ == *max_element(walling_robots_.begin(), walling_robots_.end())
&& walling_robots_.size() > 3) {
&& walling_robots_.size() > MAX_WALLERS) {
send_leave_wall_request();
next_state = ENTERING_MARKING;
}
Expand Down Expand Up @@ -143,9 +141,6 @@ std::optional<RobotIntent> Defense::state_to_task(RobotIntent intent) {
Waller waller{waller_id_, (int)walling_robots_.size()};
return waller.get_task(intent, last_world_state_, this->field_dimensions_);
}
} else if (current_state_ == MARKING) {
//Marker marker = Marker((u_int8_t) robot_id_);
return marker_.get_task(intent, last_world_state_, this->field_dimensions_);
} else if (current_state_ == FACING) {
rj_geometry::Point robot_position =
last_world_state_->get_robot(true, robot_id_).pose.position();
Expand All @@ -157,9 +152,13 @@ std::optional<RobotIntent> Defense::state_to_task(RobotIntent intent) {
intent.motion_command = face_ball_cmd;
return intent;
} else if (current_state_ == ENTERING_MARKING) {
//Prepares a robot for marking. NOTE: May update to add move to center of field
auto empty_motion_cmd = planning::MotionCommand{};
intent.motion_command = empty_motion_cmd;
return intent;
} else if (current_state_ == MARKING) {
//Marker marker = Marker((u_int8_t) robot_id_);
return marker_.get_task(intent, last_world_state_, this->field_dimensions_);
}

return std::nullopt;
Expand Down
6 changes: 4 additions & 2 deletions soccer/src/soccer/strategy/agent/position/defense.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,8 @@ class Defense : public Position {
private:
int move_ct_ = 0;

static constexpr int MAX_WALLERS {3};

Check warning on line 46 in soccer/src/soccer/strategy/agent/position/defense.hpp

View workflow job for this annotation

GitHub Actions / build-and-test

invalid case style for constexpr variable 'MAX_WALLERS'

/**
* @brief The derived_get_task method returns the task for the defensive robot
* to do based on the game situation. The method will continuously look to assign
Expand All @@ -62,8 +64,8 @@ class Defense : public Position {
RECEIVING, // physically intercepting the ball from a pass
PASSING, // physically kicking the ball towards another robot
FACING, // turning to face the passing robot
MARKING,
ENTERING_MARKING,
MARKING, // Following closely to an offense robot
ENTERING_MARKING, // Choosing/waiting for a robot to mark
};


Expand Down
4 changes: 4 additions & 0 deletions soccer/src/soccer/strategy/agent/position/marker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,10 @@ std::optional<RobotIntent> Marker::get_task(RobotIntent intent,

int Marker::choose_target(WorldState* ws) {

//TODO: (James Vogt, github: jvogt23)
//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 < 11; i++) {
if (std::fabs(ws->get_robot(false, i).pose.position().x()) < 2.5
&& ws->get_robot(false, i).pose.position().y() < Y_BOUND
Expand Down
8 changes: 6 additions & 2 deletions soccer/src/soccer/strategy/agent/position/marker.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,12 +11,16 @@


namespace strategy {

/**
* Represents a Marker, a defensive role that targets an enemy robot
* and follows it around the field while it is on our side, blocking passes.
*/
class Marker : public RoleInterface {

Check warning on line 19 in soccer/src/soccer/strategy/agent/position/marker.hpp

View workflow job for this annotation

GitHub Actions / build-and-test

class 'Marker' defines a default destructor but does not define a copy constructor, a copy assignment operator, a move constructor or a move assignment operator
private:
const double factor = 0.5;
int target {-1};

Check warning on line 21 in soccer/src/soccer/strategy/agent/position/marker.hpp

View workflow job for this annotation

GitHub Actions / build-and-test

invalid case style for private member 'target'

const double Y_BOUND {4.5};
static constexpr double Y_BOUND {4.5};

Check warning on line 23 in soccer/src/soccer/strategy/agent/position/marker.hpp

View workflow job for this annotation

GitHub Actions / build-and-test

invalid case style for constexpr variable 'Y_BOUND'

public:
Marker(u_int8_t robot_id);
Expand Down
5 changes: 4 additions & 1 deletion soccer/src/soccer/strategy/agent/position/offense.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,10 @@ Offense::State Offense::update_state() {
}

std::optional<RobotIntent> Offense::state_to_task(RobotIntent intent) {
SPDLOG_INFO(current_state_);
//This was added to our code when we merged from ros2.
//Please let us know whether this log is needed when
//reviewing.
//SPDLOG_INFO(current_state_);

if (current_state_ == IDLING) {
// Do nothing
Expand Down

0 comments on commit 1e8cacf

Please sign in to comment.