Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Dev/rc24 tmp #143

Merged
merged 28 commits into from
Jul 24, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
28 commits
Select commit Hold shift + click to select a range
630c5e5
Mark distance is now a config.
lordhippo Jul 19, 2024
3c20591
Increase marker distance during their kickoff.
lordhippo Jul 19, 2024
4329786
Remove opp defence area obstacle during all ball placements.
lordhippo Jul 19, 2024
bb44118
Fix opp penalty area size during stop and freekicks.
lordhippo Jul 19, 2024
bf6f45f
Move velocity profiles to config.
lordhippo Jul 19, 2024
77c7c36
Merge branch 'main' into dev/rc24-tmp
lordhippo Jul 19, 2024
9040f9e
Enable assignment during our placement.
lordhippo Jul 19, 2024
406a812
Don't halt roles with no point in strategy.
lordhippo Jul 19, 2024
fe20e2f
Use zones in chip shoot.
lordhippo Jul 19, 2024
3f18879
Use mm/s for shoot speeds.
lordhippo Jul 19, 2024
4c1cc82
Use 1 more command to predict our robots.
lordhippo Jul 19, 2024
73e0964
Improve attacker and add intercept.
lordhippo Jul 19, 2024
a2e61b1
Improve rrt waypoint cache.
lordhippo Jul 20, 2024
3d163fc
Increase robot radius based on relative speeds.
lordhippo Jul 20, 2024
8697b15
Merge branch 'main' into dev/rc24-tmp
lordhippo Jul 20, 2024
6c24f48
Made continuous elendil a define.
lordhippo Jul 20, 2024
a736274
Rejects static poses if they block opp goal.
lordhippo Jul 20, 2024
9e333ee
Fix chip calibration result.
lordhippo Jul 20, 2024
62946e7
Increase kick speed during our ball placement.
lordhippo Jul 20, 2024
eecf51e
Disable switches during our ball placement.
lordhippo Jul 20, 2024
54e6a14
Add an obstacle for ball during our ball placement for all robots exc…
lordhippo Jul 20, 2024
bec2779
Don't extend our robots, and opps for attack.
lordhippo Jul 20, 2024
463c424
Reduce gk chip speed.
lordhippo Jul 20, 2024
049416a
Fix build issue.
lordhippo Jul 20, 2024
372e161
Strategies for robocin.
lordhippo Jul 20, 2024
709b124
Use precise motion when passing.
lordhippo Jul 20, 2024
a6ece1e
Robot 11 config.
lordhippo Jul 20, 2024
068cf5f
Final config changes.
lordhippo Jul 24, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
28 changes: 25 additions & 3 deletions data/config.toml
Original file line number Diff line number Diff line change
Expand Up @@ -40,17 +40,39 @@ ip = '127.0.0.1'
port = 10302

[soccer]
chip_tune_coef = 2.5
def_ball_distance_coef = 0.69999999999999996
def_max_extension_area = 1100.0
def_prediction_time = 0.5
def_tight_start_angle = 30.0
gk_tight_start_angle = 15.0
kick_tune_coef = 1.0
mark_distance = 250.0
mark_in_stop = true
one_touch_beta = 0.40000000000000002
one_touch_gamma = 0.14000000000000001
one_touch_shoot_k = 4000.0
kick_tune_coef = 1.0
chip_tune_coef = 2.5

[soccer.velocity_profile.aroom]
acceleration = 2160.0
deceleration = 2700.0
speed = 900.0

[soccer.velocity_profile.kharaki]
acceleration = 4010.0
deceleration = 4860.0
speed = 2200.0

[soccer.velocity_profile.mamooli]
acceleration = 3500.0
deceleration = 3850.0
speed = 1800.0

[soccer.velocity_profile.sooski]
acceleration = 1620.0
deceleration = 2700.0
speed = 450.0

[[soccer.robot_physical_status]]
has_chip_kick = true
has_direct_kick = true
Expand Down Expand Up @@ -130,7 +152,7 @@ chip_tune_coef = 2.5

