Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
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
12 changes: 6 additions & 6 deletions config/settings.ini
Original file line number Diff line number Diff line change
@@ -1,14 +1,14 @@
; KN2C SSL Configuration File

[Game]
Mode=Real;Simulation;
Mode=Simulation;Real;
[Team]
Color =Yellow;Blue;
Color =Blue;Yellow;
Side =Left;Right;
[Field]
Size = Double;Single;
[Transmitter]
SerialPort = /dev/ttyUSB1
SerialPort = /dev/ttyUSB0

[VisionConfig]
UsingCameras = 7;CAMERA_NONE = 0, CAMERA_0 = 1, CAMERA_1 = 2, CAMERA_2 = 3, CAMERA_3 = 4, CAMERA_BOTH_L = 5,CAMERA_BOTH_R = 6,CAMERA_ALL = 7
Expand All @@ -17,11 +17,11 @@ UsingCameras = 7;CAMERA_NONE = 0, CAMERA_0 = 1, CAMERA_1 = 2, CAMERA_2 = 3, CAME
RefereeBall = 100

[Simulation]
RefIP = 224.5.23.1
RefIP = 224.5.23.1;127.0.0.1;
RefPort = 10001
RefPortNew = 10003
RefUseNew = 1
VisionIP = 224.5.23.6;127.0.0.1;
VisionIP = 127.0.0.1;224.5.23.6;
VisionPort = 10020

[Real]
Expand All @@ -33,7 +33,7 @@ VisionIP = 224.5.23.2
VisionPort = 10006

[grSim]
CommandIP = 224.5.23.6;127.0.0.1;
CommandIP = 127.0.0.1;224.5.23.6;
CommandPort = 20011
BluePort = 30011
YellowPort = 30012
Expand Down
43 changes: 16 additions & 27 deletions src/ai/agent.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,6 @@ Agent::Agent() :
{
wm = 0;
id = -1;

ctrl = new Controller();
}

void Agent::setID(int id)
Expand All @@ -31,33 +29,31 @@ void Agent::SendCommand(RobotCommand rc)
{
if(!wm->ourRobot[id].isValid) return;

if( id == 0 ) wm->debug_pos.clear();
ControllerInput ci = nav.calc(rc);
ControllerResult co = ctrl->calc(ci);

if( !controllerResultIsValid(co) )
if( id == 0 )
{
delete ctrl;
ctrl = new Controller();
wm->debug_pos.append(ci.mid_pos.loc);
wm->debug_pos.append(ci.cur_pos.loc);
}

ControllerResult co = ctrl.calc(ci);

// Real Game Packet
RobotData reRD;
reRD.RID = id;
reRD.Vx_sp = co.rs.VX * 1000;
reRD.Vy_sp = co.rs.VY * 1000;
reRD.Wr_sp = co.rs.VW * 1000;
reRD.Vx = wm->ourRobot[id].vel.loc.x * 1000;
reRD.Vy = wm->ourRobot[id].vel.loc.y * 1000;
reRD.Wr = wm->ourRobot[id].vel.dir * 100;
reRD.alpha = wm->ourRobot[id].pos.dir * 1000;
reRD.KICK = (quint8) rc.kickspeedx;
reRD.CHIP = (quint8) rc.kickspeedz;
reRD.SPIN = 128;//for test
reRD.RID = id;
reRD.M0 = co.msR.M0;
reRD.M1 = co.msR.M1;
reRD.M2 = co.msR.M2;
reRD.M3 = co.msR.M3;
reRD.KCK = (quint8) rc.kickspeedx;
reRD.CHP = (quint8) rc.kickspeedz;

outputBuffer->wpck.AddRobot(reRD);


// grSim Packet
grRobotData grRD;

grRD.rid = id;
grRD.velx = co.rs.VX;
grRD.vely = co.rs.VY;
Expand Down Expand Up @@ -106,14 +102,7 @@ bool Agent::grSimPacketIsValid(grRobotData grRD)
if( !isnan(grRD.velx) && !isnan(grRD.vely) && !isnan(grRD.velw) &&
!isnan(grRD.wheel1) && !isnan(grRD.wheel2) && !isnan(grRD.wheel3) && !isnan(grRD.wheel4) )
return true;

return false;
}

bool Agent::controllerResultIsValid(ControllerResult co)
{
if( isnan(co.rs.VW) || isnan(co.rs.VX) || isnan(co.rs.VY) )
return false;

return true;
}

2 changes: 1 addition & 1 deletion src/ai/agent.h
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ class Agent : public Robot

