Skip to content

Commit

Permalink
Fix Code Style On fix-pivot-kick (#2250)
Browse files Browse the repository at this point in the history
automated style fixes

Co-authored-by: sanatd33 <sanatd33@users.noreply.github.com>
  • Loading branch information
github-actions[bot] and sanatd33 committed Apr 17, 2024
1 parent 6336e21 commit 596a5d4
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,8 @@ LinePivotPathPlanner::State LinePivotPathPlanner::next_state(const PlanRequest&
double vel = plan_request.world_state->get_robot(true, static_cast<int>(plan_request.shell_id))
.velocity.linear()
.mag();
if (current_state_ == LINE && (target_point.dist_to(current_point) < 0.3) && (vel < 0.3) && (!plan_request.play_state.is_stop())) {
if (current_state_ == LINE && (target_point.dist_to(current_point) < 0.3) && (vel < 0.3) &&
(!plan_request.play_state.is_stop())) {
return PIVOT;
}
if (current_state_ == PIVOT && (pivot_point.dist_to(current_point) > (dist_from_point * 5))) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,8 @@
#include "strategy/agent/position/offense.hpp"
#include "strategy/agent/position/penalty_player.hpp"
#include "strategy/agent/position/pivot_test.hpp"
#include "strategy/agent/position/solo_offense.hpp"
#include "strategy/agent/position/position.hpp"
#include "strategy/agent/position/solo_offense.hpp"

namespace strategy {

Expand Down
17 changes: 9 additions & 8 deletions soccer/src/soccer/strategy/agent/position/solo_offense.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,12 +60,15 @@ SoloOffense::State SoloOffense::next_state() {
}

std::optional<RobotIntent> SoloOffense::state_to_task(RobotIntent intent) {

switch (current_state_) {
case MARKER: {
auto marker_target_pos = last_world_state_->get_robot(false, marking_id_).pose.position();
auto target = marker_target_pos + (field_dimensions_.our_goal_loc() - marker_target_pos).normalized(kRobotRadius * 5);
auto mark_cmd = planning::MotionCommand{"path_target", planning::LinearMotionInstant{target}, planning::FaceBall{}, true};
auto marker_target_pos =
last_world_state_->get_robot(false, marking_id_).pose.position();
auto target =
marker_target_pos +
(field_dimensions_.our_goal_loc() - marker_target_pos).normalized(kRobotRadius * 5);
auto mark_cmd = planning::MotionCommand{
"path_target", planning::LinearMotionInstant{target}, planning::FaceBall{}, true};
intent.motion_command = mark_cmd;

return intent;
Expand Down Expand Up @@ -93,9 +96,6 @@ std::optional<RobotIntent> SoloOffense::state_to_task(RobotIntent intent) {
return intent;
}




rj_geometry::Point SoloOffense::calculate_best_shot() const {
// Goal location
rj_geometry::Point their_goal_pos = field_dimensions_.their_goal_loc();
Expand All @@ -120,7 +120,8 @@ rj_geometry::Point SoloOffense::calculate_best_shot() const {
return best_shot;
}

double SoloOffense::distance_from_their_robots(rj_geometry::Point tail, rj_geometry::Point head) const {
double SoloOffense::distance_from_their_robots(rj_geometry::Point tail,
rj_geometry::Point head) const {
rj_geometry::Point vec = head - tail;
auto& their_robots = this->last_world_state_->their_robots;

Expand Down

0 comments on commit 596a5d4

Please sign in to comment.