[[soccer.robot_physical_status]]
has_chip_kick = false
has_direct_kick = true
has_direct_kick = false
has_dribbler = false
id = 11
is_3D_printed = true
Expand Down
Binary file modified data/strategy.ims
Binary file not shown.
2 changes: 1 addition & 1 deletion source/common
Submodule common updated 1 files
+70 −30 source/config/soccer.h
8 changes: 4 additions & 4 deletions source/sender/command.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#pragma once

namespace Tyr::Sender

Check failure on line 3 in source/sender/command.h

View workflow job for this annotation

GitHub Actions / check

source/sender/command.h:3:1 [clang-diagnostic-error]

unknown type name 'namespace'

Check failure on line 3 in source/sender/command.h

View workflow job for this annotation

GitHub Actions / check

source/sender/command.h:3:14 [clang-diagnostic-error]

expected ';' after top level declarator

Check failure on line 3 in source/sender/command.h

View workflow job for this annotation

GitHub Actions / check

source/sender/command.h:3:15 [clang-diagnostic-error]

expected identifier or '('
{
struct Command
{
Expand All @@ -12,13 +12,13 @@
Common::Angle current_angle;
Common::Angle target_angle;

int shoot = 0;
int chip = 0;
int dribbler = 0;
float shoot = 0;
float chip = 0;
float dribbler = 0;

Command() = default;

Command(const Protos::Immortals::Command &t_command)
explicit Command(const Protos::Immortals::Command &t_command)
{
vision_id = t_command.vision_id();

Expand Down
12 changes: 7 additions & 5 deletions source/sender/nrf.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,8 +50,6 @@
return 0;
}

t_raw_shoot = std::clamp(t_raw_shoot, 0.0f, 6500.f) / 1000.f;

float calib_shoot = t_coeffs.x * t_raw_shoot + t_coeffs.y;

calib_shoot = std::clamp(calib_shoot, 0.0f, 100.0f);
Expand All @@ -65,7 +63,7 @@

buff_idx = 0;
auto buffer = commUDP->getBuffer();
for (int i = 0; i < buffer.size(); i++)

Check warning on line 66 in source/sender/nrf.cpp

View workflow job for this annotation

GitHub Actions / build (macos, debug)

comparison of integers of different signs: 'int' and 'size_type' (aka 'unsigned long') [-Wsign-compare]

Check warning on line 66 in source/sender/nrf.cpp

View workflow job for this annotation

GitHub Actions / build (macos, release)

comparison of integers of different signs: 'int' and 'size_type' (aka 'unsigned long') [-Wsign-compare]

Check warning on line 66 in source/sender/nrf.cpp

View workflow job for this annotation

GitHub Actions / build (ubuntu, release)

comparison of integer expressions of different signedness: ‘int’ and ‘std::span<char>::size_type’ {aka ‘long unsigned int’} [-Wsign-compare]

Check warning on line 66 in source/sender/nrf.cpp

View workflow job for this annotation

GitHub Actions / build (ubuntu, debug)

comparison of integer expressions of different signedness: ‘int’ and ‘std::span<char>::size_type’ {aka ‘long unsigned int’} [-Wsign-compare]
{
buffer[i] = 0x00;
}
Expand Down Expand Up @@ -102,15 +100,19 @@
convert_float_to_2x_buff(data + 9, command.current_angle.deg());
if (command.shoot > 0)
{
const float raw_shoot = std::clamp(command.shoot, 0.0f, 6500.f) / 1000.f;
const float calibrated_shoot = getCalibratedShootPow(raw_shoot, shoot_coeffs[command.vision_id]);

data[11] = static_cast<unsigned char> (getCalibratedShootPow(Common::config().soccer.kick_tune_coef * command.shoot,
shoot_coeffs[command.vision_id]));
data[11] = static_cast<unsigned char>(calibrated_shoot);
data[12] = 0x00;
}
else if (command.chip > 0)
{
const float raw_chip = std::clamp(command.chip, 0.0f, 150.f);
const float calibrated_chip = getCalibratedShootPow(raw_chip, chip_coeffs[command.vision_id]);

data[11] = 0x00;
data[12] = getCalibratedShootPow(Common::config().soccer.chip_tune_coef * command.chip, chip_coeffs[command.vision_id]);
data[12] = static_cast<unsigned char>(calibrated_chip);
}
else
{
Expand Down
2 changes: 1 addition & 1 deletion source/soccer/ai.h
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#pragma once

Check notice on line 1 in source/soccer/ai.h

View workflow job for this annotation

GitHub Actions / check

Run clang-format on source/soccer/ai.h

File source/soccer/ai.h does not conform to Custom style guidelines. (lines 191)

#include "dss/dss.h"
#include "errt/errt.h"
Expand Down Expand Up @@ -188,7 +188,7 @@
void gkHi(int t_robot_num);
void runningDef(int t_robot_num, Common::Vec2 t_target, Common::Vec2 *t_defend_target);
void defenceWall(int t_robot_num, bool t_kick_off = false);
void attacker(int t_robot_num, Common::Angle t_angle, float t_kick, int t_chip, bool t_kiss, bool t_dribbler);
void attacker(int t_robot_num, Common::Angle t_angle, float t_kick, int t_chip, bool t_kiss, bool t_dribbler, bool precise = false);
void waitForPass(int t_robot_num, bool t_chip = false, const Common::Vec2 *t_target = nullptr,
Common::Vec2 *t_stat_pos = nullptr);
void waitForOmghi(int t_robot_num);
Expand Down
2 changes: 1 addition & 1 deletion source/soccer/assignment/cost_static.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ int Ai::staticRoleCost(const int t_robot_idx, const Assignment &t_assignment) co
if (t_assignment.needs_chip != physical_status.has_chip_kick)
caps_cost += 5000;

int switch_cost = t_robot_idx == *t_assignment.role ? 0 : 500;
int switch_cost = t_robot_idx == *t_assignment.role ? 0 : 200;

return dis_cost + caps_cost + switch_cost;
}
Expand Down
6 changes: 5 additions & 1 deletion source/soccer/assignment/create_mids.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,11 @@ void Ai::createMidAssignments()
const bool shoot = !m_is_defending;
const bool chip = !m_is_defending && role == &m_mid5;

createStaticAssignment(role, Assignment::Priority::Low, shoot, chip);
const bool important_dmf = role == &m_mid5 && (m_ref_state.ourBallPlacement() || m_ref_state.ourFreeKick());
const Assignment::Priority priority =
important_dmf ? Assignment::Priority::High : Assignment::Priority::Low;

createStaticAssignment(role, priority, shoot, chip);
}
}
}
Expand Down
16 changes: 8 additions & 8 deletions source/soccer/dss/dss.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include "dss.h"

