Skip to content

Commit

Permalink
Merge Settle into Collect (#2320)
Browse files Browse the repository at this point in the history
* good colelct

* Fix Code Style On settle-collect (#2321)

automated style fixes

Co-authored-by: sanatd33 <[email protected]>

* settle nonesense

* Fix Code Style On settle-collect (#2324)

automated style fixes

Co-authored-by: sid-parikh <[email protected]>

* removed unnessesary change

* started changes

* Fix Code Style On settle-collect (#2339)

* pr updates

* completed settle into colelct merge

* removed angle planning NaN

* Fix Code Style On settle-collect (#2347)

automated style fixes

Co-authored-by: sid-parikh <[email protected]>

* fix naming

---------

Co-authored-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com>
Co-authored-by: sanatd33 <[email protected]>
Co-authored-by: sid-parikh <[email protected]>
  • Loading branch information
4 people authored Feb 19, 2025
1 parent fc3ba75 commit 298910d
Show file tree
Hide file tree
Showing 7 changed files with 474 additions and 205 deletions.
584 changes: 408 additions & 176 deletions soccer/src/soccer/planning/planner/collect_path_planner.cpp

Large diffs are not rendered by default.

57 changes: 39 additions & 18 deletions soccer/src/soccer/planning/planner/collect_path_planner.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,13 @@ class CollectPathPlanner : public PathPlanner {
enum CollectPathPathPlannerStates {
// From start of subbehavior to the start of the slow part of the
// approach
CoarseApproach,
COARSE_APPROACH,
// Intercepts a moving ball
INTERCEPT,
// Slows down the velocity of an intercepted ball
DAMPEN,
// From the slow part of the approach to the touching of the ball
FineApproach,
// From touching the ball to stopped with the ball in the mouth
Control
FINE_APPROACH,
};

CollectPathPlanner()
Expand All @@ -39,47 +41,66 @@ class CollectPathPlanner : public PathPlanner {
// and won't intercept ball correctly anymore
void check_solution_validity(BallState ball, RobotInstant start);

void process_state_transition(BallState ball, RobotInstant start_instant);
void process_state_transition(const PlanRequest& request, BallState ball,
RobotInstant* start_instant);

Trajectory coarse_approach(
const PlanRequest& plan_request, RobotInstant start,
const rj_geometry::ShapeSet& static_obstacles,
const std::vector<DynamicObstacle>& dynamic_obstacles);

Trajectory intercept(const PlanRequest& plan_request, RobotInstant start_instant,
const rj_geometry::ShapeSet& static_obstacles,
const std::vector<DynamicObstacle>& dynamic_obstacles);

// Dampen doesn't need to take obstacles into account.
Trajectory dampen(const PlanRequest& plan_request, RobotInstant start_instant,
const rj_geometry::ShapeSet& static_obstacles,
const std::vector<DynamicObstacle>& dynamic_obstacles);

Trajectory fine_approach(
const PlanRequest& plan_request, RobotInstant start_instant,
const rj_geometry::ShapeSet& static_obstacles,
const std::vector<DynamicObstacle>& dynamic_obstacles);

Trajectory control(const PlanRequest& plan_request, RobotInstant start,
const Trajectory& partial_path,
const rj_geometry::ShapeSet& static_obstacles,
const std::vector<DynamicObstacle>& dynamic_obstacles);

Trajectory invalid(const PlanRequest& plan_request,
const rj_geometry::ShapeSet& static_obstacles,
const std::vector<DynamicObstacle>& dynamic_obstacles);

Trajectory previous_;

CollectPathPathPlannerStates current_state_ = CollectPathPathPlannerStates::CoarseApproach;
CollectPathPathPlannerStates current_state_ = CollectPathPathPlannerStates::COARSE_APPROACH;

// Ball Velocity Filtering Variables
rj_geometry::Point average_ball_vel_;
bool average_ball_vel_initialized_ = false;

rj_geometry::Point approach_direction_;
bool approach_direction_created_ = false;

bool control_path_created_ = false;

rj_geometry::Point path_coarse_target_;
bool path_coarse_target_initialized_ = false;

// is_done vars
std::optional<LinearMotionInstant> cached_start_instant_;
std::optional<rj_geometry::Point> cached_robot_pos_;
std::optional<rj_geometry::Point> cached_ball_pos_;
// Intercept Target Filtering Variables
rj_geometry::Point avg_instantaneous_intercept_target_;
bool first_intercept_target_found_ = false;

// Only change the target of the path if it changes significantly
rj_geometry::Point path_intercept_target_;

// Have we already made a dampen path
bool path_created_for_dampen_ = false;

// Do we have the ball in the robot
bool is_ball_sense_ = false;

// Threshold for switching from dampen to fine approach
static constexpr double kDampenBallSpeedThreshold{0.75};

// Threshold for ball velocity to try to intercept;
static constexpr double kInterceptVelocityThreshold{0.2};

// Threshold for chasing after the ball instead of intercepting (deg)
static constexpr double kChaseAngleThreshold{45};
};

} // namespace planning
21 changes: 18 additions & 3 deletions soccer/src/soccer/planning/planner/settle_path_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ using namespace rj_geometry;

namespace planning {

// Do not use anymore, use collect
Trajectory SettlePathPlanner::plan(const PlanRequest& plan_request) {
const auto state = plan_request.play_state.state();
if (state == PlayState::Stop || state == PlayState::Halt) {
Expand Down Expand Up @@ -90,7 +91,8 @@ Trajectory SettlePathPlanner::plan(const PlanRequest& plan_request) {
delta_pos, face_pos);
break;
case SettlePathPlannerStates::Dampen:
result = dampen(plan_request, start_instant, delta_pos, face_pos);
result = dampen(plan_request, start_instant, static_obstacles, dynamic_obstacles,
delta_pos, face_pos);
break;
default:
result = invalid(plan_request, static_obstacles, dynamic_obstacles);
Expand Down Expand Up @@ -387,6 +389,8 @@ Trajectory SettlePathPlanner::intercept(const PlanRequest& plan_request, RobotIn
}

Trajectory SettlePathPlanner::dampen(const PlanRequest& plan_request, RobotInstant start_instant,
const rj_geometry::ShapeSet& static_obstacles,
const std::vector<DynamicObstacle>& dynamic_obstacles,
rj_geometry::Point delta_pos, rj_geometry::Point face_pos) {
// Only run once if we can

Expand Down Expand Up @@ -467,8 +471,19 @@ Trajectory SettlePathPlanner::dampen(const PlanRequest& plan_request, RobotInsta
// Target stopping point with 0 speed.
LinearMotionInstant final_stopping_motion{final_stopping_point};

Trajectory dampen_end = CreatePath::simple(start_instant.linear_motion(), final_stopping_motion,
plan_request.constraints.mot, start_instant.stamp);
Trajectory dampen_end;

if (previous_.empty()) {
dampen_end = CreatePath::intermediate(start_instant.linear_motion(), final_stopping_motion,
plan_request.constraints.mot, start_instant.stamp,
static_obstacles, dynamic_obstacles,
plan_request.field_dimensions, plan_request.shell_id);
} else {
dampen_end = CreatePath::intermediate(
previous_.last().linear_motion(), final_stopping_motion, plan_request.constraints.mot,
previous_.last().stamp, static_obstacles, dynamic_obstacles,
plan_request.field_dimensions, plan_request.shell_id);
}

dampen_end.set_debug_text("Damping");

Expand Down
2 changes: 2 additions & 0 deletions soccer/src/soccer/planning/planner/settle_path_planner.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,8 @@ class SettlePathPlanner : public PathPlanner {

// Dampen doesn't need to take obstacles into account.
Trajectory dampen(const PlanRequest& plan_request, RobotInstant start_instant,
const rj_geometry::ShapeSet& static_obstacles,
const std::vector<DynamicObstacle>& dynamic_obstacles,
rj_geometry::Point delta_pos, rj_geometry::Point face_pos);

Trajectory invalid(const PlanRequest& plan_request,
Expand Down
4 changes: 2 additions & 2 deletions soccer/src/soccer/planning/primitives/create_path.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,8 +125,8 @@ Trajectory intermediate(const LinearMotionInstant& start, const LinearMotionInst
// If the trajectory does not hit an obstacle, it is valid
if ((!trajectory_hits_static(trajectory, static_obstacles, start_time, nullptr))) {
auto angle = (final_inter - start.position).angle();
cached_intermediate_tuple_[robot_id] = {
abs(angle), (final_inter - start.position).mag(), signbit(angle) ? -1 : 1};
cached_intermediate_tuple_[robot_id] = {abs(angle), signbit(angle) ? -1 : 1,
(final_inter - start.position).mag()};
return trajectory;
}
}
Expand Down
8 changes: 4 additions & 4 deletions soccer/src/soccer/planning/trajectory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,12 +23,12 @@ Trajectory::Trajectory(Trajectory a, const Trajectory& b) {

using rj_geometry::Point;
if (!a_end.position().near_point(b_begin.position(), 1e-6) ||
!a_end.linear_velocity().near_point(b_begin.linear_velocity(), 1e-6) ||
!a_end.linear_velocity().near_point(b_begin.linear_velocity(), 1e-1) ||
a_end.stamp != b_begin.stamp) {
SPDLOG_ERROR("points near? {}, vels near? {}, timestamps match? {}",
!a_end.position().near_point(b_begin.position(), 1e-6),
!a_end.linear_velocity().near_point(b_begin.linear_velocity(), 1e-6),
a_end.stamp != b_begin.stamp);
a_end.position().near_point(b_begin.position(), 1e-6),
a_end.linear_velocity().near_point(b_begin.linear_velocity(), 1e-1),
a_end.stamp == b_begin.stamp);
throw std::invalid_argument(
"Cannot splice trajectories a and b, where a.last() != b.first()");
}
Expand Down
3 changes: 1 addition & 2 deletions soccer/src/soccer/strategy/agent/position/solo_offense.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,8 +99,7 @@ std::optional<RobotIntent> SoloOffense::state_to_task(RobotIntent intent) {
robotToBall = robotToBall.normalized(length);
planning::LinearMotionInstant target{
last_world_state_->get_robot(true, robot_id_).pose.position() + robotToBall};
auto pivot_cmd =
planning::MotionCommand{"path_target", target, planning::FaceTarget{}, true};
auto pivot_cmd = planning::MotionCommand{"collect"};
intent.motion_command = pivot_cmd;
intent.dribbler_speed = 255;
return intent;
Expand Down

0 comments on commit 298910d

Please sign in to comment.