Skip to content

Commit

Permalink
automated style fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
jacksherling authored Feb 17, 2025
1 parent 83debe9 commit 27bca3b
Show file tree
Hide file tree
Showing 6 changed files with 38 additions and 39 deletions.
64 changes: 36 additions & 28 deletions soccer/src/soccer/strategy/agent/position/defense.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,15 +36,17 @@ Defense::State Defense::update_state() {
}

switch (current_state_) {
case IDLING:{
break;}
case JOINING_WALL:{
case IDLING: {
break;
}
case JOINING_WALL: {
send_join_wall_request();
// SPDLOG_INFO("join wall {}", robot_id_);
next_state = WALLING;
walling_robots_ = {(u_int8_t)robot_id_};
break;}
case WALLING:{
break;
}
case WALLING: {
// If a wall is already full,
// Remove the robot with the highest ID from a wall
// and make them a marker instead.
Expand All @@ -54,46 +56,53 @@ Defense::State Defense::update_state() {
// SPDLOG_INFO("leave wall {}", robot_id_);
next_state = ENTERING_MARKING;
}
//wall stealing
if(can_steal_ball()) {
// wall stealing
if (can_steal_ball()) {
send_leave_wall_request();
next_state = STEALING;
}
break;}
case SEARCHING:{
break;}
case RECEIVING:{
break;
}
case SEARCHING: {
break;
}
case RECEIVING: {
// transition to idling if we are close enough to the ball
if (distance_to_ball < ball_receive_distance_) {
next_state = IDLING;
}
break;}
case PASSING:{
break;
}
case PASSING: {
// transition to idling if we no longer have the ball (i.e. it was passed or it was
// stolen)
if (check_is_done() || distance_to_ball > ball_lost_distance_) {
next_state = JOINING_WALL;
}
break;}
case FACING:{
break;
}
case FACING: {
if (check_is_done()) {
next_state = IDLING;
}}
case MARKING:{
}
}
case MARKING: {
if (marker_.get_target() == -1 || marker_.target_out_of_bounds(world_state)) {
next_state = ENTERING_MARKING;
}
break;}
case ENTERING_MARKING:{
break;
}
case ENTERING_MARKING: {
marker_.choose_target(world_state);
int target_id = marker_.get_target();
if (target_id == -1) {
next_state = ENTERING_MARKING;
} else {
next_state = MARKING;
}
break;}
case STEALING: // wall steal
break;
}
case STEALING: // wall steal
{
// Go to passing if successful
if (check_is_done()) {
Expand All @@ -108,12 +117,11 @@ Defense::State Defense::update_state() {
/*if (timed_out()) {
// If we timed out and the ball is close, assume we have it
// (because is_done for settle/collect are not great)
next_state = IDLING;
next_state = IDLING;
}*/
}
case CLEARING:
{
if(check_is_done()) {
case CLEARING: {
if (check_is_done()) {
next_state = JOINING_WALL;
}
}
Expand Down Expand Up @@ -171,7 +179,7 @@ std::optional<RobotIntent> Defense::state_to_task(RobotIntent intent) {
if (!walling_robots_.empty() && waller_id_ != -1) {
Waller waller{waller_id_, walling_robots_};
return waller.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 @@ -190,12 +198,12 @@ std::optional<RobotIntent> Defense::state_to_task(RobotIntent 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_);
} else if(current_state_ == STEALING) { //wall stealer
} else if (current_state_ == STEALING) { // wall stealer
auto collect_cmd = planning::MotionCommand{"collect"};
intent.motion_command = collect_cmd;
intent.dribbler_speed = 255.0;
return intent;
} else if(current_state_ == CLEARING) {
} else if (current_state_ == CLEARING) {
planning::LinearMotionInstant target{clear_point_};
auto line_kick_cmd = planning::MotionCommand{"line_kick", target};
intent.motion_command = line_kick_cmd;
Expand Down
5 changes: 1 addition & 4 deletions soccer/src/soccer/strategy/agent/position/defense.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,9 +44,8 @@ class Defense : public Position {
void revive() override;

private:

const rj_geometry::Point clear_point_{0.0, 4.5};

// static constexpr int kMaxWallers{6};
static constexpr int kMaxWallers{
static_cast<int>(kNumShells)}; // This effectively turns off marking
Expand Down Expand Up @@ -85,8 +84,6 @@ class Defense : public Position {
*/
void send_join_wall_request();



/**
* @brief Sends a LeaveWallRequest to each of the robots in walling_robots_.
*/
Expand Down
1 change: 0 additions & 1 deletion soccer/src/soccer/strategy/agent/position/offense.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -268,7 +268,6 @@ std::optional<RobotIntent> Offense::state_to_task(RobotIntent intent) {
auto collect_cmd = planning::MotionCommand{"collect"};
intent.motion_command = collect_cmd;
intent.dribbler_speed = 255.0;


return intent;
}
Expand Down
1 change: 0 additions & 1 deletion soccer/src/soccer/strategy/agent/position/offense.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -243,5 +243,4 @@ class Offense : public Position {
std::unordered_map<int, rj_geometry::Point> seeker_points_;
};


} // namespace strategy
4 changes: 1 addition & 3 deletions soccer/src/soccer/strategy/agent/position/position.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -295,7 +295,7 @@ class Position {
// set to true when the ball gets close to this robot
bool chasing_ball = false;

/**
/**
* @return whether the ball is in an area that non-goalies cannot reach.
*/
bool ball_in_red() const;
Expand All @@ -318,8 +318,6 @@ class Position {
// Current goalie
int goalie_id_;



private:
/**
* @brief allow derived classes to change behavior of get_task(). See
Expand Down
2 changes: 0 additions & 2 deletions soccer/src/soccer/strategy/agent/position/waller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,6 @@ std::optional<RobotIntent> Waller::get_task(RobotIntent intent, const WorldState
auto goal_pos = rj_geometry::Point{0, 0};
auto num_wallers = walling_robots_.size();



// Find ball_direction unit vector
rj_geometry::Point ball_dir_vector{(ball_pos - goal_pos)};

Expand Down

0 comments on commit 27bca3b

Please sign in to comment.