Check notice on line 1 in source/soccer/dss/dss.cpp

View workflow job for this annotation

GitHub Actions / check

Run clang-format on source/soccer/dss/dss.cpp

File source/soccer/dss/dss.cpp does not conform to Custom style guidelines. (lines 30, 32, 56)

#include "../obstacle/map.h"
#include "trajectory.h"
Expand Down Expand Up @@ -27,9 +27,9 @@
const Common::RobotState &state_b, const Common::Vec2 &cmd_b) const
{
const Trajectory traj_a =
Trajectory::MakeTrajectory(state_a, cmd_a, m_profile.max_dec, 1.0f / Common::config().vision.vision_frame_rate);
Trajectory::MakeTrajectory(state_a, cmd_a, m_profile.deceleration, 1.0f / Common::config().vision.vision_frame_rate);
const Trajectory traj_b =
Trajectory::MakeTrajectory(state_b, cmd_b, m_profile.max_dec, 1.0f / Common::config().vision.vision_frame_rate);
Trajectory::MakeTrajectory(state_b, cmd_b, m_profile.deceleration, 1.0f / Common::config().vision.vision_frame_rate);

return Parabolic::HaveOverlap(traj_a.acc, traj_b.acc, Common::field().robot_radius * 2.f) ||
Parabolic::HaveOverlap(traj_a.dec, traj_b.dec, Common::field().robot_radius * 2.f) ||
Expand All @@ -40,9 +40,9 @@
bool Dss::collisionWithOpp(const Common::RobotState &state_own, const Common::Vec2 &cmd_own,
const Common::RobotState &state_opp) const
{
const Trajectory traj_own = Trajectory::MakeTrajectory(state_own, cmd_own, m_profile.max_dec,
const Trajectory traj_own = Trajectory::MakeTrajectory(state_own, cmd_own, m_profile.deceleration,
1.0f / Common::config().vision.vision_frame_rate);
const Trajectory traj_opp = Trajectory::MakeOpponentTrajectory(state_opp, m_profile.max_dec);
const Trajectory traj_opp = Trajectory::MakeOpponentTrajectory(state_opp, m_profile.deceleration);

return Parabolic::HaveOverlap(traj_own.acc, traj_opp.dec, Common::field().robot_radius * 2.f) ||
Parabolic::HaveOverlap(traj_own.dec, traj_opp.dec, Common::field().robot_radius * 2.f) ||
Expand All @@ -53,7 +53,7 @@
bool Dss::RobotHasStaticCollision(const Common::RobotState &state, const Common::Vec2 &cmd) const
{
const Trajectory traj =
Trajectory::MakeTrajectory(state, cmd, m_profile.max_dec, 1.0f / Common::config().vision.vision_frame_rate);
Trajectory::MakeTrajectory(state, cmd, m_profile.deceleration, 1.0f / Common::config().vision.vision_frame_rate);

return Parabolic::HasStaticOverlap(traj.acc) || Parabolic::HasStaticOverlap(traj.dec) ||
Parabolic::HasStaticOverlap(traj.dec);
Expand Down Expand Up @@ -132,7 +132,7 @@
else
{
const float dec =
std::min(m_profile.max_dec, state.velocity.length() * Common::config().vision.vision_frame_rate);
std::min(m_profile.deceleration, state.velocity.length() * Common::config().vision.vision_frame_rate);
computed_motions[robot_idx] = state.velocity.normalized() * (-dec);
}
}
Expand All @@ -144,7 +144,7 @@
// TODO: in simulation setting a lower dec compared
// to motion plan results in better avoidance.
// Verify on the real field
m_profile.max_dec /= 2.0f;
m_profile.deceleration /= 2.0f;

const Common::Vec2 target_a_cmd = GetAccFromMotion(robot_num, motion);
const float target_a_cmd_mag = target_a_cmd.length();
Expand All @@ -162,7 +162,7 @@
else
{
const float dec =
std::min(m_profile.max_dec, state.velocity.length() * Common::config().vision.vision_frame_rate);
std::min(m_profile.deceleration, state.velocity.length() * Common::config().vision.vision_frame_rate);
a_cmd = state.velocity.normalized() * (-dec);
float error = ComputeError(target_a_cmd, a_cmd);

Expand Down
24 changes: 15 additions & 9 deletions source/soccer/errt/errt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ void Planner::init(const Common::Vec2 init, const Common::Vec2 final, const floa
m_step_size = step;

m_tree.reset();
m_tree.AddNode(init_state, nullptr);
m_tree.addNode(init_state, nullptr);

m_started_in_obs = g_obs_map.isInObstacle(init);
}
Expand Down Expand Up @@ -62,14 +62,14 @@ Node *Planner::extend(Node *s, Common::Vec2 &target)
if (g_obs_map.collisionDetect(new_state, s->state))
return nullptr;

return m_tree.AddNode(new_state, s);
return m_tree.addNode(new_state, s);
}

void Planner::setWayPoints()
{
m_waypoints.clear();

Node *n = m_tree.NearestNeighbour(final_state);
Node *n = m_tree.nearestNeighbour(final_state);
m_waypoints.push_back(n->state);

while (n->parent)
Expand All @@ -85,28 +85,34 @@ void Planner::setWayPoints()

Common::Vec2 Planner::plan()
{
if (m_cached_waypoints.empty())
{
Common::logWarning("cached waypoints are empty");
}

// return final_state;
if (!g_obs_map.collisionDetect(init_state, final_state))
{
m_tree.AddNode(final_state, m_tree.NearestNeighbour(final_state));
// TODO: slice the path so that the cache contains valid waypoints
m_tree.addNode(final_state, m_tree.nearestNeighbour(final_state));
}
else
{
for (int i = 0; ((i < m_max_nodes) && (!isReached())); i++)
{
Common::Vec2 r = chooseTarget();
extend(m_tree.NearestNeighbour(r), r);
extend(m_tree.nearestNeighbour(r), r);
}

if ((isReached()) && (!g_obs_map.isInObstacle(final_state)) &&
(final_state.distanceTo(m_tree.NearestNeighbour(final_state)->state) > 1))
(final_state.distanceTo(m_tree.nearestNeighbour(final_state)->state) > 1))
{
m_tree.AddNode(final_state, m_tree.NearestNeighbour(final_state));
m_tree.addNode(final_state, m_tree.nearestNeighbour(final_state));
}
}

setWayPoints();
optimize_tree();
optimizeTree();

if (m_started_in_obs || m_waypoints.size() <= 1)
{
Expand All @@ -118,7 +124,7 @@ Common::Vec2 Planner::plan()
}
}

void Planner::optimize_tree()
void Planner::optimizeTree()
{
for (size_t i = 0; i < m_waypoints.size() - 1; i++)
{
Expand Down
19 changes: 9 additions & 10 deletions source/soccer/errt/errt.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,12 @@
#include "../obstacle/map.h"
#include "tree.h"

namespace Tyr::Soccer

Check failure on line 6 in source/soccer/errt/errt.h

View workflow job for this annotation

GitHub Actions / check

source/soccer/errt/errt.h:6:1 [clang-diagnostic-error]

unknown type name 'namespace'

Check failure on line 6 in source/soccer/errt/errt.h

View workflow job for this annotation

GitHub Actions / check

source/soccer/errt/errt.h:6:14 [clang-diagnostic-error]

expected ';' after top level declarator

Check failure on line 6 in source/soccer/errt/errt.h

View workflow job for this annotation

GitHub Actions / check

source/soccer/errt/errt.h:6:15 [clang-diagnostic-error]

expected identifier or '('
{
class Planner
{
public:
Planner(int t_max_nodes = 1000);
Planner(int t_max_nodes = 2000);
~Planner() = default;

void init(Common::Vec2 init, Common::Vec2 final, float step);
Expand All @@ -32,7 +32,7 @@

// TODO: move to setting
float goal_target_prob = 0.1f;
float waypoint_target_prob = 0.5f;
float waypoint_target_prob = 0.8f;
float acceptable_dis = 90.0f;

Common::Random m_random;
Expand All @@ -41,8 +41,8 @@

Common::Vec2 randomState()
{
return Common::Vec2((m_random.get(-1.0f, 1.0f) * (Common::field().width + 250.0f)),
(m_random.get(-1.0f, 1.0f) * (Common::field().height + 250.0f)));
return Common::Vec2((m_random.get(-1.0f, 1.0f) * (Common::field().width + Common::field().boundary_width)),
(m_random.get(-1.0f, 1.0f) * (Common::field().height + Common::field().boundary_width)));
}

Common::Vec2 nearestFree(Common::Vec2 state);
Expand All @@ -51,27 +51,27 @@
Node *extend(Node *s, Common::Vec2 &target);
void setWayPoints();

Common::Vec2 getWayPoint(const unsigned int i)
Common::Vec2 getWayPoint(const unsigned int i) const
{
return m_waypoints[i];
}

unsigned int getWayPointNum()
unsigned int getWayPointNum() const
{
return m_waypoints.size();
}

bool isReached()
{
return final_state.distanceTo(m_tree.NearestNeighbour(final_state)->state) <= acceptable_dis;
return final_state.distanceTo(m_tree.nearestNeighbour(final_state)->state) <= acceptable_dis;
}

void optimize_tree();
void optimizeTree();
};

inline Common::Vec2 Planner::chooseTarget()
{
float r = m_random.get(0.0f, 1.0f);
const float r = m_random.get(0.0f, 1.0f);

if (r <= goal_target_prob)
{
Expand All @@ -82,7 +82,6 @@
const int idx = m_random.get(0, static_cast<int>(m_cached_waypoints.size()) - 1);
return m_cached_waypoints[idx];
}

else
{
return randomState();
Expand Down
Loading
Loading