private:
int id;
Controller *ctrl;
Controller ctrl;
Navigation nav;
OutputBuffer *outputBuffer;
WorldModel *wm;
Expand Down
2 changes: 2 additions & 0 deletions src/ai/ai.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@ AI::AI(WorldModel *worldmodel, QString field_size, OutputBuffer *outputbuffer, Q
outputbuffer(outputbuffer)
{
qDebug() << "AI Initialization...";
qDebug()<<"WTF WTF WTF";
connect(&timer, SIGNAL(timeout()), this, SLOT(timer_timeout()));

Field::setup_consts(field_size);
Expand Down Expand Up @@ -52,6 +53,7 @@ AI::AI(WorldModel *worldmodel, QString field_size, OutputBuffer *outputbuffer, Q
plays.append(new PlayTest2(wm));
plays.append(new PlayLearning(wm));
plays.append(new PlayFormations(wm));

}

void AI::Start()
Expand Down
116 changes: 94 additions & 22 deletions src/ai/mapsearchnode.cpp
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@

#include "mapsearchnode.h"
#include "worldmodel.h"

Expand Down Expand Up @@ -82,37 +83,102 @@ bool MapSearchNode::GetSuccessors(AStarSearch<MapSearchNode> *astarsearch, MapSe
wm->navigation_pos.clear();
//kamin

for(int i=0; i<obs.size(); i++)
for(int i=0; i<obs.size(); i++)//obs.size()//-2// test
{
Circle2D obs_circle=obs.at(i);
int p_count = 6;
double p_dist = obs_circle.radius();//2*ROBOT_RADIUS+BALL_RADIUS; //

for(int j=0; j<p_count; j++)
{
Vector2D v(p_dist, p_dist);
v.rotate(360/p_count * j);
MapSearchNode node = obs[i].center() + v;
//kamin
bool checkNodeInterference = true;

for(int g=0;g<obs.size();g++)
if(i<obs.size()-2){
for(int j=0; j<p_count; j++)
{
if(obs[g].contains(node.vec))
Vector2D v(p_dist, p_dist);
v.rotate(360/p_count * j);
MapSearchNode node = obs[i].center() + v;
//kamin
bool checkNodeInterference = true;

for(int g=0;g<obs.size();g++)
{
checkNodeInterference = false;
if(obs[g].contains(node.vec))
{
checkNodeInterference = false;
}
}
}

if(checkNodeInterference == true)
if(checkNodeInterference == true)
{
wm->navigation_pos.append(node.vec);
//kamout
if(node.vec != parent) astarsearch->AddSuccessor(node);
}
}
}
else{
int goal_p_count=8;
for(int j=0; j<goal_p_count; j++)
{
wm->navigation_pos.append(node.vec);
//kamout
if(node.vec != parent) astarsearch->AddSuccessor(node);
Vector2D v(p_dist, p_dist);
v.rotate(360/goal_p_count * j);
MapSearchNode node = obs[i].center() + v;
//kamin
bool checkNodeInterference = true;

for(int g=0;g<obs.size();g++)
{
if(obs[g].contains(node.vec))
{
checkNodeInterference = false;
}
}

if(checkNodeInterference == true)
{
wm->navigation_pos.append(node.vec);
//kamout
if(node.vec != parent) astarsearch->AddSuccessor(node);
}
}
}
}


//test
// for(int i=obs.size()-2; i<obs.size(); i++)
// {
// Circle2D obs_circle=obs.at(i);
// int p_count = 8;
// double p_dist = obs_circle.radius();//2*ROBOT_RADIUS+BALL_RADIUS; //

// for(int j=0; j<p_count; j++)
// {
// Vector2D v(p_dist, p_dist);
// v.rotate(360/p_count * j);
// MapSearchNode node = obs[i].center() + v;
// //kamin
// bool checkNodeInterference = true;

// for(int g=0;g<obs.size();g++)
// {
// if(obs[g].contains(node.vec))
// {
// checkNodeInterference = false;
// }
// }

// if(checkNodeInterference == true)
// {
// wm->navigation_pos.append(node.vec);
// //kamout
// if(node.vec != parent) astarsearch->AddSuccessor(node);
// }
// }
// }


//test

MapSearchNode goal;
goal.vec = astarsearch->GetSolutionEnd()->vec;
astarsearch->AddSuccessor(goal);
Expand Down Expand Up @@ -146,11 +212,8 @@ float MapSearchNode::GetCost(MapSearchNode &successor)
QList<Circle2D> MapSearchNode::getObsCircle()
{
QList<Circle2D> result;

double b_rad = ROBOT_RADIUS + 2*BALL_RADIUS;
double r_rad = ROBOT_RADIUS * 2;


double b_rad = ROBOT_RADIUS + 2*BALL_RADIUS+50;
double r_rad = ROBOT_RADIUS * 2+50;
if(isBallObs && wm->ball.isValid)
{
Circle2D c(wm->ball.pos.loc, b_rad);
Expand All @@ -164,7 +227,7 @@ QList<Circle2D> MapSearchNode::getObsCircle()
Vector2D bloc = wm->ball.pos.loc;

double bang = (bloc - rpos.loc).dir().radian() - rpos.dir;
if (bang > M_PI) bang -= 2 * M_PI;
if (bang > M_PI) bang -= 2 * M_PI;//
if (bang < -M_PI) bang += 2 * M_PI;

if(fabs(bang) > M_PI_4 * 3 / 4)
Expand Down Expand Up @@ -192,6 +255,15 @@ QList<Circle2D> MapSearchNode::getObsCircle()
result.append(c);
}



Circle2D oppGoal(Field::oppGoalCenter,1000);
Circle2D ourGoal(Field::ourGoalCenter,1000);

result.append(oppGoal);
result.append(ourGoal);


// for(int i=0; i<wm->predict_pos.size(); i++)
// {
// Circle2D c(wm->predict_pos[i], b_rad);
Expand Down
2 changes: 1 addition & 1 deletion src/ai/play.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ Tactic* Play::getTactic(int id)

bool Play::conditionChanged()
{
bool out;
bool out = true;
QList<int> activeAgents=wm->kn->ActiveAgents();
if(activeAgents.size() != numberOfPlayers)
{
Expand Down
3 changes: 3 additions & 0 deletions src/ai/play/freeKicks/freeKicks.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,9 @@
#include "freekick10.h"
#include "freekick11.h"
#include "freekick47.h"
//armin sadreddin
#include "freekicktest1.h"
//armin sadreddin

#include "freekickdirect.h"

Expand Down
Loading